diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py index a3f2ff57875b98a42ce65c785f62d710fccc2a10..4da7abda2299fa2aced15258d501787feae743d6 100644 --- a/crocoddyl/actuation.py +++ b/crocoddyl/actuation.py @@ -22,9 +22,10 @@ class ActuationModelUAM: self.cf = coefF def calc(self, data, x, u): + # data.a[2:] = u d, cf, cm = self.d, self.cf, self.cf S = np.array(np.zeros([self.nv,self.nu])) - S[2:6,:4] = np.array([[1,1,1,1],[-d,d,-d,d],[-d,-d,d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]]) + S[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]]) np.fill_diagonal(S[6:, 4:], 1) data.a = np.dot(S,u) return data.a @@ -48,17 +49,14 @@ class ActuationDataUAM: self.Au = self.A[:, ndx:] self.Au[2:6,:4] = np.array([[1,1,1,1],[-d,d,d,-d],[-d,d,-d,d],[-cm/cf,-cm/cf,cm/cf,cm/cf]]) np.fill_diagonal(self.Au[6:, 4:], 1) - # Actuation considering motor forces instead of thrust and moments - # This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment - # [ 0, 0, 0, 0] - # [ 0, 0, 0, 0] - # [ 1, 1, 1, 1] - # [ -d, d, -d, d] - # [ -d, -d, d, d] - # [ -cm/cf, -cm/cf, cm/cf, cm/cf] - - - + #np.fill_diagonal(self.Au[2:, :], 1) +# This is the matrix that, given a force vector representing the four motors, outputs the thrust and moment +# [ 0, 0, 0, 0] +# [ 0, 0, 0, 0] +# [ 1, 1, 1, 1] +# [ -d, d, -d, d] +# [ -d, -d, d, d] +# [ -cm/cf, -cm/cf, cm/cf, cm/cf] class ActuationModelFreeFloating: diff --git a/crocoddyl/fddp.py b/crocoddyl/fddp.py index b209133a66e7b2ea4fed7f6e052ca7b97039e354..7f81ab26f727c91379f20685384988fa0ca37021 100644 --- a/crocoddyl/fddp.py +++ b/crocoddyl/fddp.py @@ -1,5 +1,6 @@ import numpy as np import scipy.linalg as scl +import time from .solver import SolverAbstract from .utils import raiseIfNan @@ -140,7 +141,9 @@ class SolverFDDP(SolverAbstract): recalc = True while True: try: + # t = time.time() self.computeDirection(recalc=recalc) + # print "TIME, Solving: Compute direction. Iteration " + str(i) + ": " + str(time.time()-t) except ArithmeticError: recalc = False self.increaseRegularization() diff --git a/examples/kinton_flying_base.py b/examples/kinton_flying_base.py new file mode 100644 index 0000000000000000000000000000000000000000..8aab5679203b7b784d5d7e61bf21c1fcf3e9fc77 --- /dev/null +++ b/examples/kinton_flying_base.py @@ -0,0 +1,178 @@ +from crocoddyl import * +import pinocchio as pin +import numpy as np +from crocoddyl.diagnostic import displayTrajectory + +# LOAD ROBOT +robot = loadKinton() +robot.initViewer(loadModel=True) +robot.display(robot.q0) + +robot.framesForwardKinematics(robot.q0) + +rmodel = robot.model + +# DEFINE TARGET POSITION +target_pos = np.array([0,0,1]) +target_quat = pin.Quaternion(1, 0, 0, 0) +target_quat.normalize() + +# Plot goal frame +robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4) +robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]]) +robot.viewer.gui.refresh() + +# ACTUATION MODEL +distanceRotorCOG = 0.1525 +cf = 6.6e-5 +cm = 1e-6 +actModel = ActuationModelUAM(robot.model, distanceRotorCOG, cf, cm) + +# COST MODEL +# Create a cost model per the running and terminal action model. +runningCostModel = CostModelSum(robot.model, actModel.nu) +terminalCostModel = CostModelSum(robot.model, actModel.nu) + +frameName = 'base_link' +state = StatePinocchio(robot.model) +SE3ref = pin.SE3() +SE3ref.translation = target_pos.reshape(3,1) +SE3ref.rotation = target_quat.matrix() + + +wBasePos = [1] +wBaseOri = [500] +wArmPos = [1] +wBaseVel = [10] +wBaseRate = [10] +wArmVel = [10] +stateWeights = np.array(wBasePos * 3 + wBaseOri * 3 + wArmPos * (robot.model.nv - 6) + wBaseVel * robot.model.nv) +controlWeights = np.array([0.1]*4 + [100]*6) + +goalTrackingCost = CostModelFramePlacement(rmodel, + frame=rmodel.getFrameId(frameName), + ref=SE3ref, + nu =actModel.nu) + +xRegCost = CostModelState(rmodel, + state, + ref=state.zero(), + nu=actModel.nu, + activation=ActivationModelWeightedQuad(stateWeights)) +uRegCost = CostModelControl(rmodel, + nu=robot. + model.nv-2, + activation = ActivationModelWeightedQuad(controlWeights)) +uLimCost = CostModelControl(rmodel, + nu=robot. + model.nv-2, + activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1, -1, -1, -1, -1, -1, -1]), + np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1]))) + +# Then let's add the running and terminal cost functions +runningCostModel.addCost(name="pos", weight=0.1, cost=goalTrackingCost) +runningCostModel.addCost(name="regx", weight=1e-4, cost=xRegCost) +runningCostModel.addCost(name="regu", weight=1e-6, cost=uRegCost) +runningCostModel.addCost(name="limu", weight=1e-3, cost=uLimCost) +terminalCostModel.addCost(name="pos", weight=0, cost=goalTrackingCost) + +# DIFFERENTIAL ACTION MODEL +runningModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, runningCostModel)) +terminalModel = IntegratedActionModelEuler(DifferentialActionModelUAM(robot.model, actModel, terminalCostModel)) + +# DEFINING THE SHOOTING PROBLEM & SOLVING +import time + +# Defining the time duration for running action models and the terminal one +dt = 1e-2 +runningModel.timeStep = dt + +T = 100 +q0 = rmodel.referenceConfigurations["initial_pose"].copy() +v0 = pin.utils.zero(rmodel.nv) +x0 = m2a(np.concatenate([q0, v0])) +rmodel.defaultState = x0.copy() + +t = time.time() +problem = ShootingProblem(x0, [runningModel] * T, terminalModel) +print "TIME: Shooting problem, " + str(time.time()-t) + +# Creating the DDP solver for this OC problem, defining a logger +fddp = SolverFDDP(problem) +fddp.callback = [CallbackDDPVerbose()] +fddp.callback.append(CallbackDDPLogger()) +#fddp.setCallbacks([CallbackVerbose()]) + +# us0 = [ +# m.differential.quasiStatic(d.differential, rmodel.defaultState) +# if isinstance(m, IntegratedActionModelEuler) else np.zeros(0) +# for m, d in zip(fddp.problem.runningModels, fddp.problem.runningDatas)] +# xs0 = [problem.initialState]*len(fddp.models()) + +# Solving it with the DDP algorithm +#fddp.solve(init_xs=xs0, init_us=us0) +t = time.time() +fddp.solve() +print "TIME: Solve time, " + str(time.time()-t) + +displayTrajectory(robot, fddp.xs, runningModel.timeStep) + +# Control trajectory +f1 = [] +f2 = []; +f3 = []; +f4 = []; + +for u in fddp.us: + f1.append(u[0]) + f2.append(u[1]) + f3.append(u[2]) + f4.append(u[3]) + +# State trajectory +Xx = []; +Xy = []; +Xz = []; +Vx = []; +Vy = []; +Vz = []; + + +for x in fddp.xs: + Xx.append(x[0]) + Xy.append(x[1]) + Xz.append(x[2]) + Vx.append(x[13]) + Vy.append(x[14]) + Vz.append(x[15]) + +import matplotlib.pyplot as plt +t = np.arange(0., 1, dt) + +fig, axs = plt.subplots(2,2, figsize=(15,10)) +fig.suptitle('Motor forces') +axs[0, 0].plot(t,f1) +axs[0, 0].set_title('Motor 1') +axs[0, 1].plot(t,f2) +axs[0, 1].set_title('Motor 2') +axs[1, 0].plot(t,f3) +axs[1, 0].set_title('Motor 3') +axs[1, 1].plot(t,f4) +axs[1, 1].set_title('Motor 4') + +plt.figure() +t = np.append(t, 1) +plt.plot(t,Xx,t,Xy,t,Xz) +plt.legend(['x','y','z']) +plt.title('State - Position') +plt.ylabel('Position, [m]') +plt.xlabel('[s]') + +plt.figure() +plt.plot(t,Vx,t,Vy,t,Vz) +plt.legend(['x','y','z']) +plt.title('State - Velocity') +plt.ylabel('Velocity, [m/s]') +plt.xlabel('[s]') + +plt.show() diff --git a/examples/notebooks/kinton_fixed_base.ipynb b/examples/notebooks/kinton_fixed_base.ipynb index c47122f4878dcf4e48104cca531c156cf708a445..dad285041ad10db2eaef228e0e630ec32cc823bb 100644 --- a/examples/notebooks/kinton_fixed_base.ipynb +++ b/examples/notebooks/kinton_fixed_base.ipynb @@ -45,16 +45,21 @@ "target_quat.normalize()\n", "\n", "# Plot goal frame\n", - "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 4)\n", + "robot.viewer.gui.addXYZaxis('world/framegoal', [1., 0., 0., 1.], .015, 1)\n", "robot.viewer.gui.applyConfiguration('world/framegoal', target_pos.tolist() + [target_quat[0], target_quat[1], target_quat[2], target_quat[3]])\n", "robot.viewer.gui.refresh()\n", "\n", "IDX_BASE = robot.model.getFrameId('base_link', pin.FrameType.BODY)\n", "Mbase = robot.data.oMf[IDX_BASE]\n", - "robot.viewer.gui.addXYZaxis('world/framebase', [1., 0., 0., 1.], .015, 4)\n", + "robot.viewer.gui.addXYZaxis('world/framebase', [1., 0., 0., 1.], .03, 0.5)\n", "robot.viewer.gui.applyConfiguration('world/framebase', pin.se3ToXYZQUATtuple(Mbase))\n", "robot.viewer.gui.refresh()\n", - "Mbase" + "\n", + "IDX_EE = robot.model.getFrameId('link6', pin.FrameType.BODY)\n", + "Mee = robot.data.oMf[IDX_EE]\n", + "robot.viewer.gui.addXYZaxis('world/frameee', [1., 0., 0., 1.], .03, 0.5)\n", + "robot.viewer.gui.applyConfiguration('world/frameee', pin.se3ToXYZQUATtuple(Mee))\n", + "robot.viewer.gui.refresh()" ] }, { @@ -1430,7 +1435,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4, diff --git a/examples/notebooks/kinton_flying_base.ipynb b/examples/notebooks/kinton_flying_base.ipynb index 0ab3183e4a3955bc193bea078bff43ff29b6fc45..c37bf320d9121f118a33155357499842492c37e0 100644 --- a/examples/notebooks/kinton_flying_base.ipynb +++ b/examples/notebooks/kinton_flying_base.ipynb @@ -302,7 +302,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4, diff --git a/examples/notebooks/kinton_flying_mission.ipynb b/examples/notebooks/kinton_flying_mission.ipynb index 51afa8a87f65ed4940f5a518908bf5abc78390cb..e86064df1cdeeb1a6ee4384f70c5fd94648c6261 100644 --- a/examples/notebooks/kinton_flying_mission.ipynb +++ b/examples/notebooks/kinton_flying_mission.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 66, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -14,13 +14,13 @@ }, { "cell_type": "code", - "execution_count": 67, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "# LOAD ROBOT\n", "robot = loadKinton()\n", - "robot.initDisplay(loadModel=True)\n", + "robot.initViewer(loadModel=True)\n", "robot.display(robot.q0)\n", "\n", "robot.framesForwardKinematics(robot.q0)\n", @@ -30,7 +30,7 @@ }, { "cell_type": "code", - "execution_count": 113, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -81,10 +81,11 @@ " np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))\n", "\n", " # Then let's add the running and terminal cost functions\n", - " runningCostModel.addCost(name=\"pos\", weight=1, cost=goalTrackingCost)\n", - " runningCostModel.addCost(name=\"regx\", weight=1e-7, cost=xRegCost)\n", - " runningCostModel.addCost(name=\"regu\", weight=1e-4, cost=uRegCost)\n", + " runningCostModel.addCost(name=\"pos\", weight=0.1, cost=goalTrackingCost)\n", + " runningCostModel.addCost(name=\"regx\", weight=1e-4, cost=xRegCost)\n", + " runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n", " #runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n", + " terminalCostModel.addCost(name=\"pos\", weight=10, cost=goalTrackingCost)\n", "\n", " # DIFFERENTIAL ACTION MODEL\n", " dmodel = DifferentialActionModelUAM(rmodel, actModel, runningCostModel)\n", @@ -95,7 +96,7 @@ }, { "cell_type": "code", - "execution_count": 114, + "execution_count": 4, "metadata": { "scrolled": true }, @@ -104,11 +105,11 @@ "# DEFINING THE SHOOTING PROBLEM & SOLVING\n", "\n", "# Defining the time duration for running action models and the terminal one\n", - "dt = 1e-3\n", + "dt = 1e-2\n", "\n", "# For this optimal control problem, we define 250 knots (or running action\n", "# models) plus a terminal knot\n", - "T = 500\n", + "T = 50\n", "\n", "\n", "# DEFINE POSITION WAYPOINTS\n", @@ -129,7 +130,7 @@ }, { "cell_type": "code", - "execution_count": 115, + "execution_count": 5, "metadata": {}, "outputs": [ { @@ -137,121 +138,37 @@ "output_type": "stream", "text": [ "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 0 4.12884e+02 3.67938e-02 1.31497e+03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 1 2.38168e+02 4.37121e-02 4.15129e+02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 2 2.07246e+02 3.80014e-02 8.08585e+01 1.00000e-09 1.00000e-09 0.5000 1\n", - " 3 2.01504e+02 6.09189e-03 1.26262e+01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 4 2.00397e+02 1.11327e-02 2.47216e+00 1.00000e-09 1.00000e-09 1.0000 1\n", - " 5 2.00145e+02 4.89374e-04 9.23825e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 6 1.99985e+02 4.08639e-04 7.66832e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 7 1.99885e+02 2.97127e-04 6.72826e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 8 1.99826e+02 2.78160e-04 5.62730e-01 1.00000e-09 1.00000e-09 1.0000 1\n", - " 9 1.99788e+02 3.32463e-04 4.99581e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 0 3.51425e+00 1.27336e-04 1.22872e+01 1.00000e-09 1.00000e-09 0.5000 0\n", + " 1 2.32067e+00 4.16275e-05 3.89873e+00 1.00000e-09 1.00000e-09 0.5000 0\n", + " 2 1.17724e+00 5.80554e-05 2.00231e+00 1.00000e-09 1.00000e-09 1.0000 1\n", + " 3 1.09163e+00 1.06224e-05 2.37892e-01 1.00000e-09 1.00000e-09 1.0000 1\n", + " 4 1.06827e+00 1.78135e-06 7.83426e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 5 1.06011e+00 1.57027e-06 2.81042e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 6 1.05728e+00 1.83779e-07 1.06911e-02 1.00000e-09 1.00000e-09 1.0000 1\n", + " 7 1.05611e+00 3.19838e-07 4.55371e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 8 1.05558e+00 3.47870e-08 2.19753e-03 1.00000e-09 1.00000e-09 1.0000 1\n", + " 9 1.05530e+00 9.59146e-08 1.17187e-03 1.00000e-09 1.00000e-09 1.0000 1\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 10 1.99673e+02 4.31859e-04 4.33920e-01 1.00000e-09 1.00000e-09 0.5000 1\n", - " 11 1.99659e+02 3.16549e-05 2.10171e-02 1.00000e-09 1.00000e-09 1.0000 1\n", - " 12 1.99654e+02 3.98525e-06 7.16689e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 13 1.99651e+02 5.27315e-06 4.64218e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 14 1.99649e+02 6.87421e-06 3.54310e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 15 1.99648e+02 9.59427e-06 3.31298e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 16 1.99648e+02 1.33639e-05 3.50811e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 17 1.99647e+02 1.92685e-05 4.33352e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 18 1.99646e+02 2.77032e-05 5.52910e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 19 1.99645e+02 3.59833e-07 6.54565e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 10 1.05514e+00 1.33286e-08 6.87744e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 11 1.05505e+00 3.73615e-08 4.35857e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 12 1.05499e+00 7.66134e-09 2.97648e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 13 1.05496e+00 1.79607e-08 2.15688e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 14 1.05493e+00 5.28123e-09 1.64650e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 15 1.05491e+00 1.02704e-08 1.30749e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 16 1.05490e+00 3.91971e-09 1.07069e-04 1.00000e-09 1.00000e-09 1.0000 1\n", + " 17 1.05488e+00 6.66467e-09 8.96834e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 18 1.05487e+00 3.00024e-09 7.63338e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 19 1.05487e+00 4.68907e-09 6.57508e-05 1.00000e-09 1.00000e-09 1.0000 1\n", "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 20 1.99645e+02 4.93022e-07 6.38851e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 21 1.99644e+02 7.04896e-07 6.54829e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 22 1.99644e+02 1.00715e-06 6.96629e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 23 1.99643e+02 1.46463e-06 7.69297e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 24 1.99643e+02 2.12629e-06 8.79861e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 25 1.99642e+02 3.11183e-06 1.04658e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 26 1.99642e+02 4.54850e-06 1.28989e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 27 1.99641e+02 6.67282e-06 1.65051e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 28 1.99641e+02 9.78380e-06 2.17569e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 29 1.99641e+02 1.43706e-05 2.95283e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 30 1.99640e+02 2.11225e-05 4.09048e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 31 1.99639e+02 2.83572e-07 5.96823e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 32 1.99639e+02 3.96363e-07 6.20164e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 33 1.99638e+02 5.65593e-07 6.53720e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 34 1.99637e+02 8.01686e-07 6.99668e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 35 1.99637e+02 1.15466e-06 7.64695e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 36 1.99636e+02 1.65631e-06 8.55478e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 37 1.99636e+02 2.39368e-06 9.85617e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 38 1.99635e+02 3.45025e-06 1.16962e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 39 1.99635e+02 4.98928e-06 1.43516e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 40 1.99634e+02 7.20340e-06 1.81347e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 41 1.99634e+02 1.04132e-05 2.36121e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 42 1.99634e+02 1.50477e-05 3.14641e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 43 1.99633e+02 2.17590e-05 4.28683e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 44 1.99632e+02 3.15119e-05 5.93587e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 45 1.99631e+02 3.80198e-07 7.03865e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 46 1.99631e+02 5.23991e-07 7.32775e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 47 1.99630e+02 7.38637e-07 7.74974e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 48 1.99629e+02 1.02834e-06 8.31246e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 49 1.99629e+02 1.45715e-06 9.09909e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 50 1.99628e+02 2.04964e-06 1.01689e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 51 1.99627e+02 2.90795e-06 1.16822e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 52 1.99627e+02 4.10701e-06 1.37673e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 53 1.99626e+02 5.82397e-06 1.67332e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 54 1.99626e+02 8.23618e-06 2.08521e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 55 1.99625e+02 1.16689e-05 2.67241e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 56 1.99625e+02 1.65142e-05 3.49328e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 57 1.99624e+02 2.33965e-05 4.66633e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 58 1.99623e+02 3.31810e-05 6.32127e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 59 1.99622e+02 3.63119e-07 7.96719e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 60 1.99621e+02 4.87484e-07 8.21522e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 61 1.99620e+02 6.70729e-07 8.57725e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 62 1.99620e+02 9.08512e-07 9.04717e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 63 1.99619e+02 1.25716e-06 9.69006e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 64 1.99618e+02 1.72338e-06 1.05410e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 65 1.99617e+02 2.38848e-06 1.17185e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 66 1.99617e+02 3.29106e-06 1.32984e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 67 1.99616e+02 4.55918e-06 1.54961e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 68 1.99615e+02 6.29277e-06 1.84679e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 69 1.99615e+02 8.70729e-06 2.26081e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 70 1.99614e+02 1.20237e-05 2.82389e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 71 1.99614e+02 1.66223e-05 3.60888e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 72 1.99613e+02 2.29727e-05 4.68360e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 73 1.99611e+02 3.17782e-05 6.18582e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 74 1.99611e+02 3.11900e-07 8.72919e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 75 1.99610e+02 4.07247e-07 8.90782e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 76 1.99609e+02 5.43301e-07 9.17106e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 77 1.99608e+02 7.12379e-07 9.50400e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 78 1.99607e+02 9.57466e-07 9.95153e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 79 1.99607e+02 1.27369e-06 1.05274e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 80 1.99606e+02 1.71701e-06 1.13089e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 81 1.99605e+02 2.29949e-06 1.23268e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 82 1.99604e+02 3.10158e-06 1.37149e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 83 1.99603e+02 4.16385e-06 1.55334e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 84 1.99602e+02 5.61273e-06 1.80175e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 85 1.99602e+02 7.53748e-06 2.12814e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 86 1.99601e+02 1.01511e-05 2.57435e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 87 1.99600e+02 1.36278e-05 3.16181e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 88 1.99600e+02 1.83472e-05 3.96650e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 89 1.99599e+02 2.46376e-05 5.02936e-03 1.00000e-09 1.00000e-09 1.0000 1\n" - ] - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "iter \t cost \t stop \t grad \t xreg \t ureg \t step \t feas\n", - " 90 1.99599e+02 3.32130e-05 6.49300e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 91 1.99597e+02 4.47017e-05 8.43978e-03 1.00000e-09 1.00000e-09 0.5000 1\n", - " 92 1.99596e+02 3.66901e-07 9.40917e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 93 1.99595e+02 4.64742e-07 9.53069e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 94 1.99594e+02 6.07280e-07 9.76036e-04 1.00000e-09 1.00000e-09 1.0000 1\n", - " 95 1.99593e+02 7.73138e-07 1.00503e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 96 1.99592e+02 1.01393e-06 1.04490e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 97 1.99592e+02 1.30863e-06 1.09510e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 98 1.99591e+02 1.71772e-06 1.16344e-03 1.00000e-09 1.00000e-09 1.0000 1\n", - " 99 1.99590e+02 2.23199e-06 1.24991e-03 1.00000e-09 1.00000e-09 1.0000 1\n" + " 20 1.05486e+00 2.32762e-09 5.70767e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 21 1.05486e+00 3.45906e-09 4.98511e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 22 1.05485e+00 1.81663e-09 4.36968e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 23 1.05485e+00 2.62022e-09 3.84228e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 24 1.05484e+00 1.42137e-09 3.38379e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 25 1.05484e+00 2.01389e-09 2.98487e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 26 1.05484e+00 1.11298e-09 2.63449e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 27 1.05484e+00 1.56013e-09 2.32720e-05 1.00000e-09 1.00000e-09 1.0000 1\n", + " 28 1.05484e+00 8.71453e-10 2.05599e-05 1.00000e-09 1.00000e-09 1.0000 1\n" ] }, { @@ -259,10000 +176,1000 @@ "text/plain": [ "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.,\n", " 0., 0., 0., 0., 0., 0., 0., 0.]),\n", - " array([ 5.85237457e-10, 6.69571510e-07, 4.25906477e-04, 4.17502505e-04,\n", - " -3.62684019e-07, -4.68765744e-06, 9.99999913e-01, -9.56465445e-06,\n", - " 8.43478756e-04, 1.11094600e-06, -1.84457793e-07, -1.16338927e-06,\n", - " -9.85723371e-06, 7.36290330e-07, 8.47388501e-04, 4.25906173e-01,\n", - " 8.35005034e-01, -7.25368058e-04, -9.37531516e-03, -9.56465445e-03,\n", - " 8.43478756e-01, 1.11094600e-03, -1.84457793e-04, -1.16338927e-03,\n", - " -9.85723371e-03]),\n", - " array([ 1.03432885e-09, 1.27302072e-06, 1.26476098e-03, 1.22073318e-03,\n", - " -9.78886079e-07, -1.31160456e-05, 9.99999255e-01, -2.67855299e-05,\n", - " 2.46630307e-03, 3.48823902e-06, -5.54600309e-07, -3.45543133e-06,\n", - " -2.89867371e-05, 1.55244230e-06, 1.97768966e-03, 8.38852477e-01,\n", - " 1.60646193e+00, -1.23191183e-03, -1.68568509e-02, -1.72208754e-02,\n", - " 1.62282432e+00, 2.37729303e-03, -3.70142516e-04, -2.29204206e-03,\n", - " -1.91295034e-02]),\n", - " array([ 5.89453206e-10, 8.34477566e-07, 2.50387234e-03, 2.37908637e-03,\n", - " -1.74808137e-06, -2.44212111e-05, 9.99997170e-01, -4.99211323e-05,\n", - " 4.80670099e-03, 7.25663559e-06, -1.11149958e-06, -6.84266012e-06,\n", - " -5.68253825e-05, 2.86958577e-06, 4.02203147e-03, 1.23910519e+00,\n", - " 2.31671027e+00, -1.53560901e-03, -2.26107638e-02, -2.31356025e-02,\n", - " 2.34039792e+00, 3.76839657e-03, -5.56899267e-04, -3.38722879e-03,\n", - " -2.78386455e-02]),\n", - " array([-1.48321731e-09, -1.81425878e-06, 4.13080237e-03, 3.86305564e-03,\n", - " -2.57982276e-06, -3.78244201e-05, 9.99992538e-01, -7.74009509e-05,\n", - " 7.80512412e-03, 1.25155063e-05, -1.85598860e-06, -1.12926868e-05,\n", - " -9.28305989e-05, 4.82272782e-06, 7.50679968e-03, 1.62691546e+00,\n", - " 2.96795325e+00, -1.65478901e-03, -2.68078089e-02, -2.74798186e-02,\n", - " 2.99842314e+00, 5.25887070e-03, -7.44489029e-04, -4.45002670e-03,\n", - " -3.60052164e-02]),\n", - " array([-5.85284962e-09, -7.99040667e-06, 6.13335163e-03, 5.64416231e-03,\n", - " -3.39459419e-06, -5.26323956e-05, 9.99984070e-01, -1.07825625e-04,\n", - " 1.14041064e-02, 1.93432203e-05, -2.78859131e-06, -1.67740278e-05,\n", - " -1.36479059e-04, 7.30086275e-06, 1.28626029e-02, 2.00251854e+00,\n", - " 3.56225405e+00, -1.60924465e-03, -2.96192810e-02, -3.04246738e-02,\n", - " 3.59898224e+00, 6.82771405e-03, -9.32602703e-04, -5.48134095e-03,\n", - " -4.36484600e-02]),\n", - " array([-1.30977462e-08, -1.91210223e-05, 8.49954585e-03, 7.69488303e-03,\n", - " -4.12416624e-06, -6.82359106e-05, 9.99970392e-01, -1.39963908e-04,\n", - " 1.55481201e-02, 2.78007492e-05, -3.90946509e-06, -2.32559520e-05,\n", - " -1.87265345e-04, 9.99658751e-06, 2.04324757e-02, 2.36613384e+00,\n", - " 4.10153336e+00, -1.41948357e-03, -3.12136817e-02, -3.21382835e-02,\n", - " 4.14401372e+00, 8.45752887e-03, -1.12087378e-03, -6.48192426e-03,\n", - " -5.07862861e-02]),\n", - " array([-2.36894767e-08, -3.67075965e-05, 1.12176230e-02, 9.98857688e-03,\n", - " -4.71153952e-06, -8.41070622e-05, 9.99950109e-01, -1.72747053e-04,\n", - " 2.01834309e-02, 3.79345872e-05, -5.21835480e-06, -3.07083473e-05,\n", - " -2.44700603e-04, 1.24592544e-05, 3.04793640e-02, 2.71796555e+00,\n", - " 4.58756800e+00, -1.10610879e-03, -3.17540389e-02, -3.27831444e-02,\n", - " 4.63531084e+00, 1.01338379e-02, -1.30888971e-03, -7.45239523e-03,\n", - " -5.74352583e-02]),\n", - " array([-3.79842115e-08, -6.22941093e-05, 1.42760215e-02, 1.24994127e-02,\n", - " -5.11055829e-06, -9.97955128e-05, 9.99921874e-01, -2.05261158e-04,\n", - " 2.52579520e-02, 4.97790857e-05, -6.71455679e-06, -3.91016025e-05,\n", - " -3.08311193e-04, 1.41471688e-05, 4.31929422e-02, 3.05820372e+00,\n", - " 5.02199040e+00, -6.89317036e-04, -3.13958068e-02, -3.25141050e-02,\n", - " 5.07452111e+00, 1.18444986e-02, -1.49620200e-03, -8.39325520e-03,\n", - " -6.36105898e-02]),\n", - " array([-5.62189492e-08, -9.74382616e-05, 1.76633692e-02, 1.52022970e-02,\n", - " -5.28527106e-06, -1.14923950e-04, 9.99884432e-01, -2.36737989e-04,\n", - " 3.07210986e-02, 6.33582948e-05, -8.39689202e-06, -4.84065062e-05,\n", - " -3.77637339e-04, 1.44756381e-05, 5.86958117e-02, 3.38702561e+00,\n", - " 5.40628879e+00, -1.88502894e-04, -3.02852801e-02, -3.14768318e-02,\n", - " 5.46314656e+00, 1.35792091e-02, -1.68233523e-03, -9.30490377e-03,\n", - " -6.93261465e-02]),\n", - " array([-7.85109992e-08, -1.43685635e-04, 2.13684740e-02, 1.80728028e-02,\n", - " -5.20910820e-06, -1.29182988e-04, 9.99836665e-01, -2.66544702e-04,\n", - " 3.65236432e-02, 7.86873966e-05, -1.02636870e-05, -5.85941592e-05,\n", - " -4.52231795e-04, 1.28587897e-05, 7.70491303e-02, 3.70459735e+00,\n", - " 5.74180817e+00, 3.78043213e-04, -2.85584558e-02, -2.98067128e-02,\n", - " 5.80254461e+00, 1.53291017e-02, -1.86679498e-03, -1.01876530e-02,\n", - " -7.45944559e-02]),\n", - " array([-1.04859607e-07, -2.02546561e-04, 2.53803152e-02, 2.10870997e-02,\n", - " -4.86393796e-06, -1.42325690e-04, 9.99777632e-01, -2.94172841e-04,\n", - " 4.26175728e-02, 9.57738085e-05, -1.23127618e-05, -6.96358995e-05,\n", - " -5.31658517e-04, 8.74398375e-06, 9.82577220e-02, 4.01107566e+00,\n", - " 6.02975176e+00, 9.93355004e-04, -2.63402837e-02, -2.76281386e-02,\n", - " 6.09392961e+00, 1.70864119e-02, -2.04907481e-03, -1.10417403e-02,\n", - " -7.94267215e-02]),\n", - " array([-1.35149009e-07, -2.75475507e-04, 2.96880359e-02, 2.42218854e-02,\n", - " -4.23905441e-06, -1.54161892e-04, 9.99706595e-01, -3.19226952e-04,\n", - " 4.89559477e-02, 1.14618025e-04, -1.45414242e-05, -8.15032399e-05,\n", - " -6.15491359e-04, 1.63837769e-06, 1.22274713e-01, 4.30660963e+00,\n", - " 6.27118303e+00, 1.64193957e-03, -2.37442487e-02, -2.50541113e-02,\n", - " 6.33837485e+00, 1.88442164e-02, -2.22866239e-03, -1.18673404e-02,\n", - " -8.38328417e-02]),\n", - " array([-1.69152509e-07, -3.63852816e-04, 3.42809375e-02, 2.74543186e-02,\n", - " -3.33014166e-06, -1.64552441e-04, 9.99623046e-01, -3.41413079e-04,\n", - " 5.54927626e-02, 1.35214255e-04, -1.69464690e-05, -9.41678157e-05,\n", - " -7.03312791e-04, -8.87224659e-06, 1.49005739e-01, 4.59134253e+00,\n", - " 6.46702808e+00, 2.30986651e-03, -2.08722333e-02, -2.21861269e-02,\n", - " 6.53681498e+00, 2.05962303e-02, -2.40504485e-03, -1.26645758e-02,\n", - " -8.78214326e-02]),\n", - " array([-2.06537356e-07, -4.68968632e-04, 3.91484738e-02, 3.07619544e-02,\n", - " -2.13825122e-06, -1.73403480e-04, 9.99526724e-01, -3.60527367e-04,\n", - " 6.21828115e-02, 1.57550908e-04, -1.95241825e-05, -1.07601343e-04,\n", - " -7.94712645e-04, -2.31118785e-05, 1.78312764e-01, 4.86541363e+00,\n", - " 6.61807846e+00, 2.98480680e-03, -1.78146126e-02, -1.91142880e-02,\n", - " 6.69004887e+00, 2.23366530e-02, -2.57771341e-03, -1.34335270e-02,\n", - " -9.13998538e-02]),\n", - " array([-2.46870369e-07, -5.92008908e-04, 4.42802471e-02, 3.41226803e-02,\n", - " -6.68820940e-07, -1.80660867e-04, 9.99417635e-01, -3.76444970e-04,\n", - " 6.89815542e-02, 1.81610964e-04, -2.22703500e-05, -1.21775583e-04,\n", - " -8.89286883e-04, -4.13091085e-05, 2.10017548e-01, 5.12895980e+00,\n", - " 6.72499431e+00, 3.65603040e-03, -1.46505406e-02, -1.59176028e-02,\n", - " 6.79874273e+00, 2.40600560e-02, -2.74616752e-03, -1.41742407e-02,\n", - " -9.45742382e-02]),\n", - " array([-2.89624303e-07, -7.34043346e-04, 4.96660051e-02, 3.75146548e-02,\n", - " 1.06924267e-06, -1.86304797e-04, 9.99296060e-01, -3.89109403e-04,\n", - " 7.58449878e-02, 2.07372268e-04, -2.51802683e-05, -1.36662322e-04,\n", - " -9.86636406e-04, -6.35974409e-05, 2.43904800e-01, 5.38211718e+00,\n", - " 6.78830770e+00, 4.31437059e-03, -1.14483882e-02, -1.26644331e-02,\n", - " 6.86343356e+00, 2.57613038e-02, -2.90991832e-03, -1.48867388e-02,\n", - " -9.73495228e-02]),\n", - " array([-3.34185018e-07, -8.96015191e-04, 5.52956381e-02, 4.09162481e-02,\n", - " 3.06440325e-06, -1.90344700e-04, 9.99162562e-01, -3.98522460e-04,\n", - " 8.27295206e-02, 2.34807769e-04, -2.82487601e-05, -1.52233347e-04,\n", - " -1.08636589e-03, -9.00200611e-05, 2.79725054e-01, 5.62502257e+00,\n", - " 6.80842632e+00, 4.95216239e-03, -8.26629917e-03, -9.41305713e-03,\n", - " 6.88453276e+00, 2.74355007e-02, -3.06849179e-03, -1.55710249e-02,\n", - " -9.97294828e-02]),\n", - " array([-3.79859484e-07, -1.07873276e-03, 6.11591772e-02, 4.43059840e-02,\n", - " 5.30324475e-06, -1.92814445e-04, 9.99017989e-01, -4.04734778e-04,\n", - " 8.95918507e-02, 2.63885727e-04, -3.14701915e-05, -1.68460439e-04,\n", - " -1.18808266e-03, -1.20538027e-04, 3.17197281e-01, 5.85781476e+00,\n", - " 6.78563728e+00, 5.56316107e-03, -5.15283567e-03, -6.21231796e-03,\n", - " 6.86233010e+00, 2.90779583e-02, -3.22143141e-03, -1.62270919e-02,\n", - " -1.01716767e-01]),\n", - " array([-4.25884687e-07, -1.28286264e-03, 6.72467929e-02, 4.76624842e-02,\n", - " 7.77112778e-06, -1.93767888e-04, 9.98863479e-01, -4.07837109e-04,\n", - " 9.63888484e-02, 2.94569904e-04, -3.48384921e-05, -1.85315367e-04,\n", - " -1.29139559e-03, -1.55040895e-04, 3.56011286e-01, 6.08063567e+00,\n", - " 6.72011115e+00, 6.14244637e-03, -2.14768501e-03, -3.10233087e-03,\n", - " 6.79699770e+00, 3.06841775e-02, -3.36830060e-03, -1.68549280e-02,\n", - " -1.03312936e-01]),\n", - " array([-4.71437426e-07, -1.50892445e-03, 7.35487947e-02, 5.09644141e-02,\n", - " 1.04527507e-05, -1.93274790e-04, 9.98700451e-01, -4.07952337e-04,\n", - " 1.03077443e-01, 3.26819745e-04, -3.83471769e-05, -2.02769890e-04,\n", - " -1.39591409e-03, -1.93358890e-04, 3.95829896e-01, 6.29363124e+00,\n", - " 6.61190614e+00, 6.68631703e-03, 7.17592561e-04, -1.15228218e-04,\n", - " 6.68859429e+00, 3.22498409e-02, -3.50868484e-03, -1.74545228e-02,\n", - " -1.04518499e-01]),\n", - " array([-5.15644982e-07, -1.75728712e-03, 8.00556302e-02, 5.41904313e-02,\n", - " 1.33326176e-05, -1.91417103e-04, 9.98530601e-01, -4.05228259e-04,\n", - " 1.09614512e-01, 3.60590558e-04, -4.19893706e-05, -2.20795763e-04,\n", - " -1.50124705e-03, -2.35275806e-04, 4.36290969e-01, 6.49695227e+00,\n", - " 6.46097243e+00, 7.19217947e-03, 3.41879530e-03, 2.72407749e-03,\n", - " 6.53706955e+00, 3.37708127e-02, -3.64219364e-03, -1.80258729e-02,\n", - " -1.05332955e-01]),\n", - " array([-5.57596603e-07, -2.02816659e-03, 8.67578847e-02, 5.73191347e-02,\n", - " 1.63954173e-05, -1.88285650e-04, 9.98355889e-01, -3.99831132e-04,\n", - " 1.15956781e-01, 3.95833700e-04, -4.57578329e-05, -2.39364750e-04,\n", - " -1.60700188e-03, -2.80541994e-04, 4.77009246e-01, 6.69075488e+00,\n", - " 6.26715660e+00, 7.65843387e-03, 5.93830608e-03, 5.39712778e-03,\n", - " 6.34226863e+00, 3.52431414e-02, -3.76846234e-03, -1.85689872e-02,\n", - " -1.05754833e-01]),\n", - " array([-5.96355709e-07, -2.32162491e-03, 9.36462816e-02, 6.03290164e-02,\n", - " 1.96263195e-05, -1.83977171e-04, 9.98178529e-01, -3.91939969e-04,\n", - " 1.22060718e-01, 4.32496765e-04, -4.96449868e-05, -2.58448643e-04,\n", - " -1.71278362e-03, -3.28886874e-04, 5.17578053e-01, 6.87520088e+00,\n", - " 6.03020624e+00, 8.08436028e-03, 8.26432649e-03, 7.89116261e-03,\n", - " 6.10393676e+00, 3.66630651e-02, -3.88715387e-03, -1.90838928e-02,\n", - " -1.05781736e-01]),\n", - " array([-6.30972686e-07, -2.63757061e-03, 1.00711682e-01, 6.31984148e-02,\n", - " 2.30111965e-05, -1.78591746e-04, 9.98000966e-01, -3.81741584e-04,\n", - " 1.27882442e-01, 4.70523781e-04, -5.36429473e-05, -2.78019282e-04,\n", - " -1.81819400e-03, -3.80030560e-04, 5.57570882e-01, 7.05045787e+00,\n", - " 5.74977463e+00, 8.47000694e-03, 1.03901293e-02, 1.01983851e-02,\n", - " 5.82172398e+00, 3.80270164e-02, -3.99796047e-03, -1.95706396e-02,\n", - " -1.05410382e-01]),\n", - " array([-6.60498125e-07, -2.97576035e-03, 1.07945084e-01, 6.59054699e-02,\n", - " 2.65367770e-05, -1.72230576e-04, 9.97825856e-01, -3.69426329e-04,\n", - " 1.33377632e-01, 5.09855407e-04, -5.77435527e-05, -2.98048588e-04,\n", - " -1.92283065e-03, -4.33694299e-04, 5.96542855e-01, 7.21669912e+00,\n", - " 5.42542553e+00, 8.81608226e-03, 1.23133381e-02, 1.23152549e-02,\n", - " 5.49519000e+00, 3.93316256e-02, -4.10060541e-03, -2.00293059e-02,\n", - " -1.04636648e-01]),\n", - " array([-6.83996332e-07, -3.33580177e-03, 1.15337624e-01, 6.84280796e-02,\n", - " 3.01907425e-05, -1.64994109e-04, 9.97656038e-01, -3.55184514e-04,\n", - " 1.38501441e-01, 5.50429129e-04, -6.19383975e-05, -3.18508592e-04,\n", - " -2.02628626e-03, -4.89609540e-04, 6.34032096e-01, 7.37410313e+00,\n", - " 5.05663813e+00, 9.12385177e-03, 1.40352393e-02, 1.42418155e-02,\n", - " 5.12380916e+00, 4.05737225e-02, -4.19484485e-03, -2.04600042e-02,\n", - " -1.03455619e-01]),\n", - " array([-7.00558938e-07, -3.71715752e-03, 1.22880574e-01, 7.07438589e-02,\n", - " 3.39617741e-05, -1.56980484e-04, 9.97494502e-01, -3.39203452e-04,\n", - " 1.43208416e-01, 5.92179464e-04, -6.62188673e-05, -3.39371479e-04,\n", - " -2.12814789e-03, -5.47525519e-04, 6.69561004e-01, 7.52285308e+00,\n", - " 4.64281209e+00, 9.39504097e-03, 1.55601332e-02, 1.59810612e-02,\n", - " 4.70697555e+00, 4.17503351e-02, -4.28046977e-03, -2.08628866e-02,\n", - " -1.01861629e-01]),\n", - " array([-7.09318432e-07, -4.11915034e-03, 1.30565343e-01, 7.28300995e-02,\n", - " 3.78395579e-05, -1.48284292e-04, 9.97344350e-01, -3.21665108e-04,\n", - " 1.47452424e-01, 6.35038150e-04, -7.05761754e-05, -3.60609630e-04,\n", - " -2.22799621e-03, -6.07215357e-04, 7.02637463e-01, 7.66313587e+00,\n", - " 4.18327272e+00, 9.63174439e-03, 1.68947243e-02, 1.75383447e-02,\n", - " 4.24400819e+00, 4.28586859e-02, -4.35730816e-03, -2.12381510e-02,\n", - " -9.98483140e-02]),\n", - " array([-7.09461423e-07, -4.54096934e-03, 1.38383473e-01, 7.46637318e-02,\n", - " 4.18147577e-05, -1.38995615e-04, 9.97208758e-01, -3.02744279e-04,\n", - " 1.51186581e-01, 6.78934336e-04, -7.50014028e-05, -3.82195677e-04,\n", - " -2.32540486e-03, -6.68480710e-04, 7.32755980e-01, 7.79514097e+00,\n", - " 3.67727625e+00, 9.83634143e-03, 1.80475551e-02, 1.89208286e-02,\n", - " 3.73415642e+00, 4.38961855e-02, -4.42522734e-03, -2.15860474e-02,\n", - " -9.74086549e-02]),\n", - " array([-7.00241483e-07, -4.98167720e-03, 1.46326640e-01, 7.62212889e-02,\n", - " 4.58789613e-05, -1.29199335e-04, 9.97090917e-01, -2.82607298e-04,\n", - " 1.54363186e-01, 7.23794760e-04, -7.94855395e-05, -4.04102562e-04,\n", - " -2.41993990e-03, -7.31155068e-04, 7.59398774e-01, 7.91905899e+00,\n", - " 3.12401536e+00, 1.00114188e-02, 1.90284829e-02, 2.01369807e-02,\n", - " 3.17660540e+00, 4.48604244e-02, -4.48413673e-03, -2.19068850e-02,\n", - " -9.45350324e-02]),\n", - " array([-6.80991409e-07, -5.44021852e-03, 1.54386652e-01, 7.74788721e-02,\n", - " 5.00246075e-05, -1.18974680e-04, 9.96993986e-01, -2.61411186e-04,\n", - " 1.56933668e-01, 7.69543923e-04, -8.40195303e-05, -4.26303602e-04,\n", - " -2.51115917e-03, -7.95105818e-04, 7.82036827e-01, 8.03507990e+00,\n", - " 2.52262474e+00, 1.01596998e-02, 1.98482001e-02, 2.11961127e-02,\n", - " 2.57048179e+00, 4.57491631e-02, -4.53399077e-03, -2.22010401e-02,\n", - " -9.12192762e-02]),\n", - " array([-6.51134765e-07, -5.91542905e-03, 1.62555445e-01, 7.84121187e-02,\n", - " 5.42448985e-05, -1.08395002e-04, 9.96921022e-01, -2.39303223e-04,\n", - " 1.58848528e-01, 8.16104245e-04, -8.85943227e-05, -4.48772566e-04,\n", - " -2.59861189e-03, -8.60235234e-04, 8.00130905e-01, 8.14339103e+00,\n", - " 1.87218693e+00, 1.02839793e-02, 2.05177957e-02, 2.21079630e-02,\n", - " 1.91485961e+00, 4.65603215e-02, -4.57479242e-03, -2.24689639e-02,\n", - " -8.74527187e-02]),\n", - " array([-6.10196588e-07, -6.40604607e-03, 1.70825082e-01, 7.89961716e-02,\n", - " 5.85337025e-05, -9.75277523e-05, 9.96874913e-01, -2.16420902e-04,\n", - " 1.60057294e-01, 8.63396213e-04, -9.32009197e-05, -4.71483758e-04,\n", - " -2.68183814e-03, -9.26480524e-04, 8.13132571e-01, 8.24417471e+00,\n", - " 1.17173831e+00, 1.03870657e-02, 2.10483593e-02, 2.28823205e-02,\n", - " 1.20876626e+00, 4.72919684e-02, -4.60659702e-03, -2.27111919e-02,\n", - " -8.32262501e-02]),\n", - " array([-5.57813175e-07, -6.91071966e-03, 1.79187747e-01, 7.92056520e-02,\n", - " 6.28854496e-05, -8.64346426e-05, 9.96858291e-01, -1.92892212e-04,\n", - " 1.60508483e-01, 9.11338526e-04, -9.78304364e-05, -4.94412112e-04,\n", - " -2.76036852e-03, -9.93813085e-04, 8.20485204e-01, 8.33760557e+00,\n", - " 4.20275316e-01, 1.04717277e-02, 2.14506242e-02, 2.35286905e-02,\n", - " 4.51188866e-01, 4.79423130e-02, -4.62951664e-03, -2.29283538e-02,\n", - " -7.85303750e-02]),\n", - " array([-4.93740867e-07, -7.42802505e-03, 1.87635745e-01, 7.90146341e-02,\n", - " 6.72950229e-05, -7.51719695e-05, 9.96873451e-01, -1.68836212e-04,\n", - " 1.60149564e-01, 9.59848224e-04, -1.02474161e-04, -5.17533296e-04,\n", - " -2.83372379e-03, -1.06223709e-03, 8.21625041e-01, 8.42384763e+00,\n", - " -3.83239119e-01, 1.05406465e-02, 2.17346481e-02, 2.40559998e-02,\n", - " -3.58919290e-01, 4.85096977e-02, -4.64372509e-03, -2.31211845e-02,\n", - " -7.33552717e-02]),\n", - " array([-4.17863781e-07, -7.95647593e-03, 1.96161496e-01, 7.83966239e-02,\n", - " 7.17576459e-05, -6.37910878e-05, 9.96922244e-01, -1.44363870e-04,\n", - " 1.58926932e-01, 1.00884082e-03, -1.07123625e-04, -5.40823833e-04,\n", - " -2.90141464e-03, -1.13178750e-03, 8.15982275e-01, 8.50305091e+00,\n", - " -1.23986883e+00, 1.05963728e-02, 2.19095318e-02, 2.44723415e-02,\n", - " -1.22263194e+00, 4.89925970e-02, -4.64946343e-03, -2.32905364e-02,\n", - " -6.76908536e-02]),\n", - " array([-3.30200477e-07, -8.49453887e-03, 2.04757532e-01, 7.73245409e-02,\n", - " 7.62687661e-05, -5.23390120e-05, 9.97005971e-01, -1.19579114e-04,\n", - " 1.56785889e-01, 1.05823044e-03, -1.11770671e-04, -5.64261225e-04,\n", - " -2.96294147e-03, -1.20252755e-03, 8.02982224e-01, 8.57534784e+00,\n", - " -2.15069742e+00, 1.06412876e-02, 2.19831711e-02, 2.47847562e-02,\n", - " -2.14104277e+00, 4.93896199e-02, -4.64704624e-03, -2.34373924e-02,\n", - " -6.15268336e-02]),\n", - " array([-2.30909530e-07, -9.04064879e-03, 2.13416492e-01, 7.57707042e-02,\n", - " 8.08239341e-05, -4.08591305e-05, 9.97125264e-01, -9.45800610e-05,\n", - " 1.53670631e-01, 1.10792996e-03, -1.16407540e-04, -5.87824106e-04,\n", - " -3.01779426e-03, -1.27454573e-03, 7.82046614e-01, 8.64084930e+00,\n", - " -3.11682097e+00, 1.06775676e-02, 2.19620460e-02, 2.49990532e-02,\n", - " -3.11525808e+00, 4.96995213e-02, -4.63686851e-03, -2.35628805e-02,\n", - " -5.48527902e-02]),\n", - " array([-1.20294029e-07, -9.59322556e-03, 2.22131117e-01, 7.37068240e-02,\n", - " 8.54186750e-05, -2.93920148e-05, 9.97279949e-01, -6.94603928e-05,\n", - " 1.49524242e-01, 1.15785118e-03, -1.21026953e-04, -6.11492396e-04,\n", - " -3.06545250e-03, -1.34795229e-03, 7.52595013e-01, 8.69964026e+00,\n", - " -4.13934040e+00, 1.07071539e-02, 2.18510425e-02, 2.51196682e-02,\n", - " -4.14638902e+00, 4.99212218e-02, -4.61941334e-03, -2.36682901e-02,\n", - " -4.76582384e-02]),\n", - " array([ 1.19498685e-09, -1.01506917e-02, 2.30894249e-01, 7.11039988e-02,\n", - " 9.00483509e-05, -1.79763062e-05, 9.97468903e-01, -4.43108333e-05,\n", - " 1.44288698e-01, 1.20790502e-03, -1.25622213e-04, -6.35247484e-04,\n", - " -3.10538521e-03, -1.42287502e-03, 7.14046452e-01, 8.75177522e+00,\n", - " -5.21935341e+00, 1.07317242e-02, 2.16533094e-02, 2.51495595e-02,\n", - " -5.23554355e+00, 5.00538393e-02, -4.59526034e-03, -2.37550884e-02,\n", - " -3.99327025e-02]),\n", - " array([ 1.32956118e-07, -1.07114914e-02, 2.39698826e-01, 6.79327191e-02,\n", - " 9.47080093e-05, -6.64966360e-06, 9.97689900e-01, -1.92206891e-05,\n", - " 1.37904880e-01, 1.25800176e-03, -1.30187308e-04, -6.59072424e-04,\n", - " -3.13705100e-03, -1.49945447e-03, 6.65821298e-01, 8.79727328e+00,\n", - " -6.35794612e+00, 1.07526693e-02, 2.13701513e-02, 2.50901442e-02,\n", - " -6.38381792e+00, 5.00967325e-02, -4.56509487e-03, -2.38249399e-02,\n", - " -3.16657929e-02]),\n", - " array([ 2.74236204e-07, -1.12741105e-02, 2.48537879e-01, 6.41628800e-02,\n", - " 9.93922145e-05, 4.55024897e-06, 9.97939435e-01, 5.72058605e-06,\n", - " 1.30312592e-01, 1.30805132e-03, -1.34717026e-04, -6.82952150e-04,\n", - " -3.15989829e-03, -1.57783807e-03, 6.07343427e-01, 8.83611285e+00,\n", - " -7.55618425e+00, 1.07710729e-02, 2.10009584e-02, 2.49412751e-02,\n", - " -7.59228779e+00, 5.00495608e-02, -4.52971795e-03, -2.38797260e-02,\n", - " -2.28472874e-02]),\n", - " array([ 4.24129890e-07, -1.18370983e-02, 2.57404528e-01, 5.97638021e-02,\n", - " 1.04094858e-04, 1.55847535e-05, 9.98212541e-01, 3.04218462e-05,\n", - " 1.21450594e-01, 1.35796368e-03, -1.39207083e-04, -7.06873716e-04,\n", - " -3.17336550e-03, -1.65817329e-03, 5.38042773e-01, 8.86822625e+00,\n", - " -8.81510376e+00, 1.07876970e-02, 2.05431770e-02, 2.47012601e-02,\n", - " -8.86199883e+00, 4.99123602e-02, -4.49005699e-03, -2.39215662e-02,\n", - " -1.34672158e-02]),\n", - " array([ 5.81580157e-07, -1.23990895e-02, 2.66291985e-01, 5.47042653e-02,\n", - " 1.08808942e-04, 2.64131513e-05, 9.98502594e-01, 5.47887731e-05,\n", - " 1.11256637e-01, 1.40764931e-03, -1.43654260e-04, -7.30826557e-04,\n", - " -3.17688145e-03, -1.74059933e-03, 4.57358327e-01, 8.89349392e+00,\n", - " -1.01357012e+01, 1.08029717e-02, 1.99923231e-02, 2.43669270e-02,\n", - " -1.01939569e+01, 4.96856377e-02, -4.44717709e-03, -2.39528410e-02,\n", - " -3.51594939e-03]),\n", - " array([ 7.45379792e-07, -1.29588291e-02, 2.75193554e-01, 4.89525533e-02,\n", - " 1.13526337e-04, 3.69917436e-05, 9.98801098e-01, 7.87225078e-05,\n", - " 9.96675193e-02, 1.45701980e-03, -1.48056553e-04, -7.54802773e-04,\n", - " -3.16986575e-03, -1.82523726e-03, 3.64741672e-01, 8.91173854e+00,\n", - " -1.15189232e+01, 1.08169927e-02, 1.93420432e-02, 2.39337346e-02,\n", - " -1.15891175e+01, 4.93704862e-02, -4.40229287e-03, -2.39762154e-02,\n", - " 7.01570471e-03]),\n", - " array([ 9.14173846e-07, -1.35151967e-02, 2.84102633e-01, 4.24765153e-02,\n", - " 1.18237506e-04, 4.72729056e-05, 9.99097457e-01, 1.02118440e-04,\n", - " 8.66191443e-02, 1.50598852e-03, -1.52413334e-04, -7.78797435e-04,\n", - " -3.15172934e-03, -1.91217818e-03, 2.59661151e-01, 8.92271895e+00,\n", - " -1.29656558e+01, 1.08295256e-02, 1.85842271e-02, 2.33959325e-02,\n", - " -1.30483750e+01, 4.89687191e-02, -4.35678079e-03, -2.39946625e-02,\n", - " 1.81364042e-02]),\n", - " array([ 1.08646310e-06, -1.40672333e-02, 2.93012718e-01, 3.52436429e-02,\n", - " 1.22931195e-04, 5.72042457e-05, 9.99378741e-01, 1.24865209e-04,\n", - " 7.20465932e-02, 1.55447155e-03, -1.56725525e-04, -8.02808924e-04,\n", - " -3.12187518e-03, -2.00146933e-03, 1.41606768e-01, 8.92612405e+00,\n", - " -1.44767130e+01, 1.08400203e-02, 1.77091769e-02, 2.27467692e-02,\n", - " -1.45725511e+01, 4.84830266e-02, -4.31219142e-03, -2.40114887e-02,\n", - " 2.98541667e-02]),\n", - " array([ 1.26060862e-06, -1.46141679e-02, 3.01917414e-01, 2.72211688e-02,\n", - " 1.27594102e-04, 6.67278817e-05, 9.99629425e-01, 1.46843960e-04,\n", - " 5.58842108e-02, 1.60238870e-03, -1.60995787e-04, -8.26839281e-04,\n", - " -3.07969892e-03, -2.09309780e-03, 1.00959485e-02, 8.92156670e+00,\n", - " -1.60528244e+01, 1.08476360e-02, 1.67058375e-02, 2.19787506e-02,\n", - " -1.61623824e+01, 4.79171514e-02, -4.27026171e-03, -2.40303569e-02,\n", - " 4.21762595e-02]),\n", - " array([ 1.43483759e-06, -1.51554460e-02, 3.10810446e-01, 1.83761865e-02,\n", - " 1.32210505e-04, 7.57798713e-05, 9.99831132e-01, 1.67927904e-04,\n", - " 3.80657031e-02, 1.64966478e-03, -1.65228714e-04, -8.50894591e-04,\n", - " -3.02458983e-03, -2.18697192e-03, -1.35319742e-01, 8.90857775e+00,\n", - " -1.76946229e+01, 1.08512787e-02, 1.55620915e-02, 2.10839444e-02,\n", - " -1.78185077e+01, 4.72760837e-02, -4.23292657e-03, -2.40553102e-02,\n", - " 5.51090826e-02]),\n", - " array([ 1.60725048e-06, -1.56907576e-02, 3.19685675e-01, 8.67579729e-03,\n", - " 1.36761888e-04, 8.42898330e-05, 9.99962352e-01, 1.87982234e-04,\n", - " 1.85242488e-02, 1.69623105e-03, -1.69431043e-04, -8.74985383e-04,\n", - " -2.95593179e-03, -2.28290009e-03, -2.95046774e-01, 8.88660036e+00,\n", - " -1.94026309e+01, 1.08496518e-02, 1.42651244e-02, 2.00543291e-02,\n", - " -1.95414543e+01, 4.65662713e-02, -4.20232940e-03, -2.40907918e-02,\n", - " 6.86580459e-02]),\n", - " array([ 1.77582985e-06, -1.62200652e-02, 3.28537117e-01, -1.91271515e-03,\n", - " 1.41226548e-04, 9.21807981e-05, 9.99998157e-01, 2.06864414e-04,\n", - " -2.80737511e-03, 1.74202689e-03, -1.73611874e-04, -8.99127046e-04,\n", - " -2.87310435e-03, -2.38056749e-03, -4.69440607e-01, 8.85498468e+00,\n", - " -2.11772460e+01, 1.08413213e-02, 1.28018605e-02, 1.88821804e-02,\n", - " -2.13316239e+01, 4.57958409e-02, -4.18083094e-03, -2.41416631e-02,\n", - " 8.28274393e-02]),\n", - " array([ 1.93845099e-06, -1.67436317e-02, 3.37358971e-01, -1.34216761e-02,\n", - " 1.45579216e-04, 9.93693342e-05, 9.99909910e-01, 2.24424902e-04,\n", - " -2.59966525e-02, 1.78700172e-03, -1.77782889e-04, -9.23340261e-04,\n", - " -2.77548405e-03, -2.47951088e-03, -6.58795289e-01, 8.81298319e+00,\n", - " -2.30187265e+01, 1.08247950e-02, 1.11594705e-02, 1.75604878e-02,\n", - " -2.31892773e+01, 4.49748255e-02, -4.17101554e-03, -2.42132154e-02,\n", - " 9.76202960e-02]),\n", - " array([ 2.09289476e-06, -1.72620460e-02, 3.46145652e-01, -2.58827756e-02,\n", - " 1.49790706e-04, 1.05765977e-04, 9.99664968e-01, 2.40508291e-04,\n", - " -5.11111711e-02, 1.83111711e-03, -1.81958583e-04, -9.47651437e-04,\n", - " -2.66244580e-03, -2.57909215e-03, -8.63331582e-01, 8.75974684e+00,\n", - " -2.49271752e+01, 1.07986135e-02, 9.32595014e-03, 1.60833895e-02,\n", - " -2.51145187e+01, 4.41153897e-02, -4.17569398e-03, -2.43111759e-02,\n", - " 1.13038249e-01]),\n", - " array([ 2.23686284e-06, -1.77762469e-02, 3.54891822e-01, -3.93267836e-02,\n", - " 1.53827623e-04, 1.11276009e-04, 9.99226385e-01, 2.54954903e-04,\n", - " -7.82184497e-02, 1.87434915e-03, -1.86156485e-04, -9.72093141e-04,\n", - " -2.53336443e-03, -2.67847156e-03, -1.08318349e+00, 8.69432225e+00,\n", - " -2.69025232e+01, 1.07614518e-02, 7.29076528e-03, 1.44466120e-02,\n", - " -2.71072785e+01, 4.32320437e-02, -4.19790173e-03, -2.44417036e-02,\n", - " 1.29081378e-01]),\n", - " array([ 2.36799573e-06, -1.82875429e-02, 3.63592445e-01, -5.37832209e-02,\n", - " 1.57652146e-04, 1.15800618e-04, 9.98552616e-01, 2.67602802e-04,\n", - " -1.07385746e-01, 1.91669099e-03, -1.90397376e-04, -9.96704515e-04,\n", - " -2.38761637e-03, -2.77658183e-03, -1.31838312e+00, 8.61565029e+00,\n", - " -2.89445124e+01, 1.07122246e-02, 5.04555532e-03, 1.26478989e-02,\n", - " -2.91672967e+01, 4.23418359e-02, -4.24089124e-03, -2.46113742e-02,\n", - " 1.45748053e-01]),\n", - " array([ 2.48389392e-06, -1.87976276e-02, 3.72242832e-01, -6.92799817e-02,\n", - " 1.61221939e-04, 1.19238454e-04, 9.97597235e-01, 2.78290214e-04,\n", - " -1.38679850e-01, 1.95815550e-03, -1.94705493e-04, -1.02153166e-03,\n", - " -2.22458161e-03, -2.87210468e-03, -1.56884376e+00, 8.52256634e+00,\n", - " -3.10526769e+01, 1.06501890e-02, 2.58488557e-03, 1.06874115e-02,\n", - " -3.12941034e+01, 4.14645119e-02, -4.30811677e-03, -2.48271496e-02,\n", - " 1.63034766e-01]),\n", - " array([ 2.58214227e-06, -1.93085879e-02, 3.80838703e-01, -8.58429046e-02,\n", - " 1.64490204e-04, 1.21487611e-04, 9.96308664e-01, 2.86858294e-04,\n", - " -1.72166850e-01, 1.99877813e-03, -1.99108703e-04, -1.04662799e-03,\n", - " -2.04364565e-03, -2.96345161e-03, -1.83434123e+00, 8.41380264e+00,\n", - " -3.32263249e+01, 1.05750342e-02, -9.29667526e-05, 8.56807998e-03,\n", - " -3.34870006e+01, 4.06226251e-02, -4.40321007e-03, -2.50963285e-02,\n", - " 1.80935957e-01]),\n", - " array([ 2.66033805e-06, -1.98229037e-02, 3.89376251e-01, -1.03495287e-01,\n", - " 1.67405928e-04, 1.22448032e-04, 9.94629922e-01, 2.93154184e-04,\n", - " -2.07911892e-01, 2.03861971e-03, -2.03638648e-04, -1.07205447e-03,\n", - " -1.84420182e-03, -3.04875112e-03, -2.11449340e+00, 8.28799309e+00,\n", - " -3.54645178e+01, 1.04869446e-02, -2.98521098e-03, 6.29589013e-03,\n", - " -3.57450416e+01, 3.98415860e-02, -4.52994481e-03, -2.54264755e-02,\n", - " 1.99443835e-01]),\n", - " array([ 2.71612255e-06, -2.03434377e-02, 3.97852220e-01, -1.22257343e-01,\n", - " 1.69914345e-04, 1.22024335e-04, 9.92498412e-01, 2.97034269e-04,\n", - " -2.45978902e-01, 2.07776934e-03, -2.08330836e-04, -1.09787979e-03,\n", - " -1.62565363e-03, -3.12584477e-03, -2.40873811e+00, 8.14368098e+00,\n", - " -3.77660503e+01, 1.03866203e-02, -6.08374777e-03, 3.88008490e-03,\n", - " -3.80670102e+01, 3.91496311e-02, -4.69218789e-03, -2.58253222e-02,\n", - " 2.18548184e-01]),\n", - " array([ 2.74721637e-06, -2.08734111e-02, 4.06263976e-01, -1.42145597e-01,\n", - " 1.71957652e-04, 1.20129028e-04, 9.89845738e-01, 2.98367539e-04,\n", - " -2.86430302e-01, 2.11634704e-03, -2.13224671e-04, -1.12418043e-03,\n", - " -1.38741746e-03, -3.19229461e-03, -2.71630954e+00, 7.97933011e+00,\n", - " -4.01294291e+01, 1.02752355e-02, -9.37440632e-03, 1.33326989e-03,\n", - " -4.04513998e+01, 3.85776969e-02, -4.89383515e-03, -2.63006377e-02,\n", - " 2.38236175e-01]),\n", - " array([ 2.75145833e-06, -2.14163656e-02, 4.14609598e-01, -1.63172216e-01,\n", - " 1.73475992e-04, 1.16686095e-04, 9.86597580e-01, 2.97038952e-04,\n", - " -3.29326693e-01, 2.15450622e-03, -2.18363401e-04, -1.15104049e-03,\n", - " -1.12892530e-03, -3.24540469e-03, -3.03621329e+00, 7.79333985e+00,\n", - " -4.25528509e+01, 1.01543112e-02, -1.28362430e-02, -1.32858645e-03,\n", - " -4.28963908e+01, 3.81591762e-02, -5.13872944e-03, -2.68600616e-02,\n", - " 2.58492160e-01]),\n", - " array([ 2.72684779e-06, -2.19761060e-02, 4.22887951e-01, -1.85344283e-01,\n", - " 1.74408707e-04, 1.11634881e-04, 9.82673625e-01, 2.92952695e-04,\n", - " -3.74726521e-01, 2.19243575e-03, -2.23793959e-04, -1.17855139e-03,\n", - " -8.49627825e-04, -3.28225896e-03, -3.36720071e+00, 7.58406458e+00,\n", - " -4.50341798e+01, 1.00254795e-02, -1.64409344e-02, -4.08625729e-03,\n", - " -4.53998282e+01, 3.79295367e-02, -5.43055859e-03, -2.75108975e-02,\n", - " 2.79297471e-01]),\n", - " array([ 2.67159009e-06, -2.25566243e-02, 4.31098780e-01, -2.08663002e-01,\n", - " 1.74695874e-04, 1.04934219e-04, 9.77987582e-01, 2.86035239e-04,\n", - " -4.22685720e-01, 2.23036152e-03, -2.29566691e-04, -1.20681125e-03,\n", - " -5.48997619e-04, -3.29977810e-03, -3.70774274e+00, 7.34983804e+00,\n", - " -4.75709252e+01, 9.89011229e-03, -2.01523003e-02, -6.91745557e-03,\n", - " -4.79591989e+01, 3.79257728e-02, -5.77273153e-03, -2.82598598e-02,\n", - " 3.00630206e-01]),\n", - " array([ 2.58414514e-06, -2.31620010e-02, 4.39242777e-01, -2.33122846e-01,\n", - " 1.74280073e-04, 9.65667145e-05, 9.72447273e-01, 2.76238139e-04,\n", - " -4.73257328e-01, 2.26854718e-03, -2.35734921e-04, -1.23592402e-03,\n", - " -2.26532596e-04, -3.29479671e-03, -4.05600415e+00, 7.08900314e+00,\n", - " -5.01602185e+01, 9.74879113e-03, -2.39259962e-02, -9.79710071e-03,\n", - " -5.05716082e+01, 3.81856568e-02, -6.16823069e-03, -2.91127719e-02,\n", - " 3.22465023e-01]),\n", - " array([ 2.46327874e-06, -2.37962837e-02, 4.47321652e-01, -2.58710657e-01,\n", - " 1.73108361e-04, 8.65430820e-05, 9.65954843e-01, 2.63540527e-04,\n", - " -5.26491085e-01, 2.30729393e-03, -2.42354361e-04, -1.26599823e-03,\n", - " 1.18240330e-04, -3.26416222e-03, -4.40981893e+00, 6.79994754e+00,\n", - " -5.27987902e+01, 9.60059698e-03, -2.77094185e-02, -1.26976116e-02,\n", - " -5.32337571e+01, 3.87467453e-02, -6.61943991e-03, -3.00742139e-02,\n", - " 3.44772926e-01]),\n", - " array([ 2.30811699e-06, -2.44633416e-02, 4.55338185e-01, -2.85404690e-01,\n", - " 1.71134366e-04, 7.49064382e-05, 9.58407079e-01, 2.47951364e-04,\n", - " -5.82433005e-01, 2.34693900e-03, -2.49482309e-04, -1.29714535e-03,\n", - " 4.85761386e-04, -3.20485564e-03, -4.76666778e+00, 6.48114539e+00,\n", - " -5.54829477e+01, 9.44220971e-03, -3.14418713e-02, -1.55891628e-02,\n", - " -5.59419195e+01, 3.96450779e-02, -7.12794765e-03, -3.11471176e-02,\n", - " 3.67521056e-01]),\n", - " array([ 2.11820378e-06, -2.51666968e-02, 4.63296253e-01, -3.13173631e-01,\n", - " 1.68320437e-04, 6.17364110e-05, 9.49695870e-01, 2.29511548e-04,\n", - " -6.41124924e-01, 2.38785250e-03, -2.57176636e-04, -1.32947766e-03,\n", - " 8.76433870e-04, -3.11413326e-03, -5.12365911e+00, 6.13120542e+00,\n", - " -5.82085527e+01, 9.26682307e-03, -3.50550496e-02, -1.84398158e-02,\n", - " -5.86919195e+01, 4.09134903e-02, -7.69432685e-03, -3.23323132e-02,\n", - " 3.90672484e-01]),\n", - " array([ 1.89356220e-06, -2.59093348e-02, 4.71200826e-01, -3.41975588e-01,\n", - " 1.64639718e-04, 4.71529270e-05, 9.39708821e-01, 2.08296135e-04,\n", - " -7.02604034e-01, 2.43043193e-03, -2.65494530e-04, -1.36310570e-03,\n", - " 1.29061988e-03, -2.98968732e-03, -5.47751473e+00, 5.74892543e+00,\n", - " -6.09709999e+01, 9.06291039e-03, -3.84739031e-02, -2.12154131e-02,\n", - " -6.14791100e+01, 4.25794338e-02, -8.31789412e-03, -3.36280312e-02,\n", - " 4.14186008e-01]),\n", - " array([ 1.63476024e-06, -2.66934981e-02, 4.79057934e-01, -3.71757081e-01,\n", - " 1.60078076e-04, 3.13195014e-05, 9.28330031e-01, 1.84417039e-04,\n", - " -7.66902386e-01, 2.47509410e-03, -2.74490983e-04, -1.39813507e-03,\n", - " 1.72863584e-03, -2.82982210e-03, -5.82456207e+00, 5.33335284e+00,\n", - " -6.37651968e+01, 8.81292329e-03, -4.16179569e-02, -2.38790962e-02,\n", - " -6.42983523e+01, 4.46621728e-02, -8.99645325e-03, -3.50293716e-02,\n", - " 4.38015962e-01]),\n", - " array([ 1.34298156e-06, -2.75204686e-02, 4.86874579e-01, -4.02452045e-01,\n", - " 1.54635772e-04, 1.44458065e-05, 9.15441056e-01, 1.58026741e-04,\n", - " -8.34046382e-01, 2.52226332e-03, -2.84217013e-04, -1.43466282e-03,\n", - " 2.19074787e-03, -2.63364063e-03, -6.16073444e+00, 4.88385095e+00,\n", - " -6.65855442e+01, 8.49207772e-03, -4.44031771e-02, -2.63902982e-02,\n", - " -6.71439959e+01, 4.71692160e-02, -9.72603030e-03, -3.65277530e-02,\n", - " 4.62112032e-01]),\n", - " array([ 1.02010097e-06, -2.83903484e-02, 4.94658605e-01, -4.33980884e-01,\n", - " 1.48328854e-04, -3.21078248e-06, 9.00922067e-01, 1.29323661e-04,\n", - " -9.04056243e-01, 2.57235517e-03, -2.94717623e-04, -1.47277318e-03,\n", - " 2.67716695e-03, -2.40123554e-03, -6.48158143e+00, 4.40016996e+00,\n", - " -6.94259178e+01, 8.06748678e-03, -4.67444798e-02, -2.87030794e-02,\n", - " -7.00098610e+01, 5.00918525e-02, -1.05006100e-02, -3.81103643e-02,\n", - " 4.86419079e-01]),\n", - " array([ 6.68762868e-07, -2.93018500e-02, 5.02418504e-01, -4.66249590e-01,\n", - " 1.41190309e-04, -2.13450921e-05, 8.84653209e-01, 9.85599075e-05,\n", - " -9.76945465e-01, 2.62575492e-03, -3.06029510e-04, -1.51253283e-03,\n", - " 3.18804393e-03, -2.13387558e-03, -6.78229130e+00, 3.88252150e+00,\n", - " -7.22796527e+01, 7.49803970e-03, -4.85589855e-02, -3.07637538e-02,\n", - " -7.28892217e+01, 5.33997530e-02, -1.13118869e-02, -3.97596463e-02,\n", - " 5.10876980e-01]),\n", - " array([ 2.92457829e-07, -3.02521088e-02, 5.10163167e-01, -4.99148973e-01,\n", - " 1.33271131e-04, -3.96061171e-05, 8.66516176e-01, 6.60519527e-05,\n", - " -1.05272026e+00, 2.68278973e-03, -3.18178556e-04, -1.55398567e-03,\n", - " 3.72346441e-03, -1.83417735e-03, -7.05772734e+00, 3.33165494e+00,\n", - " -7.51395272e+01, 6.73558953e-03, -4.97701042e-02, -3.25079547e-02,\n", - " -7.57747904e+01, 5.70348060e-02, -1.21490459e-02, -4.14528362e-02,\n", - " 5.35420478e-01]),\n", - " array([-1.04412232e-07, -3.12365363e-02, 5.17901571e-01, -5.32554034e-01,\n", - " 1.24641611e-04, -5.76018973e-05, 8.46395996e-01, 3.21942888e-05,\n", - " -1.13137896e+00, 2.74369451e-03, -3.31177149e-04, -1.59714728e-03,\n", - " 4.28344345e-03, -1.50624802e-03, -7.30247998e+00, 2.74893338e+00,\n", - " -7.79977499e+01, 5.72815239e-03, -5.03124796e-02, -3.38576640e-02,\n", - " -7.86587047e+01, 6.09047772e-02, -1.29985923e-02, -4.31616176e-02,\n", - " 5.59979044e-01]),\n", - " array([-5.16496610e-07, -3.22487282e-02, 5.25642414e-01, -5.66323521e-01,\n", - " 1.15393209e-04, -7.49084038e-05, 8.24183020e-01, -2.52504184e-06,\n", - " -1.21291147e+00, 2.80857256e-03, -3.45021399e-04, -1.64199921e-03,\n", - " 4.86792020e-03, -1.15578030e-03, -7.51093642e+00, 2.13640639e+00,\n", - " -8.08459467e+01, 4.42583385e-03, -5.01377014e-02, -3.47193306e-02,\n", - " -8.15325138e+01, 6.48780543e-02, -1.38442507e-02, -4.48519224e-02,\n", - " 5.84476750e-01]),\n", - " array([-9.37509930e-07, -3.32804495e-02, 5.33393704e-01, -6.00299714e-01,\n", - " 1.05641372e-04, -9.10836796e-05, 7.99775114e-01, -3.75100176e-05,\n", - " -1.29729864e+00, 2.87735420e-03, -3.59688355e-04, -1.68848314e-03,\n", - " 5.47675235e-03, -7.90073423e-04, -7.67736881e+00, 1.49687650e+00,\n", - " -8.36751494e+01, 2.78990338e-03, -4.92204812e-02, -3.49849757e-02,\n", - " -8.43871674e+01, 6.87816373e-02, -1.46669560e-02, -4.64839351e-02,\n", - " 6.08832149e-01]),\n", - " array([-1.36032823e-06, -3.43217105e-02, 5.41162309e-01, -6.34308485e-01,\n", - " 9.55292506e-05, -1.05688286e-04, 7.73080025e-01, -7.20488406e-05,\n", - " -1.38451164e+00, 2.94975956e-03, -3.75133315e-04, -1.73649550e-03,\n", - " 6.10971051e-03, -4.17945009e-04, -7.79604186e+00, 8.33955516e-01,\n", - " -8.64757838e+01, 8.04610682e-04, -4.75646687e-02, -3.45388230e-02,\n", - " -8.72130034e+01, 7.24053667e-02, -1.54449599e-02, -4.80123545e-02,\n", - " 6.32958158e-01]),\n", - " array([-1.77719786e-06, -3.53609512e-02, 5.48953507e-01, -6.68159670e-01,\n", - " 8.52315760e-05, -1.18312265e-04, 7.44017899e-01, -1.05320702e-04,\n", - " -1.47451138e+00, 3.02527506e-03, -3.91287390e-04, -1.78588246e-03,\n", - " 6.76647245e-03, -4.94907612e-05, -7.86133975e+00, 1.52106714e-01,\n", - " -8.92376576e+01, -1.51014154e-03, -4.52081043e-02, -3.32718614e-02,\n", - " -8.99997363e+01, 7.55154949e-02, -1.61540752e-02, -4.93869621e-02,\n", - " 6.56761938e-01]),\n", - " array([-2.18007661e-06, -3.63853424e-02, 5.56770543e-01, -7.01647807e-01,\n", - " 7.49568449e-05, -1.28607074e-04, 7.12523918e-01, -1.36425654e-04,\n", - " -1.56724782e+00, 3.10315420e-03, -4.08055473e-04, -1.83643600e-03,\n", - " 7.44661721e-03, 3.04351778e-04, -7.86791156e+00, -5.43331645e-01,\n", - " -9.19499477e+01, -4.08900634e-03, -4.22249823e-02, -3.11049522e-02,\n", - " -9.27364435e+01, 7.78791381e-02, -1.67680821e-02, -5.05535416e-02,\n", - " 6.80144760e-01]),\n", - " array([-2.56109807e-06, -3.73812081e-02, 5.64614241e-01, -7.34553278e-01,\n", - " 6.49450141e-05, -1.36318462e-04, 6.78551000e-01, -1.64442813e-04,\n", - " -1.66265937e+00, 3.18245145e-03, -4.25314789e-04, -1.88789118e-03,\n", - " 8.14961906e-03, 6.32460724e-04, -7.81083317e+00, -1.24614589e+00,\n", - " -9.46011845e+01, -6.81927116e-03, -3.87243887e-02, -2.80171586e-02,\n", - " -9.54115498e+01, 7.92972568e-02, -1.72593167e-02, -5.14551811e-02,\n", - " 7.03001851e-01]),\n", - " array([-2.91310899e-06, -3.83345639e-02, 5.72482696e-01, -7.66643889e-01,\n", - " 5.54578545e-05, -1.41313845e-04, 6.42072523e-01, -1.88513800e-04,\n", - " -1.76067218e+00, 3.26208990e-03, -4.42914248e-04, -1.93992515e-03,\n", - " 8.87484126e-03, 9.24387197e-04, -7.68578256e+00, -1.94927413e+00,\n", - " -9.71792339e+01, -9.55094707e-03, -3.48442312e-02, -2.40709877e-02,\n", - " -9.80128094e+01, 7.96384483e-02, -1.75994584e-02, -5.20339692e-02,\n", - " 7.25222201e-01]),\n", - " array([-3.23018941e-06, -3.92317542e-02, 5.80371082e-01, -7.97676923e-01,\n", - " 4.67606743e-05, -1.43597032e-04, 6.03084989e-01, -2.07937191e-04,\n", - " -1.86119947e+00, 3.34095193e-03, -4.60674772e-04, -1.99215822e-03,\n", - " 9.62152960e-03, 1.17131788e-03, -7.48922405e+00, -2.64486508e+00,\n", - " -9.96712752e+01, -1.21191375e-02, -3.07409551e-02, -1.94233903e-02,\n", - " -1.00527284e+02, 7.88620226e-02, -1.77605238e-02, -5.22330731e-02,\n", - " 7.46688339e-01]),\n", - " array([-3.50805143e-06, -4.00601624e-02, 5.88271620e-01, -8.27401682e-01,\n", - " 3.90971030e-05, -1.43305305e-04, 5.61610572e-01, -2.22251479e-04,\n", - " -1.96414078e+00, 3.41797234e-03, -4.78390828e-04, -2.04415738e-03,\n", - " 1.03888057e-02, 1.36697424e-03, -7.21859567e+00, -3.32437200e+00,\n", - " -1.02063776e+02, -1.43732470e-02, -2.65768751e-02, -1.43142882e-02,\n", - " -1.02941315e+02, 7.70204158e-02, -1.77160567e-02, -5.19991568e-02,\n", - " 7.67276054e-01]),\n", - " array([-3.74423791e-06, -4.08089544e-02, 5.96173721e-01, -8.55562537e-01,\n", - " 3.26616677e-05, -1.40688598e-04, 5.17699454e-01, -2.31284833e-04,\n", - " -2.06938128e+00, 3.49221127e-03, -4.95833310e-04, -2.09544245e-03,\n", - " 1.11756598e-02, 1.50824890e-03, -6.87249248e+00, -3.97868413e+00,\n", - " -1.04342459e+02, -1.62035067e-02, -2.25078565e-02, -9.03335384e-03,\n", - " -1.05240494e+02, 7.42389332e-02, -1.74424816e-02, -5.12850687e-02,\n", - " 7.86854100e-01]),\n", - " array([-3.93810005e-06, -4.14698050e-02, 6.04064325e-01, -8.81902472e-01,\n", - " 2.75762026e-05, -1.36075749e-04, 4.71431873e-01, -2.35160543e-04,\n", - " -2.17679090e+00, 3.56289215e-03, -5.12753867e-04, -2.14549514e-03,\n", - " 1.19809436e-02, 1.59542463e-03, -6.45083762e+00, -4.59829671e+00,\n", - " -1.06492270e+02, -1.75560461e-02, -1.86738047e-02, -3.87571071e-03,\n", - " -1.07409628e+02, 7.06808775e-02, -1.69205571e-02, -5.00526912e-02,\n", - " 8.05283853e-01]),\n", - " array([-4.09059207e-06, -4.20375534e-02, 6.11928442e-01, -9.06167117e-01,\n", - " 2.38750133e-05, -1.29835680e-04, 4.22919778e-01, -2.34261845e-04,\n", - " -2.28622360e+00, 3.62940378e-03, -5.28890714e-04, -2.19377096e-03,\n", - " 1.28033626e-02, 1.63193088e-03, -5.95503156e+00, -5.17351894e+00,\n", - " -1.08497336e+02, -1.84331210e-02, -1.51929857e-02, 8.98698237e-04,\n", - " -1.09432697e+02, 6.65116322e-02, -1.61368469e-02, -4.82758164e-02,\n", - " 8.22418968e-01]),\n", - " array([-4.20395487e-06, -4.25107255e-02, 6.19749879e-01, -9.28109226e-01,\n", - " 2.15010856e-05, -1.22341022e-04, 3.72308002e-01, -2.29170389e-04,\n", - " -2.39751641e+00, 3.69127692e-03, -5.43975821e-04, -2.23971383e-03,\n", - " 1.36414676e-02, 1.62371330e-03, -5.38806976e+00, -5.69471717e+00,\n", - " -1.10340924e+02, -1.88813879e-02, -1.21594047e-02, 5.09145656e-03,\n", - " -1.11292813e+02, 6.18731311e-02, -1.50851069e-02, -4.59428774e-02,\n", - " 8.38105018e-01]),\n", - " array([-4.28136116e-06, -4.28918674e-02, 6.27512114e-01, -9.47493548e-01,\n", - " 2.03131559e-05, -1.13938939e-04, 3.19774862e-01, -2.20594838e-04,\n", - " -2.51048859e+00, 3.74815005e-03, -5.57743307e-04, -2.28277317e-03,\n", - " 1.44936467e-02, 1.57836712e-03, -4.75461847e+00, -6.15258845e+00,\n", - " -1.12005399e+02, -1.89745271e-02, -9.64125415e-03, 8.57555094e-03,\n", - " -1.12972177e+02, 5.68731301e-02, -1.37674859e-02, -4.30593413e-02,\n", - " 8.52179122e-01]),\n", - " array([-4.32657484e-06, -4.31876414e-02, 6.35199275e-01, -9.64102018e-01,\n", - " 2.01022124e-05, -1.04930895e-04, 2.65532085e-01, -2.09301342e-04,\n", - " -2.62494062e+00, 3.79973714e-03, -5.69938744e-04, -2.32242273e-03,\n", - " 1.53581163e-02, 1.50419764e-03, -4.06103882e+00, -6.53845700e+00,\n", - " -1.13472174e+02, -1.87961370e-02, -7.67823177e-03, 1.12934960e-02,\n", - " -1.14452032e+02, 5.15870902e-02, -1.21954371e-02, -3.96495550e-02,\n", - " 8.64469594e-01]),\n", - " array([-4.34365628e-06, -4.34086529e-02, 6.42797145e-01, -9.77739169e-01,\n", - " 2.06159762e-05, -9.55611101e-05, 2.09823991e-01, -1.96050441e-04,\n", - " -2.74065324e+00, 3.84580453e-03, -5.80328990e-04, -2.35818057e-03,\n", - " 1.62329119e-02, 1.40934201e-03, -3.31535078e+00, -6.84458371e+00,\n", - " -1.14721674e+02, -1.84263238e-02, -6.27611667e-03, 1.32509011e-02,\n", - " -1.15712621e+02, 4.60673939e-02, -1.03902462e-02, -3.57578411e-02,\n", - " 8.74795595e-01]),\n", - " array([-4.33673355e-06, -4.35689955e-02, 6.50294124e-01, -9.88237659e-01,\n", - " 2.15904661e-05, -8.60128985e-05, 1.52925868e-01, -1.81538926e-04,\n", - " -2.85738640e+00, 3.88615941e-03, -5.88712086e-04, -2.38962923e-03,\n", - " 1.71158787e-02, 1.30104939e-03, -2.52712987e+00, -7.06447653e+00,\n", - " -1.15733297e+02, -1.79328587e-02, -5.39789940e-03, 1.45115150e-02,\n", - " -1.16733152e+02, 4.03548851e-02, -8.38309619e-03, -3.14486606e-02,\n", - " 8.82966836e-01]),\n", - " array([-4.30985972e-06, -4.36855291e-02, 6.57682059e-01, -9.95463758e-01,\n", - " 2.27882368e-05, -7.64125552e-05, 9.51414775e-02, -1.66341686e-04,\n", - " -2.97487816e+00, 3.92064899e-03, -5.94926695e-04, -2.41643494e-03,\n", - " 1.80046621e-02, 1.18519253e-03, -1.70733259e+00, -7.19318742e+00,\n", - " -1.16485383e+02, -1.73662096e-02, -4.95158853e-03, 1.51972399e-02,\n", - " -1.17491763e+02, 3.44895753e-02, -6.21460845e-03, -2.68057069e-02,\n", - " 8.88783329e-01]),\n", - " array([-4.26698224e-06, -4.37769326e-02, 6.64956858e-01, -9.99322659e-01,\n", - " 2.40429457e-05, -6.68413124e-05, 3.67996958e-02, -1.50847332e-04,\n", - " -3.09284366e+00, 3.94916826e-03, -5.98860524e-04, -2.43836480e-03,\n", - " 1.88966973e-02, 1.06607508e-03, -8.68049836e-01, -7.22758051e+00,\n", - " -1.16955188e+02, -1.67571742e-02, -4.77540663e-03, 1.54943535e-02,\n", - " -1.17965502e+02, 2.85192713e-02, -3.93382896e-03, -2.19298571e-02,\n", - " 8.92035210e-01]),\n", - " array([-4.21205736e-06, -4.38625944e-02, 6.72118839e-01, -9.99763445e-01,\n", - " 2.53094856e-05, -5.73567391e-05, -2.17497163e-02, -1.35181557e-04,\n", - " -3.21097397e+00, 3.97167442e-03, -6.00457189e-04, -2.45530078e-03,\n", - " 1.97891999e-02, 9.46595982e-04, -2.21913891e-02, -7.16655492e+00,\n", - " -1.17118877e+02, -1.61158154e-02, -4.62145282e-03, 1.56657753e-02,\n", - " -1.18130313e+02, 2.25061629e-02, -1.59666571e-03, -1.69359895e-02,\n", - " 8.92502643e-01]),\n", - " array([-4.14934291e-06, -4.39614301e-02, 6.79172760e-01, -9.96783523e-01,\n", - " 2.67180988e-05, -4.80255252e-05, -8.01411524e-02, -1.19113074e-04,\n", - " -3.32893500e+00, 3.98820642e-03, -5.99721015e-04, -2.46724955e-03,\n", - " 2.06791557e-02, 8.28823375e-04, 8.16890547e-01, -7.01120671e+00,\n", - " -1.16951512e+02, -1.54305277e-02, -4.13914503e-03, 1.60684829e-02,\n", - " -1.17961029e+02, 1.65319989e-02, 7.36174750e-04, -1.19487673e-02,\n", - " 8.89955800e-01]),\n", - " array([-4.08308133e-06, -4.40904964e-02, 6.86127495e-01, -9.90428888e-01,\n", - " 2.83029865e-05, -3.89035646e-05, -1.38023965e-01, -1.02582057e-04,\n", - " -3.44641742e+00, 3.99897733e-03, -5.96717773e-04, -2.47434382e-03,\n", - " 2.15637767e-02, 7.15086849e-04, 1.63577509e+00, -6.76490756e+00,\n", - " -1.16477637e+02, -1.47441961e-02, -3.52463857e-03, 1.65310168e-02,\n", - " -1.17482421e+02, 1.07709033e-02, 3.00324163e-03, -7.09426793e-03,\n", - " 8.84620956e-01]),\n", - " array([-4.01708631e-06, -4.42639786e-02, 6.92995434e-01, -9.80789804e-01,\n", - " 3.00304922e-05, -3.00253591e-05, -1.95067576e-01, -8.56358750e-05,\n", - " -3.56313556e+00, 4.00434058e-03, -5.91569413e-04, -2.47683174e-03,\n", - " 2.24404910e-02, 6.07667596e-04, 2.42182121e+00, -6.43320891e+00,\n", - " -1.15720688e+02, -1.40921999e-02, -2.92326775e-03, 1.69461821e-02,\n", - " -1.16718138e+02, 5.36324983e-03, 5.14836030e-03, -2.48791916e-03,\n", - " 8.76714289e-01]),\n", - " array([-3.95448664e-06, -4.44923969e-02, 6.99791645e-01, -9.67995951e-01,\n", - " 3.18269323e-05, -2.14014011e-05, -2.50965810e-01, -6.83742883e-05,\n", - " -3.67882633e+00, 4.00475935e-03, -5.84446725e-04, -2.47506199e-03,\n", - " 2.33069333e-02, 5.08292414e-04, 3.16355512e+00, -6.02356193e+00,\n", - " -1.14703038e+02, -1.34992506e-02, -2.43029875e-03, 1.72615867e-02,\n", - " -1.15690764e+02, 4.18774090e-04, 7.12268717e-03, 1.76975150e-03,\n", - " 8.66442318e-01]),\n", - " array([-3.89761083e-06, -4.47820832e-02, 7.06532869e-01, -9.52211196e-01,\n", - " 3.36035247e-05, -1.30218709e-05, -3.05440399e-01, -5.09041444e-05,\n", - " -3.79324819e+00, 4.00077925e-03, -5.75560500e-04, -2.46946573e-03,\n", - " 2.41609356e-02, 4.17915877e-04, 3.85098466e+00, -5.54497962e+00,\n", - " -1.13446058e+02, -1.29782391e-02, -2.09451008e-03, 1.74701439e-02,\n", - " -1.14421864e+02, -3.98010029e-03, 8.88622504e-03, 5.59625774e-03,\n", - " 8.54002340e-01]),\n", - " array([-3.84798528e-06, -4.51349532e-02, 7.13236458e-01, -9.33628141e-01,\n", - " 3.52767258e-05, -4.86491048e-06, -3.58243624e-01, -3.33030234e-05,\n", - " -3.90618023e+00, 3.99300412e-03, -5.65151741e-04, -2.46053663e-03,\n", - " 2.50005185e-02, 3.36745633e-04, 4.47583153e+00, -5.00766141e+00,\n", - " -1.11970157e+02, -1.25302479e-02, -1.92373495e-03, 1.76011210e-02,\n", - " -1.12932039e+02, -7.77513305e-03, 1.04087595e-02, 8.92909625e-03,\n", - " 8.39582870e-01]),\n", - " array([-3.80641333e-06, -4.55485697e-02, 7.19919319e-01, -9.12462608e-01,\n", - " 3.67829871e-05, 3.09221431e-06, -4.09160100e-01, -1.55913162e-05,\n", - " -4.01742120e+00, 3.98207448e-03, -5.53481519e-04, -2.44881014e-03,\n", - " 2.58238825e-02, 2.64441700e-04, 5.03167739e+00, -4.42260064e+00,\n", - " -1.10294842e+02, -1.21450934e-02, -1.89166794e-03, 1.77117072e-02,\n", - " -1.11240972e+02, -1.09296324e-02, 1.16702222e-02, 1.17264977e-02,\n", - " 8.23364045e-01]),\n", - " array([-3.77310120e-06, -4.60164680e-02, 7.26596945e-01, -8.88948198e-01,\n", - " 3.80874618e-05, 1.08607031e-05, -4.58007751e-01, 2.28724103e-06,\n", - " -4.12678868e+00, 3.96864787e-03, -5.40820993e-04, -2.43484306e-03,\n", - " 2.66294005e-02, 2.00410891e-04, 5.51402530e+00, -3.80119467e+00,\n", - " -1.08438752e+02, -1.18020687e-02, -1.94554036e-03, 1.78785572e-02,\n", - " -1.09367479e+02, -1.34266138e-02, 1.26605255e-02, 1.39670787e-02,\n", - " 8.05518002e-01]),\n", - " array([-3.74779762e-06, -4.65286979e-02, 7.33282612e-01, -8.63331033e-01,\n", - " 3.91865837e-05, 1.84282522e-05, -5.04638014e-01, 2.04757234e-05,\n", - " -4.23411822e+00, 3.95337982e-03, -5.27442050e-04, -2.41919451e-03,\n", - " 2.74156098e-02, 1.44118299e-04, 5.92028211e+00, -3.15487493e+00,\n", - " -1.06419707e+02, -1.14709273e-02, -2.01455743e-03, 1.81884824e-02,\n", - " -1.07329542e+02, -1.52680495e-02, 1.33789434e-02, 1.56485493e-02,\n", - " 7.86209211e-01]),\n", - " array([-3.72991756e-06, -4.70725234e-02, 7.39986754e-01, -8.35864810e-01,\n", - " 4.01048576e-05, 2.57493653e-05, -5.48935348e-01, 3.92033129e-05,\n", - " -4.33926257e+00, 3.93690448e-03, -5.13608918e-04, -2.40240883e-03,\n", - " 2.81812045e-02, 9.53462001e-05, 6.24967137e+00, -2.49477151e+00,\n", - " -1.04254736e+02, -1.11134991e-02, -2.01912990e-03, 1.87275895e-02,\n", - " -1.05144349e+02, -1.64753378e-02, 1.38331314e-02, 1.67856744e-02,\n", - " 7.65594754e-01]),\n", - " array([-3.71862661e-06, -4.76332154e-02, 7.46716566e-01, -8.06806220e-01,\n", - " 4.08867509e-05, 3.27398928e-05, -5.90816148e-01, 5.87722184e-05,\n", - " -4.44209089e+00, 3.91981381e-03, -4.99571033e-04, -2.38500113e-03,\n", - " 2.89250291e-02, 5.43452536e-05, 6.50308855e+00, -1.83142304e+00,\n", - " -1.01960108e+02, -1.06865515e-02, -1.88080642e-03, 1.95689054e-02,\n", - " -1.02828318e+02, -1.70906744e-02, 1.40378853e-02, 1.74077066e-02,\n", - " 7.43824560e-01]),\n", - " array([-3.71287479e-06, -4.81948760e-02, 7.53475810e-01, -7.76410817e-01,\n", - " 4.15853044e-05, 3.92775526e-05, -6.30227134e-01, 7.95320392e-05,\n", - " -4.54248801e+00, 3.90263551e-03, -4.85557293e-04, -2.36744562e-03,\n", - " 2.96460707e-02, 2.18443096e-05, 6.68291188e+00, -1.17453935e+00,\n", - " -9.95513514e+01, -1.01463820e-02, -1.53238655e-03, 2.07598209e-02,\n", - " -1.00397122e+02, -1.71782944e-02, 1.40137403e-02, 1.75555078e-02,\n", - " 7.21041590e-01]),\n", - " array([-3.71138383e-06, -4.87412392e-02, 7.60264835e-01, -7.44929371e-01,\n", - " 4.22497710e-05, 4.52093968e-05, -6.67143334e-01, 1.01844098e-04,\n", - " -4.64035371e+00, 3.88581158e-03, -4.71771791e-04, -2.35016706e-03,\n", - " 3.03434526e-02, -1.08589298e-06, 6.79278284e+00, -5.32820312e-01,\n", - " -9.70432722e+01, -9.45502084e-03, -9.27096877e-04, 2.23120588e-02,\n", - " -9.78657027e+01, -1.68239316e-02, 1.37855017e-02, 1.72785631e-02,\n", - " 6.97381980e-01]),\n", - " array([-3.71260904e-06, -4.92564009e-02, 7.67080766e-01, -7.12604732e-01,\n", - " 4.29148909e-05, 5.03657416e-05, -7.01565743e-01, 1.26041458e-04,\n", - " -4.73560200e+00, 3.86968072e-03, -4.58391000e-04, -2.33353500e-03,\n", - " 3.10164278e-02, -1.32855070e-05, 6.83736964e+00, 8.61687632e-02,\n", - " -9.44499641e+01, -8.58695463e-03, -4.52745123e-05, 2.41973603e-02,\n", - " -9.52482845e+01, -1.61308652e-02, 1.33807913e-02, 1.66320606e-02,\n", - " 6.72975153e-01]),\n", - " array([-3.71470724e-06, -4.97254464e-02, 7.73917832e-01, -6.79669209e-01,\n", - " 4.35939744e-05, 5.45783597e-05, -7.33518753e-01, 1.52392361e-04,\n", - " -4.82816038e+00, 3.85446870e-03, -4.45562318e-04, -2.31786082e-03,\n", - " 3.16643717e-02, -1.38137661e-05, 6.82212589e+00, 6.76067707e-01,\n", - " -9.17848176e+01, -7.53447515e-03, 1.10288910e-03, 2.63509023e-02,\n", - " -9.25583812e+01, -1.52120131e-02, 1.28286820e-02, 1.56741776e-02,\n", - " 6.47943905e-01]),\n", - " array([-3.71554053e-06, -5.01349529e-02, 7.80767804e-01, -6.46342458e-01,\n", - " 4.42768181e-05, 5.76994761e-05, -7.63047457e-01, 1.81074200e-04,\n", - " -4.91796918e+00, 3.84028939e-03, -4.33403840e-04, -2.30339714e-03,\n", - " 3.22867762e-02, -2.23523729e-06, 6.75305528e+00, 1.23174293e+00,\n", - " -8.90605259e+01, -6.30978760e-03, 2.47918777e-03, 2.86818392e-02,\n", - " -8.98088025e+01, -1.41793138e-02, 1.21584780e-02, 1.44636762e-02,\n", - " 6.22404466e-01]),\n", - " array([-3.71273225e-06, -5.04733593e-02, 7.87620483e-01, -6.12829861e-01,\n", - " 4.49320822e-05, 5.96179564e-05, -7.90214879e-01, 2.12161942e-04,\n", - " -5.00498084e+00, 3.82715632e-03, -4.22005155e-04, -2.29033927e-03,\n", - " 3.28832427e-02, 2.11851854e-05, 6.63649074e+00, 1.74926605e+00,\n", - " -8.62890895e+01, -4.94306379e-03, 4.02326940e-03, 3.10877419e-02,\n", - " -8.70116595e+01, -1.31330677e-02, 1.13986846e-02, 1.30578716e-02,\n", - " 5.96466566e-01]),\n", - " array([-3.70377286e-06, -5.07312030e-02, 7.94464223e-01, -5.79321359e-01,\n", - " 4.55127134e-05, 6.02700852e-05, -8.15099231e-01, 2.45630626e-04,\n", - " -5.08915921e+00, 3.81500232e-03, -4.11428966e-04, -2.27882826e-03,\n", - " 3.34534762e-02, 5.54175479e-05, 6.47889471e+00, 2.22585715e+00,\n", - " -8.34818208e+01, -3.47714965e-03, 5.66097815e-03, 3.34686845e-02,\n", - " -8.41783684e+01, -1.21539993e-02, 1.05761888e-02, 1.15110056e-02,\n", - " 5.70233483e-01]),\n", - " array([-3.68615746e-06, -5.09012345e-02, 8.01286450e-01, -5.45990707e-01,\n", - " 4.59626643e-05, 5.96439577e-05, -8.37791228e-01, 2.81368340e-04,\n", - " -5.17047887e+00, 3.80370276e-03, -4.01713312e-04, -2.26895524e-03,\n", - " 3.39972783e-02, 9.87322941e-05, 6.28668489e+00, 2.65980040e+00,\n", - " -8.06493496e+01, -1.96071633e-03, 7.31326013e-03, 3.57377137e-02,\n", - " -8.13196565e+01, -1.12995637e-02, 9.71565440e-03, 9.87302420e-03,\n", - " 5.43802108e-01]),\n", - " array([-3.65753057e-06, -5.09784222e-02, 8.08074144e-01, -5.12995100e-01,\n", - " 4.62234372e-05, 5.77780183e-05, -8.58391532e-01, 3.19194815e-04,\n", - " -5.24892443e+00, 3.79309840e-03, -3.92874194e-04, -2.26076650e-03,\n", - " 3.45145413e-02, 1.48864391e-04, 6.06608792e+00, 3.05033981e+00,\n", - " -7.78016295e+01, -4.41774345e-04, 8.90403936e-03, 3.78264754e-02,\n", - " -7.84455686e+01, -1.06043635e-02, 8.83911770e-03, 8.18874037e-03,\n", - " 5.17263021e-01]),\n", - " array([-3.61581583e-06, -5.09598687e-02, 8.14814277e-01, -4.80475130e-01,\n", - " 4.62395457e-05, 5.47551938e-05, -8.77008349e-01, 3.58881377e-04,\n", - " -5.32448991e+00, 3.78301499e-03, -3.84908433e-04, -2.25426916e-03,\n", - " 3.50052419e-02, 2.03230109e-04, 5.82302179e+00, 3.39756221e+00,\n", - " -7.49479468e+01, 1.03716410e-03, 1.03661424e-02, 3.96865614e-02,\n", - " -7.55654761e+01, -1.00834026e-02, 7.96576134e-03, 6.49734090e-03,\n", - " 4.90700585e-01]),\n", - " array([-3.55931544e-06, -5.08446563e-02, 8.21494192e-01, -4.48555018e-01,\n", - " 4.59625275e-05, 5.06943450e-05, -8.93755219e-01, 4.00169378e-04,\n", - " -5.39717800e+00, 3.77327838e-03, -3.77796597e-04, -2.24943697e-03,\n", - " 3.54694350e-02, 2.59152219e-04, 5.56300624e+00, 3.70227407e+00,\n", - " -7.20969317e+01, 2.44184855e-03, 1.16450170e-02, 4.12880009e-02,\n", - " -7.26880878e+01, -9.73661781e-03, 7.11183607e-03, 4.83219099e-03,\n", - " 4.64193062e-01]),\n", - " array([-3.48677283e-06, -5.06336418e-02, 8.28101908e-01, -4.17343084e-01,\n", - " 4.53535143e-05, 4.57405828e-05, -9.08749001e-01, 4.42785718e-04,\n", - " -5.46699946e+00, 3.76372492e-03, -3.71505895e-04, -2.24621609e-03,\n", - " 3.59072477e-02, 3.14060751e-04, 5.29109946e+00, 3.96587749e+00,\n", - " -6.92565708e+01, 3.74720306e-03, 1.27004464e-02, 4.26163401e-02,\n", - " -6.98214637e+01, -9.55345728e-03, 6.29070190e-03, 3.22088275e-03,\n", - " 4.37812752e-01]),\n", - " array([-3.39739890e-06, -5.03292205e-02, 8.34626367e-01, -3.86932395e-01,\n", - " 4.43845514e-05, 4.00556177e-05, -9.22108084e-01, 4.86455073e-04,\n", - " -5.53397249e+00, 3.75420811e-03, -3.65992935e-04, -2.24453061e-03,\n", - " 3.63188739e-02, 3.65650393e-04, 5.01185848e+00, 4.19025001e+00,\n", - " -6.64342237e+01, 4.93691512e-03, 1.35066842e-02, 4.36693548e-02,\n", - " -6.69730304e+01, -9.51680787e-03, 5.51295994e-03, 1.68547455e-03,\n", - " 4.11626152e-01]),\n", - " array([-3.29086642e-06, -4.99350733e-02, 8.41057600e-01, -3.57401565e-01,\n", - " 4.30389272e-05, 3.38089122e-05, -9.33950812e-01, 5.30909052e-04,\n", - " -5.59812209e+00, 3.74460209e-03, -3.61206285e-04, -2.24428774e-03,\n", - " 3.67045680e-02, 4.11987673e-04, 4.72932025e+00, 4.37763153e+00,\n", - " -6.36366406e+01, 6.00225724e-03, 1.40514759e-02, 4.44539796e-02,\n", - " -6.41495996e+01, -9.60602510e-03, 4.78664992e-03, 2.42870584e-04,\n", - " 3.85694135e-01]),\n", - " array([-3.16727990e-06, -4.94559124e-02, 8.47386849e-01, -3.28815652e-01,\n", - " 4.13107686e-05, 2.71700714e-05, -9.44394125e-01, 5.75892750e-04,\n", - " -5.65947948e+00, 3.73480299e-03, -3.57088794e-04, -2.24538244e-03,\n", - " 3.70646402e-02, 4.51569550e-04, 4.44700012e+00, 4.53052087e+00,\n", - " -6.08699822e+01, 6.94058666e-03, 1.43343894e-02, 4.49836974e-02,\n", - " -6.13573881e+01, -9.79909825e-03, 4.11749098e-03, -1.09470467e-03,\n", - " 3.60072149e-01]),\n", - " array([-3.02712819e-06, -4.88972349e-02, 8.53606620e-01, -3.01227132e-01,\n", - " 3.92041293e-05, 2.03026577e-05, -9.53552418e-01, 6.21169183e-04,\n", - " -5.71808152e+00, 3.72472888e-03, -3.53579647e-04, -2.24770162e-03,\n", - " 3.73994506e-02, 4.83340071e-04, 4.16790442e+00, 4.65158362e+00,\n", - " -5.81398414e+01, 7.75382196e-03, 1.43647903e-02, 4.52764331e-02,\n", - " -5.86020400e+01, -1.00741055e-02, 3.50914733e-03, -2.31917653e-03,\n", - " 3.34810426e-01]),\n", - " array([-2.87122698e-06, -4.82650938e-02, 8.59710698e-01, -2.74676903e-01,\n", - " 3.67317564e-05, 1.33594475e-05, -9.61536581e-01, 6.66522085e-04,\n", - " -5.77397017e+00, 3.71431874e-03, -3.50616143e-04, -2.25112769e-03,\n", - " 3.77094048e-02, 5.06674068e-04, 3.89455401e+00, 4.74357193e+00,\n", - " -5.54512669e+01, 8.44706691e-03, 1.41597088e-02, 4.53529026e-02,\n", - " -5.58886497e+01, -1.04101392e-02, 2.96350338e-03, -3.42606710e-03,\n", - " 3.09954207e-01]),\n", - " array([-2.70065688e-06, -4.75658901e-02, 8.65694124e-01, -2.49195317e-01,\n", - " 3.39136881e-05, 6.47904366e-06, -9.68453248e-01, 7.11757430e-04,\n", - " -5.82719196e+00, 3.70353089e-03, -3.48135207e-04, -2.25554163e-03,\n", - " 3.79949488e-02, 5.21337298e-04, 3.62901580e+00, 4.80925650e+00,\n", - " -5.28087872e+01, 9.02745927e-03, 1.37417727e-02, 4.52353443e-02,\n", - " -5.32217869e+01, -1.07878580e-02, 2.48093631e-03, -4.41394509e-03,\n", - " 2.85543969e-01]),\n", - " array([-2.51670176e-06, -4.68061905e-02, 8.71553137e-01, -2.24803191e-01,\n", - " 3.07757957e-05, -2.16305441e-07, -9.74404189e-01, 7.56703986e-04,\n", - " -5.87779748e+00, 3.69234110e-03, -3.46074630e-04, -2.26082553e-03,\n", - " 3.82565644e-02, 5.27431786e-04, 3.37293971e+00, 4.85137048e+00,\n", - " -5.02164356e+01, 9.50326348e-03, 1.31373160e-02, 4.49465567e-02,\n", - " -5.06055215e+01, -1.11897884e-02, 2.06057718e-03, -5.28389768e-03,\n", - " 2.61615667e-01]),\n", - " array([-2.32079042e-06, -4.59925719e-02, 8.77285103e-01, -2.01512805e-01,\n", - " 2.73483583e-05, -6.62185587e-06, -9.79485880e-01, 8.01213167e-04,\n", - " -5.92584093e+00, 3.68074064e-03, -3.44374076e-04, -2.26686457e-03,\n", - " 3.84947654e-02, 5.25333781e-04, 3.12759886e+00, 4.87256458e+00,\n", - " -4.76777760e+01, 9.88319294e-03, 1.23747266e-02, 4.45091804e-02,\n", - " -4.80434498e+01, -1.16004597e-02, 1.70055412e-03, -6.03903837e-03,\n", - " 2.38200967e-01]),\n", - " array([-2.11444379e-06, -4.51314925e-02, 8.82888421e-01, -1.79328851e-01,\n", - " 2.36647306e-05, -1.26506743e-05, -9.83789186e-01, 8.45158341e-04,\n", - " -5.97137965e+00, 3.66873421e-03, -3.42975862e-04, -2.27354863e-03,\n", - " 3.87100929e-02, 5.15630243e-04, 2.89393103e+00, 4.87537234e+00,\n", - " -4.51959284e+01, 1.01759316e-02, 1.14830638e-02, 4.39451741e-02,\n", - " -4.55387200e+01, -1.20064311e-02, 1.39821341e-03, -6.68405955e-03,\n", - " 2.15327490e-01]),\n", - " array([-1.89922882e-06, -4.42291882e-02, 8.88362421e-01, -1.58249344e-01,\n", - " 1.97601423e-05, -1.82332796e-05, -9.87399182e-01, 8.88433786e-04,\n", - " -6.01447371e+00, 3.65633796e-03, -3.41825546e-04, -2.28077346e-03,\n", - " 3.89031119e-02, 4.99058174e-04, 2.67258008e+00, 4.86218466e+00,\n", - " -4.27735944e+01, 1.03898190e-02, 1.04909464e-02, 4.32754454e-02,\n", - " -4.30940583e+01, -1.23962493e-02, 1.15031643e-03, -7.22483481e-03,\n", - " 1.93019047e-01]),\n", - " array([-1.67671939e-06, -4.32915929e-02, 8.93707265e-01, -1.38266473e-01,\n", - " 1.56706521e-05, -2.33167857e-05, -9.90395063e-01, 9.30953390e-04,\n", - " -6.05518550e+00, 3.64357760e-03, -3.40872335e-04, -2.28844154e-03,\n", - " 3.90744078e-02, 4.76449709e-04, 2.46393595e+00, 4.83523229e+00,\n", - " -4.04130829e+01, 1.05326628e-02, 9.42570198e-03, 4.25196039e-02,\n", - " -4.07117943e+01, -1.27603597e-02, 9.53211422e-04, -7.66807250e-03,\n", - " 1.71295874e-01]),\n", - " array([-1.44846420e-06, -4.23242799e-02, 8.98923838e-01, -1.19367391e-01,\n", - " 1.14322635e-05, -2.78636931e-05, -9.92850152e-01, 9.72649202e-04,\n", - " -6.09357939e+00, 3.63048661e-03, -3.40069354e-04, -2.29646256e-03,\n", - " 3.92245827e-02, 4.48684673e-04, 2.26817259e+00, 4.79657511e+00,\n", - " -3.81163349e+01, 1.06116479e-02, 8.31275072e-03, 4.16958114e-02,\n", - " -3.83938864e+01, -1.30909890e-02, 8.02980632e-04, -8.02102003e-03,\n", - " 1.50174860e-01]),\n", - " array([-1.21596127e-06, -4.13324224e-02, 9.04013648e-01, -1.01534946e-01,\n", - " 7.08019986e-06, -3.18504530e-05, -9.94831973e-01, 1.01346991e-03,\n", - " -6.12972133e+00, 3.61710460e-03, -3.39373790e-04, -2.30475377e-03,\n", - " 3.93542524e-02, 4.16651326e-04, 2.08528320e+00, 4.74809711e+00,\n", - " -3.58849472e+01, 1.06333118e-02, 7.17519511e-03, 4.08207077e-02,\n", - " -3.61419460e+01, -1.33820087e-02, 6.95563952e-04, -8.29121628e-03,\n", - " 1.29669769e-01]),\n", - " array([-9.80638331e-07, -4.03207697e-02, 9.08978727e-01, -8.47483442e-02,\n", - " 2.64833102e-06, -3.52659082e-05, -9.96402387e-01, 1.05337930e-03,\n", - " -6.16367859e+00, 3.60347581e-03, -3.38746929e-04, -2.31324006e-03,\n", - " 3.94640439e-02, 3.81215341e-04, 1.91511228e+00, 4.69150605e+00,\n", - " -3.37201966e+01, 1.06035675e-02, 6.03358296e-03, 3.99093937e-02,\n", - " -3.39572610e+01, -1.36287881e-02, 6.26860746e-04, -8.48628866e-03,\n", - " 1.09791458e-01]),\n", - " array([-7.43838430e-07, -3.92936368e-02, 9.13821542e-01, -6.89837598e-02,\n", - " -1.83126466e-06, -3.81096929e-05, -9.97617782e-01, 1.09235476e-03,\n", - " -6.19551941e+00, 3.58964777e-03, -3.38154117e-04, -2.32185385e-03,\n", - " 3.95545920e-02, 3.43196486e-04, 1.75738451e+00, 4.62833674e+00,\n", - " -3.16230619e+01, 1.05277527e-02, 4.90581107e-03, 3.89754574e-02,\n", - " -3.18408190e+01, -1.38280415e-02, 5.92811958e-04, -8.61379042e-03,\n", - " 9.05480802e-02]),\n", - " array([-5.06809993e-07, -3.82549053e-02, 9.18544911e-01, -5.42148733e-02,\n", - " -6.32861737e-06, -4.03906540e-05, -9.98529291e-01, 1.13038579e-03,\n", - " -6.22531274e+00, 3.57567009e-03, -3.37564653e-04, -2.33053493e-03,\n", - " 3.96265373e-02, 3.03352256e-04, 1.61173031e+00, 4.55995710e+00,\n", - " -2.95942459e+01, 1.04106936e-02, 3.80713892e-03, 3.80310296e-02,\n", - " -2.97933291e+01, -1.39776751e-02, 5.89464687e-04, -8.68107353e-03,\n", - " 7.19452864e-02]),\n", - " array([-2.70700611e-07, -3.72080328e-02, 9.23151927e-01, -4.04133597e-02,\n", - " -1.08160800e-05, -4.21253410e-05, -9.99183046e-01, 1.16747265e-03,\n", - " -6.25312798e+00, 3.56159346e-03, -3.36951631e-04, -2.33923012e-03,\n", - " 3.96805237e-02, 2.62367449e-04, 1.47770813e+00, 4.48757637e+00,\n", - " -2.76341965e+01, 1.02567733e-02, 2.75028460e-03, 3.70868592e-02,\n", - " -2.78152429e+01, -1.40766367e-02, 6.13021481e-04, -8.69519265e-03,\n", - " 5.39864140e-02]),\n", - " array([-3.65538927e-08, -3.61560687e-02, 9.27645894e-01, -2.75493194e-02,\n", - " -1.52684554e-05, -4.33365954e-05, -9.99620444e-01, 1.20362505e-03,\n", - " -6.27903476e+00, 3.54746869e-03, -3.36291755e-04, -2.34789295e-03,\n", - " 3.97171964e-02, 2.20848688e-04, 1.35482377e+00, 4.41225471e+00,\n", - " -2.57431259e+01, 1.00699981e-02, 1.74557886e-03, 3.61524004e-02,\n", - " -2.59067742e+01, -1.41247698e-02, 6.59876511e-04, -8.66283537e-03,\n", - " 3.66726683e-02]),\n", - " array([ 1.94691193e-07, -3.51016757e-02, 9.32030262e-01, -1.55916585e-02,\n", - " -1.96630531e-05, -4.40522596e-05, -9.99878442e-01, 1.23886095e-03,\n", - " -6.30310268e+00, 3.53334601e-03, -3.35565114e-04, -2.35648323e-03,\n", - " 3.97371996e-02, 1.79322882e-04, 1.24254672e+00, 4.33491366e+00,\n", - " -2.39210298e+01, 9.85405670e-03, 8.01156501e-04, 3.52359045e-02,\n", - " -2.40679186e+01, -1.41226772e-02, 7.26640670e-04, -8.59027471e-03,\n", - " 2.00032950e-02]),\n", - " array([ 4.22199012e-07, -3.40471536e-02, 9.36308582e-01, -4.50842205e-03,\n", - " -2.39796883e-05, -4.43040163e-05, -9.99989836e-01, 1.27320547e-03,\n", - " -6.32540115e+00, 3.51927442e-03, -3.34754956e-04, -2.36496657e-03,\n", - " 3.97411754e-02, 1.38238719e-04, 1.14032398e+00, 4.25634719e+00,\n", - " -2.21677056e+01, 9.61237078e-03, -7.68313832e-05, 3.43445124e-02,\n", - " -2.22984711e+01, -1.40715926e-02, 8.10157470e-04, -8.48333987e-03,\n", - " 3.97574349e-03]),\n", - " array([ 6.45234423e-07, -3.29944663e-02, 9.40484455e-01, 5.73291578e-03,\n", - " -2.82006357e-05, -4.41263595e-05, -9.99983565e-01, 1.30668981e-03,\n", - " -6.34599919e+00, 3.50530116e-03, -3.33847445e-04, -2.37331397e-03,\n", - " 3.97297612e-02, 9.79703623e-05, 1.04759141e+00, 4.17723278e+00,\n", - " -2.04827686e+01, 9.34813615e-03, -8.83997595e-04, 3.34843440e-02,\n", - " -2.05980435e+01, -1.39732633e-02, 9.07511416e-04, -8.34740176e-03,\n", - " -1.14141785e-02]),\n", - " array([ 8.63158767e-07, -3.19452694e-02, 9.44561502e-01, 1.51652005e-02,\n", - " -3.23105494e-05, -4.35556967e-05, -9.99885000e-01, 1.33935039e-03,\n", - " -6.36496527e+00, 3.49147131e-03, -3.32831415e-04, -2.38150134e-03,\n", - " 3.97035891e-02, 5.88226779e-05, 9.63783120e-01, 4.09814242e+00,\n", - " -1.88656689e+01, 9.06435369e-03, -1.61750146e-03, 3.26605819e-02,\n", - " -1.89660805e+01, -1.38298444e-02, 1.01603033e-03, -8.18737033e-03,\n", - " -2.61721581e-02]),\n", - " array([ 1.07542499e-06, -3.09009384e-02, 9.48543324e-01, 2.38213815e-02,\n", - " -3.62963549e-05, -4.26295734e-05, -9.99716229e-01, 1.37122794e-03,\n", - " -6.38236715e+00, 3.47782751e-03, -3.31698132e-04, -2.38950904e-03,\n", - " 3.96632838e-02, 2.10374106e-05, 8.88338838e-01, 4.01955325e+00,\n", - " -1.73157059e+01, 8.76385170e-03, -2.27584101e-03, 3.18775492e-02,\n", - " -1.74018748e+01, -1.36438045e-02, 1.13328293e-03, -8.00770107e-03,\n", - " -4.03052395e-02]),\n", - " array([ 1.28157214e-06, -2.98625961e-02, 9.52433480e-01, 3.17343279e-02,\n", - " -4.01471237e-05, -4.13860123e-05, -9.99496338e-01, 1.40236672e-03,\n", - " -6.39827173e+00, 3.46440966e-03, -3.30441059e-04, -2.39732145e-03,\n", - " 3.96094621e-02, -1.52001436e-05, 8.20709825e-01, 3.94185770e+00,\n", - " -1.58320429e+01, 8.44930052e-03, -2.85865945e-03, 3.11387796e-02,\n", - " -1.59045818e+01, -1.34178428e-02, 1.25707274e-03, -7.81240834e-03,\n", - " -5.38216930e-02]),\n", - " array([ 1.48121949e-06, -2.88311395e-02, 9.56235465e-01, 3.89366721e-02,\n", - " -4.38539326e-05, -3.98629563e-05, -9.99241679e-01, 1.43281380e-03,\n", - " -6.41274496e+00, 3.45125485e-03, -3.29055630e-04, -2.40492653e-03,\n", - " 3.95427312e-02, -4.97543215e-05, 7.60363336e-01, 3.86537311e+00,\n", - " -1.44137206e+01, 8.12322094e-03, -3.36656878e-03, 3.04470815e-02,\n", - " -1.44732332e+01, -1.31548181e-02, 1.38542927e-03, -7.60508387e-03,\n", - " -6.67308929e-02]),\n", - " array([ 1.67406034e-06, -2.78072657e-02, 9.59952692e-01, 4.54606788e-02,\n", - " -4.74097159e-05, -3.80978041e-05, -9.98966127e-01, 1.46261840e-03,\n", - " -6.42585171e+00, 3.43839716e-03, -3.27539032e-04, -2.41231545e-03,\n", - " 3.94636880e-02, -8.25323970e-05, 7.06785939e-01, 3.79035061e+00,\n", - " -1.30596693e+01, 7.78798781e-03, -3.80099177e-03, 2.98045949e-02,\n", - " -1.31067493e+01, -1.28576876e-02, 1.51659724e-03, -7.38891871e-03,\n", - " -7.90432011e-02]),\n", - " array([ 1.85985581e-06, -2.67914960e-02, 9.63588477e-01, 5.13381351e-02,\n", - " -5.08091108e-05, -3.61270269e-05, -9.98681327e-01, 1.49183124e-03,\n", - " -6.43765566e+00, 3.42586770e-03, -3.25890008e-04, -2.41948218e-03,\n", - " 3.93729182e-02, -1.13478194e-04, 6.59485863e-01, 3.71698340e+00,\n", - " -1.17687215e+01, 7.44583038e-03, -4.16402234e-03, 2.92128429e-02,\n", - " -1.18039515e+01, -1.25294565e-02, 1.64902447e-03, -7.16672750e-03,\n", - " -9.07698590e-02]),\n", - " array([ 2.03842855e-06, -2.57841981e-02, 9.67146030e-01, 5.66002603e-02,\n", - " -5.40483020e-05, -3.39858570e-05, -9.98396918e-01, 1.52050402e-03,\n", - " -6.44821924e+00, 3.41369457e-03, -3.24108659e-04, -2.42642315e-03,\n", - " 3.92709953e-02, -1.42566135e-04, 6.17994532e-01, 3.64541427e+00,\n", - " -1.05396225e+01, 7.09883057e-03, -4.45830354e-03, 2.86727796e-02,\n", - " -1.05635736e+01, -1.21731363e-02, 1.78134898e-03, -6.94097402e-03,\n", - " -1.01922885e-01]),\n", - " array([ 2.20965660e-06, -2.47856075e-02, 9.70628447e-01, 6.12776314e-02,\n", - " -5.71248661e-05, -3.17080372e-05, -9.98120758e-01, 1.54868885e-03,\n", - " -6.45760351e+00, 3.40190285e-03, -3.22196273e-04, -2.43313695e-03,\n", - " 3.91584803e-02, -1.69795803e-04, 5.81867449e-01, 3.57574249e+00,\n", - " -9.37104118e+00, 6.74892019e-03, -4.68692187e-03, 2.81848328e-02,\n", - " -9.38427201e+00, -1.17917108e-02, 1.91238567e-03, -6.71379725e-03,\n", - " -1.12514980e-01]),\n", - " array([ 2.37346737e-06, -2.37958463e-02, 9.74038700e-01, 6.54001242e-02,\n", - " -6.00376188e-05, -2.93256230e-05, -9.97859118e-01, 1.57643780e-03,\n", - " -6.46586814e+00, 3.39051474e-03, -3.20155160e-04, -2.43962399e-03,\n", - " 3.90359209e-02, -1.95187059e-04, 5.50684539e-01, 3.50802996e+00,\n", - " -8.26157971e+00, 6.39787823e-03, -4.85331612e-03, 2.77489451e-02,\n", - " -8.26463582e+00, -1.13881103e-02, 2.04111292e-03, -6.48703740e-03,\n", - " -1.22559434e-01]),\n", - " array([ 2.52983188e-06, -2.28149405e-02, 9.77379640e-01, 6.89968655e-02,\n", - " -6.27864666e-05, -2.68688301e-05, -9.97616874e-01, 1.60380241e-03,\n", - " -6.47307134e+00, 3.37954955e-03, -3.17988501e-04, -2.44588625e-03,\n", - " 3.89038508e-02, -2.18775721e-04, 5.24050084e-01, 3.44230686e+00,\n", - " -7.20978286e+00, 6.04732871e-03, -4.96119890e-03, 2.73646134e-02,\n", - " -7.20319627e+00, -1.09651914e-02, 2.16665934e-03, -6.26226128e-03,\n", - " -1.32070048e-01]),\n", - " array([ 2.67875928e-06, -2.18428358e-02, 9.80653987e-01, 7.20961964e-02,\n", - " -6.53722634e-05, -2.43659195e-05, -9.97397681e-01, 1.63083334e-03,\n", - " -6.47926978e+00, 3.36902383e-03, -3.15700210e-04, -2.45192704e-03,\n", - " 3.87627898e-02, -2.40609806e-04, 5.01592327e-01, 3.37857656e+00,\n", - " -6.21414649e+00, 5.69873963e-03, -5.01448915e-03, 2.70309261e-02,\n", - " -6.19843526e+00, -1.05257213e-02, 2.28829092e-03, -6.04078701e-03,\n", - " -1.41061049e-01]),\n", - " array([ 2.82029157e-06, -2.08794116e-02, 9.83864335e-01, 7.47256447e-02,\n", - " -6.77966747e-05, -2.18431165e-05, -9.97204128e-01, 1.65757994e-03,\n", - " -6.48451857e+00, 3.35895146e-03, -3.13294812e-04, -2.45775074e-03,\n", - " 3.86132428e-02, -2.60746292e-04, 4.82962832e-01, 3.31682002e+00,\n", - " -5.27312573e+00, 5.35342343e-03, -5.01725371e-03, 2.67466015e-02,\n", - " -5.24879356e+00, -1.00723682e-02, 2.40539859e-03, -5.82370741e-03,\n", - " -1.49547021e-01]),\n", - " array([ 2.95449880e-06, -1.99244932e-02, 9.87013149e-01, 7.69119046e-02,\n", - " -7.00620497e-05, -1.93245570e-05, -9.97037890e-01, 1.68408996e-03,\n", - " -6.48887125e+00, 3.34934377e-03, -3.10777325e-04, -2.46336266e-03,\n", - " 3.84556999e-02, -2.79248390e-04, 4.67835662e-01, 3.25699977e+00,\n", - " -4.38514238e+00, 5.01253896e-03, -4.97365652e-03, 2.65100245e-02,\n", - " -4.35267831e+00, -9.60769363e-03, 2.51748646e-03, -5.61191236e-03,\n", - " -1.57542836e-01]),\n", - " array([ 3.08147452e-06, -1.89778632e-02, 9.90102767e-01, 7.86808231e-02,\n", - " -7.21713020e-05, -1.68322589e-05, -9.96899856e-01, 1.71040925e-03,\n", - " -6.49237972e+00, 3.34020962e-03, -3.08153165e-04, -2.46876877e-03,\n", - " 3.82906363e-02, -2.96183268e-04, 4.55906439e-01, 3.19906326e+00,\n", - " -3.54859200e+00, 4.67709520e-03, -4.88791396e-03, 2.63192844e-02,\n", - " -3.50847020e+00, -9.13414873e-03, 2.62416059e-03, -5.40610970e-03,\n", - " -1.65063586e-01]),\n", - " array([ 3.20133153e-06, -1.80392707e-02, 9.93135399e-01, 8.00573920e-02,\n", - " -7.41277993e-05, -1.43861136e-05, -9.96790253e-01, 1.73658146e-03,\n", - " -6.49509425e+00, 3.33155555e-03, -3.05428046e-04, -2.47397561e-03,\n", - " 3.81185118e-02, -3.11620188e-04, 4.46891313e-01, 3.14294588e+00,\n", - " -2.76185040e+00, 4.34795644e-03, -4.76425537e-03, 2.61722125e-02,\n", - " -2.71452997e+00, -8.65407196e-03, 2.72511850e-03, -5.20684481e-03,\n", - " -1.72124528e-01]),\n", - " array([ 3.31419816e-06, -1.71084399e-02, 9.96113134e-01, 8.10657438e-02,\n", - " -7.59352633e-05, -1.20038975e-05, -9.96708753e-01, 1.76264788e-03,\n", - " -6.49706345e+00, 3.32338586e-03, -3.02607907e-04, -2.47899013e-03,\n", - " 3.79397708e-02, -3.25629015e-04, 4.40525894e-01, 3.08857362e+00,\n", - " -2.02327970e+00, 4.02584896e-03, -4.60688763e-03, 2.60664200e-02,\n", - " -1.96920454e+00, -8.16968897e-03, 2.82013937e-03, -5.01451883e-03,\n", - " -1.78741029e-01]),\n", - " array([ 3.42021471e-06, -1.61850773e-02, 9.99037935e-01, 8.17291523e-02,\n", - " -7.75976795e-05, -9.70129828e-06, -9.96654574e-01, 1.78864722e-03,\n", - " -6.49833429e+00, 3.31570275e-03, -2.99698832e-04, -2.48381954e-03,\n", - " 3.77548423e-02, -3.38279053e-04, 4.36564165e-01, 3.03586526e+00,\n", - " -1.33123394e+00, 3.71136890e-03, -4.41996332e-03, 2.59993357e-02,\n", - " -1.27083273e+00, -7.68311337e-03, 2.90907491e-03, -4.82940551e-03,\n", - " -1.84928511e-01]),\n", - " array([ 3.51953040e-06, -1.52688779e-02, 1.00191165e+00, 8.20700356e-02,\n", - " -7.91192169e-05, -7.49195724e-06, -9.96626561e-01, 1.81461546e-03,\n", - " -6.49895204e+00, 3.30850640e-03, -2.96706991e-04, -2.48847120e-03,\n", - " 3.75641399e-02, -3.49638164e-04, 4.34777397e-01, 2.98473439e+00,\n", - " -6.84064343e-01, 3.40499110e-03, -4.20755186e-03, 2.59682430e-02,\n", - " -6.17750475e-01, -7.19634842e-03, 2.99184091e-03, -4.65166670e-03,\n", - " -1.90702405e-01]),\n", - " array([ 3.61230053e-06, -1.43595300e-02, 1.00473602e+00, 8.21099626e-02,\n", - " -8.05041580e-05, -5.38752363e-06, -9.96623273e-01, 1.84058578e-03,\n", - " -6.49896033e+00, 3.30179511e-03, -2.93638581e-04, -2.49295257e-03,\n", - " 3.73680617e-02, -3.59772126e-04, 4.34953092e-01, 2.93509103e+00,\n", - " -8.01240771e-02, 3.10707879e-03, -3.97361325e-03, 2.59703172e-02,\n", - " -8.29569560e-03, -6.71128905e-03, 3.06840947e-03, -4.48136669e-03,\n", - " -1.96078111e-01]),\n", - " array([ 3.69868405e-06, -1.34567203e-02, 1.00751265e+00, 8.18696609e-02,\n", - " -8.17568383e-05, -3.39772111e-06, -9.96643041e-01, 1.86658844e-03,\n", - " -6.49840114e+00, 3.29556538e-03, -2.90499780e-04, -2.49727105e-03,\n", - " 3.71669908e-02, -3.68744206e-04, 4.36893950e-01, 2.88684309e+00,\n", - " 4.82227281e-01, 2.81789361e-03, -3.72197440e-03, 2.60026607e-02,\n", - " 5.59187212e-01, -6.22972425e-03, 3.13880182e-03, -4.31848520e-03,\n", - " -2.01070952e-01]),\n", - " array([ 3.77884142e-06, -1.25601369e-02, 1.01024305e+00, 8.13690271e-02,\n", - " -8.28815950e-05, -1.53042448e-06, -9.96684039e-01, 1.89265077e-03,\n", - " -6.49731480e+00, 3.28981205e-03, -2.87296698e-04, -2.50143398e-03,\n", - " 3.69612947e-02, -3.76614896e-04, 4.40416889e-01, 2.83989752e+00,\n", - " 1.00461967e+00, 2.53760603e-03, -3.45630777e-03, 2.60623376e-02,\n", - " 1.08634326e+00, -5.75333936e-03, 3.20308178e-03, -4.16292938e-03,\n", - " -2.05696140e-01]),\n", - " array([ 3.85293276e-06, -1.16694723e-02, 1.01292864e+00, 8.06271386e-02,\n", - " -8.38827251e-05, 2.08254507e-07, -9.96744329e-01, 1.91879718e-03,\n", - " -6.49574000e+00, 3.28452833e-03, -2.84035348e-04, -2.50544853e-03,\n", - " 3.67513259e-02, -3.83441788e-04, 4.45352109e-01, 2.79416141e+00,\n", - " 1.48866878e+00, 2.26630575e-03, -3.18011224e-03, 2.61464060e-02,\n", - " 1.57480311e+00, -5.28371837e-03, 3.26134979e-03, -4.01454462e-03,\n", - " -2.09968743e-01]),\n", - " array([ 3.92111621e-06, -1.07844260e-02, 1.01557072e+00, 7.96622662e-02,\n", - " -8.47644517e-05, 1.81387335e-06, -9.96821908e-01, 1.94504913e-03,\n", - " -6.49371382e+00, 3.27970598e-03, -2.80721611e-04, -2.50932165e-03,\n", - " 3.65374223e-02, -3.89279570e-04, 4.51542204e-01, 2.74954273e+00,\n", - " 1.93597268e+00, 2.00401192e-03, -2.89669666e-03, 2.62519485e-02,\n", - " 2.02617958e+00, -4.82234603e-03, 3.31373747e-03, -3.87312440e-03,\n", - " -2.13903652e-01]),\n", - " array([ 3.98354670e-06, -9.90470595e-03, 1.01817049e+00, 7.84918886e-02,\n", - " -8.55308971e-05, 3.28355820e-06, -9.96914749e-01, 1.97142523e-03,\n", - " -6.49127175e+00, 3.27533537e-03, -2.77361208e-04, -2.51306007e-03,\n", - " 3.63199067e-02, -3.94180097e-04, 4.58841333e-01, 2.70595108e+00,\n", - " 2.34810863e+00, 1.75068303e-03, -2.60916553e-03, 2.63761005e-02,\n", - " 2.44206453e+00, -4.37060974e-03, 3.36040265e-03, -3.73841920e-03,\n", - " -2.17515552e-01]),\n", - " array([ 4.04037475e-06, -9.03003017e-03, 1.02072906e+00, 7.71327072e-02,\n", - " -8.61860639e-05, 4.61589772e-06, -9.97020831e-01, 1.99794130e-03,\n", - " -6.48844773e+00, 3.27140557e-03, -2.73959683e-04, -2.51667022e-03,\n", - " 3.60990878e-02, -3.98192534e-04, 4.67114443e-01, 2.66329823e+00,\n", - " 2.72663031e+00, 1.50622637e-03, -2.32040731e-03, 2.65160753e-02,\n", - " 2.82402599e+00, -3.92980125e-03, 3.40152496e-03, -3.61014453e-03,\n", - " -2.20818900e-01]),\n", - " array([ 4.09174566e-06, -8.16012746e-03, 1.02324746e+00, 7.56006618e-02,\n", - " -8.67338217e-05, 5.81083247e-06, -9.97138171e-01, 2.02461049e-03,\n", - " -6.48527412e+00, 3.26790445e-03, -2.70522381e-04, -2.52015820e-03,\n", - " 3.58752599e-02, -4.01363537e-04, 4.76236540e-01, 2.62149856e+00,\n", - " 3.07306523e+00, 1.27050683e-03, -2.03308523e-03, 2.66691868e-02,\n", - " 3.17360559e+00, -3.50111812e-03, 3.43730177e-03, -3.48798813e-03,\n", - " -2.23827899e-01]),\n", - " array([ 4.13779877e-06, -7.29473812e-03, 1.02572661e+00, 7.39109472e-02,\n", - " -8.71778987e-05, 6.86954115e-06, -9.97264842e-01, 2.05144336e-03,\n", - " -6.48178181e+00, 3.26481879e-03, -2.67054437e-04, -2.52352982e-03,\n", - " 3.56487034e-02, -4.03737466e-04, 4.86092019e-01, 2.58046941e+00,\n", - " 3.38891247e+00, 1.04335508e-03, -1.74963054e-03, 2.68328694e-02,\n", - " 3.49231627e+00, -3.08566509e-03, 3.46794459e-03, -3.37161645e-03,\n", - " -2.26556480e-01]),\n", - " array([ 4.17866698e-06, -6.43361417e-03, 1.02816737e+00, 7.20780299e-02,\n", - " -8.75218789e-05, 7.79432472e-06, -9.97398992e-01, 2.07844806e-03,\n", - " -6.47800017e+00, 3.26213433e-03, -2.63560761e-04, -2.52679050e-03,\n", - " 3.54196852e-02, -4.05356616e-04, 4.96574033e-01, 2.54013136e+00,\n", - " 3.67564059e+00, 8.24575027e-04, -1.47223843e-03, 2.70046943e-02,\n", - " 3.78164013e+00, -2.68445525e-03, 3.49367582e-03, -3.26068034e-03,\n", - " -2.29018280e-01]),\n", - " array([ 4.21447632e-06, -5.57651948e-03, 1.03057051e+00, 7.01156658e-02,\n", - " -8.77692019e-05, 8.58848963e-06, -9.97538864e-01, 2.10563044e-03,\n", - " -6.47395714e+00, 3.25983592e-03, -2.60046035e-04, -2.52994532e-03,\n", - " 3.51884585e-02, -4.06261441e-04, 5.07583917e-01, 2.50040838e+00,\n", - " 3.93468585e+00, 6.13950437e-04, -1.20286624e-03, 2.71823837e-02,\n", - " 4.04302671e+00, -2.29841124e-03, 3.51472592e-03, -3.15482019e-03,\n", - " -2.31226628e-01]),\n", - " array([ 4.24534580e-06, -4.72322960e-03, 1.03293671e+00, 6.80369182e-02,\n", - " -8.79231668e-05, 9.25623135e-06, -9.97682800e-01, 2.13299426e-03,\n", - " -6.46967925e+00, 3.25790755e-03, -2.56514704e-04, -2.53299899e-03,\n", - " 3.49552640e-02, -4.06490785e-04, 5.19030642e-01, 2.46122799e+00,\n", - " 4.16745057e+00, 4.11250884e-04, -9.43234200e-04, 2.73638210e-02,\n", - " 4.27789129e+00, -1.92836635e-03, 3.53133078e-03, -3.05367041e-03,\n", - " -2.33194533e-01]),\n", - " array([ 4.27138720e-06, -3.87353143e-03, 1.03526660e+00, 6.58541755e-02,\n", - " -8.79869379e-05, 9.80251916e-06, -9.97829254e-01, 2.16054132e-03,\n", - " -6.46519163e+00, 3.25633249e-03, -2.52970975e-04, -2.53595585e-03,\n", - " 3.47203293e-02, -4.06082086e-04, 5.30830326e-01, 2.42252130e+00,\n", - " 4.37530180e+00, 2.16236865e-04, -6.94828357e-04, 2.75470586e-02,\n", - " 4.48761351e+00, -1.57506580e-03, 3.54372953e-03, -2.95686336e-03,\n", - " -2.34934666e-01]),\n", - " array([ 4.29270515e-06, -3.02722280e-03, 1.03756073e+00, 6.35791702e-02,\n", - " -8.79635522e-05, 1.02329832e-05, -9.97976794e-01, 2.18827164e-03,\n", - " -6.46051810e+00, 3.25509332e-03, -2.49418812e-04, -2.53881989e-03,\n", - " 3.44838700e-02, -4.05071573e-04, 5.42905766e-01, 2.38422306e+00,\n", - " 4.55957006e+00, 2.86641997e-05, -4.58905639e-04, 2.77303237e-02,\n", - " 4.67353619e+00, -1.23916800e-03, 3.55216252e-03, -2.86403277e-03,\n", - " -2.36459357e-01]),\n", - " array([ 4.30939712e-06, -2.18411191e-03, 1.03981957e+00, 6.12229973e-02,\n", - " -8.78559285e-05, 1.05538048e-05, -9.98124109e-01, 2.21618366e-03,\n", - " -6.45568113e+00, 3.25417207e-03, -2.45861942e-04, -2.54159470e-03,\n", - " 3.42460894e-02, -4.03494434e-04, 5.55186010e-01, 2.34627165e+00,\n", - " 4.72154836e+00, -1.51712284e-04, -2.36500862e-04, 2.79120197e-02,\n", - " 4.83696427e+00, -9.21246090e-04, 3.55686961e-03, -2.77481672e-03,\n", - " -2.37780577e-01]),\n", - " array([ 4.32155365e-06, -1.34401674e-03, 1.04204355e+00, 5.87961339e-02,\n", - " -8.76668768e-05, 1.07716109e-05, -9.98270007e-01, 2.24427439e-03,\n", - " -6.45070197e+00, 3.25355028e-03, -2.42303854e-04, -2.54428356e-03,\n", - " 3.40071795e-02, -4.01384964e-04, 5.67605961e-01, 2.30860902e+00,\n", - " 4.86249137e+00, -3.25135726e-04, -2.84354748e-05, 2.80907274e-02,\n", - " 4.97916399e+00, -6.21789626e-04, 3.55808868e-03, -2.68886010e-03,\n", - " -2.38909940e-01]),\n", - " array([ 4.32925852e-06, -5.06764323e-04, 1.04423302e+00, 5.63084573e-02,\n", - " -8.73991082e-05, 1.08933733e-05, -9.98413416e-01, 2.27253959e-03,\n", - " -6.44560061e+00, 3.25320908e-03, -2.38747799e-04, -2.54688938e-03,\n", - " 3.37673208e-02, -3.98776684e-04, 5.80106005e-01, 2.27118063e+00,\n", - " 4.98361470e+00, -4.91844816e-04, 1.64672179e-04, 2.82652021e-02,\n", - " 5.10136217e+00, -3.41206514e-04, 3.55605431e-03, -2.60581681e-03,\n", - " -2.39858689e-01]),\n", - " array([ 4.33258900e-06, 3.27809932e-04, 1.04638828e+00, 5.37692656e-02,\n", - " -8.70552448e-05, 1.09263135e-05, -9.98553383e-01, 2.30097396e-03,\n", - " -6.44039586e+00, 3.25312925e-03, -2.35196803e-04, -2.54941473e-03,\n", - " 3.35266831e-02, -3.95702435e-04, 5.92631669e-01, 2.23393536e+00,\n", - " 5.08609440e+00, -6.52071936e-04, 3.42395293e-04, 2.84343702e-02,\n", - " 5.20474571e+00, -7.98252198e-05, 3.55099676e-03, -2.52535147e-03,\n", - " -2.40637700e-01]),\n", - " array([ 4.33161622e-06, 1.15986299e-03, 1.04850958e+00, 5.11872957e-02,\n", - " -8.66378289e-05, 1.08778131e-05, -9.98689067e-01, 2.32957129e-03,\n", - " -6.43510540e+00, 3.25329136e-03, -2.31653662e-04, -2.55186187e-03,\n", - " 3.32854256e-02, -3.92194452e-04, 6.05133297e-01, 2.19682542e+00,\n", - " 5.17106656e+00, -8.06041789e-04, 5.04485971e-04, 2.85973233e-02,\n", - " 5.29046119e+00, 1.62102743e-04, 3.54314097e-03, -2.44714087e-03,\n", - " -2.41257470e-01]),\n", - " array([ 4.32640545e-06, 1.98954492e-03, 1.05059711e+00, 4.85707439e-02,\n", - " -8.61493323e-05, 1.07553310e-05, -9.98819741e-01, 2.35832460e-03,\n", - " -6.42974579e+00, 3.25367576e-03, -2.28120956e-04, -2.55423275e-03,\n", - " 3.30436975e-02, -3.88284408e-04, 6.17565753e-01, 2.15980619e+00,\n", - " 5.23962706e+00, -9.53970464e-04, 6.50861773e-04, 2.87533113e-02,\n", - " 5.35961457e+00, 3.84400036e-04, 3.53270586e-03, -2.37087515e-03,\n", - " -2.41728121e-01]),\n", - " array([ 4.31701655e-06, 2.81699963e-03, 1.05265101e+00, 4.59272846e-02,\n", - " -8.55921639e-05, 1.05663276e-05, -9.98944782e-01, 2.38722633e-03,\n", - " -6.42433251e+00, 3.25426272e-03, -2.24601052e-04, -2.55652901e-03,\n", - " 3.28016381e-02, -3.84003446e-04, 6.29888136e-01, 2.12283613e+00,\n", - " 5.29283143e+00, -1.09606488e-03, 7.81591660e-04, 2.89017341e-02,\n", - " 5.41327111e+00, 5.86960438e-04, 3.51990373e-03, -2.29625860e-03,\n", - " -2.42059398e-01]),\n", - " array([ 4.30350426e-06, 3.64236561e-03, 1.05467137e+00, 4.32640901e-02,\n", - " -8.49686769e-05, 1.03181952e-05, -9.99063667e-01, 2.41626846e-03,\n", - " -6.41888006e+00, 3.25503246e-03, -2.21096112e-04, -2.55875202e-03,\n", - " 3.25593774e-02, -3.79382180e-04, 6.42063514e-01, 2.08587663e+00,\n", - " 5.33169482e+00, -1.23252252e-03, 8.96881558e-04, 2.90421323e-02,\n", - " 5.45245533e+00, 7.69745502e-04, 3.50493970e-03, -2.22301038e-03,\n", - " -2.42260667e-01]),\n", - " array([ 4.28591870e-06, 4.46577657e-03, 1.05665827e+00, 4.05878501e-02,\n", - " -8.42811757e-05, 1.00181962e-05, -9.99175970e-01, 2.44544264e-03,\n", - " -6.41340191e+00, 3.25596524e-03, -2.17608101e-04, -2.56090288e-03,\n", - " 3.23170365e-02, -3.74450691e-04, 6.54058682e-01, 2.04889186e+00,\n", - " 5.35719209e+00, -1.36353147e-03, 9.97059754e-04, 2.91741774e-02,\n", - " 5.47815107e+00, 9.32780955e-04, 3.48801143e-03, -2.15086488e-03,\n", - " -2.42340920e-01]),\n", - " array([ 4.26430576e-06, 5.28736213e-03, 1.05861169e+00, 3.79047906e-02,\n", - " -8.35319204e-05, 9.67340807e-06, -9.99281352e-01, 2.47474030e-03,\n", - " -6.40791061e+00, 3.25704140e-03, -2.14138792e-04, -2.56298245e-03,\n", - " 3.20747277e-02, -3.69238507e-04, 6.65843919e-01, 2.01184864e+00,\n", - " 5.37025798e+00, -1.48927062e-03, 1.08256232e-03, 2.92976612e-02,\n", - " 5.49130167e+00, 1.07615286e-03, 3.46930879e-03, -2.07957199e-03,\n", - " -2.42308772e-01]),\n", - " array([ 4.23870747e-06, 6.10724846e-03, 1.06053162e+00, 3.52206936e-02,\n", - " -8.27231313e-05, 9.29067512e-06, -9.99379555e-01, 2.50415279e-03,\n", - " -6.40241780e+00, 3.25824140e-03, -2.10689778e-04, -2.56499135e-03,\n", - " 3.18325552e-02, -3.63774567e-04, 6.77392773e-01, 1.97471630e+00,\n", - " 5.37178741e+00, -1.60991005e-03, 1.15391872e-03, 2.94124852e-02,\n", - " 5.49281031e+00, 1.20000358e-03, 3.44901371e-03, -2.00889714e-03,\n", - " -2.42172469e-01]),\n", - " array([ 4.20916251e-06, 6.92555883e-03, 1.06241800e+00, 3.25409159e-02,\n", - " -8.18569924e-05, 8.87656762e-06, -9.99470401e-01, 2.53367144e-03,\n", - " -6.39693426e+00, 3.25954593e-03, -2.07262478e-04, -2.56692997e-03,\n", - " 3.15906154e-02, -3.58087183e-04, 6.88681846e-01, 1.93746651e+00,\n", - " 5.36263578e+00, -1.72561153e-03, 1.21173780e-03, 2.95186495e-02,\n", - " 5.48354025e+00, 1.30452753e-03, 3.42730010e-03, -1.93862127e-03,\n", - " -2.41939888e-01]),\n", - " array([ 4.17570658e-06, 7.74241418e-03, 1.06427072e+00, 2.98704081e-02,\n", - " -8.09356536e-05, 8.43734724e-06, -9.99553776e-01, 2.56328768e-03,\n", - " -6.39146994e+00, 3.26093589e-03, -2.03858145e-04, -2.56879851e-03,\n", - " 3.13489968e-02, -3.52203997e-04, 6.99690596e-01, 1.90007318e+00,\n", - " 5.34361945e+00, -1.83652907e-03, 1.25669427e-03, 2.96162423e-02,\n", - " 5.46431537e+00, 1.38996683e-03, 3.40433378e-03, -1.86854054e-03,\n", - " -2.41618542e-01]),\n", - " array([ 4.13837281e-06, 8.55793361e-03, 1.06608966e+00, 2.72137336e-02,\n", - " -7.99612323e-05, 7.97893894e-06, -9.99629635e-01, 2.59299311e-03,\n", - " -6.38603402e+00, 3.26239250e-03, -2.00477872e-04, -2.57059698e-03,\n", - " 3.11077812e-02, -3.46151927e-04, 7.10401151e-01, 1.86251227e+00,\n", - " 5.31551619e+00, -1.94280959e-03, 1.28951575e-03, 2.97054287e-02,\n", - " 5.43592061e+00, 1.45660680e-03, 3.38027254e-03, -1.79846614e-03,\n", - " -2.41215586e-01]),\n", - " array([ 4.09719222e-06, 9.37223482e-03, 1.06787466e+00, 2.45750865e-02,\n", - " -7.89358143e-05, 7.50690893e-06, -9.99697984e-01, 2.62277955e-03,\n", - " -6.38063492e+00, 3.26389727e-03, -1.97122606e-04, -2.57232520e-03,\n", - " 3.08670434e-02, -3.39957122e-04, 7.20798124e-01, 1.82476170e+00,\n", - " 5.27906577e+00, -2.04459349e-03, 1.31097064e-03, 2.97864404e-02,\n", - " 5.39910254e+00, 1.50477144e-03, 3.35526624e-03, -1.72822376e-03,\n", - " -2.40737821e-01]),\n", - " array([ 4.05219408e-06, 1.01854345e-02, 1.06962552e+00, 2.19583105e-02,\n", - " -7.78614541e-05, 7.02644830e-06, -9.99758884e-01, 2.65263911e-03,\n", - " -6.37528035e+00, 3.26543209e-03, -1.93793149e-04, -2.57398286e-03,\n", - " 3.06268517e-02, -3.33644915e-04, 7.30868446e-01, 1.78680121e+00,\n", - " 5.23497055e+00, -2.14201533e-03, 1.32185661e-03, 2.98595659e-02,\n", - " 5.35456998e+00, 1.53481881e-03, 3.32945691e-03, -1.65765323e-03,\n", - " -2.40191702e-01]),\n", - " array([ 4.00340631e-06, 1.09976489e-02, 1.07134204e+00, 1.93669165e-02,\n", - " -7.67401742e-05, 6.54236185e-06, -9.99812441e-01, 2.68256425e-03,\n", - " -6.36997735e+00, 3.26697923e-03, -1.90490170e-04, -2.57556946e-03,\n", - " 3.03872684e-02, -3.27239770e-04, 7.40601205e-01, 1.74861221e+00,\n", - " 5.18389616e+00, -2.23520436e-03, 1.32299014e-03, 2.99251407e-02,\n", - " 5.30299469e+00, 1.54713648e-03, 3.30297892e-03, -1.58660792e-03,\n", - " -2.39583340e-01]),\n", - " array([ 3.95085588e-06, 1.18089937e-02, 1.07302397e+00, 1.68041003e-02,\n", - " -7.55739648e-05, 6.05906192e-06, -9.99858798e-01, 2.71254779e-03,\n", - " -6.36473234e+00, 3.26852136e-03, -1.87214211e-04, -2.57708442e-03,\n", - " 3.01483499e-02, -3.20765248e-04, 7.49987484e-01, 1.71017768e+00,\n", - " 5.12647221e+00, -2.32428515e-03, 1.31519675e-03, 2.99835383e-02,\n", - " 5.24501208e+00, 1.54213696e-03, 3.27595920e-03, -1.51495415e-03,\n", - " -2.38918515e-01]),\n", - " array([ 3.89456916e-06, 1.26195847e-02, 1.07467106e+00, 1.42727600e-02,\n", - " -7.43647825e-05, 5.58056645e-06, -9.99898136e-01, 2.74258295e-03,\n", - " -6.35955112e+00, 3.27004162e-03, -1.83965693e-04, -2.57852699e-03,\n", - " 2.99101472e-02, -3.14243966e-04, 7.59020221e-01, 1.67148207e+00,\n", - " 5.06329305e+00, -2.40937797e-03, 1.29930229e-03, 3.00351620e-02,\n", - " 5.18122193e+00, 1.52025321e-03, 3.24851745e-03, -1.44257062e-03,\n", - " -2.38202678e-01]),\n", - " array([ 3.83457231e-06, 1.34295380e-02, 1.07628302e+00, 1.17755132e-02,\n", - " -7.31145487e-05, 5.11050114e-06, -9.99930664e-01, 2.77266339e-03,\n", - " -6.35443893e+00, 3.27152355e-03, -1.80744927e-04, -2.57989634e-03,\n", - " 2.96727062e-02, -3.07697567e-04, 7.67694067e-01, 1.63251115e+00,\n", - " 4.99491852e+00, -2.49059933e-03, 1.27612508e-03, 3.00804367e-02,\n", - " 5.11218927e+00, 1.48193429e-03, 3.22076635e-03, -1.36934774e-03,\n", - " -2.37440961e-01]),\n", - " array([ 3.77089156e-06, 1.42389700e-02, 1.07785955e+00, 9.31471324e-03,\n", - " -7.18251488e-05, 4.65210505e-06, -9.99956615e-01, 2.80278319e-03,\n", - " -6.34940048e+00, 3.27295119e-03, -1.77552115e-04, -2.58119152e-03,\n", - " 2.94360680e-02, -3.01146697e-04, 7.76005249e-01, 1.59325197e+00,\n", - " 4.92187481e+00, -2.56806221e-03, 1.24646899e-03, 3.01198023e-02,\n", - " 5.03844510e+00, 1.42764107e-03, 3.19281186e-03, -1.29518696e-03,\n", - " -2.36638184e-01]),\n", - " array([ 3.70355358e-06, 1.50479979e-02, 1.07940033e+00, 6.89246568e-03,\n", - " -7.04984302e-05, 4.20823929e-06, -9.99976244e-01, 2.83293690e-03,\n", - " -6.34444000e+00, 3.27430903e-03, -1.74387362e-04, -2.58241152e-03,\n", - " 2.92002692e-02, -2.94610983e-04, 7.83951449e-01, 1.55369270e+00,\n", - " 4.84465530e+00, -2.64187641e-03, 1.21111739e-03, 3.01537068e-02,\n", - " 4.96048735e+00, 1.35784216e-03, 3.16475345e-03, -1.22000011e-03,\n", - " -2.35798864e-01]),\n", - " array([ 3.63258579e-06, 1.58567394e-02, 1.08090503e+00, 4.51064421e-03,\n", - " -6.91362009e-05, 3.78139839e-06, -9.99989825e-01, 2.86311950e-03,\n", - " -6.33956122e+00, 3.27558204e-03, -1.71250677e-04, -2.58355523e-03,\n", - " 2.89653419e-02, -2.88109027e-04, 7.91531680e-01, 1.51382259e+00,\n", - " 4.76372144e+00, -2.71214870e-03, 1.17082804e-03, 3.01826011e-02,\n", - " 4.87878168e+00, 1.27300993e-03, 3.13668440e-03, -1.14370874e-03,\n", - " -2.34927219e-01]),\n", - " array([ 3.55801665e-06, 1.66653131e-02, 1.08237329e+00, 2.17090598e-03,\n", - " -6.77402283e-05, 3.37372381e-06, -9.99997641e-01, 2.89332643e-03,\n", - " -6.33476745e+00, 3.27675566e-03, -1.68141985e-04, -2.58462148e-03,\n", - " 2.87313148e-02, -2.81658400e-04, 7.98746174e-01, 1.47363184e+00,\n", - " 4.67950359e+00, -2.77898295e-03, 1.12632876e-03, 3.02069333e-02,\n", - " 4.79376244e+00, 1.17361682e-03, 3.10869202e-03, -1.06624347e-03,\n", - " -2.34027185e-01]),\n", - " array([ 3.47987592e-06, 1.74738385e-02, 1.08380475e+00, -1.25293349e-04,\n", - " -6.63122379e-05, 2.98701938e-06, -9.99999990e-01, 2.92355358e-03,\n", - " -6.33006162e+00, 3.27781579e-03, -1.65061127e-04, -2.58560902e-03,\n", - " 2.84982123e-02, -2.75275646e-04, 8.05596275e-01, 1.43311159e+00,\n", - " 4.59240201e+00, -2.84248016e-03, 1.07831391e-03, 3.02271446e-02,\n", - " 4.70583354e+00, 1.06013177e-03, 3.08085798e-03, -9.87543295e-04,\n", - " -2.33102415e-01]),\n", - " array([ 3.39819495e-06, 1.82824363e-02, 1.08519903e+00, -2.37668500e-03,\n", - " -6.48539126e-05, 2.62276811e-06, -9.99997174e-01, 2.95379725e-03,\n", - " -6.32544625e+00, 3.27874881e-03, -1.62007869e-04, -2.58651657e-03,\n", - " 2.82660561e-02, -2.68976290e-04, 8.12084334e-01, 1.39225379e+00,\n", - " 4.50278773e+00, -2.90273844e-03, 1.02744165e-03, 3.02436657e-02,\n", - " 4.61536942e+00, 9.33016919e-04, 3.05325857e-03, -9.07555016e-04,\n", - " -2.32156293e-01]),\n", - " array([ 3.31300690e-06, 1.90912277e-02, 1.08655574e+00, -4.58217298e-03,\n", - " -6.33668914e-05, 2.28215019e-06, -9.99989500e-01, 2.98405416e-03,\n", - " -6.32092353e+00, 3.27954153e-03, -1.58981904e-04, -2.58734281e-03,\n", - " 2.80348641e-02, -2.62774853e-04, 8.18213618e-01, 1.35105115e+00,\n", - " 4.41100351e+00, -2.95985290e-03, 9.74331857e-04, 3.02569132e-02,\n", - " 4.52271598e+00, 7.92724527e-04, 3.02596491e-03, -8.26232577e-04,\n", - " -2.31191944e-01]),\n", - " array([ 3.22434699e-06, 1.99003353e-02, 1.08787449e+00, -6.74082037e-03,\n", - " -6.18527698e-05, 1.96606173e-06, -9.99977278e-01, 3.01432145e-03,\n", - " -6.31649534e+00, 3.28018123e-03, -1.55982860e-04, -2.58808634e-03,\n", - " 2.78046519e-02, -2.56684875e-04, 8.23988219e-01, 1.30949711e+00,\n", - " 4.31736476e+00, -3.01391553e-03, 9.19564705e-04, 3.02672872e-02,\n", - " 4.42819153e+00, 6.39694106e-04, 2.99904329e-03, -7.43536500e-04,\n", - " -2.30212237e-01]),\n", - " array([ 3.13225273e-06, 2.07098824e-02, 1.08915485e+00, -8.85183609e-03,\n", - " -6.03130990e-05, 1.67513398e-06, -9.99960820e-01, 3.04459661e-03,\n", - " -6.31216325e+00, 3.28065558e-03, -1.53010305e-04, -2.58874578e-03,\n", - " 2.75754321e-02, -2.50718937e-04, 8.29412965e-01, 1.26758575e+00,\n", - " 4.22216052e+00, -3.06501497e-03, 8.63679828e-04, 3.02751691e-02,\n", - " 4.33208775e+00, 4.74349819e-04, 2.97255536e-03, -6.59433323e-04,\n", - " -2.29219801e-01]),\n", - " array([ 3.03676407e-06, 2.15199933e-02, 1.09039641e+00, -1.09145622e-02,\n", - " -5.87493866e-05, 1.40975284e-06, -9.99940433e-01, 3.07487753e-03,\n", - " -6.30792858e+00, 3.28095268e-03, -1.50063747e-04, -2.58931967e-03,\n", - " 2.73472150e-02, -2.44888696e-04, 8.34493351e-01, 1.22531177e+00,\n", - " 4.12565440e+00, -3.11323629e-03, 8.07176008e-04, 3.02809202e-02,\n", - " 4.23467069e+00, 2.97098117e-04, 2.94655839e-03, -5.73895065e-04,\n", - " -2.28217026e-01]),\n", - " array([ 2.93792363e-06, 2.23307932e-02, 1.09159876e+00, -1.29284615e-02,\n", - " -5.71630972e-05, 1.17007831e-06, -9.99916422e-01, 3.10516241e-03,\n", - " -6.30379240e+00, 3.28106100e-03, -1.47142641e-04, -2.58980657e-03,\n", - " 2.71200090e-02, -2.39204911e-04, 8.39235456e-01, 1.18267045e+00,\n", - " 4.02808557e+00, -3.15866069e-03, 7.50511322e-04, 3.02848803e-02,\n", - " 4.13618168e+00, 1.08325612e-04, 2.92110553e-03, -4.86898728e-04,\n", - " -2.27206080e-01]),\n", - " array([ 2.83577683e-06, 2.31424080e-02, 1.09276144e+00, -1.48931060e-02,\n", - " -5.55556532e-05, 9.56063751e-07, -9.99889090e-01, 3.13544978e-03,\n", - " -6.29975556e+00, 3.28096940e-03, -1.44246395e-04, -2.59020500e-03,\n", - " 2.68938200e-02, -2.33677485e-04, 8.43645883e-01, 1.13965757e+00,\n", - " 3.92966967e+00, -3.20136522e-03, 6.94103713e-04, 3.02873672e-02,\n", - " 4.03683834e+00, -9.16028053e-05, 2.89624597e-03, -3.98425825e-04,\n", - " -2.26188914e-01]),\n", - " array([ 2.73037208e-06, 2.39549645e-02, 1.09388403e+00, -1.68081649e-02,\n", - " -5.39284363e-05, 7.67474725e-07, -9.99858731e-01, 3.16573846e-03,\n", - " -6.29581873e+00, 3.28066705e-03, -1.41374370e-04, -2.59051346e-03,\n", - " 2.66686528e-02, -2.28315500e-04, 8.47731690e-01, 1.09626946e+00,\n", - " 3.83059979e+00, -3.24142245e-03, 6.38331894e-04, 3.02886760e-02,\n", - " 3.93683554e+00, -3.02345608e-04, 2.87202521e-03, -3.08461949e-04,\n", - " -2.25167268e-01]),\n", - " array([ 2.62176090e-06, 2.47685898e-02, 1.09496608e+00, -1.86733948e-02,\n", - " -5.22827891e-05, 6.03907336e-07, -9.99825636e-01, 3.19602754e-03,\n", - " -6.29198238e+00, 3.28014347e-03, -1.38525885e-04, -2.59073046e-03,\n", - " 2.64445101e-02, -2.23127258e-04, 8.51500341e-01, 1.05250289e+00,\n", - " 3.73104745e+00, -3.27890010e-03, 5.83536580e-04, 3.02890792e-02,\n", - " 3.83634634e+00, -5.23586044e-04, 2.84848522e-03, -2.16996364e-04,\n", - " -2.24142686e-01]),\n", - " array([ 2.50999802e-06, 2.55834117e-02, 1.09600713e+00, -2.04886282e-02,\n", - " -5.06200173e-05, 4.64805847e-07, -9.99790085e-01, 3.22631636e-03,\n", - " -6.28824686e+00, 3.27938843e-03, -1.35700220e-04, -2.59085448e-03,\n", - " 2.62213936e-02, -2.18120321e-04, 8.54959645e-01, 1.00835511e+00,\n", - " 3.63116352e+00, -3.31386075e-03, 5.30021943e-04, 3.02888272e-02,\n", - " 3.73552302e+00, -7.55033314e-04, 2.82566465e-03, -1.24021640e-04,\n", - " -2.23116521e-01]),\n", - " array([ 2.39514152e-06, 2.63995584e-02, 1.09700675e+00, -2.22537644e-02,\n", - " -4.89413918e-05, 3.49479543e-07, -9.99752353e-01, 3.25660451e-03,\n", - " -6.28461236e+00, 3.27839201e-03, -1.32896621e-04, -2.59088401e-03,\n", - " 2.59993036e-02, -2.13301548e-04, 8.58117716e-01, 9.63823795e-01,\n", - " 3.53107920e+00, -3.34636145e-03, 4.78057277e-04, 3.02881481e-02,\n", - " 3.63449795e+00, -9.96423533e-04, 2.80359896e-03, -2.95333170e-05,\n", - " -2.22089944e-01]),\n", - " array([ 2.27725292e-06, 2.72171583e-02, 1.09796446e+00, -2.39687595e-02,\n", - " -4.72481515e-05, 2.57118727e-07, -9.99712707e-01, 3.28689176e-03,\n", - " -6.28107898e+00, 3.27714449e-03, -1.30114301e-04, -2.59081754e-03,\n", - " 2.57782397e-02, -2.08677141e-04, 8.60982925e-01, 9.18907064e-01,\n", - " 3.43090694e+00, -3.37645343e-03, 4.27878816e-04, 3.02872490e-02,\n", - " 3.53338459e+00, -1.24752048e-03, 2.78232065e-03, 6.64704008e-05,\n", - " -2.21063955e-01]),\n", - " array([ 2.15639724e-06, 2.80363399e-02, 1.09887981e+00, -2.56336177e-02,\n", - " -4.55415063e-05, 1.86809806e-07, -9.99671404e-01, 3.31717808e-03,\n", - " -6.27764670e+00, 3.27563637e-03, -1.27352441e-04, -2.59065355e-03,\n", - " 2.55582003e-02, -2.04252679e-04, 8.63563866e-01, 8.73603451e-01,\n", - " 3.33074136e+00, -3.40418177e-03, 3.79691664e-04, 3.02863164e-02,\n", - " 3.43227846e+00, -1.50811611e-03, 2.76185934e-03, 1.63988913e-04,\n", - " -2.20039387e-01]),\n", - " array([ 2.03264308e-06, 2.88572318e-02, 1.09975233e+00, -2.72483829e-02,\n", - " -4.38226402e-05, 1.37549411e-07, -9.99628693e-01, 3.34746360e-03,\n", - " -6.27431544e+00, 3.27385834e-03, -1.24610199e-04, -2.59039053e-03,\n", - " 2.53391834e-02, -2.00033160e-04, 8.65869320e-01, 8.27911911e-01,\n", - " 3.23066023e+00, -3.42958507e-03, 3.33671793e-04, 3.02855174e-02,\n", - " 3.33125800e+00, -1.77803093e-03, 2.74224194e-03, 2.63019461e-04,\n", - " -2.19016920e-01]),\n", - " array([ 1.90606267e-06, 2.96799624e-02, 1.10058158e+00, -2.88131303e-02,\n", - " -4.20927147e-05, 1.08257553e-07, -9.99584815e-01, 3.37774860e-03,\n", - " -6.27108505e+00, 3.27180123e-03, -1.21886706e-04, -2.59002697e-03,\n", - " 2.51211863e-02, -1.96023030e-04, 8.67908230e-01, 7.81831816e-01,\n", - " 3.13072535e+00, -3.45269522e-03, 2.89968082e-04, 3.02850005e-02,\n", - " 3.23038558e+00, -2.05711411e-03, 2.72349280e-03, 3.63557340e-04,\n", - " -2.17997087e-01]),\n", - " array([ 1.77673191e-06, 3.05046596e-02, 1.10136706e+00, -3.03279592e-02,\n", - " -4.03528725e-05, 9.77897800e-08, -9.99540001e-01, 3.40803349e-03,\n", - " -6.26795535e+00, 3.26945599e-03, -1.19181073e-04, -2.58956138e-03,\n", - " 2.49042060e-02, -1.92226224e-04, 8.69689669e-01, 7.35362965e-01,\n", - " 3.03098346e+00, -3.47353712e-03, 2.48704364e-04, 3.02848970e-02,\n", - " 3.12970836e+00, -2.34524348e-03, 2.70563375e-03, 4.65596073e-04,\n", - " -2.16980282e-01]),\n", - " array([ 1.64473038e-06, 3.13314511e-02, 1.10210834e+00, -3.17929854e-02,\n", - " -3.86042413e-05, 1.04948374e-07, -9.99494475e-01, 3.43831881e-03,\n", - " -6.26492609e+00, 3.26681366e-03, -1.16492388e-04, -2.58899225e-03,\n", - " 2.46882392e-02, -1.88646193e-04, 8.71222827e-01, 6.88505589e-01,\n", - " 2.93146718e+00, -3.49212851e-03, 2.09981441e-04, 3.02853220e-02,\n", - " 3.02925924e+00, -2.64232528e-03, 2.68868429e-03, 5.69127561e-04,\n", - " -2.15966768e-01]),\n", - " array([ 1.51014137e-06, 3.21604638e-02, 1.10280493e+00, -3.32083351e-02,\n", - " -3.68479374e-05, 1.28492589e-07, -9.99448450e-01, 3.46860519e-03,\n", - " -6.26199703e+00, 3.26386537e-03, -1.13819727e-04, -2.58831811e-03,\n", - " 2.44732825e-02, -1.85285929e-04, 8.72516990e-01, 6.41260360e-01,\n", - " 2.83219586e+00, -3.50847972e-03, 1.73879061e-04, 3.02863755e-02,\n", - " 2.92905772e+00, -2.94829382e-03, 2.67266163e-03, 6.74142204e-04,\n", - " -2.14956688e-01]),\n", - " array([ 1.37305185e-06, 3.29918238e-02, 1.10345637e+00, -3.45741382e-02,\n", - " -3.50850704e-05, 1.67147971e-07, -9.99402135e-01, 3.49889333e-03,\n", - " -6.25916792e+00, 3.26060226e-03, -1.11162146e-04, -2.58753748e-03,\n", - " 2.42593325e-02, -1.82147995e-04, 8.73581527e-01, 5.93628411e-01,\n", - " 2.73317645e+00, -3.52259362e-03, 1.40457824e-04, 3.02881439e-02,\n", - " 2.82911084e+00, -3.26311091e-03, 2.65758077e-03, 7.80628998e-04,\n", - " -2.13950069e-01]),\n", - " array([ 1.23355248e-06, 3.38256561e-02, 1.10406220e+00, -3.58905225e-02,\n", - " -3.33167467e-05, 2.19614806e-07, -9.99355727e-01, 3.52918404e-03,\n", - " -6.25643850e+00, 3.25701549e-03, -1.08518691e-04, -2.58664890e-03,\n", - " 2.40463856e-02, -1.79234546e-04, 8.74425880e-01, 5.45611349e-01,\n", - " 2.63440444e+00, -3.53446545e-03, 1.09760994e-04, 3.02907009e-02,\n", - " 2.72941401e+00, -3.58676521e-03, 2.64345461e-03, 8.88575599e-04,\n", - " -2.12946833e-01]),\n", - " array([ 1.09173757e-06, 3.46620846e-02, 1.10462197e+00, -3.71576088e-02,\n", - " -3.15440740e-05, 2.84575731e-07, -9.99309417e-01, 3.55947814e-03,\n", - " -6.25380855e+00, 3.25309622e-03, -1.05888397e-04, -2.58565094e-03,\n", - " 2.38344388e-02, -1.76547341e-04, 8.75059559e-01, 4.97211280e-01,\n", - " 2.53586465e+00, -3.54408282e-03, 8.18162189e-05, 3.02941085e-02,\n", - " 2.62995190e+00, -3.91927139e-03, 2.63029398e-03, 9.97968377e-04,\n", - " -2.11946805e-01]),\n", - " array([ 9.47705031e-07, 3.55012319e-02, 1.10513520e+00, -3.83755053e-02,\n", - " -2.97681654e-05, 3.60702584e-07, -9.99263389e-01, 3.58977656e-03,\n", - " -6.25127785e+00, 3.24883555e-03, -1.03270290e-04, -2.58454214e-03,\n", - " 2.36234891e-02, -1.74087766e-04, 8.75492137e-01, 4.48430828e-01,\n", - " 2.43753211e+00, -3.55142566e-03, 5.66371259e-05, 3.02984187e-02,\n", - " 2.53069929e+00, -4.26066913e-03, 2.61810771e-03, 1.10879243e-03,\n", - " -2.10949719e-01]),\n", - " array([ 8.01556293e-07, 3.63432187e-02, 1.10560145e+00, -3.95443036e-02,\n", - " -2.79901435e-05, 4.46662537e-07, -9.99217818e-01, 3.62008024e-03,\n", - " -6.24884623e+00, 3.24422453e-03, -1.00663387e-04, -2.58332111e-03,\n", - " 2.34135339e-02, -1.71856835e-04, 8.75733251e-01, 3.99273167e-01,\n", - " 2.33937287e+00, -3.55646629e-03, 3.42248010e-05, 3.03036738e-02,\n", - " 2.43162193e+00, -4.61102209e-03, 2.60690270e-03, 1.22103158e-03,\n", - " -2.09955226e-01]),\n", - " array([ 6.53396267e-07, 3.71881643e-02, 1.10602025e+00, -4.06640744e-02,\n", - " -2.62111449e-05, 5.41123589e-07, -9.99172874e-01, 3.65039014e-03,\n", - " -6.24651355e+00, 3.23925411e-03, -9.80667031e-05, -2.58198644e-03,\n", - " 2.32045710e-02, -1.69855208e-04, 8.75792603e-01, 3.49742041e-01,\n", - " 2.24134486e+00, -3.55916948e-03, 1.45691330e-05, 3.03099079e-02,\n", - " 2.33267732e+00, -4.97041666e-03, 2.59668391e-03, 1.33466838e-03,\n", - " -2.08962904e-01]),\n", - " array([ 5.03333229e-07, 3.80361857e-02, 1.10639117e+00, -4.17348637e-02,\n", - " -2.44323238e-05, 6.42759478e-07, -9.99128721e-01, 3.68070729e-03,\n", - " -6.24427974e+00, 3.23391515e-03, -9.54792487e-05, -2.58053676e-03,\n", - " 2.29965987e-02, -1.68083185e-04, 8.75679964e-01, 2.99841806e-01,\n", - " 2.14339866e+00, -3.55949260e-03, -2.34997673e-06, 3.03171473e-02,\n", - " 2.23381561e+00, -5.33896063e-03, 2.58745444e-03, 1.44968405e-03,\n", - " -2.07972261e-01]),\n", - " array([ 3.51478721e-07, 3.88873977e-02, 1.10671376e+00, -4.27566898e-02,\n", - " -2.26548564e-05, 7.50254079e-07, -9.99085514e-01, 3.71103270e-03,\n", - " -6.24214476e+00, 3.22819837e-03, -9.29000331e-05, -2.57897070e-03,\n", - " 2.27896160e-02, -1.66540711e-04, 8.75405184e-01, 2.49577452e-01,\n", - " 2.04547835e+00, -3.55738576e-03, -1.65615422e-05, 3.03254121e-02,\n", - " 2.13498032e+00, -5.71678176e-03, 2.57921553e-03, 1.56605841e-03,\n", - " -2.06982747e-01]),\n", - " array([ 1.97947422e-07, 3.97419127e-02, 1.10698757e+00, -4.37295400e-02,\n", - " -2.08799446e-05, 8.62305368e-07, -9.99043406e-01, 3.74136742e-03,\n", - " -6.24010865e+00, 3.22209434e-03, -9.03280665e-05, -2.57728693e-03,\n", - " 2.25836222e-02, -1.65227372e-04, 8.74978197e-01, 1.98954646e-01,\n", - " 1.94752223e+00, -3.55279210e-03, -2.81025580e-05, 3.03347160e-02,\n", - " 2.03610918e+00, -6.10402624e-03, 2.57196661e-03, 1.68376986e-03,\n", - " -2.05993758e-01]),\n", - " array([ 4.28570140e-08, 4.05998402e-02, 1.10721218e+00, -4.46533684e-02,\n", - " -1.91088198e-05, 9.77629005e-07, -9.99002541e-01, 3.77171249e-03,\n", - " -6.23817151e+00, 3.21559349e-03, -8.77623612e-05, -2.57548414e-03,\n", - " 2.23786176e-02, -1.64142389e-04, 8.74409037e-01, 1.47979764e-01,\n", - " 1.84946366e+00, -3.54564800e-03, -3.70172010e-05, 3.03450677e-02,\n", - " 1.93713492e+00, -6.50085705e-03, 2.56570527e-03, 1.80279523e-03,\n", - " -2.05004645e-01]),\n", - " array([-1.13671981e-07, 4.14612871e-02, 1.10738716e+00, -4.55280936e-02,\n", - " -1.73427464e-05, 1.09496161e-06, -9.98963059e-01, 3.80206896e-03,\n", - " -6.23633353e+00, 3.20868603e-03, -8.52019339e-05, -2.57356103e-03,\n", - " 2.21746029e-02, -1.63284606e-04, 8.73707842e-01, 9.66599316e-02,\n", - " 1.75123174e+00, -3.53588341e-03, -4.33561650e-05, 3.03564712e-02,\n", - " 1.83798600e+00, -6.90745224e-03, 2.56042733e-03, 1.92310972e-03,\n", - " -2.04014719e-01]),\n", - " array([-2.71516373e-07, 4.23263567e-02, 1.10751209e+00, -4.63535972e-02,\n", - " -1.55830254e-05, 1.21306381e-06, -9.98925094e-01, 3.83243788e-03,\n", - " -6.23459494e+00, 3.20136203e-03, -8.26458071e-05, -2.57151634e-03,\n", - " 2.19715796e-02, -1.62652476e-04, 8.72884877e-01, 4.50030627e-02,\n", - " 1.65275216e+00, -3.52342225e-03, -4.71761223e-05, 3.03689262e-02,\n", - " 1.73858738e+00, -7.32400309e-03, 2.55612680e-03, 2.04468677e-03,\n", - " -2.03023260e-01]),\n", - " array([-4.30550498e-07, 4.31951491e-02, 1.10758656e+00, -4.71297218e-02,\n", - " -1.38309975e-05, 1.33072304e-06, -9.98888777e-01, 3.86282031e-03,\n", - " -6.23295608e+00, 3.19361132e-03, -8.00930112e-05, -2.56934884e-03,\n", - " 2.17695501e-02, -1.62244053e-04, 8.71950542e-01, -6.98209939e-03,\n", - " 1.55394782e+00, -3.50818273e-03, -4.85393068e-05, 3.03824289e-02,\n", - " 1.63886125e+00, -7.75071222e-03, 2.55279590e-03, 2.16749794e-03,\n", - " -2.02029523e-01]),\n", - " array([-5.90646433e-07, 4.40677606e-02, 1.10761017e+00, -4.78562708e-02,\n", - " -1.20880459e-05, 1.44675634e-06, -9.98854232e-01, 3.89321729e-03,\n", - " -6.23141735e+00, 3.18542353e-03, -7.75425861e-05, -2.56705733e-03,\n", - " 2.15685173e-02, -1.62056963e-04, 8.70915392e-01, -5.92859397e-02,\n", - " 1.45473964e+00, -3.49007787e-03, -4.75132113e-05, 3.03969718e-02,\n", - " 1.53872780e+00, -8.18779163e-03, 2.55042509e-03, 2.29151277e-03,\n", - " -2.01032744e-01]),\n", - " array([-7.51674222e-07, 4.49442833e-02, 1.10758254e+00, -4.85330071e-02,\n", - " -1.03555993e-05, 1.56001291e-06, -9.98821579e-01, 3.92362983e-03,\n", - " -6.22997925e+00, 3.17678807e-03, -7.49935831e-05, -2.56464063e-03,\n", - " 2.13684852e-02, -1.62088394e-04, 8.69790147e-01, -1.11897929e-01,\n", - " 1.35504719e+00, -3.46901595e-03, -4.41703886e-05, 3.04125449e-02,\n", - " 1.43810584e+00, -8.63546062e-03, 2.54900300e-03, 2.41669863e-03,\n", - " -2.00032145e-01]),\n", - " array([-9.13502130e-07, 4.58248053e-02, 1.10750327e+00, -4.91596529e-02,\n", - " -8.63513434e-06, 1.66937678e-06, -9.98790933e-01, 3.95405897e-03,\n", - " -6.22864233e+00, 3.16769412e-03, -7.24450666e-05, -2.56209761e-03,\n", - " 2.11694582e-02, -1.62335065e-04, 8.68585716e-01, -1.64806581e-01,\n", - " 1.25478944e+00, -3.44490100e-03, -3.85883486e-05, 3.04291350e-02,\n", - " 1.33691358e+00, -9.09394372e-03, 2.54851649e-03, 2.54302061e-03,\n", - " -1.99026944e-01]),\n", - " array([-1.07599691e-06, 4.67094100e-02, 1.10737200e+00, -4.97358898e-02,\n", - " -6.92817751e-06, 1.77376943e-06, -9.98762405e-01, 3.98450569e-03,\n", - " -6.22740726e+00, 3.15813065e-03, -6.98961160e-05, -2.55942717e-03,\n", - " 2.09714419e-02, -1.62793208e-04, 8.67313208e-01, -2.17999407e-01,\n", - " 1.15388539e+00, -3.41763339e-03, -3.08495391e-05, 3.04467265e-02,\n", - " 1.23506926e+00, -9.56346846e-03, 2.54895062e-03, 2.67044128e-03,\n", - " -1.98016359e-01]),\n", - " array([-1.23902411e-06, 4.75981758e-02, 1.10718839e+00, -5.02613592e-02,\n", - " -5.23630739e-06, 1.87215244e-06, -9.98736099e-01, 4.01497099e-03,\n", - " -6.22627477e+00, 3.14808639e-03, -6.73458274e-05, -2.55662825e-03,\n", - " 2.07744423e-02, -1.63458539e-04, 8.65983950e-01, -2.71462873e-01,\n", - " 1.05225475e+00, -3.38711042e-03, -2.10414000e-05, 3.04653016e-02,\n", - " 1.13249184e+00, -1.00442632e-02, 2.55028863e-03, 2.79892060e-03,\n", - " -1.96999614e-01]),\n", - " array([-1.40244836e-06, 4.84911761e-02, 1.10695207e+00, -5.07356625e-02,\n", - " -3.56115601e-06, 1.96353026e-06, -9.98712117e-01, 4.04545583e-03,\n", - " -6.22524567e+00, 3.13754984e-03, -6.47933154e-05, -2.55369983e-03,\n", - " 2.05784663e-02, -1.64326232e-04, 8.64609502e-01, -3.25182353e-01,\n", - " 9.49818563e-01, -3.35322687e-03, -9.25647937e-06, 3.04848400e-02,\n", - " 1.02910164e+00, -1.05365547e-02, 2.55251195e-03, 2.92841574e-03,\n", - " -1.95975946e-01]),\n", - " array([-1.56613370e-06, 4.93884789e-02, 1.10666274e+00, -5.11583628e-02,\n", - " -1.90441025e-06, 2.04695305e-06, -9.98690554e-01, 4.07596115e-03,\n", - " -6.22432085e+00, 3.12650927e-03, -6.22377152e-05, -2.55064095e-03,\n", - " 2.03835217e-02, -1.65390893e-04, 8.63201672e-01, -3.79142089e-01,\n", - " 8.46499865e-01, -3.31587572e-03, 4.40740224e-06, 3.05053197e-02,\n", - " 9.24820949e-01, -1.10405659e-02, 2.55560020e-03, 3.05888087e-03,\n", - " -1.94944607e-01]),\n", - " array([-1.72994396e-06, 5.02901461e-02, 1.10632008e+00, -5.15289854e-02,\n", - " -2.67812655e-07, 2.12151968e-06, -9.98671499e-01, 4.10648787e-03,\n", - " -6.22350127e+00, 3.11495276e-03, -5.96781841e-05, -2.54745068e-03,\n", - " 2.01896168e-02, -1.66646529e-04, 8.61772531e-01, -4.33325145e-01,\n", - " 7.42224255e-01, -3.27494873e-03, 1.98469521e-05, 3.05267165e-02,\n", - " 8.19574685e-01, -1.15565138e-02, 2.55953114e-03, 3.19026703e-03,\n", - " -1.93904876e-01]),\n", - " array([-1.89374311e-06, 5.11962340e-02, 1.10592379e+00, -5.18470200e-02,\n", - " 1.34683787e-06, 2.18638082e-06, -9.98655039e-01, 4.13703687e-03,\n", - " -6.22278798e+00, 3.10286815e-03, -5.71139034e-05, -2.54412816e-03,\n", - " 1.99967608e-02, -1.68086523e-04, 8.60334423e-01, -4.87713360e-01,\n", - " 6.36920508e-01, -3.23033719e-03, 3.69531807e-05, 3.05490044e-02,\n", - " 7.13290952e-01, -1.20846063e-02, 2.56428070e-03, 3.32252194e-03,\n", - " -1.92856058e-01]),\n", - " array([-2.05739565e-06, 5.21067921e-02, 1.10547360e+00, -5.21119220e-02,\n", - " 2.93768590e-06, 2.24074215e-06, -9.98641251e-01, 4.16760903e-03,\n", - " -6.22218208e+00, 3.09024311e-03, -5.45440804e-05, -2.54067257e-03,\n", - " 1.98049633e-02, -1.69703604e-04, 8.58899978e-01, -5.42287313e-01,\n", - " 5.30521145e-01, -3.18193257e-03, 5.56111633e-05, 3.05721558e-02,\n", - " 6.05901634e-01, -1.26250406e-02, 2.56982298e-03, 3.45558985e-03,\n", - " -1.91797494e-01]),\n", - " array([-2.22076702e-06, 5.30218635e-02, 1.10496926e+00, -5.23231149e-02,\n", - " 4.50281957e-06, 2.28386780e-06, -9.98630208e-01, 4.19820517e-03,\n", - " -6.22168474e+00, 3.07706511e-03, -5.19679502e-05, -2.53708316e-03,\n", - " 1.96142347e-02, -1.71489823e-04, 8.57482122e-01, -5.97026275e-01,\n", - " 4.22962985e-01, -3.12962726e-03, 7.56998203e-05, 3.05961412e-02,\n", - " 4.97342958e-01, -1.31780001e-02, 2.57613021e-03, 3.58941134e-03,\n", - " -1.90728564e-01]),\n", - " array([-2.38372403e-06, 5.39414841e-02, 1.10441053e+00, -5.24799929e-02,\n", - " 6.04027109e-06, 2.31508377e-06, -9.98621976e-01, 4.22882610e-03,\n", - " -6.22129718e+00, 3.06332146e-03, -4.93847775e-05, -2.53335924e-03,\n", - " 1.94245860e-02, -1.73436523e-04, 8.56094078e-01, -6.51908171e-01,\n", - " 3.14187684e-01, -3.07331526e-03, 9.70917009e-05, 3.06209302e-02,\n", - " 3.87556028e-01, -1.37436524e-02, 2.58317277e-03, 3.72392318e-03,\n", - " -1.89648691e-01]),\n", - " array([-2.54613531e-06, 5.48656829e-02, 1.10379720e+00, -5.25819231e-02,\n", - " 7.54801761e-06, 2.33378160e-06, -9.98616614e-01, 4.25947259e-03,\n", - " -6.22102069e+00, 3.04899931e-03, -4.67938582e-05, -2.52950018e-03,\n", - " 1.92360287e-02, -1.75534316e-04, 8.54749380e-01, -7.06909543e-01,\n", - " 2.04142247e-01, -3.01289297e-03, 1.19652727e-04, 3.06464906e-02,\n", - " 2.76487351e-01, -1.43221463e-02, 2.59091920e-03, 3.85905816e-03,\n", - " -1.88557348e-01]),\n", - " array([-2.70787173e-06, 5.57944809e-02, 1.10312908e+00, -5.26282487e-02,\n", - " 9.02398244e-06, 2.33942188e-06, -9.98614173e-01, 4.29014538e-03,\n", - " -6.22085661e+00, 3.03408570e-03, -4.41945221e-05, -2.52550543e-03,\n", - " 1.90485746e-02, -1.77773062e-04, 8.53461865e-01, -7.62005508e-01,\n", - " 9.27795300e-02, -2.94825978e-03, 1.43242457e-04, 3.06727898e-02,\n", - " 1.64089332e-01, -1.49136097e-02, 2.59933619e-03, 3.99474495e-03,\n", - " -1.87454061e-01]),\n", - " array([-2.86880692e-06, 5.67278916e-02, 1.10240601e+00, -5.26182918e-02,\n", - " 1.04660367e-05, 2.33153827e-06, -9.98614698e-01, 4.32084518e-03,\n", - " -6.22080628e+00, 3.01856755e-03, -4.15861335e-05, -2.52137453e-03,\n", - " 1.88622362e-02, -1.80141846e-04, 8.52245678e-01, -8.17169729e-01,\n", - " -1.99412929e-02, -2.87931900e-03, 1.67713101e-04, 3.06997938e-02,\n", - " 5.03207590e-02, -1.55181467e-02, 2.60838857e-03, 4.13090796e-03,\n", - " -1.86338413e-01]),\n", - " array([-3.02881774e-06, 5.76659203e-02, 1.10162785e+00, -5.25513574e-02,\n", - " 1.18720014e-05, 2.30974115e-06, -9.98618223e-01, 4.35157264e-03,\n", - " -6.22087114e+00, 3.00243172e-03, -3.89680941e-05, -2.51710706e-03,\n", - " 1.86770262e-02, -1.82628961e-04, 8.51115268e-01, -8.72374376e-01,\n", - " -1.34054273e-01, -2.80597843e-03, 1.92910282e-04, 3.07274685e-02,\n", - " -6.48527477e-02, -1.61358355e-02, 2.61803935e-03, 4.26746716e-03,\n", - " -1.85210049e-01]),\n", - " array([-3.18778476e-06, 5.86085640e-02, 1.10079448e+00, -5.24267363e-02,\n", - " 1.32396495e-05, 2.27372162e-06, -9.98624773e-01, 4.38232842e-03,\n", - " -6.22105260e+00, 2.98566499e-03, -3.63398444e-05, -2.51270272e-03,\n", - " 1.84929575e-02, -1.85221894e-04, 8.50085376e-01, -9.27590097e-01,\n", - " -2.49586258e-01, -2.72815117e-03, 2.18672319e-04, 3.07557789e-02,\n", - " -1.81458297e-01, -1.67667256e-02, 2.62824974e-03, 4.40433802e-03,\n", - " -1.84068681e-01]),\n", - " array([-3.34559278e-06, 5.95558109e-02, 1.09990584e+00, -5.22437092e-02,\n", - " 1.45667093e-05, 2.22325469e-06, -9.98634365e-01, 4.41311311e-03,\n", - " -6.22135211e+00, 2.96825416e-03, -3.37008652e-05, -2.50816129e-03,\n", - " 1.83100434e-02, -1.87907314e-04, 8.49171028e-01, -9.82785992e-01,\n", - " -3.66556489e-01, -2.64575616e-03, 2.44831920e-04, 3.07846916e-02,\n", - " -2.99515321e-01, -1.74108355e-02, 2.63897915e-03, 4.54143138e-03,\n", - " -1.82914091e-01]),\n", - " array([-3.50213132e-06, 6.05076409e-02, 1.09896187e+00, -5.20015507e-02,\n", - " 1.58508667e-05, 2.15820318e-06, -9.98647004e-01, 4.44392729e-03,\n", - " -6.22177115e+00, 2.95018601e-03, -3.10506800e-05, -2.50348264e-03,\n", - " 1.81282973e-02, -1.90671064e-04, 8.48387518e-01, -1.03792958e+00,\n", - " -4.84976216e-01, -2.55871903e-03, 2.71214755e-04, 3.08141732e-02,\n", - " -4.19035187e-01, -1.80681501e-02, 2.65018522e-03, 4.67865330e-03,\n", - " -1.81746130e-01]),\n", - " array([-3.65729516e-06, 6.14640244e-02, 1.09796256e+00, -5.16995334e-02,\n", - " 1.70897696e-05, 2.07852113e-06, -9.98662685e-01, 4.47477148e-03,\n", - " -6.22231117e+00, 2.93144739e-03, -2.83888562e-05, -2.49866673e-03,\n", - " 1.79477325e-02, -1.93498159e-04, 8.47750392e-01, -1.09298680e+00,\n", - " -6.04848343e-01, -2.46697273e-03, 2.97640396e-04, 3.08441917e-02,\n", - " -5.40020840e-01, -1.87386183e-02, 2.66182386e-03, 4.81590506e-03,\n", - " -1.80564731e-01]),\n", - " array([-3.81098482e-06, 6.24249230e-02, 1.09690791e+00, -5.13369320e-02,\n", - " 1.82810312e-05, 1.98425704e-06, -9.98681390e-01, 4.50564620e-03,\n", - " -6.22297363e+00, 2.91202524e-03, -2.57150069e-05, -2.49371365e-03,\n", - " 1.77683626e-02, -1.96372784e-04, 8.47275420e-01, -1.14792195e+00,\n", - " -7.26167099e-01, -2.37045812e-03, 3.23922706e-04, 3.08747168e-02,\n", - " -6.62466471e-01, -1.94221508e-02, 2.67384930e-03, 4.95308301e-03,\n", - " -1.79369902e-01]),\n", - " array([-3.96310710e-06, 6.33902889e-02, 1.09579799e+00, -5.09130282e-02,\n", - " 1.94222342e-05, 1.87555685e-06, -9.98703091e-01, 4.53655192e-03,\n", - " -6.22375999e+00, 2.89190662e-03, -2.30287928e-05, -2.48862357e-03,\n", - " 1.75902009e-02, -1.99278305e-04, 8.46978573e-01, -1.20269771e+00,\n", - " -8.48917735e-01, -2.26912467e-03, 3.49870356e-04, 3.09057206e-02,\n", - " -7.86357210e-01, -2.01186178e-02, 2.68621411e-03, 5.09007859e-03,\n", - " -1.78161735e-01]),\n", - " array([-4.11357553e-06, 6.43600650e-02, 1.09463289e+00, -5.04271150e-02,\n", - " 2.05109357e-05, 1.75266659e-06, -9.98727744e-01, 4.56748910e-03,\n", - " -6.22467166e+00, 2.87107877e-03, -2.03299235e-05, -2.48339679e-03,\n", - " 1.74132605e-02, -2.02197279e-04, 8.46875990e-01, -1.25727511e+00,\n", - " -9.73076249e-01, -2.16293094e-03, 3.75287476e-04, 3.09371784e-02,\n", - " -9.11668848e-01, -2.08278466e-02, 2.69886927e-03, 5.22677826e-03,\n", - " -1.76940407e-01]),\n", - " array([-4.26231092e-06, 6.53341847e-02, 1.09341272e+00, -4.98785017e-02,\n", - " 2.15446720e-05, 1.61593463e-06, -9.98755293e-01, 4.59845816e-03,\n", - " -6.22571003e+00, 2.84952915e-03, -1.76181592e-05, -2.47803373e-03,\n", - " 1.72375543e-02, -2.05111467e-04, 8.46983944e-01, -1.31161355e+00,\n", - " -1.09860914e+00, -2.05184524e-03, 3.99974414e-04, 3.09690692e-02,\n", - " -1.03836759e+00, -2.15496194e-02, 2.71176425e-03, 5.36306349e-03,\n", - " -1.75706180e-01]),\n", - " array([-4.40924179e-06, 6.63125720e-02, 1.09213767e+00, -4.92665185e-02,\n", - " 2.25209635e-05, 1.46581350e-06, -9.98785668e-01, 4.62945954e-03,\n", - " -6.22687644e+00, 2.82724548e-03, -1.48933122e-05, -2.47253492e-03,\n", - " 1.70630949e-02, -2.08001865e-04, 8.47318796e-01, -1.36567075e+00,\n", - " -1.22547319e+00, -1.93584607e-03, 4.23728600e-04, 3.10013763e-02,\n", - " -1.16640984e+00, -2.22836716e-02, 2.72484704e-03, 5.49881078e-03,\n", - " -1.74459407e-01]),\n", - " array([-4.55430482e-06, 6.72951413e-02, 1.09080793e+00, -4.85905215e-02,\n", - " 2.34373205e-05, 1.30286124e-06, -9.98818783e-01, 4.66049363e-03,\n", - " -6.22817218e+00, 2.80421579e-03, -1.21552480e-05, -2.46690103e-03,\n", - " 1.68898944e-02, -2.10848725e-04, 8.47896956e-01, -1.41940279e+00,\n", - " -1.35361529e+00, -1.81492264e-03, 4.46345537e-04, 3.10340884e-02,\n", - " -1.29574201e+00, -2.30296895e-02, 2.73806425e-03, 5.63389169e-03,\n", - " -1.73200532e-01]),\n", - " array([-4.69744533e-06, 6.82817979e-02, 1.08942378e+00, -4.78498979e-02,\n", - " 2.42912489e-05, 1.12774210e-06, -9.98854537e-01, 4.69156083e-03,\n", - " -6.22959848e+00, 2.78042848e-03, -9.40388674e-06, -2.46113285e-03,\n", - " 1.67179643e-02, -2.13631599e-04, 8.48734832e-01, -1.47276410e+00,\n", - " -1.48297226e+00, -1.68907529e-03, 4.67619888e-04, 3.10672001e-02,\n", - " -1.42630036e+00, -2.37873086e-02, 2.75136121e-03, 5.76817292e-03,\n", - " -1.71930088e-01]),\n", - " array([-4.83861762e-06, 6.92724376e-02, 1.08798549e+00, -4.70440711e-02,\n", - " 2.50802564e-05, 9.41226778e-07, -9.98892814e-01, 4.72266154e-03,\n", - " -6.23115649e+00, 2.75587237e-03, -6.63920470e-06, -2.45523134e-03,\n", - " 1.65473156e-02, -2.16329372e-04, 8.49848774e-01, -1.52570750e+00,\n", - " -1.61347076e+00, -1.55831593e-03, 4.87346676e-04, 3.11007127e-02,\n", - " -1.55801089e+00, -2.45561117e-02, 2.76468204e-03, 5.90151633e-03,\n", - " -1.70648704e-01]),\n", - " array([-4.97778536e-06, 7.02669471e-02, 1.08649343e+00, -4.61725058e-02,\n", - " 2.58018583e-05, 7.44191819e-07, -9.98933481e-01, 4.75379618e-03,\n", - " -6.23284728e+00, 2.73053675e-03, -3.86123492e-06, -2.44919756e-03,\n", - " 1.63779585e-02, -2.18920322e-04, 8.51255015e-01, -1.57818417e+00,\n", - " -1.74502718e+00, -1.42266832e-03, 5.05322575e-04, 3.11346350e-02,\n", - " -1.69078924e+00, -2.53356275e-02, 2.77796978e-03, 6.03377912e-03,\n", - " -1.69357103e-01]),\n", - " array([-5.11492192e-06, 7.12652044e-02, 1.08494798e+00, -4.52347130e-02,\n", - " 2.64535847e-05, 5.37618461e-07, -9.98976386e-01, 4.78496516e-03,\n", - " -6.23467182e+00, 2.70441142e-03, -1.07006846e-06, -2.44303274e-03,\n", - " 1.62099024e-02, -2.21382165e-04, 8.52969613e-01, -1.63014371e+00,\n", - " -1.87754759e+00, -1.28216847e-03, 5.21347297e-04, 3.11689837e-02,\n", - " -1.82454062e+00, -2.61253292e-02, 2.79116646e-03, 6.16481391e-03,\n", - " -1.68056102e-01]),\n", - " array([-5.25001066e-06, 7.22670787e-02, 1.08334959e+00, -4.42302556e-02,\n", - " 2.70329866e-05, 3.22590635e-07, -9.99021363e-01, 4.81616895e-03,\n", - " -6.23663098e+00, 2.67748678e-03, 1.73414482e-06, -2.43673827e-03,\n", - " 1.60431558e-02, -2.23692128e-04, 8.55008379e-01, -1.68153416e+00,\n", - " -2.01092772e+00, -1.13686486e-03, 5.35225047e-04, 3.12037847e-02,\n", - " -1.95915982e+00, -2.69246329e-02, 2.80421329e-03, 6.29446894e-03,\n", - " -1.66746612e-01]),\n", - " array([-5.38304513e-06, 7.32724310e-02, 1.08169876e+00, -4.31587535e-02,\n", - " 2.75376432e-05, 1.00292223e-07, -9.99068227e-01, 4.84740802e-03,\n", - " -6.23872551e+00, 2.64975389e-03, 4.55119556e-06, -2.43031569e-03,\n", - " 1.58777261e-02, -2.25827010e-04, 8.57386808e-01, -1.73230202e+00,\n", - " -2.14505297e+00, -9.86818664e-04, 5.46766054e-04, 3.12390730e-02,\n", - " -2.09453121e+00, -2.77328969e-02, 2.81705073e-03, 6.42258823e-03,\n", - " -1.65429640e-01]),\n", - " array([-5.51402930e-06, 7.42811146e-02, 1.07999603e+00, -4.20198886e-02,\n", - " 2.79651688e-05, -1.27996508e-07, -9.99116774e-01, 4.87868291e-03,\n", - " -6.24095604e+00, 2.62120447e-03, 7.38081425e-06, -2.42376667e-03,\n", - " 1.57136198e-02, -2.27763265e-04, 8.60120007e-01, -1.78239233e+00,\n", - " -2.27979849e+00, -8.32103941e-04, 5.55788145e-04, 3.12748937e-02,\n", - " -2.23052880e+00, -2.85494203e-02, 2.82961869e-03, 6.54901181e-03,\n", - " -1.64106286e-01]),\n", - " array([-5.64297762e-06, 7.52929751e-02, 1.07824201e+00, -4.08134101e-02,\n", - " 2.83132197e-05, -3.60903297e-07, -9.99166785e-01, 4.90999421e-03,\n", - " -6.24332306e+00, 2.59183102e-03, 1.02226709e-05, -2.41709310e-03,\n", - " 1.55508421e-02, -2.29477082e-04, 8.63222613e-01, -1.83174868e+00,\n", - " -2.41502922e+00, -6.72807780e-04, 5.62118363e-04, 3.13113022e-02,\n", - " -2.36701631e+00, -2.93734427e-02, 2.84185662e-03, 6.67357598e-03,\n", - " -1.62777746e-01]),\n", - " array([-5.76991514e-06, 7.63078516e-02, 1.07643736e+00, -3.95391399e-02,\n", - " 2.85795019e-05, -5.96969127e-07, -9.99218022e-01, 4.94134258e-03,\n", - " -6.24582690e+00, 2.56162688e-03, 1.30763746e-05, -2.41029698e-03,\n", - " 1.53893968e-02, -2.30944479e-04, 8.66708716e-01, -1.88031329e+00,\n", - " -2.55060004e+00, -5.09030387e-04, 5.65594601e-04, 3.13483646e-02,\n", - " -2.50384731e+00, -3.02041433e-02, 2.85370373e-03, 6.79611355e-03,\n", - " -1.61445307e-01]),\n", - " array([-5.89487741e-06, 7.73255768e-02, 1.07458278e+00, -3.81969769e-02,\n", - " 2.87617781e-05, -8.34654301e-07, -9.99270229e-01, 4.97272874e-03,\n", - " -6.24846777e+00, 2.53058624e-03, 1.59414737e-05, -2.40338053e-03,\n", - " 1.52292864e-02, -2.32141392e-04, 8.70591773e-01, -1.92802706e+00,\n", - " -2.68635596e+00, -3.40885147e-04, 5.66067241e-04, 3.13861579e-02,\n", - " -2.64086537e+00, -3.10406409e-02, 2.86509910e-03, 6.91645420e-03,\n", - " -1.60110345e-01]),\n", - " array([-6.01791048e-06, 7.83459777e-02, 1.07267906e+00, -3.67869030e-02,\n", - " 2.88578751e-05, -1.07234536e-06, -9.99323132e-01, 5.00415351e-03,\n", - " -6.25124567e+00, 2.49870425e-03, 1.88174556e-05, -2.39634611e-03,\n", - " 1.50705121e-02, -2.33043785e-04, 8.74884522e-01, -1.97482966e+00,\n", - " -2.82213225e+00, -1.68498647e-04, 5.63400776e-04, 3.14247699e-02,\n", - " -2.77790430e+00, -3.18819934e-02, 2.87598193e-03, 7.03442477e-03,\n", - " -1.58774328e-01]),\n", - " array([-6.13907064e-06, 7.93688768e-02, 1.07072703e+00, -3.53089869e-02,\n", - " 2.88656914e-05, -1.30836282e-06, -9.99376443e-01, 5.03561781e-03,\n", - " -6.25416046e+00, 2.46597705e-03, 2.17037473e-05, -2.38919626e-03,\n", - " 1.49130733e-02, -2.33627754e-04, 8.79598899e-01, -2.02065958e+00,\n", - " -2.95775476e+00, 7.98934016e-06, 5.57475395e-04, 3.14642995e-02,\n", - " -2.91478834e+00, -3.27271984e-02, 2.88629165e-03, 7.14984963e-03,\n", - " -1.57438811e-01]),\n", - " array([-6.25842423e-06, 8.03940926e-02, 1.06872757e+00, -3.37633896e-02,\n", - " 2.87832041e-05, -1.54096971e-06, -9.99429854e-01, 5.06712266e-03,\n", - " -6.25721179e+00, 2.43240185e-03, 2.45997154e-05, -2.38193370e-03,\n", - " 1.47569679e-02, -2.33869640e-04, 8.84745942e-01, -2.06545425e+00,\n", - " -3.09304012e+00, 1.88425891e-04, 5.48188517e-04, 3.15048557e-02,\n", - " -3.05133246e+00, -3.35751931e-02, 2.89596816e-03, 7.26255111e-03,\n", - " -1.56105432e-01]),\n", - " array([-6.37604726e-06, 8.14214403e-02, 1.06668166e+00, -3.21503684e-02,\n", - " 2.86084768e-05, -1.76838080e-06, -9.99483043e-01, 5.09866922e-03,\n", - " -6.26039914e+00, 2.39797700e-03, 2.75046675e-05, -2.37456135e-03,\n", - " 1.46021920e-02, -2.33746149e-04, 8.90335711e-01, -2.10915011e+00,\n", - " -3.22779611e+00, 3.72645004e-04, 5.35456244e-04, 3.15465578e-02,\n", - " -3.18734268e+00, -3.44248553e-02, 2.90495204e-03, 7.37234986e-03,\n", - " -1.54775912e-01]),\n", - " array([-6.49202500e-06, 8.24507333e-02, 1.06459030e+00, -3.04702818e-02,\n", - " 2.83396665e-05, -1.98877267e-06, -9.99535673e-01, 5.13025875e-03,\n", - " -6.26372175e+00, 2.36270200e-03, 3.04178522e-05, -2.36708229e-03,\n", - " 1.44487399e-02, -2.33234471e-04, 8.96377191e-01, -2.15168272e+00,\n", - " -3.36182198e+00, 5.60467691e-04, 5.19214718e-04, 3.15895343e-02,\n", - " -3.32261644e+00, -3.52750041e-02, 2.91318470e-03, 7.47906535e-03,\n", - " -1.53452049e-01]),\n", - " array([-6.60645139e-06, 8.34817837e-02, 1.06245458e+00, -2.87235931e-02,\n", - " 2.79750309e-05, -2.20029427e-06, -9.99587392e-01, 5.16189268e-03,\n", - " -6.26717870e+00, 2.32657759e-03, 3.33384608e-05, -2.35949977e-03,\n", - " 1.42966042e-02, -2.32312406e-04, 9.02878205e-01, -2.19298690e+00,\n", - " -3.49490885e+00, 7.51702083e-04, 4.99421368e-04, 3.16339222e-02,\n", - " -3.45694293e+00, -3.61244009e-02, 2.92060867e-03, 7.58251631e-03,\n", - " -1.52135719e-01]),\n", - " array([-6.71942847e-06, 8.45144040e-02, 1.06027564e+00, -2.69108750e-02,\n", - " 2.75129357e-05, -2.40107818e-06, -9.99637836e-01, 5.19357254e-03,\n", - " -6.27076880e+00, 2.28960584e-03, 3.62656286e-05, -2.35181725e-03,\n", - " 1.41457753e-02, -2.30958494e-04, 9.09845332e-01, -2.23299678e+00,\n", - " -3.62684013e+00, 9.46143551e-04, 4.76056009e-04, 3.16798657e-02,\n", - " -3.59010361e+00, -3.69717510e-02, 2.92716772e-03, 7.68252124e-03,\n", - " -1.50828867e-01]),\n", - " array([-6.83106560e-06, 8.55484076e-02, 1.05805469e+00, -2.50328130e-02,\n", - " 2.69518611e-05, -2.58925226e-06, -9.99686630e-01, 5.22530006e-03,\n", - " -6.27449067e+00, 2.25179014e-03, 3.91984358e-05, -2.34403835e-03,\n", - " 1.39962418e-02, -2.29152143e-04, 9.17283817e-01, -2.27164600e+00,\n", - " -3.75739200e+00, 1.14357484e-03, 4.49121795e-04, 3.17275151e-02,\n", - " -3.72187260e+00, -3.78157052e-02, 2.93280718e-03, 7.77889892e-03,\n", - " -1.49533506e-01]),\n", - " array([-6.94147866e-06, 8.65836107e-02, 1.05579301e+00, -2.30902089e-02,\n", - " 2.62904094e-05, -2.76295182e-06, -9.99733385e-01, 5.25707708e-03,\n", - " -6.27834269e+00, 2.21313528e-03, 4.21359098e-05, -2.33616688e-03,\n", - " 1.38479901e-02, -2.26873758e-04, 9.25197487e-01, -2.30886781e+00,\n", - " -3.88633389e+00, 1.34376621e-03, 4.18645997e-04, 3.17770248e-02,\n", - " -3.85201722e+00, -3.86548618e-02, 2.93747409e-03, 7.87146897e-03,\n", - " -1.48251710e-01]),\n", - " array([-7.05078907e-06, 8.76198332e-02, 1.05349193e+00, -2.10839843e-02,\n", - " 2.55273110e-05, -2.92033204e-06, -9.99777708e-01, 5.28890563e-03,\n", - " -6.28232299e+00, 2.17364751e-03, 4.50770273e-05, -2.32820683e-03,\n", - " 1.37010045e-02, -2.24104880e-04, 9.33588678e-01, -2.34459523e+00,\n", - " -4.01342900e+00, 1.54647556e-03, 3.84680590e-04, 3.18285521e-02,\n", - " -3.98029854e+00, -3.94877685e-02, 2.94111745e-03, 7.96005236e-03,\n", - " -1.46985614e-01]),\n", - " array([-7.15912276e-06, 8.86569001e-02, 1.05115287e+00, -1.90151832e-02,\n", - " 2.46614314e-05, -3.05958060e-06, -9.99819195e-01, 5.32078789e-03,\n", - " -6.28642946e+00, 2.13333458e-03, 4.80207157e-05, -2.32016236e-03,\n", - " 1.35552671e-02, -2.20828308e-04, 9.42458158e-01, -2.37876118e+00,\n", - " -4.13843491e+00, 1.75144855e-03, 3.47302632e-04, 3.18822546e-02,\n", - " -4.10647190e+00, -4.03129251e-02, 2.94368844e-03, 8.04447203e-03,\n", - " -1.45737403e-01]),\n", - " array([-7.26660899e-06, 8.96946431e-02, 1.04877729e+00, -1.68849747e-02,\n", - " 2.36917776e-05, -3.17893045e-06, -9.99857438e-01, 5.35272618e-03,\n", - " -6.29065975e+00, 2.09220580e-03, 5.09658564e-05, -2.31203781e-03,\n", - " 1.34107578e-02, -2.17028234e-04, 9.51805055e-01, -2.41129865e+00,\n", - " -4.26110416e+00, 1.95841876e-03, 3.06614439e-04, 3.19382884e-02,\n", - " -4.23028759e+00, -4.11287859e-02, 2.94514063e-03, 8.12455344e-03,\n", - " -1.44509309e-01]),\n", - " array([-7.37337915e-06, 9.07329020e-02, 1.04636673e+00, -1.46946558e-02,\n", - " 2.26175042e-05, -3.27667253e-06, -9.99892027e-01, 5.38472298e-03,\n", - " -6.29501124e+00, 2.05027203e-03, 5.39112866e-05, -2.30383768e-03,\n", - " 1.32674542e-02, -2.12690369e-04, 9.61626800e-01, -2.44214090e+00,\n", - " -4.38118487e+00, 2.16710777e-03, 2.62743515e-04, 3.19968054e-02,\n", - " -4.35149143e+00, -4.19337633e-02, 2.94543020e-03, 8.20012522e-03,\n", - " -1.43303606e-01]),\n", - " array([-7.47956533e-06, 9.17715258e-02, 1.04392280e+00, -1.24456527e-02,\n", - " 2.14379194e-05, -3.35116838e-06, -9.99922550e-01, 5.41678093e-03,\n", - " -6.29948106e+00, 2.00754580e-03, 5.68558027e-05, -2.29556666e-03,\n", - " 1.31253316e-02, -2.07802068e-04, 9.71919065e-01, -2.47122157e+00,\n", - " -4.49842141e+00, 2.37722527e-03, 2.15842262e-04, 3.20579506e-02,\n", - " -4.46982546e+00, -4.27262302e-02, 2.94451616e-03, 8.27101968e-03,\n", - " -1.42122605e-01]),\n", - " array([-7.58529890e-06, 9.28103749e-02, 1.04144716e+00, -1.01395227e-02,\n", - " 2.01524915e-05, -3.40086251e-06, -9.99948594e-01, 5.44890279e-03,\n", - " -6.30406609e+00, 1.96404128e-03, 5.97981633e-05, -2.28722959e-03,\n", - " 1.29843629e-02, -2.02352448e-04, 9.82675715e-01, -2.49847492e+00,\n", - " -4.61255511e+00, 2.58846911e-03, 1.66087443e-04, 3.21218598e-02,\n", - " -4.58502863e+00, -4.35045239e-02, 2.94236056e-03, 8.33707351e-03,\n", - " -1.40968644e-01]),\n", - " array([-7.69070894e-06, 9.38493221e-02, 1.03894153e+00, -7.77795556e-03,\n", - " 1.87608539e-05, -3.42429440e-06, -9.99969751e-01, 5.48109145e-03,\n", - " -6.30876293e+00, 1.91977433e-03, 6.27370919e-05, -2.27883146e-03,\n", - " 1.28445188e-02, -1.96332506e-04, 9.93888774e-01, -2.52383598e+00,\n", - " -4.72332494e+00, 2.80052542e-03, 1.13679400e-04, 3.21886560e-02,\n", - " -4.69683756e+00, -4.42669494e-02, 2.93892865e-03, 8.39812832e-03,\n", - " -1.39844085e-01]),\n", - " array([-7.79592058e-06, 9.48882546e-02, 1.03640773e+00, -5.36277412e-03,\n", - " 1.72628112e-05, -3.42010994e-06, -9.99985620e-01, 5.51334990e-03,\n", - " -6.31356792e+00, 1.87476255e-03, 6.56712810e-05, -2.27037743e-03,\n", - " 1.27057675e-02, -1.89735223e-04, 1.00554838e+00, -2.54724076e+00,\n", - " -4.83046831e+00, 3.01306862e-03, 5.88410349e-05, 3.22584469e-02,\n", - " -4.80498721e+00, -4.50117839e-02, 2.93418910e-03, 8.45403129e-03,\n", - " -1.38751304e-01]),\n", - " array([-7.90105327e-06, 9.59270750e-02, 1.03384760e+00, -2.89593489e-03,\n", - " 1.56583446e-05, -3.38707239e-06, -9.99995807e-01, 5.54568122e-03,\n", - " -6.31847713e+00, 1.82902527e-03, 6.85993952e-05, -2.26187279e-03,\n", - " 1.25680748e-02, -1.82555670e-04, 1.01764279e+00, -2.56862646e+00,\n", - " -4.93372176e+00, 3.22576144e-03, 1.81655079e-06, 3.23313215e-02,\n", - " -4.90921176e+00, -4.57372799e-02, 2.92811419e-03, 8.50463574e-03,\n", - " -1.37692689e-01]),\n", - " array([-8.00621899e-06, 9.69657034e-02, 1.03126306e+00, -3.79528026e-04,\n", - " 1.39476171e-05, -3.32407249e-06, -9.99999928e-01, 5.57808856e-03,\n", - " -6.32348638e+00, 1.78258360e-03, 7.15200751e-05, -2.25332299e-03,\n", - " 1.24314042e-02, -1.74791103e-04, 1.03015833e+00, -2.58793163e+00,\n", - " -5.03282180e+00, 3.43825498e-03, -5.71300379e-05, 3.24073471e-02,\n", - " -5.00924529e+00, -4.64416705e-02, 2.92067991e-03, 8.54980170e-03,\n", - " -1.36670626e-01]),\n", - " array([-8.11152031e-06, 9.80040786e-02, 1.02865609e+00, 2.18422309e-03,\n", - " 1.21309788e-05, -3.23013779e-06, -9.99997615e-01, 5.61057513e-03,\n", - " -6.32859120e+00, 1.73546042e-03, 7.44319413e-05, -2.24473359e-03,\n", - " 1.22957167e-02, -1.66441045e-04, 1.04307944e+00, -2.60509643e+00,\n", - " -5.12750572e+00, 3.65018865e-03, -1.17716614e-04, 3.24865657e-02,\n", - " -5.10482269e+00, -4.71231729e-02, 2.91186616e-03, 8.58939651e-03,\n", - " -1.35687499e-01]),\n", - " array([-8.21704847e-06, 9.90421597e-02, 1.02602872e+00, 4.79296266e-03,\n", - " 1.02089720e-05, -3.10444111e-06, -9.99988514e-01, 5.64314412e-03,\n", - " -6.33378688e+00, 1.68768043e-03, 7.73335982e-05, -2.23611030e-03,\n", - " 1.21609710e-02, -1.57507363e-04, 1.05638864e+00, -2.62006279e+00,\n", - " -5.21751236e+00, 3.86119022e-03, -1.79644874e-04, 3.25689916e-02,\n", - " -5.19568040e+00, -4.77799935e-02, 2.90165686e-03, 8.62329537e-03,\n", - " -1.34745677e-01]),\n", - " array([-8.32288136e-06, 1.00079928e-01, 1.02338305e+00, 7.44420374e-03,\n", - " 8.18233616e-06, -2.94630782e-06, -9.99972291e-01, 5.67579873e-03,\n", - " -6.33906844e+00, 1.63927010e-03, 8.02236382e-05, -2.22745892e-03,\n", - " 1.20271235e-02, -1.47994337e-04, 1.07006659e+00, -2.63277465e+00,\n", - " -5.30258296e+00, 4.07087580e-03, -2.42602428e-04, 3.26546074e-02,\n", - " -5.28155733e+00, -4.84103325e-02, 2.89004007e-03, 8.65138185e-03,\n", - " -1.33847509e-01]),\n", - " array([-8.42908148e-06, 1.01117387e-01, 1.02072123e+00, 1.01353300e-02,\n", - " 6.05201260e-06, -2.75522222e-06, -9.99948636e-01, 5.70854209e-03,\n", - " -6.34443063e+00, 1.59025771e-03, 8.31006463e-05, -2.21878537e-03,\n", - " 1.18941282e-02, -1.37908712e-04, 1.08409212e+00, -2.64317817e+00,\n", - " -5.38246205e+00, 4.27884984e-03, -3.06265076e-04, 3.27433618e-02,\n", - " -5.36219564e+00, -4.90123885e-02, 2.87700804e-03, 8.67354840e-03,\n", - " -1.32995315e-01]),\n", - " array([-8.53569385e-06, 1.02154566e-01, 1.01804545e+00, 1.28635978e-02,\n", - " 3.81914948e-06, -2.53083255e-06, -9.99917260e-01, 5.74137726e-03,\n", - " -6.34986797e+00, 1.54067334e-03, 8.59632036e-05, -2.21009567e-03,\n", - " 1.17619368e-02, -1.27259740e-04, 1.09844226e+00, -2.65122195e+00,\n", - " -5.45689821e+00, 4.48470516e-03, -3.70299216e-04, 3.28351662e-02,\n", - " -5.43734163e+00, -4.95843637e-02, 2.86255735e-03, 8.68969680e-03,\n", - " -1.32191382e-01]),\n", - " array([-8.64274392e-06, 1.03191520e-01, 1.01535796e+00, 1.56261391e-02,\n", - " 1.48510631e-06, -2.27295494e-06, -9.99877904e-01, 5.77430715e-03,\n", - " -6.35537472e+00, 1.49054888e-03, 8.88098925e-05, -2.20139593e-03,\n", - " 1.16304989e-02, -1.16059216e-04, 1.11309234e+00, -2.65685719e+00,\n", - " -5.52564499e+00, 4.68802298e-03, -4.34364387e-04, 3.29298926e-02,\n", - " -5.50674658e+00, -5.01244689e-02, 2.84668889e-03, 8.69973865e-03,\n", - " -1.31437950e-01]),\n", - " array([-8.75023545e-06, 1.04228330e-01, 1.01266107e+00, 1.84199642e-02,\n", - " -9.48541432e-07, -1.98157598e-06, -9.99830338e-01, 5.80733452e-03,\n", - " -6.36094489e+00, 1.43991795e-03, 9.16393004e-05, -2.19269234e-03,\n", - " 1.14997617e-02, -1.04321491e-04, 1.12801601e+00, -2.66003798e+00,\n", - " -5.58846173e+00, 4.88837302e-03, -4.98115884e-04, 3.30273710e-02,\n", - " -5.57016766e+00, -5.06309285e-02, 2.82940791e-03, 8.70359571e-03,\n", - " -1.30737209e-01]),\n", - " array([-8.85814843e-06, 1.05265106e-01, 1.00995711e+00, 2.12419654e-02,\n", - " -3.47999788e-06, -1.65685407e-06, -9.99774364e-01, 5.84046191e-03,\n", - " -6.36657226e+00, 1.38881596e-03, 9.44500244e-05, -2.18399114e-03,\n", - " 1.13696704e-02, -9.20634767e-05, 1.14318541e+00, -2.66072142e+00,\n", - " -5.64511444e+00, 5.08531361e-03, -5.61207447e-04, 3.31273872e-02,\n", - " -5.62736870e+00, -5.11019854e-02, 2.81072403e-03, 8.70120030e-03,\n", - " -1.30091290e-01]),\n", - " array([-8.96643701e-06, 1.06301988e-01, 1.00724848e+00, 2.40889212e-02,\n", - " -6.10724249e-06, -1.29911941e-06, -9.99709820e-01, 5.87369159e-03,\n", - " -6.37225038e+00, 1.33728006e-03, 9.72406756e-05, -2.17529864e-03,\n", - " 1.12401681e-02, -7.93046392e-05, 1.15857117e+00, -2.65886789e+00,\n", - " -5.69537660e+00, 5.27839193e-03, -6.23293965e-04, 3.32296817e-02,\n", - " -5.67812113e+00, -5.15359065e-02, 2.79065119e-03, 8.69249557e-03,\n", - " -1.29502258e-01]),\n", - " array([-9.07502745e-06, 1.07339143e-01, 1.00453758e+00, 2.69575004e-02,\n", - " -8.82802582e-06, -9.08872775e-07, -9.99636581e-01, 5.90702554e-03,\n", - " -6.37797258e+00, 1.28534907e-03, 1.00009883e-04, -2.16662121e-03,\n", - " 1.11111960e-02, -6.60669692e-05, 1.17414264e+00, -2.65444123e+00,\n", - " -5.73903001e+00, 5.46714420e-03, -6.84034185e-04, 3.33339475e-02,\n", - " -5.72220475e+00, -5.19309880e-02, 2.76920759e-03, 8.67743582e-03,\n", - " -1.28972101e-01]),\n", - " array([-9.18381620e-06, 1.08376773e-01, 1.00182689e+00, 2.98442673e-02,\n", - " -1.16398656e-05, -4.86782944e-07, -9.99554561e-01, 5.94046537e-03,\n", - " -6.38373199e+00, 1.23306351e-03, 1.02756299e-04, -2.15796522e-03,\n", - " 1.09826933e-02, -5.23749447e-05, 1.18986791e+00, -2.64740888e+00,\n", - " -5.77586565e+00, 5.65109612e-03, -7.43093376e-04, 3.34398304e-02,\n", - " -5.75940863e+00, -5.22855601e-02, 2.74641564e-03, 8.65598668e-03,\n", - " -1.28502729e-01]),\n", - " array([-9.29266799e-06, 1.09415109e-01, 9.99118887e-01, 3.27456867e-02,\n", - " -1.45400427e-05, -3.36829651e-08, -9.99463716e-01, 5.97401229e-03,\n", - " -6.38952152e+00, 1.18046551e-03, 1.05478601e-04, -2.14933709e-03,\n", - " 1.08545973e-02, -3.82554742e-05, 1.20571402e+00, -2.63774214e+00,\n", - " -5.80568444e+00, 5.82976328e-03, -8.00145917e-04, 3.35469275e-02,\n", - " -5.78953186e+00, -5.25979925e-02, 2.72230182e-03, 8.62812529e-03,\n", - " -1.28095959e-01]),\n", - " array([-9.40141403e-06, 1.10454413e-01, 9.96416100e-01, 3.56581297e-02,\n", - " -1.75255982e-05, 4.49434787e-07, -9.99364047e-01, 6.00766708e-03,\n", - " -6.39533391e+00, 1.12759881e-03, 1.08175497e-04, -2.14074325e-03,\n", - " 1.07268438e-02, -2.37378243e-05, 1.22164711e+00, -2.62541629e+00,\n", - " -5.82829804e+00, 6.00265178e-03, -8.54877790e-04, 3.36547882e-02,\n", - " -5.81238439e+00, -5.28666996e-02, 2.69689657e-03, 8.59384041e-03,\n", - " -1.27753514e-01]),\n", - " array([-9.50985035e-06, 1.11494980e-01, 9.93721073e-01, 3.85778801e-02,\n", - " -2.05933292e-05, 9.61424645e-07, -9.99255596e-01, 6.04143000e-03,\n", - " -6.40116169e+00, 1.07450867e-03, 1.10845731e-04, -2.13219012e-03,\n", - " 1.05993668e-02, -8.85353092e-06, 1.23763254e+00, -2.61041075e+00,\n", - " -5.84352966e+00, 6.16925892e-03, -9.06988932e-04, 3.37629145e-02,\n", - " -5.82778778e+00, -5.30901454e-02, 2.67023413e-03, 8.55313248e-03,\n", - " -1.27477013e-01]),\n", - " array([-9.61773628e-06, 1.12537139e-01, 9.91036371e-01, 4.15011404e-02,\n", - " -2.37397866e-05, 1.50099471e-06, -9.99138456e-01, 6.07530076e-03,\n", - " -6.40699727e+00, 1.02124182e-03, 1.13488084e-04, -2.12368411e-03,\n", - " 1.04720988e-02, 6.36370670e-06, 1.25363510e+00, -2.59270927e+00,\n", - " -5.85121472e+00, 6.32907405e-03, -9.56195423e-04, 3.38707622e-02,\n", - " -5.83557599e+00, -5.32668489e-02, 2.64235233e-03, 8.50601364e-03,\n", - " -1.27267963e-01]),\n", - " array([-9.72479301e-06, 1.13581248e-01, 9.88364579e-01, 4.44240389e-02,\n", - " -2.69612726e-05, 2.06671483e-06, -9.99012765e-01, 6.10927850e-03,\n", - " -6.41283287e+00, 9.67846432e-04, 1.16101376e-04, -2.11523160e-03,\n", - " 1.03449711e-02, 2.18781496e-05, 1.26961917e+00, -2.57230004e+00,\n", - " -5.85120166e+00, 6.48157966e-03, -1.00223149e-03, 3.39777429e-02,\n", - " -5.83559603e+00, -5.33953885e-02, 2.61329243e-03, 8.45250766e-03,\n", - " -1.27127757e-01]),\n", - " array([-9.83070245e-06, 1.14627699e-01, 9.85708294e-01, 4.73426370e-02,\n", - " -3.02538383e-05, 2.65702541e-06, -9.98878708e-01, 6.14336173e-03,\n", - " -6.41866058e+00, 9.14372024e-04, 1.18684475e-04, -2.10683895e-03,\n", - " 1.02179134e-02, 3.76521598e-05, 1.28554892e+00, -2.54917584e+00,\n", - " -5.84335254e+00, 6.62625246e-03, -1.04485132e-03, 3.40832263e-02,\n", - " -5.82770872e+00, -5.34744078e-02, 2.58309885e-03, 8.39264984e-03,\n", - " -1.27057664e-01]),\n", - " array([-9.93510616e-06, 1.15676916e-01, 9.83070122e-01, 5.02529366e-02,\n", - " -3.36132824e-05, 3.27024696e-06, -9.98736522e-01, 6.17754827e-03,\n", - " -6.42447236e+00, 8.60869405e-04, 1.21236294e-04, -2.09851246e-03,\n", - " 1.00908546e-02, 5.36463591e-05, 1.30138852e+00, -2.52333413e+00,\n", - " -5.82754377e+00, 6.76256488e-03, -1.08383059e-03, 3.41865434e-02,\n", - " -5.81178931e+00, -5.35026198e-02, 2.55181893e-03, 8.32648688e-03,\n", - " -1.27058822e-01]),\n", - " array([-1.00376046e-05, 1.16729350e-01, 9.80452675e-01, 5.31508879e-02,\n", - " -3.70351506e-05, 3.90459021e-06, -9.98586492e-01, 6.21183526e-03,\n", - " -6.43026009e+00, 8.07390593e-04, 1.23755797e-04, -2.09025839e-03,\n", - " 9.96372236e-03, 6.98198056e-05, 1.31710230e+00, -2.49477715e+00,\n", - " -5.80366665e+00, 6.88998650e-03, -1.11896785e-03, 3.42869896e-02,\n", - " -5.78772814e+00, -5.34788117e-02, 2.51950267e-03, 8.25407663e-03,\n", - " -1.27132239e-01]),\n", - " array([-1.01377563e-05, 1.17785487e-01, 9.77858563e-01, 5.60323975e-02,\n", - " -4.05147355e-05, 4.55816677e-06, -9.98428950e-01, 6.24621909e-03,\n", - " -6.43601552e+00, 7.53988743e-04, 1.26241999e-04, -2.08208290e-03,\n", - " 9.83644359e-03, 8.61301877e-05, 1.33265501e+00, -2.46351204e+00,\n", - " -5.77162800e+00, 7.00798589e-03, -1.15008554e-03, 3.43838294e-02,\n", - " -5.75543115e+00, -5.34018500e-02, 2.48620245e-03, 8.17548789e-03,\n", - " -1.27278779e-01]),\n", - " array([-1.02350781e-05, 1.18845838e-01, 9.75290395e-01, 5.88933367e-02,\n", - " -4.40470771e-05, 5.22900011e-06, -9.98264280e-01, 6.28069539e-03,\n", - " -6.44173034e+00, 7.00718058e-04, 1.28693972e-04, -2.07399210e-03,\n", - " 9.70894442e-03, 1.02534036e-04, 1.34801198e+00, -2.42955088e+00,\n", - " -5.73135069e+00, 7.11603252e-03, -1.17703092e-03, 3.44763006e-02,\n", - " -5.71482051e+00, -5.32706848e-02, 2.45197271e-03, 8.09080003e-03,\n", - " -1.27499162e-01]),\n", - " array([-1.03290445e-05, 1.19910945e-01, 9.72750770e-01, 6.17295504e-02,\n", - " -4.76269646e-05, 5.91503687e-06, -9.98092912e-01, 6.31525901e-03,\n", - " -6.44739618e+00, 6.47633704e-04, 1.31110841e-04, -2.06599200e-03,\n", - " 9.58115046e-03, 1.18986952e-04, 1.36313935e+00, -2.39291074e+00,\n", - " -5.68277411e+00, 7.21359887e-03, -1.19967657e-03, 3.45636196e-02,\n", - " -5.66583504e+00, -5.30843542e-02, 2.41686963e-03, 8.00010269e-03,\n", - " -1.27793961e-01]),\n", - " array([-1.04190879e-05, 1.20981373e-01, 9.70242273e-01, 6.45368653e-02,\n", - " -5.12489395e-05, 6.61415830e-06, -9.97915322e-01, 6.34990400e-03,\n", - " -6.45300461e+00, 5.94791715e-04, 1.33491792e-04, -2.05808850e-03,\n", - " 9.45298687e-03, 1.35443852e-04, 1.37800429e+00, -2.35361372e+00,\n", - " -5.62585464e+00, 7.30016281e-03, -1.21792079e-03, 3.46449871e-02,\n", - " -5.60843073e+00, -5.28419887e-02, 2.38095085e-03, 7.90349539e-03,\n", - " -1.28163594e-01]),\n", - " array([-1.05045995e-05, 1.22057714e-01, 9.67767473e-01, 6.73110993e-02,\n", - " -5.49072989e-05, 7.32419174e-06, -9.97732035e-01, 6.38462359e-03,\n", - " -6.45854719e+00, 5.42248899e-04, 1.35836067e-04, -2.05028741e-03,\n", - " 9.32437855e-03, 1.51859232e-04, 1.39257519e+00, -2.31168700e+00,\n", - " -5.56056604e+00, 7.37521003e-03, -1.23168770e-03, 3.47195943e-02,\n", - " -5.54258108e+00, -5.25428157e-02, 2.34427507e-03, 7.80108708e-03,\n", - " -1.28608322e-01]),\n", - " array([-1.05849299e-05, 1.23140582e-01, 9.65328917e-01, 7.00480705e-02,\n", - " -5.85961006e-05, 8.04292217e-06, -9.97543615e-01, 6.41941022e-03,\n", - " -6.46401547e+00, 4.90062737e-04, 1.38142969e-04, -2.04259442e-03,\n", - " 9.19525030e-03, 1.68187439e-04, 1.40682186e+00, -2.26716280e+00,\n", - " -5.48689981e+00, 7.43823682e-03, -1.24092711e-03, 3.47866286e-02,\n", - " -5.46827753e+00, -5.21861629e-02, 2.30690176e-03, 7.69299566e-03,\n", - " -1.29128245e-01]),\n", - " array([-1.06593897e-05, 1.24230613e-01, 9.62929126e-01, 7.27436059e-02,\n", - " -6.23091700e-05, 8.76810351e-06, -9.97350672e-01, 6.45425550e-03,\n", - " -6.46940100e+00, 4.38291273e-04, 1.40411860e-04, -2.03501507e-03,\n", - " 9.06552700e-03, 1.84382964e-04, 1.42071574e+00, -2.22007840e+00,\n", - " -5.40486551e+00, 7.48875283e-03, -1.24561425e-03, 3.48452810e-02,\n", - " -5.38552970e+00, -5.17714631e-02, 2.26889081e-03, 7.57934753e-03,\n", - " -1.29723302e-01]),\n", - " array([-1.07272518e-05, 1.25328460e-01, 9.60570589e-01, 7.53935516e-02,\n", - " -6.60401067e-05, 9.49746987e-06, -9.97153854e-01, 6.48915026e-03,\n", - " -6.47469536e+00, 3.86993016e-04, 1.42642162e-04, -2.02755479e-03,\n", - " 8.93513373e-03, 2.00400739e-04, 1.43423010e+00, -2.17047609e+00,\n", - " -5.31449098e+00, 7.52628410e-03, -1.24574922e-03, 3.48947527e-02,\n", - " -5.29436569e+00, -5.12982571e-02, 2.23030214e-03, 7.46027706e-03,\n", - " -1.30393266e-01]),\n", - " array([-1.07877524e-05, 1.26434793e-01, 9.58255759e-01, 7.79937810e-02,\n", - " -6.97822947e-05, 1.02287465e-05, -9.96953843e-01, 6.52408452e-03,\n", - " -6.47989020e+00, 3.36226818e-04, 1.44833357e-04, -2.02021887e-03,\n", - " 8.80399599e-03, 2.16196453e-04, 1.44734018e+00, -2.11840316e+00,\n", - " -5.21582257e+00, 7.55037615e-03, -1.24135633e-03, 3.49342620e-02,\n", - " -5.19483227e+00, -5.07661980e-02, 2.19119543e-03, 7.33592602e-03,\n", - " -1.31137740e-01]),\n", - " array([-1.08400932e-05, 1.27550297e-01, 9.55987050e-01, 8.05402052e-02,\n", - " -7.35289121e-05, 1.09596603e-05, -9.96751358e-01, 6.55904757e-03,\n", - " -6.48497719e+00, 2.86051764e-04, 1.46984987e-04, -2.01301242e-03,\n", - " 8.67203983e-03, 2.31726870e-04, 1.46002342e+00, -2.06391177e+00,\n", - " -5.10892529e+00, 7.56059725e-03, -1.23248326e-03, 3.49630519e-02,\n", - " -5.08699504e+00, -5.01750541e-02, 2.15162972e-03, 7.20644305e-03,\n", - " -1.31956163e-01]),\n", - " array([-1.08834439e-05, 1.28675667e-01, 9.53766833e-01, 8.30287813e-02,\n", - " -7.72729439e-05, 1.16879503e-05, -9.96547147e-01, 6.59402797e-03,\n", - " -6.48994813e+00, 2.36527052e-04, 1.49096650e-04, -2.00594044e-03,\n", - " 8.53919203e-03, 2.46950154e-04, 1.47225956e+00, -2.00705897e+00,\n", - " -4.99388291e+00, 7.55654163e-03, -1.21920009e-03, 3.49803969e-02,\n", - " -4.97093851e+00, -4.95247126e-02, 2.11166310e-03, 7.07198313e-03,\n", - " -1.32847801e-01]),\n", - " array([-1.09169448e-05, 1.29811608e-01, 9.51597429e-01, 8.54555226e-02,\n", - " -8.10071952e-05, 1.24113777e-05, -9.96341983e-01, 6.62901358e-03,\n", - " -6.49479490e+00, 1.87711870e-04, 1.51168003e-04, -1.99900773e-03,\n", - " 8.40538028e-03, 2.61826197e-04, 1.48403084e+00, -1.94790651e+00,\n", - " -4.87079796e+00, 7.53783293e-03, -1.20159815e-03, 3.49856104e-02,\n", - " -4.84676617e+00, -4.88151820e-02, 2.07135237e-03, 6.93270697e-03,\n", - " -1.33811751e-01]),\n", - " array([-1.09397096e-05, 1.30958829e-01, 9.49481107e-01, 8.78165072e-02,\n", - " -8.47243068e-05, 1.31277347e-05, -9.96136664e-01, 6.66399163e-03,\n", - " -6.49950950e+00, 1.39665274e-04, 1.53198755e-04, -1.99221895e-03,\n", - " 8.27053334e-03, 2.76316950e-04, 1.49532210e+00, -1.88652083e+00,\n", - " -4.73979180e+00, 7.50412746e-03, -1.17978887e-03, 3.49780516e-02,\n", - " -4.71460047e+00, -4.80465953e-02, 2.03075276e-03, 6.78878044e-03,\n", - " -1.34846940e-01]),\n", - " array([-1.09508290e-05, 1.32118044e-01, 9.47420077e-01, 9.01078874e-02,\n", - " -8.84167719e-05, 1.38348543e-05, -9.95932006e-01, 6.69894876e-03,\n", - " -6.50408408e+00, 9.24460619e-05, 1.55188673e-04, -1.98557858e-03,\n", - " 8.13458121e-03, 2.90386748e-04, 1.50612091e+00, -1.82297285e+00,\n", - " -4.60100449e+00, 7.45511767e-03, -1.15390245e-03, 3.49571325e-02,\n", - " -4.57458274e+00, -4.72192125e-02, 1.98991759e-03, 6.64037408e-03,\n", - " -1.35952126e-01]),\n", - " array([-1.09493736e-05, 1.33289964e-01, 9.45416492e-01, 9.23258988e-02,\n", - " -9.20769547e-05, 1.45306186e-05, -9.95728838e-01, 6.73387108e-03,\n", - " -6.50851095e+00, 4.61126395e-05, 1.57137571e-04, -1.97909092e-03,\n", - " 7.99745532e-03, 3.04002635e-04, 1.51641767e+00, -1.75733793e+00,\n", - " -4.45459472e+00, 7.39053534e-03, -1.12408643e-03, 3.49223243e-02,\n", - " -4.42687311e+00, -4.63334224e-02, 1.94889799e-03, 6.48766247e-03,\n", - " -1.37125898e-01]),\n", - " array([-1.09343986e-05, 1.34475300e-01, 9.43472438e-01, 9.44668689e-02,\n", - " -9.56971103e-05, 1.52129665e-05, -9.95528001e-01, 6.76874425e-03,\n", - " -6.51278260e+00, 7.22894265e-07, 1.59045314e-04, -1.97276009e-03,\n", - " 7.85908864e-03, 3.17134668e-04, 1.52620567e+00, -1.68969564e+00,\n", - " -4.30073961e+00, 7.31015491e-03, -1.09050428e-03, 3.48731640e-02,\n", - " -4.27165032e+00, -4.53897452e-02, 1.90774266e-03, 6.33082377e-03,\n", - " -1.38366678e-01]),\n", - " array([-1.09049470e-05, 1.35674753e-01, 9.41589932e-01, 9.65272261e-02,\n", - " -9.92694065e-05, 1.58799020e-05, -9.95330339e-01, 6.80355351e-03,\n", - " -6.51689171e+00, -4.36659392e-05, 1.60911811e-04, -1.96659005e-03,\n", - " 7.71941591e-03, 3.29756224e-04, 1.53548119e+00, -1.62012969e+00,\n", - " -4.13963450e+00, 7.21379651e-03, -1.05333386e-03, 3.48092603e-02,\n", - " -4.10911149e+00, -4.43888334e-02, 1.86649759e-03, 6.17003917e-03,\n", - " -1.39672725e-01]),\n", - " array([-1.08600542e-05, 1.36889016e-01, 9.39770920e-01, 9.85035081e-02,\n", - " -1.02785946e-04, 1.65295005e-05, -9.95136698e-01, 6.83828381e-03,\n", - " -6.52083119e+00, -8.69974131e-05, 1.62737017e-04, -1.96058456e-03,\n", - " 7.57837378e-03, 3.41844275e-04, 1.54424353e+00, -1.54872770e+00,\n", - " -3.97149270e+00, 7.10132898e-03, -1.01276584e-03, 3.47302988e-02,\n", - " -3.93947187e+00, -4.33314739e-02, 1.82520587e-03, 6.00549242e-03,\n", - " -1.41042133e-01]),\n", - " array([-1.07987526e-05, 1.38118770e-01, 9.38017273e-01, 1.00392370e-01,\n", - " -1.06238793e-04, 1.71599157e-05, -9.94947918e-01, 6.87291986e-03,\n", - " -6.52459415e+00, -1.29216001e-04, 1.64520925e-04, -1.95474719e-03,\n", - " 7.43590094e-03, 3.53379659e-04, 1.55249500e+00, -1.47558108e+00,\n", - " -3.79654515e+00, 6.97267253e-03, -9.69002123e-04, 3.46360474e-02,\n", - " -3.76296450e+00, -4.22185882e-02, 1.78390744e-03, 5.83736938e-03,\n", - " -1.42472837e-01]),\n", - " array([-1.07200760e-05, 1.39364678e-01, 9.36330780e-01, 1.02190593e-01,\n", - " -1.09619994e-04, 1.77693856e-05, -9.94764832e-01, 6.90744622e-03,\n", - " -6.52817399e+00, -1.70267235e-04, 1.66263563e-04, -1.94908133e-03,\n", - " 7.29193832e-03, 3.64347312e-04, 1.56024098e+00, -1.40078480e+00,\n", - " -3.61504003e+00, 6.82780135e-03, -9.22254176e-04, 3.45263605e-02,\n", - " -3.57983983e+00, -4.10512335e-02, 1.74263895e-03, 5.66585761e-03,\n", - " -1.43962617e-01]),\n", - " array([-1.06230643e-05, 1.40627386e-01, 9.34713151e-01, 1.03895093e-01,\n", - " -1.12921610e-04, 1.83562377e-05, -9.94588255e-01, 6.94184740e-03,\n", - " -6.53156436e+00, -2.10097838e-04, 1.67964997e-04, -1.94359019e-03,\n", - " 7.14642922e-03, 3.74736484e-04, 1.56748986e+00, -1.32443727e+00,\n", - " -3.42724237e+00, 6.66674580e-03, -8.72741410e-04, 3.44011833e-02,\n", - " -3.39036530e+00, -3.98306028e-02, 1.70143361e-03, 5.49114595e-03,\n", - " -1.45509100e-01]),\n", - " array([-1.05067686e-05, 1.41907516e-01, 9.33166009e-01, 1.05502924e-01,\n", - " -1.16135743e-04, 1.89188938e-05, -9.94418986e-01, 6.97610795e-03,\n", - " -6.53475918e+00, -2.48655862e-04, 1.69625318e-04, -1.93827676e-03,\n", - " 6.99931946e-03, 3.84540920e-04, 1.57425302e+00, -1.24664007e+00,\n", - " -3.23343357e+00, 6.48959441e-03, -8.20689507e-04, 3.42605543e-02,\n", - " -3.19482487e+00, -3.85580245e-02, 1.66032106e-03, 5.31342423e-03,\n", - " -1.47109764e-01]),\n", - " array([-1.03702562e-05, 1.43205664e-01, 9.31690888e-01, 1.07011291e-01,\n", - " -1.19254559e-04, 1.94558743e-05, -9.94257798e-01, 7.01021256e-03,\n", - " -6.53775270e+00, -2.85890824e-04, 1.71244645e-04, -1.93314388e-03,\n", - " 6.85055752e-03, 3.93759008e-04, 1.58054477e+00, -1.16749781e+00,\n", - " -3.03391089e+00, 6.29649542e-03, -7.66328773e-04, 3.41046087e-02,\n", - " -2.99351851e+00, -3.72349620e-02, 1.61932727e-03, 5.13288291e-03,\n", - " -1.48761943e-01]),\n", - " array([-1.02126150e-05, 1.44522400e-01, 9.30289233e-01, 1.08417555e-01,\n", - " -1.22270327e-04, 1.99658021e-05, -9.94105436e-01, 7.04414614e-03,\n", - " -6.54053946e+00, -3.21753837e-04, 1.72823120e-04, -1.92819417e-03,\n", - " 6.70009468e-03, 4.02393891e-04, 1.58638223e+00, -1.08711791e+00,\n", - " -2.82898684e+00, 6.08765807e-03, -7.09892499e-04, 3.39335797e-02,\n", - " -2.78676159e+00, -3.58630125e-02, 1.57847450e-03, 4.94971285e-03,\n", - " -1.50462836e-01]),\n", - " array([-1.00329592e-05, 1.45858262e-01, 9.28962393e-01, 1.09719237e-01,\n", - " -1.25175439e-04, 2.04474049e-05, -9.93962611e-01, 7.07789394e-03,\n", - " -6.54311434e+00, -3.56197742e-04, 1.74360901e-04, -1.92343006e-03,\n", - " 6.54788518e-03, 4.10453541e-04, 1.59178532e+00, -1.00561039e+00,\n", - " -2.61898867e+00, 5.86335342e-03, -6.51615356e-04, 3.37477998e-02,\n", - " -2.57488432e+00, -3.44439058e-02, 1.53778128e-03, 4.76410507e-03,\n", - " -1.52209504e-01]),\n", - " array([-9.83043369e-06, 1.47213752e-01, 9.27711621e-01, 1.10914028e-01,\n", - " -1.27962446e-04, 2.08995185e-05, -9.93829996e-01, 7.11144164e-03,\n", - " -6.54547258e+00, -3.89177244e-04, 1.75858164e-04, -1.91885381e-03,\n", - " 6.39388629e-03, 4.17950790e-04, 1.59677652e+00, -9.23087657e-01,\n", - " -2.40425762e+00, 5.62391479e-03, -5.91731818e-04, 3.35477011e-02,\n", - " -2.35823107e+00, -3.29795018e-02, 1.49726235e-03, 4.57625060e-03,\n", - " -1.53998885e-01]),\n", - " array([-9.60421932e-06, 1.48589339e-01, 9.26538073e-01, 1.11999795e-01,\n", - " -1.30624088e-04, 2.13210879e-05, -9.93708221e-01, 7.14477546e-03,\n", - " -6.54760974e+00, -4.20649033e-04, 1.77315092e-04, -1.91446747e-03,\n", - " 6.23805850e-03, 4.24903318e-04, 1.60138083e+00, -8.39664300e-01,\n", - " -2.18514828e+00, 5.36973773e-03, -5.30474652e-04, 3.33338148e-02,\n", - " -2.13715967e+00, -3.14717885e-02, 1.45692879e-03, 4.38634032e-03,\n", - " -1.55827795e-01]),\n", - " array([-9.35353727e-06, 1.49985452e-01, 9.25442802e-01, 1.12974582e-01,\n", - " -1.33153321e-04, 2.17111689e-05, -9.93597869e-01, 7.17788223e-03,\n", - " -6.54952178e+00, -4.50571912e-04, 1.78731880e-04, -1.91027291e-03,\n", - " 6.08036556e-03, 4.31333597e-04, 1.60562557e+00, -7.55456877e-01,\n", - " -1.96202787e+00, 5.10127956e-03, -4.68073457e-04, 3.31067701e-02,\n", - " -1.91204066e+00, -2.99228792e-02, 1.41678800e-03, 4.19456490e-03,\n", - " -1.57692933e-01]),\n", - " array([-9.07765386e-06, 1.51402477e-01, 9.24426760e-01, 1.13836623e-01,\n", - " -1.35543348e-04, 2.20689284e-05, -9.93499474e-01, 7.21074952e-03,\n", - " -6.55120503e+00, -4.78906921e-04, 1.80108724e-04, -1.90627179e-03,\n", - " 5.92077467e-03, 4.37268792e-04, 1.60954019e+00, -6.70583693e-01,\n", - " -1.73527543e+00, 4.81905846e-03, -4.04753287e-04, 3.28672916e-02,\n", - " -1.68325655e+00, -2.83350087e-02, 1.37684383e-03, 4.00111471e-03,\n", - " -1.59590895e-01]),\n", - " array([-8.77588487e-06, 1.52840760e-01, 9.23490794e-01, 1.14584338e-01,\n", - " -1.37787648e-04, 2.23936445e-05, -9.93413514e-01, 7.24336572e-03,\n", - " -6.55265623e+00, -5.05617450e-04, 1.81445821e-04, -1.90246561e-03,\n", - " 5.75925650e-03, 4.42740614e-04, 1.61315610e+00, -5.85164586e-01,\n", - " -1.50528103e+00, 4.52365203e-03, -3.40733364e-04, 3.26161969e-02,\n", - " -1.45120098e+00, -2.67105297e-02, 1.33709673e-03, 3.80617983e-03,\n", - " -1.61518174e-01]),\n", - " array([-8.44759970e-06, 1.54300599e-01, 9.22635643e-01, 1.15216347e-01,\n", - " -1.39880006e-04, 2.26847060e-05, -9.93340412e-01, 7.27572011e-03,\n", - " -6.55387251e+00, -5.30669359e-04, 1.82743365e-04, -1.89885566e-03,\n", - " 5.59578532e-03, 4.47785129e-04, 1.61650646e+00, -4.99320708e-01,\n", - " -1.27244494e+00, 4.21569548e-03, -2.76225882e-04, 3.23543927e-02,\n", - " -1.21627784e+00, -2.50519085e-02, 1.29754386e-03, 3.60995011e-03,\n", - " -1.63471171e-01]),\n", - " array([-8.09222527e-06, 1.55782249e-01, 9.21861941e-01, 1.15731466e-01,\n", - " -1.41814538e-04, 2.29416107e-05, -9.93280528e-01, 7.30780298e-03,\n", - " -6.55485141e+00, -5.54031079e-04, 1.84001544e-04, -1.89544305e-03,\n", - " 5.43033912e-03, 4.52442521e-04, 1.61962597e+00, -4.13174306e-01,\n", - " -1.03717672e+00, 3.89587932e-03, -2.11434926e-04, 3.20828701e-02,\n", - " -9.78900446e-01, -2.33617203e-02, 1.25817930e-03, 3.41261516e-03,\n", - " -1.65446204e-01]),\n", - " array([-7.70924962e-06, 1.57285913e-01, 9.21170209e-01, 1.16128717e-01,\n", - " -1.43585718e-04, 2.31639642e-05, -9.93234162e-01, 7.33960568e-03,\n", - " -6.55559090e+00, -5.75673723e-04, 1.85220538e-04, -1.89222868e-03,\n", - " 5.26289961e-03, 4.56756816e-04, 1.62255060e+00, -3.26848498e-01,\n", - " -7.99894332e-01, 3.56494654e-03, -1.46555516e-04, 3.18026995e-02,\n", - " -7.39490568e-01, -2.16426435e-02, 1.21899424e-03, 3.21436451e-03,\n", - " -1.67439514e-01]),\n", - " array([-7.29822516e-06, 1.58811750e-01, 9.20560862e-01, 1.16407326e-01,\n", - " -1.45188401e-04, 2.33514770e-05, -9.93201547e-01, 7.37112070e-03,\n", - " -6.55608938e+00, -5.95571177e-04, 1.86400516e-04, -1.88921330e-03,\n", - " 5.09345233e-03, 4.60775559e-04, 1.62531738e+00, -2.40467059e-01,\n", - " -5.61023192e-01, 3.22368953e-03, -8.17727725e-05, 3.15150242e-02,\n", - " -4.98477498e-01, -1.98974546e-02, 1.17997725e-03, 3.01538767e-03,\n", - " -1.69447272e-01]),\n", - " array([-6.85877157e-06, 1.60359864e-01, 9.20034200e-01, 1.16566731e-01,\n", - " -1.46617850e-04, 2.35039623e-05, -9.93182851e-01, 7.40234176e-03,\n", - " -6.55634568e+00, -6.13700199e-04, 1.87541630e-04, -1.88639742e-03,\n", - " 4.92198674e-03, 4.64549462e-04, 1.62796416e+00, -1.54154191e-01,\n", - " -3.20995192e-01, 2.87294641e-03, -1.72612274e-05, 3.12210541e-02,\n", - " -2.56297066e-01, -1.81290216e-02, 1.14111446e-03, 2.81587434e-03,\n", - " -1.71465594e-01]),\n", - " array([-6.39057835e-06, 1.61930312e-01, 9.19590412e-01, 1.16606581e-01,\n", - " -1.47869752e-04, 2.36213320e-05, -9.93178173e-01, 7.43326381e-03,\n", - " -6.55635907e+00, -6.30040496e-04, 1.88644020e-04, -1.88378141e-03,\n", - " 4.74849620e-03, 4.68132007e-04, 1.63052931e+00, -6.80343054e-02,\n", - " -8.02477039e-02, 2.51359717e-03, 4.68157226e-05, 3.09220579e-02,\n", - " -1.33906334e-02, -1.63402976e-02, 1.10238991e-03, 2.61601448e-03,\n", - " -1.73490544e-01]),\n", - " array([-5.89340685e-06, 1.63523098e-01, 9.19229574e-01, 1.16526740e-01,\n", - " -1.48940242e-04, 2.37035936e-05, -9.93187543e-01, 7.46388317e-03,\n", - " -6.55612927e+00, -6.44574810e-04, 1.89707806e-04, -1.88136541e-03,\n", - " 4.57297805e-03, 4.71579024e-04, 1.63305148e+00, 1.77682023e-02,\n", - " 1.60777447e-01, 2.14655935e-03, 1.10306213e-04, 3.06193550e-02,\n", - " 2.29795946e-01, -1.45343138e-02, 1.06378581e-03, 2.41599856e-03,\n", - " -1.75518144e-01]),\n", - " array([-5.36709203e-06, 1.65138177e-01, 9.18951648e-01, 1.16327288e-01,\n", - " -1.49825916e-04, 2.37508457e-05, -9.93210924e-01, 7.49419748e-03,\n", - " -6.55565646e+00, -6.57288983e-04, 1.90733089e-04, -1.87914939e-03,\n", - " 4.39543366e-03, 4.74948240e-04, 1.63556934e+00, 1.03129179e-01,\n", - " 4.01635029e-01, 1.77278347e-03, 1.73070125e-04, 3.03143070e-02,\n", - " 4.72813381e-01, -1.27141723e-02, 1.02528283e-03, 2.21601768e-03,\n", - " -1.77544387e-01]),\n", - " array([-4.81154362e-06, 1.66775452e-01, 9.18756483e-01, 1.16008522e-01,\n", - " -1.50523847e-04, 2.37632738e-05, -9.93248206e-01, 7.52420578e-03,\n", - " -6.55494125e+00, -6.68172021e-04, 1.91719949e-04, -1.87713313e-03,\n", - " 4.21586842e-03, 4.78298804e-04, 1.63812131e+00, 1.87924939e-01,\n", - " 6.41877479e-01, 1.39324827e-03, 2.34979231e-04, 3.00083084e-02,\n", - " 7.15210026e-01, -1.08830382e-02, 9.86860433e-04, 2.01626379e-03,\n", - " -1.79565245e-01]),\n", - " array([-4.22674691e-06, 1.68434775e-01, 9.18643814e-01, 1.15570957e-01,\n", - " -1.51031600e-04, 2.37411457e-05, -9.93299215e-01, 7.55390856e-03,\n", - " -6.55398472e+00, -6.77216152e-04, 1.92668446e-04, -1.87531620e-03,\n", - " 4.03429174e-03, 4.81690799e-04, 1.64074527e+00, 2.72032495e-01,\n", - " 8.81055986e-01, 1.00895565e-03, 2.95917050e-04, 2.97027774e-02,\n", - " 9.56532980e-01, -9.04413150e-03, 9.48497184e-04, 1.81692985e-03,\n", - " -1.81576675e-01]),\n", - " array([-3.61276305e-06, 1.70115949e-01, 9.18613260e-01, 1.15015327e-01,\n", - " -1.51347238e-04, 2.36848063e-05, -9.93363705e-01, 7.58330771e-03,\n", - " -6.55278839e+00, -6.84416871e-04, 1.93578617e-04, -1.87369799e-03,\n", - " 3.85071711e-03, 4.85184732e-04, 1.64347834e+00, 3.55329782e-01,\n", - " 1.11872161e+00, 6.20925547e-04, 3.55778636e-04, 2.93991455e-02,\n", - " 1.19632920e+00, -7.20071920e-03, 9.10171096e-04, 1.61821000e-03,\n", - " -1.83574636e-01]),\n", - " array([-2.96972888e-06, 1.71818729e-01, 9.18664330e-01, 1.14342581e-01,\n", - " -1.51469330e-04, 2.35946731e-05, -9.93441367e-01, 7.61240656e-03,\n", - " -6.55135424e+00, -6.89772978e-04, 1.94450477e-04, -1.87227769e-03,\n", - " 3.66516201e-03, 4.88841023e-04, 1.64635658e+00, 4.37695898e-01,\n", - " 1.35442637e+00, 2.30190662e-04, 4.14470172e-04, 2.90988474e-02,\n", - " 1.43414664e+00, -5.35610631e-03, 8.71859953e-04, 1.42029970e-03,\n", - " -1.85555094e-01]),\n", - " array([-2.29785625e-06, 1.73542821e-01, 9.18796416e-01, 1.13553890e-01,\n", - " -1.51396959e-04, 2.34712311e-05, -9.93531827e-01, 7.64120987e-03,\n", - " -6.54968470e+00, -6.93286605e-04, 1.95284019e-04, -1.87105429e-03,\n", - " 3.47764798e-03, 4.92719494e-04, 1.64941476e+00, 5.19011327e-01,\n", - " 1.58772444e+00, -1.62208830e-04, 4.71908435e-04, 2.88033108e-02,\n", - " 1.66953539e+00, -3.51362726e-03, 8.33541636e-04, 1.22339587e-03,\n", - " -1.87514032e-01]),\n", - " array([-1.59743092e-06, 1.75287887e-01, 9.19008798e-01, 1.12650636e-01,\n", - " -1.51129719e-04, 2.33150277e-05, -9.93634646e-01, 7.66972381e-03,\n", - " -6.54778266e+00, -6.94963242e-04, 1.96079213e-04, -1.87002659e-03,\n", - " 3.28820052e-03, 4.96878853e-04, 1.65268609e+00, 5.99158185e-01,\n", - " 1.81817321e+00, -5.55230568e-04, 5.28020097e-04, 2.85139459e-02,\n", - " 1.90204882e+00, -1.67663687e-03, 7.95194452e-04, 1.02769704e-03,\n", - " -1.89447465e-01]),\n", - " array([-8.68810987e-07, 1.77053542e-01, 9.19300647e-01, 1.11634420e-01,\n", - " -1.50667718e-04, 2.31266681e-05, -9.93749331e-01, 7.69795595e-03,\n", - " -6.54565141e+00, -6.94811743e-04, 1.96836011e-04, -1.86919319e-03,\n", - " 3.09684907e-03, 5.01376193e-04, 1.65620203e+00, 6.78020448e-01,\n", - " 2.04533450e+00, -9.47835229e-04, 5.82740912e-04, 2.82321344e-02,\n", - " 2.13124474e+00, 1.51498805e-04, 7.56797451e-04, 8.33403337e-04,\n", - " -1.91351445e-01]),\n", - " array([-1.12424830e-07, 1.78839362e-01, 9.19671019e-01, 1.10507051e-01,\n", - " -1.50011577e-04, 2.29068105e-05, -9.93875328e-01, 7.72591517e-03,\n", - " -6.54329472e+00, -6.92844331e-04, 1.97554341e-04, -1.86855247e-03,\n", - " 2.90362700e-03, 5.06266506e-04, 1.65999204e+00, 7.55484198e-01,\n", - " 2.26877567e+00, -1.33899163e-03, 6.36014763e-04, 2.79592198e-02,\n", - " 2.35668658e+00, 1.96741169e-03, 7.18330729e-04, 6.40716611e-04,\n", - " -1.93222076e-01]),\n", - " array([ 6.71231351e-07, 1.80644880e-01, 9.20118863e-01, 1.09270550e-01,\n", - " -1.49162417e-04, 2.26561620e-05, -9.94012034e-01, 7.75361166e-03,\n", - " -6.54071678e+00, -6.89076590e-04, 1.98234117e-04, -1.86810263e-03,\n", - " 2.70857148e-03, 5.11602207e-04, 1.66408339e+00, 8.31437858e-01,\n", - " 2.48807079e+00, -1.72768167e-03, 6.87792611e-04, 2.76964966e-02,\n", - " 2.57794452e+00, 3.76774100e-03, 6.79775726e-04, 4.49840388e-04,\n", - " -1.95055519e-01]),\n", - " array([ 1.48159642e-06, 1.82469593e-01, 9.20643019e-01, 1.07927142e-01,\n", - " -1.48121859e-04, 2.23754744e-05, -9.94158795e-01, 7.78105686e-03,\n", - " -6.53792218e+00, -6.83527448e-04, 1.98875233e-04, -1.86784165e-03,\n", - " 2.51172347e-03, 5.17432692e-04, 1.66850094e+00, 9.05772438e-01,\n", - " 2.70280178e+00, -2.11290506e-03, 7.38031356e-04, 2.74452007e-02,\n", - " 2.79459666e+00, 5.54914261e-03, 6.41115493e-04, 2.60979838e-04,\n", - " -1.96848009e-01]),\n", - " array([ 2.31804759e-06, 1.84312962e-01, 9.21242220e-01, 1.06479255e-01,\n", - " -1.46892012e-04, 2.20655409e-05, -9.94314913e-01, 7.80826336e-03,\n", - " -6.53491595e+00, -6.76219149e-04, 1.99477568e-04, -1.86776731e-03,\n", - " 2.31312761e-03, 5.23803919e-04, 1.67326700e+00, 9.78381774e-01,\n", - " 2.91255952e+00, -2.49368381e-03, 7.86692618e-04, 2.72064995e-02,\n", - " 3.00623017e+00, 7.30829835e-03, 6.02334956e-04, 7.43416846e-05,\n", - " -1.98595861e-01]),\n", - " array([ 3.17990406e-06, 1.86174415e-01, 9.21915096e-01, 1.04929513e-01,\n", - " -1.45475456e-04, 2.17271926e-05, -9.94479651e-01, 7.83524485e-03,\n", - " -6.53170351e+00, -6.67177224e-04, 2.00040989e-04, -1.86787718e-03,\n", - " 2.11283213e-03, 5.30758022e-04, 1.67840118e+00, 1.04916277e+00,\n", - " 3.11694504e+00, -2.86906638e-03, 8.33741471e-04, 2.69814829e-02,\n", - " 3.21244242e+00, 9.04192530e-03, 5.63421143e-04, -1.09865945e-04,\n", - " -2.00295478e-01]),\n", - " array([ 4.06643102e-06, 1.88053351e-01, 9.22660173e-01, 1.03280736e-01,\n", - " -1.43875234e-04, 2.13612962e-05, -9.94652235e-01, 7.86201600e-03,\n", - " -6.52829067e+00, -6.56430439e-04, 2.00565352e-04, -1.86816861e-03,\n", - " 1.91088876e-03, 5.38332957e-04, 1.68392020e+00, 1.11801565e+00,\n", - " 3.31557056e+00, -3.23813155e-03, 8.79145152e-04, 2.67711549e-02,\n", - " 3.41284212e+00, 1.07467850e-02, 5.24363393e-04, -2.91433714e-04,\n", - " -2.01943368e-01]),\n", - " array([ 4.97684391e-06, 1.89949144e-01, 9.23475877e-01, 1.01535928e-01,\n", - " -1.42094832e-04, 2.09687519e-05, -9.94831863e-01, 7.88859243e-03,\n", - " -6.52468362e+00, -6.44010747e-04, 2.01050506e-04, -1.86863876e-03,\n", - " 1.70735261e-03, 5.46562194e-04, 1.68983785e+00, 1.18484418e+00,\n", - " 3.50806062e+00, -3.59999192e-03, 9.22871757e-04, 2.65764253e-02,\n", - " 3.60705038e+00, 1.24196924e-02, 4.85153539e-04, -4.70151336e-04,\n", - " -2.03536149e-01]),\n", - " array([ 5.91031301e-06, 1.91861142e-01, 9.24360537e-01, 9.96982749e-02,\n", - " -1.40138165e-04, 2.05504919e-05, -9.95017705e-01, 7.91499053e-03,\n", - " -6.52088892e+00, -6.29953222e-04, 2.01496292e-04, -1.86928457e-03,\n", - " 1.50228206e-03, 5.55474444e-04, 1.69616487e+00, 1.24955592e+00,\n", - " 3.69405315e+00, -3.95379702e-03, 9.64888961e-04, 2.63981030e-02,\n", - " 3.79470181e+00, 1.40575251e-02, 4.45786056e-04, -6.45807884e-04,\n", - " -2.05070557e-01]),\n", - " array([ 6.86596823e-06, 1.93788674e-01, 9.25312388e-01, 9.77711376e-02,\n", - " -1.38009553e-04, 2.01074796e-05, -9.95208915e-01, 7.94122742e-03,\n", - " -6.51691347e+00, -6.14295990e-04, 2.01902550e-04, -1.87010276e-03,\n", - " 1.29573859e-03, 5.65093432e-04, 1.70290886e+00, 1.31206246e+00,\n", - " 3.87320047e+00, -4.29873600e-03, 1.00516278e-03, 2.62368891e-02,\n", - " 3.97544560e+00, 1.56572315e-02, 4.06258187e-04, -8.18192162e-04,\n", - " -2.06543462e-01]),\n", - " array([ 7.84290410e-06, 1.95731053e-01, 9.26329572e-01, 9.57580442e-02,\n", - " -1.35713704e-04, 1.96407091e-05, -9.95404630e-01, 7.96732079e-03,\n", - " -6.51276452e+00, -5.97080150e-04, 2.02269120e-04, -1.87108986e-03,\n", - " 1.08778672e-03, 5.75437713e-04, 1.71007426e+00, 1.37227964e+00,\n", - " 4.04517036e+00, -4.63404001e-03, 1.04365641e-03, 2.60933718e-02,\n", - " 4.14894648e+00, 1.72158397e-02, 3.66570030e-04, -9.87093138e-04,\n", - " -2.07951872e-01]),\n", - " array([ 8.84018492e-06, 1.97687577e-01, 9.27410144e-01, 9.36626825e-02,\n", - " -1.33255692e-04, 1.91512057e-05, -9.95603979e-01, 7.99328881e-03,\n", - " -6.50844964e+00, -5.78349685e-04, 2.02595845e-04, -1.87224216e-03,\n", - " 8.78493782e-04, 5.86520534e-04, 1.71766235e+00, 1.43012778e+00,\n", - " 4.20964698e+00, -4.95898402e-03, 1.08032914e-03, 2.59680218e-02,\n", - " 4.31488575e+00, 1.87304658e-02, 3.26724597e-04, -1.15230042e-03,\n", - " -2.09292940e-01]),\n", - " array([ 9.85685002e-06, 1.99657535e-01, 9.28552073e-01, 9.14888924e-02,\n", - " -1.30640935e-04, 1.86400267e-05, -9.95806088e-01, 8.01915000e-03,\n", - " -6.50397668e+00, -5.58151363e-04, 2.02882572e-04, -1.87355576e-03,\n", - " 6.67929801e-04, 5.98349743e-04, 1.72567121e+00, 1.48553192e+00,\n", - " 4.36633184e+00, -5.27288838e-03, 1.11513540e-03, 2.58611883e-02,\n", - " 4.47296217e+00, 2.01983213e-02, 2.86727839e-04, -1.31360482e-03,\n", - " -2.10563981e-01]),\n", - " array([ 1.08919192e-05, 2.01640209e-01, 9.29753248e-01, 8.92406565e-02,\n", - " -1.27875172e-04, 1.81082626e-05, -9.96010085e-01, 8.04492310e-03,\n", - " -6.49935378e+00, -5.36534642e-04, 2.03129161e-04, -1.87502656e-03,\n", - " 4.56167331e-04, 6.10927742e-04, 1.73409578e+00, 1.53842198e+00,\n", - " 4.51494463e+00, -5.57511987e-03, 1.14802395e-03, 2.57730971e-02,\n", - " 4.62289292e+00, 2.16167214e-02, 2.46588636e-04, -1.47079892e-03,\n", - " -2.11762470e-01]),\n", - " array([ 1.19443978e-05, 2.03634879e-01, 9.31011482e-01, 8.69220917e-02,\n", - " -1.24964438e-04, 1.75570388e-05, -9.96215104e-01, 8.07062695e-03,\n", - " -6.49458937e+00, -5.13551550e-04, 2.03335480e-04, -1.87665024e-03,\n", - " 2.43281275e-04, 6.24251486e-04, 1.74292789e+00, 1.58873301e+00,\n", - " 4.65522413e+00, -5.86509241e-03, 1.17893718e-03, 2.57038487e-02,\n", - " 4.76441438e+00, 2.29830917e-02, 2.06318760e-04, -1.62367774e-03,\n", - " -2.12886056e-01]),\n", - " array([ 1.30132826e-05, 2.05640823e-01, 9.32324514e-01, 8.45374395e-02,\n", - " -1.21915044e-04, 1.69875180e-05, -9.96420296e-01, 8.09628036e-03,\n", - " -6.48969209e+00, -4.89256574e-04, 2.03501413e-04, -1.87842228e-03,\n", - " 2.93487065e-05, 6.38312523e-04, 1.75215635e+00, 1.63640538e+00,\n", - " 4.78692896e+00, -6.14226741e-03, 1.20781068e-03, 2.56534180e-02,\n", - " 4.89728296e+00, 2.42949757e-02, 1.65932801e-04, -1.77203940e-03,\n", - " -2.13932568e-01]),\n", - " array([ 1.40975666e-05, 2.07657323e-01, 9.33690015e-01, 8.20910560e-02,\n", - " -1.18733550e-04, 1.64009024e-05, -9.96624826e-01, 8.12190202e-03,\n", - " -6.48467081e+00, -4.63706533e-04, 2.03626861e-04, -1.88033796e-03,\n", - " -1.85551314e-04, 6.53097082e-04, 1.76176708e+00, 1.68138489e+00,\n", - " 4.90983828e+00, -6.40615374e-03, 1.23457287e-03, 2.56216552e-02,\n", - " 5.02127585e+00, 2.55500410e-02, 1.25448063e-04, -1.91568591e-03,\n", - " -2.14900020e-01]),\n", - " array([ 1.51962446e-05, 2.09683668e-01, 9.35105594e-01, 7.95874013e-02,\n", - " -1.15426743e-04, 1.57984360e-05, -9.96827885e-01, 8.14751031e-03,\n", - " -6.47953462e+00, -4.36960448e-04, 2.03711745e-04, -1.88239239e-03,\n", - " -4.01337932e-04, 6.68586194e-04, 1.77174316e+00, 1.72362305e+00,\n", - " 5.02375252e+00, -6.65630739e-03, 1.25914499e-03, 2.56082876e-02,\n", - " 5.13619163e+00, 2.67460856e-02, 8.48844349e-05, -2.05442385e-03,\n", - " -2.15786618e-01]),\n", - " array([ 1.63083182e-05, 2.11719157e-01, 9.36568798e-01, 7.70310296e-02,\n", - " -1.12001616e-04, 1.51814079e-05, -9.97028690e-01, 8.17312323e-03,\n", - " -6.47429277e+00, -4.09079404e-04, 2.03756009e-04, -1.88458045e-03,\n", - " -6.17928698e-04, 6.84755857e-04, 1.78206502e+00, 1.76307710e+00,\n", - " 5.12849393e+00, -6.89233089e-03, 1.28144113e-03, 2.56129222e-02,\n", - " 5.24185096e+00, 2.78810439e-02, 4.42642287e-05, -2.18806526e-03,\n", - " -2.16590766e-01]),\n", - " array([ 1.74328008e-05, 2.13763100e-01, 9.38077124e-01, 7.44265771e-02,\n", - " -1.08465340e-04, 1.45511545e-05, -9.97226490e-01, 8.19875828e-03,\n", - " -6.46895467e+00, -3.80126412e-04, 2.03759621e-04, -1.88689688e-03,\n", - " -8.35239768e-04, 7.01577235e-04, 1.79271059e+00, 1.79971024e+00,\n", - " 5.22390714e+00, -7.11387240e-03, 1.30136860e-03, 2.56350501e-02,\n", - " 5.33809705e+00, 2.89529919e-02, 3.61199664e-06, -2.31642839e-03,\n", - " -2.17311071e-01]),\n", - " array([ 1.85687222e-05, 2.15814825e-01, 9.39628019e-01, 7.17787516e-02,\n", - " -1.04825247e-04, 1.39090620e-05, -9.97420573e-01, 8.22443233e-03,\n", - " -6.46352987e+00, -3.50166259e-04, 2.03722576e-04, -1.88933622e-03,\n", - " -1.05318611e-03, 7.19016886e-04, 1.80365551e+00, 1.83349171e+00,\n", - " 5.30985962e+00, -7.32062462e-03, 1.31882848e-03, 2.56740514e-02,\n", - " 5.42479617e+00, 2.99601527e-02, -3.70456765e-05, -2.43933858e-03,\n", - " -2.17946345e-01]),\n", - " array([ 1.97151334e-05, 2.17873676e-01, 9.41218886e-01, 6.90923202e-02,\n", - " -1.01088806e-04, 1.32565687e-05, -9.97610265e-01, 8.25016153e-03,\n", - " -6.45802804e+00, -3.19265359e-04, 2.03644895e-04, -1.89189285e-03,\n", - " -1.27168172e-03, 7.37037030e-04, 1.81487324e+00, 1.86439687e+00,\n", - " 5.38624208e+00, -7.51232354e-03, 1.33371639e-03, 2.57292010e-02,\n", - " 5.50183804e+00, 3.09009003e-02, -7.76804001e-05, -2.55662908e-03,\n", - " -2.18495611e-01]),\n", - " array([ 2.08711106e-05, 2.19939017e-01, 9.42847092e-01, 6.63720979e-02,\n", - " -9.72636012e-05, 1.25951671e-05, -9.97794936e-01, 8.27596121e-03,\n", - " -6.45245890e+00, -2.87491594e-04, 2.03526633e-04, -1.89456099e-03,\n", - " -1.49063983e-03, 7.55595831e-04, 1.82633538e+00, 1.89240730e+00,\n", - " 5.45296878e+00, -7.68874702e-03, 1.34592342e-03, 2.57996757e-02,\n", - " 5.56913614e+00, 3.17737648e-02, -1.18262222e-04, -2.66814190e-03,\n", - " -2.18958107e-01]),\n", - " array([ 2.20357593e-05, 2.22010236e-01, 9.44509971e-01, 6.36229355e-02,\n", - " -9.33573137e-05, 1.19264050e-05, -9.97974004e-01, 8.30184577e-03,\n", - " -6.44683227e+00, -2.54914159e-04, 2.03367873e-04, -1.89733472e-03,\n", - " -1.70997312e-03, 7.74647713e-04, 1.83801180e+00, 1.91751085e+00,\n", - " 5.50997775e+00, -7.84971328e-03, 1.35533737e-03, 2.58845620e-02,\n", - " 5.62662795e+00, 3.25774355e-02, -1.58759887e-04, -2.77372868e-03,\n", - " -2.19333284e-01]),\n", - " array([ 2.32082180e-05, 2.24086745e-01, 9.46204832e-01, 6.08497075e-02,\n", - " -8.93777012e-05, 1.12518862e-05, -9.98146936e-01, 8.32782863e-03,\n", - " -6.44115800e+00, -2.21603394e-04, 2.03168732e-04, -1.90020797e-03,\n", - " -1.92959393e-03, 7.94143698e-04, 1.84987093e+00, 1.93970166e+00,\n", - " 5.55723098e+00, -7.99507927e-03, 1.36184406e-03, 2.59828646e-02,\n", - " 5.67427513e+00, 3.33107647e-02, -1.99141105e-04, -2.87325146e-03,\n", - " -2.19620810e-01]),\n", - " array([ 2.43876615e-05, 2.26167985e-01, 9.47928962e-01, 5.80572994e-02,\n", - " -8.53325794e-05, 1.05732710e-05, -9.98313249e-01, 8.35392215e-03,\n", - " -6.43544593e+00, -1.87630624e-04, 2.02929359e-04, -1.90317455e-03,\n", - " -2.14941450e-03, 8.14031751e-04, 1.86187998e+00, 1.95898017e+00,\n", - " 5.59471448e+00, -8.12473910e-03, 1.36532894e-03, 2.60935156e-02,\n", - " 5.71206357e+00, 3.39727703e-02, -2.39372827e-04, -2.96658355e-03,\n", - " -2.19820571e-01]),\n", - " array([ 2.55733040e-05, 2.28253421e-01, 9.49679633e-01, 5.52505964e-02,\n", - " -8.12298047e-05, 9.89227501e-06, -9.98472516e-01, 8.38013753e-03,\n", - " -6.42970593e+00, -1.53067985e-04, 2.02649938e-04, -1.90622816e-03,\n", - " -2.36934717e-03, 8.34257156e-04, 1.87400521e+00, 1.97535313e+00,\n", - " 5.62243828e+00, -8.23862239e-03, 1.36567870e-03, 2.62153845e-02,\n", - " 5.74000339e+00, 3.45626388e-02, -2.79421526e-04, -3.05361024e-03,\n", - " -2.19932672e-01]),\n", - " array([ 2.67644015e-05, 2.30342551e-01, 9.51454110e-01, 5.24344701e-02,\n", - " -7.70772568e-05, 9.21066794e-06, -9.98624364e-01, 8.40648482e-03,\n", - " -6.42394780e+00, -1.17988258e-04, 2.02330684e-04, -1.90936239e-03,\n", - " -2.58930460e-03, 8.54762888e-04, 1.88621213e+00, 1.98883355e+00,\n", - " 5.64043634e+00, -8.33669268e-03, 1.36278319e-03, 2.63472884e-02,\n", - " 5.75812888e+00, 3.50797272e-02, -3.19253481e-04, -3.13422956e-03,\n", - " -2.19957432e-01]),\n", - " array([ 2.79602543e-05, 2.32434903e-01, 9.53249654e-01, 4.96137668e-02,\n", - " -7.28828230e-05, 8.53027073e-06, -9.98768476e-01, 8.43297282e-03,\n", - " -6.41818130e+00, -8.24646932e-05, 2.01971849e-04, -1.91257075e-03,\n", - " -2.80919999e-03, 8.75490008e-04, 1.89846582e+00, 1.99944062e+00,\n", - " 5.64876639e+00, -8.41894588e-03, 1.35653730e-03, 2.64880029e-02,\n", - " 5.76649829e+00, 3.55235647e-02, -3.58835048e-04, -3.20835296e-03,\n", - " -2.19895386e-01]),\n", - " array([ 2.91602088e-05, 2.34530035e-01, 9.55063530e-01, 4.67932954e-02,\n", - " -6.86543822e-05, 7.85295212e-06, -9.98904591e-01, 8.45960910e-03,\n", - " -6.41241611e+00, -4.65708393e-05, 2.01573716e-04, -1.91584665e-03,\n", - " -3.02894727e-03, 8.96378061e-04, 1.91073114e+00, 2.00719968e+00,\n", - " 5.64750965e+00, -8.48540883e-03, 1.34684304e-03, 2.66362732e-02,\n", - " 5.76519361e+00, 3.58938539e-02, -3.98132943e-04, -3.27590597e-03,\n", - " -2.19747284e-01]),\n", - " array([ 3.03636589e-05, 2.36627540e-01, 9.56893009e-01, 4.39778153e-02,\n", - " -6.43997909e-05, 7.18062395e-06, -9.99032506e-01, 8.48639992e-03,\n", - " -6.40666179e+00, -1.03803675e-05, 2.01136602e-04, -1.91918348e-03,\n", - " -3.24846135e-03, 9.17365469e-04, 1.92297301e+00, 2.01214205e+00,\n", - " 5.63677055e+00, -8.53613790e-03, 1.33361156e-03, 2.67908250e-02,\n", - " 5.75432021e+00, 3.61904719e-02, -4.37114496e-04, -3.33682871e-03,\n", - " -2.19514083e-01]),\n", - " array([ 3.15700472e-05, 2.38727041e-01, 9.58735380e-01, 4.11720245e-02,\n", - " -6.01268685e-05, 6.51523550e-06, -9.99152071e-01, 8.51335030e-03,\n", - " -6.40092778e+00, 2.60331030e-05, 2.00660854e-04, -1.92257456e-03,\n", - " -3.46765830e-03, 9.38389939e-04, 1.93515662e+00, 2.01430495e+00,\n", - " 5.61667625e+00, -8.57121780e-03, 1.31676532e-03, 2.69503763e-02,\n", - " 5.73400646e+00, 3.64134704e-02, -4.75747913e-04, -3.39107646e-03,\n", - " -2.19196948e-01]),\n", - " array([ 3.27788657e-05, 2.40828195e-01, 9.60587951e-01, 3.83805482e-02,\n", - " -5.58433843e-05, 5.85876664e-06, -9.99263194e-01, 8.54046395e-03,\n", - " -6.39522338e+00, 6.25961790e-05, 2.00146851e-04, -1.92601318e-03,\n", - " -3.68645555e-03, 9.59388861e-04, 1.94724771e+00, 2.01373133e+00,\n", - " 5.58737623e+00, -8.59076038e-03, 1.29624014e-03, 2.71136485e-02,\n", - " 5.70440318e+00, 3.65630760e-02, -5.14002508e-04, -3.43862007e-03,\n", - " -2.18797244e-01]),\n", - " array([ 3.39896562e-05, 2.42930692e-01, 9.62448055e-01, 3.56079274e-02,\n", - " -5.15570440e-05, 5.21321996e-06, -9.99365835e-01, 8.56774332e-03,\n", - " -6.38955770e+00, 9.92358683e-05, 1.99595002e-04, -1.92949262e-03,\n", - " -3.90477208e-03, 9.80299708e-04, 1.95921277e+00, 2.01046970e+00,\n", - " 5.54904165e+00, -8.59490368e-03, 1.27198727e-03, 2.72793772e-02,\n", - " 5.66568311e+00, 3.66396893e-02, -5.51848930e-04, -3.47944629e-03,\n", - " -2.18316535e-01]),\n", - " array([ 3.52020102e-05, 2.45034255e-01, 9.64313058e-01, 3.28586083e-02,\n", - " -4.72754770e-05, 4.58061188e-06, -9.99460009e-01, 8.59518965e-03,\n", - " -6.38393966e+00, 1.35879752e-04, 1.99005743e-04, -1.93300618e-03,\n", - " -4.12252866e-03, 1.00106042e-03, 1.97101928e+00, 2.00457393e+00,\n", - " 5.50186476e+00, -8.58381105e-03, 1.24397535e-03, 2.74463233e-02,\n", - " 5.61804026e+00, 3.66438840e-02, -5.89259361e-04, -3.51355809e-03,\n", - " -2.17756575e-01]),\n", - " array([ 3.64155684e-05, 2.47138638e-01, 9.66180363e-01, 3.01369312e-02,\n", - " -4.30062247e-05, 3.96296272e-06, -9.99545779e-01, 8.62280293e-03,\n", - " -6.37837797e+00, 1.72456158e-04, 1.98379535e-04, -1.93654716e-03,\n", - " -4.33964796e-03, 1.02160981e-03, 1.98263591e+00, 1.99610307e+00,\n", - " 5.44605815e+00, -8.55767040e-03, 1.21219231e-03, 2.76132835e-02,\n", - " 5.56168919e+00, 3.65764056e-02, -6.26207704e-04, -3.54097483e-03,\n", - " -2.17119300e-01]),\n", - " array([ 3.76300202e-05, 2.49243626e-01, 9.68047413e-01, 2.74471206e-02,\n", - " -3.87567277e-05, 3.36228592e-06, -9.99623256e-01, 8.65058203e-03,\n", - " -6.37288110e+00, 2.08894327e-04, 1.97716866e-04, -1.94010889e-03,\n", - " -4.55605478e-03, 1.04188790e-03, 1.99403269e+00, 1.98512107e+00,\n", - " 5.38185402e+00, -8.51669362e-03, 1.17664704e-03, 2.77791001e-02,\n", - " 5.49686421e+00, 3.64381693e-02, -6.62669745e-04, -3.56173238e-03,\n", - " -2.16406826e-01]),\n", - " array([ 3.88451026e-05, 2.51349035e-01, 9.69911701e-01, 2.47932755e-02,\n", - " -3.45343147e-05, 2.78057637e-06, -9.99692599e-01, 8.67852470e-03,\n", - " -6.36745728e+00, 2.45124585e-04, 1.97018242e-04, -1.94368477e-03,\n", - " -4.77167622e-03, 1.06183632e-03, 2.00518124e+00, 1.97169661e+00,\n", - " 5.30950330e+00, -8.46111608e-03, 1.13737097e-03, 2.79426703e-02,\n", - " 5.42381856e+00, 3.62302578e-02, -6.98623285e-04, -3.57588310e-03,\n", - " -2.15621439e-01]),\n", - " array([ 4.00605988e-05, 2.53454712e-01, 9.71770771e-01, 2.21793601e-02,\n", - " -3.03461900e-05, 2.21979810e-06, -9.99754007e-01, 8.70662766e-03,\n", - " -6.36211446e+00, 2.81078503e-04, 1.96284194e-04, -1.94726827e-03,\n", - " -4.98644180e-03, 1.08139862e-03, 2.01605488e+00, 1.95590274e+00,\n", - " 5.22927478e+00, -8.39119619e-03, 1.09441940e-03, 2.81029551e-02,\n", - " 5.34282349e+00, 3.59539178e-02, -7.34048261e-04, -3.58349584e-03,\n", - " -2.14765583e-01]),\n", - " array([ 4.12763364e-05, 2.55560530e-01, 9.73622222e-01, 1.96091949e-02,\n", - " -2.61994225e-05, 1.68187137e-06, -9.99807721e-01, 8.73488664e-03,\n", - " -6.35686029e+00, 3.16689060e-04, 1.95515267e-04, -1.95085292e-03,\n", - " -5.20028366e-03, 1.10052064e-03, 2.02662880e+00, 1.93781670e+00,\n", - " 5.14145412e+00, -8.30721519e-03, 1.04787258e-03, 2.82589869e-02,\n", - " 5.25416727e+00, 3.56105572e-02, -7.68926834e-04, -3.58465572e-03,\n", - " -2.13841858e-01]),\n", - " array([ 4.24921858e-05, 2.57666390e-01, 9.75463716e-01, 1.70864489e-02,\n", - " -2.21009340e-05, 1.16865924e-06, -9.99854016e-01, 8.76329652e-03,\n", - " -6.35170214e+00, 3.51890800e-04, 1.94712024e-04, -1.95443239e-03,\n", - " -5.41313667e-03, 1.11915078e-03, 2.03688018e+00, 1.91751959e+00,\n", - " 5.04634286e+00, -8.20947683e-03, 9.97836552e-04, 2.84098768e-02,\n", - " 5.15815421e+00, 3.52017405e-02, -8.03243456e-04, -3.57946391e-03,\n", - " -2.12853007e-01]),\n", - " array([ 4.37080576e-05, 2.59772216e-01, 9.77292981e-01, 1.46146314e-02,\n", - " -1.80574876e-05, 6.81953944e-07, -9.99893200e-01, 8.79185134e-03,\n", - " -6.34664704e+00, 3.86619985e-04, 1.93875039e-04, -1.95800043e-03,\n", - " -5.62493857e-03, 1.13724033e-03, 2.04678827e+00, 1.89509606e+00,\n", - " 4.94425741e+00, -8.09830728e-03, 9.44443702e-04, 2.85548205e-02,\n", - " 5.05510360e+00, 3.47291847e-02, -8.36984910e-04, -3.56803730e-03,\n", - " -2.11801905e-01]),\n", - " array([ 4.49239009e-05, 2.61877960e-01, 9.79107812e-01, 1.21970853e-02,\n", - " -1.40756761e-05, 2.23463119e-07, -9.99925613e-01, 8.82054444e-03,\n", - " -6.34170169e+00, 4.20814739e-04, 1.93004899e-04, -1.96155093e-03,\n", - " -5.83563013e-03, 1.15474370e-03, 2.05633452e+00, 1.87063404e+00,\n", - " 4.83552785e+00, -7.97405490e-03, 8.87852990e-04, 2.86931035e-02,\n", - " 4.94534858e+00, 3.41947542e-02, -8.70140329e-04, -3.55050809e-03,\n", - " -2.10691554e-01]),\n", - " array([ 4.61397001e-05, 2.63983593e-01, 9.80906078e-01, 9.83698063e-03,\n", - " -1.01619106e-05, -2.05203971e-07, -9.99951616e-01, 8.84936855e-03,\n", - " -6.33687245e+00, 4.54415194e-04, 1.92102197e-04, -1.96507796e-03,\n", - " -6.04515520e-03, 1.17161871e-03, 2.06550263e+00, 1.84422443e+00,\n", - " 4.72049693e+00, -7.83709021e-03, 8.28249870e-04, 2.88241055e-02,\n", - " 4.82923498e+00, 3.36004551e-02, -9.02701190e-04, -3.52702326e-03,\n", - " -2.09525068e-01]),\n", - " array([ 4.73554726e-05, 2.66089106e-01, 9.82685725e-01, 7.53730852e-03,\n", - " -6.32240896e-06, -6.02549938e-07, -9.99971594e-01, 8.87831585e-03,\n", - " -6.33216533e+00, 4.87363624e-04, 1.91167536e-04, -1.96857570e-03,\n", - " -6.25346086e-03, 1.18782676e-03, 2.07427855e+00, 1.81596075e+00,\n", - " 4.59951878e+00, -7.68780567e-03, 7.65845879e-04, 2.89473031e-02,\n", - " 4.70712023e+00, 3.29484292e-02, -9.34661289e-04, -3.49774406e-03,\n", - " -2.08305664e-01]),\n", - " array([ 4.85712658e-05, 2.68194511e-01, 9.84444779e-01, 5.30087614e-03,\n", - " -2.56318437e-06, -9.67202392e-07, -9.99985950e-01, 8.90737813e-03,\n", - " -6.32758596e+00, 5.19604571e-04, 1.90201519e-04, -1.97203855e-03,\n", - " -6.46049751e-03, 1.20333308e-03, 2.08265059e+00, 1.78593886e+00,\n", - " 4.47295783e+00, -7.52661554e-03, 7.00877883e-04, 2.90622719e-02,\n", - " 4.57937205e+00, 3.22409475e-02, -9.66016692e-04, -3.46284532e-03,\n", - " -2.07036652e-01]),\n", - " array([ 4.97871543e-05, 2.70299835e-01, 9.86181345e-01, 3.13030209e-03,\n", - " 1.10996622e-06, -1.29792647e-06, -9.99995101e-01, 8.93654681e-03,\n", - " -6.32313959e+00, 5.51084974e-04, 1.89204754e-04, -1.97546106e-03,\n", - " -6.66621893e-03, 1.21810683e-03, 2.09060935e+00, 1.75425660e+00,\n", - " 4.34118753e+00, -7.35395569e-03, 6.33606988e-04, 2.91686874e-02,\n", - " 4.44636732e+00, 3.14804029e-02, -9.96765665e-04, -3.42251476e-03,\n", - " -2.05721422e-01]),\n", - " array([ 5.10032369e-05, 2.72405120e-01, 9.87893618e-01, 1.02801245e-03,\n", - " 4.69147334e-06, -1.59363661e-06, -9.99999472e-01, 8.96581314e-03,\n", - " -6.31883110e+00, 5.81754277e-04, 1.88177845e-04, -1.97883801e-03,\n", - " -6.87058237e-03, 1.23212131e-03, 2.09814776e+00, 1.72101351e+00,\n", - " 4.20458914e+00, -7.17028328e-03, 5.64317112e-04, 2.92663251e-02,\n", - " 4.30849078e+00, 3.06693030e-02, -1.02690859e-03, -3.37695223e-03,\n", - " -2.04363438e-01]),\n", - " array([ 5.22196333e-05, 2.74510420e-01, 9.89579876e-01, -1.00376246e-03,\n", - " 8.17600615e-06, -1.85340740e-06, -9.99999496e-01, 8.99516820e-03,\n", - " -6.31466497e+00, 6.11564539e-04, 1.87121397e-04, -1.98216438e-03,\n", - " -7.07354859e-03, 1.24535398e-03, 2.10526101e+00, 1.68631049e+00,\n", - " 4.06355051e+00, -6.97607642e-03, 4.93313238e-04, 2.93550588e-02,\n", - " 4.16613384e+00, 2.98102619e-02, -1.05644787e-03, -3.32636886e-03,\n", - " -2.02966218e-01]),\n", - " array([ 5.34364814e-05, 2.76615802e-01, 9.91238489e-01, -2.96299071e-03,\n", - " 1.15584834e-05, -2.07648331e-06, -9.99995610e-01, 9.02460306e-03,\n", - " -6.31064527e+00, 6.40470531e-04, 1.86036009e-04, -1.98543537e-03,\n", - " -7.27508192e-03, 1.25778662e-03, 2.11194654e+00, 1.65024948e+00,\n", - " 3.91846481e+00, -6.77183366e-03, 4.20919359e-04, 2.94348587e-02,\n", - " 4.01969326e+00, 2.89059917e-02, -1.08538780e-03, -3.27098622e-03,\n", - " -2.01533331e-01]),\n", - " array([ 5.46539342e-05, 2.78721342e-01, 9.92867917e-01, -4.84784072e-03,\n", - " 1.48340842e-05, -2.26228723e-06, -9.99988249e-01, 9.05410884e-03,\n", - " -6.30677570e+00, 6.68429825e-04, 1.84922275e-04, -1.98864640e-03,\n", - " -7.47515030e-03, 1.26940531e-03, 2.11820397e+00, 1.61293319e+00,\n", - " 3.76972933e+00, -6.55807343e-03, 3.47476129e-04, 2.95057882e-02,\n", - " 3.86956995e+00, 2.79592940e-02, -1.11373445e-03, -3.21103537e-03,\n", - " -2.00068381e-01]),\n", - " array([ 5.58721565e-05, 2.80827122e-01, 9.94466712e-01, -6.65668264e-03,\n", - " 1.79982580e-05, -2.41042759e-06, -9.99977844e-01, 9.08367684e-03,\n", - " -6.30305954e+00, 6.95402875e-04, 1.83780779e-04, -1.99179316e-03,\n", - " -7.67372530e-03, 1.28020045e-03, 2.12403501e+00, 1.57446471e+00,\n", - " 3.61774417e+00, -6.33533333e-03, 2.73338257e-04, 2.95679994e-02,\n", - " 3.71616769e+00, 2.69730502e-02, -1.14149553e-03, -3.14675594e-03,\n", - " -1.98574997e-01]),\n", - " array([ 5.70913224e-05, 2.82933231e-01, 9.96033521e-01, -8.38808898e-03,\n", - " 2.10467348e-05, -2.52070397e-06, -9.99964819e-01, 9.11329857e-03,\n", - " -6.29949964e+00, 7.21353087e-04, 1.82612099e-04, -1.99487156e-03,\n", - " -7.87078212e-03, 1.29016677e-03, 2.12944335e+00, 1.53494730e+00,\n", - " 3.46291109e+00, -6.10416929e-03, 1.98871660e-04, 2.96217283e-02,\n", - " 3.55989188e+00, 2.59502125e-02, -1.16868022e-03, -3.07839512e-03,\n", - " -1.97056822e-01]),\n", - " array([ 5.83116120e-05, 2.85039762e-01, 9.97567085e-01, -1.00408347e-02,\n", - " 2.39755346e-05, -2.59311119e-06, -9.99949589e-01, 9.14296586e-03,\n", - " -6.29609850e+00, 7.46246882e-04, 1.81416800e-04, -1.99787776e-03,\n", - " -8.06629962e-03, 1.29930325e-03, 2.13443462e+00, 1.49448405e+00,\n", - " 3.30563223e+00, -5.86515455e-03, 1.24450430e-04, 2.96672890e-02,\n", - " 3.40114836e+00, 2.48937941e-02, -1.19529904e-03, -3.00620670e-03,\n", - " -1.95517502e-01]),\n", - " array([ 5.95332092e-05, 2.87146810e-01, 9.99066238e-01, -1.16138969e-02,\n", - " 2.67809753e-05, -2.62784161e-06, -9.99932556e-01, 9.17267093e-03,\n", - " -6.29285815e+00, 7.70053740e-04, 1.80195436e-04, -2.00080821e-03,\n", - " -8.26026030e-03, 1.30761303e-03, 2.13901622e+00, 1.45317762e+00,\n", - " 3.14630895e+00, -5.61887860e-03, 5.04536219e-05, 2.97050674e-02,\n", - " 3.24034214e+00, 2.38068587e-02, -1.22136369e-03, -2.93045000e-03,\n", - " -1.93960676e-01]),\n", - " array([ 6.07562984e-05, 2.89254470e-01, 1.00052991e+00, -1.31064530e-02,\n", - " 2.94596820e-05, -2.62528581e-06, -9.99914106e-01, 9.20240644e-03,\n", - " -6.28978028e+00, 7.92746251e-04, 1.78948550e-04, -2.00365960e-03,\n", - " -8.45265026e-03, 1.31510334e-03, 2.14319722e+00, 1.41112993e+00,\n", - " 2.98534063e+00, -5.36594587e-03, -2.27380653e-05, 2.97355134e-02,\n", - " 3.07787626e+00, 2.26925109e-02, -1.24688688e-03, -2.85138888e-03,\n", - " -1.92389961e-01]),\n", - " array([ 6.19810628e-05, 2.91362840e-01, 1.00195714e+00, -1.45178800e-02,\n", - " 3.20085930e-05, -2.58603143e-06, -9.99894610e-01, 9.23216558e-03,\n", - " -6.28686613e+00, 8.14300137e-04, 1.77676667e-04, -2.00642889e-03,\n", - " -8.64345921e-03, 1.32178530e-03, 2.14698824e+00, 1.36844194e+00,\n", - " 2.82312354e+00, -5.10697434e-03, -9.47456950e-05, 2.97591341e-02,\n", - " 2.91415060e+00, 2.15538856e-02, -1.27188218e-03, -2.76929069e-03,\n", - " -1.90808949e-01]),\n", - " array([ 6.32076814e-05, 2.93472013e-01, 1.00334703e+00, -1.58477515e-02,\n", - " 3.44249671e-05, -2.51086023e-06, -9.99874416e-01, 9.26194206e-03,\n", - " -6.28411657e+00, 8.34694274e-04, 1.76380304e-04, -2.00911332e-03,\n", - " -8.83268040e-03, 1.32767378e-03, 2.15040128e+00, 1.32521340e+00,\n", - " 2.66004970e+00, -4.84259402e-03, -1.65195530e-04, 2.97764854e-02,\n", - " 2.74956076e+00, 2.03941377e-02, -1.29636384e-03, -2.68442526e-03,\n", - " -1.89221188e-01]),\n", - " array([ 6.44363271e-05, 2.95582080e-01, 1.00469881e+00, -1.70958350e-02,\n", - " 3.67063890e-05, -2.40074340e-06, -9.99853855e-01, 9.29173022e-03,\n", - " -6.28153207e+00, 8.53910706e-04, 1.75059957e-04, -2.01171038e-03,\n", - " -9.02031058e-03, 1.33278721e-03, 2.15344962e+00, 1.28154257e+00,\n", - " 2.49650581e+00, -4.57344531e-03, -2.33722463e-04, 2.97881635e-02,\n", - " 2.58449698e+00, 1.92164317e-02, -1.32034667e-03, -2.59706387e-03,\n", - " -1.87630181e-01]),\n", - " array([ 6.56671651e-05, 2.97693130e-01, 1.00601179e+00, -1.82620887e-02,\n", - " 3.88507735e-05, -2.25683512e-06, -9.99833233e-01, 9.32152502e-03,\n", - " -6.27911273e+00, 8.71934637e-04, 1.73716111e-04, -2.01421786e-03,\n", - " -9.20634995e-03, 1.33714736e-03, 2.15614763e+00, 1.23752601e+00,\n", - " 2.33287222e+00, -4.30017722e-03, -2.99973386e-04, 2.97947969e-02,\n", - " 2.41934306e+00, 1.80239313e-02, -1.34384584e-03, -2.50747826e-03,\n", - " -1.86039370e-01]),\n", - " array([ 6.69003506e-05, 2.99805245e-01, 1.00728536e+00, -1.93466578e-02,\n", - " 4.08563692e-05, -2.08046446e-06, -9.99812835e-01, 9.35132206e-03,\n", - " -6.27685825e+00, 8.88754426e-04, 1.72349234e-04, -2.01663380e-03,\n", - " -9.39080207e-03, 1.34077910e-03, 2.15851067e+00, 1.19325838e+00,\n", - " 2.16952187e+00, -4.02344550e-03, -3.63610465e-04, 2.97970374e-02,\n", - " 2.25447537e+00, 1.68197892e-02, -1.36687678e-03, -2.41593964e-03,\n", - " -1.84452128e-01]),\n", - " array([ 6.81360275e-05, 3.01918502e-01, 1.00851904e+00, -2.03498698e-02,\n", - " 4.27217613e-05, -1.87312562e-06, -9.99792919e-01, 9.38111761e-03,\n", - " -6.27476799e+00, 9.04361563e-04, 1.70959779e-04, -2.01895652e-03,\n", - " -9.57367383e-03, 1.34371014e-03, 2.16055491e+00, 1.14883224e+00,\n", - " 2.00681937e+00, -3.74391070e-03, -4.24314272e-04, 2.97955517e-02,\n", - " 2.09026184e+00, 1.56071370e-02, -1.38945501e-03, -2.32271775e-03,\n", - " -1.82871755e-01]),\n", - " array([ 6.93743270e-05, 3.04032971e-01, 1.00971240e+00, -2.12722300e-02,\n", - " 4.44458722e-05, -1.63646674e-06, -9.99773720e-01, 9.41090862e-03,\n", - " -6.27284093e+00, 9.18750639e-04, 1.69548183e-04, -2.02118460e-03,\n", - " -9.75497529e-03, 1.34597075e-03, 2.16229719e+00, 1.10433780e+00,\n", - " 1.84512010e+00, -3.46223617e-03, -4.81786729e-04, 2.97910130e-02,\n", - " 1.92706107e+00, 1.43890751e-02, -1.41159600e-03, -2.22807990e-03,\n", - " -1.81301463e-01]),\n", - " array([ 7.06153664e-05, 3.06148716e-01, 1.01086512e+00, -2.21144164e-02,\n", - " 4.60279627e-05, -1.37227728e-06, -9.99755445e-01, 9.44069272e-03,\n", - " -6.27107571e+00, 9.31919302e-04, 1.68114868e-04, -2.02331689e-03,\n", - " -9.93471967e-03, 1.34759351e-03, 2.16375489e+00, 1.05986284e+00,\n", - " 1.68476929e+00, -3.17908596e-03, -5.35753839e-04, 2.97840929e-02,\n", - " 1.76522146e+00, 1.31686635e-02, -1.43331510e-03, -2.13229014e-03,\n", - " -1.79744372e-01]),\n", - " array([ 7.18592485e-05, 3.08265793e-01, 1.01197697e+00, -2.28772739e-02,\n", - " 4.74676302e-05, -1.08247417e-06, -9.99738280e-01, 9.47046817e-03,\n", - " -6.26947063e+00, 9.43868214e-04, 1.66660241e-04, -2.02535249e-03,\n", - " -1.01129232e-02, 1.34861296e-03, 2.16494578e+00, 1.01549245e+00,\n", - " 1.52610123e+00, -2.89512271e-03, -5.85968152e-04, 2.97754532e-02,\n", - " 1.60508035e+00, 1.19489119e-02, -1.45462736e-03, -2.03560837e-03,\n", - " -1.78203503e-01]),\n", - " array([ 7.31060602e-05, 3.10384251e-01, 1.01304778e+00, -2.35618086e-02,\n", - " 4.87648072e-05, -7.69086854e-07, -9.99722381e-01, 9.50023391e-03,\n", - " -6.26802366e+00, 9.54600985e-04, 1.65184693e-04, -2.02729078e-03,\n", - " -1.02896049e-02, 1.34906537e-03, 2.16588786e+00, 9.71308949e-01,\n", - " 1.36943852e+00, -2.61100553e-03, -6.32210954e-04, 2.97657389e-02,\n", - " 1.44696327e+00, 1.07327710e-02, -1.47554748e-03, -1.93828954e-03,\n", - " -1.76681767e-01]),\n", - " array([ 7.43558727e-05, 3.12504129e-01, 1.01407750e+00, -2.41691812e-02,\n", - " 4.99197580e-05, -4.34241374e-07, -9.99707881e-01, 9.52998948e-03,\n", - " -6.26673248e+00, 9.64124109e-04, 1.63688604e-04, -2.02913137e-03,\n", - " -1.04647869e-02, 1.34898836e-03, 2.16659928e+00, 9.27391694e-01,\n", - " 1.21509136e+00, -2.32738787e-03, -6.74294143e-04, 2.97555709e-02,\n", - " 1.29118324e+00, 9.52312419e-03, -1.49608968e-03, -1.84058289e-03,\n", - " -1.75181964e-01]),\n", - " array([ 7.56087405e-05, 3.14625460e-01, 1.01506614e+00, -2.47007009e-02,\n", - " 5.09330741e-05, -8.01437409e-08, -9.99694890e-01, 9.55973502e-03,\n", - " -6.26559444e+00, 9.72446888e-04, 1.62172336e-04, -2.03087410e-03,\n", - " -1.06384937e-02, 1.34842066e-03, 2.16709816e+00, 8.83816992e-01,\n", - " 1.06335686e+00, -2.04491540e-03, -7.12061769e-04, 2.97455397e-02,\n", - " 1.13804010e+00, 8.32277874e-03, -1.51626767e-03, -1.74273125e-03,\n", - " -1.73706775e-01]),\n", - " array([ 7.68647020e-05, 3.16748268e-01, 1.01601378e+00, -2.51578181e-02,\n", - " 5.18056690e-05, 2.90937322e-07, -9.99683491e-01, 9.58947122e-03,\n", - " -6.26460662e+00, 9.79581347e-04, 1.60636241e-04, -2.03251907e-03,\n", - " -1.08107524e-02, 1.34740175e-03, 2.16740250e+00, 8.40657967e-01,\n", - " 9.14518487e-01, -1.76422391e-03, -7.45391232e-04, 2.97361996e-02,\n", - " 9.87819892e-01, 7.13445866e-03, -1.53609452e-03, -1.64497036e-03,\n", - " -1.72258754e-01]),\n", - " array([ 7.81237787e-05, 3.18872567e-01, 1.01692060e+00, -2.55421173e-02,\n", - " 5.25387720e-05, 6.76688020e-07, -9.99673746e-01, 9.61919928e-03,\n", - " -6.26376583e+00, 9.85542144e-04, 1.59080659e-04, -2.03406660e-03,\n", - " -1.09815928e-02, 1.34597161e-03, 2.16753008e+00, 7.97984464e-01,\n", - " 7.68845529e-01, -1.48593727e-03, -7.74194115e-04, 2.97280634e-02,\n", - " 8.40794346e-01, 5.96079727e-03, -1.55558265e-03, -1.54752826e-03,\n", - " -1.70840327e-01]),\n", - " array([ 7.93859761e-05, 3.20998366e-01, 1.01778683e+00, -2.58553101e-02,\n", - " 5.31339200e-05, 1.07476735e-06, -9.99665694e-01, 9.64892088e-03,\n", - " -6.26306861e+00, 9.90346474e-04, 1.57505915e-04, -2.03551722e-03,\n", - " -1.11510465e-02, 1.34417039e-03, 2.16749833e+00, 7.55862962e-01,\n", - " 6.26592589e-01, -1.21066547e-03, -7.98416663e-04, 2.97215982e-02,\n", - " 6.97220387e-01, 4.80433062e-03, -1.57474380e-03, -1.45062475e-03,\n", - " -1.69453786e-01]),\n", - " array([ 8.06512838e-05, 3.23125663e-01, 1.01861279e+00, -2.60992274e-02,\n", - " 5.35929497e-05, 1.48282497e-06, -9.99659356e-01, 9.67863810e-03,\n", - " -6.26251127e+00, 9.94013966e-04, 1.55912326e-04, -2.03687169e-03,\n", - " -1.13191478e-02, 1.34203813e-03, 2.16732424e+00, 7.14356497e-01,\n", - " 4.87999189e-01, -9.39002673e-04, -8.18039892e-04, 2.97172216e-02,\n", - " 5.57339718e-01, 3.66749138e-03, -1.59358894e-03, -1.35447087e-03,\n", - " -1.68101284e-01]),\n", - " array([ 8.19196761e-05, 3.25254452e-01, 1.01939885e+00, -2.62758116e-02,\n", - " 5.39179878e-05, 1.89851896e-06, -9.99654730e-01, 9.70835340e-03,\n", - " -6.26208989e+00, 9.96566569e-04, 1.54300198e-04, -2.03813096e-03,\n", - " -1.14859327e-02, 1.33961454e-03, 2.16702430e+00, 6.73524596e-01,\n", - " 3.53289408e-01, -6.71525457e-04, -8.33079343e-04, 2.97152984e-02,\n", - " 4.21378455e-01, 2.55260324e-03, -1.61212830e-03, -1.25926848e-03,\n", - " -1.66784836e-01]),\n", - " array([ 8.31911124e-05, 3.27384715e-01, 1.02014545e+00, -2.63871088e-02,\n", - " 5.41114408e-05, 2.31953321e-06, -9.99651798e-01, 9.73806954e-03,\n", - " -6.26180034e+00, 9.98028445e-04, 1.52669826e-04, -2.03929617e-03,\n", - " -1.16514390e-02, 1.33693865e-03, 2.16661439e+00, 6.33423230e-01,\n", - " 2.22671583e-01, -4.08791040e-04, -8.43584483e-04, 2.97161388e-02,\n", - " 2.89546828e-01, 1.46187604e-03, -1.63037135e-03, -1.16520983e-03,\n", - " -1.65506311e-01]),\n", - " array([ 8.44655383e-05, 3.29516432e-01, 1.02085311e+00, -2.64352610e-02,\n", - " 5.41759843e-05, 2.74359435e-06, -9.99650526e-01, 9.76778954e-03,\n", - " -6.26163830e+00, 9.98425846e-04, 1.51021500e-04, -2.04036865e-03,\n", - " -1.18157064e-02, 1.33404868e-03, 2.16610974e+00, 5.94104769e-01,\n", - " 9.63380704e-02, -1.51335699e-04, -8.49637816e-04, 2.97199964e-02,\n", - " 1.62038943e-01, 3.97401291e-04, -1.64832680e-03, -1.07247727e-03,\n", - " -1.64267432e-01]),\n", - " array([ 8.57428867e-05, 3.31649573e-01, 1.02152238e+00, -2.64224980e-02,\n", - " 5.41145505e-05, 3.16848799e-06, -9.99650863e-01, 9.79751660e-03,\n", - " -6.26159927e+00, 9.97786995e-04, 1.49355497e-04, -2.04134989e-03,\n", - " -1.19787762e-02, 1.33098172e-03, 2.16552486e+00, 5.55617954e-01,\n", - " -2.55349295e-02, 1.00326740e-04, -8.51353580e-04, 2.97270680e-02,\n", - " 3.90325979e-02, -6.38851521e-04, -1.66600261e-03, -9.81242938e-04,\n", - " -1.63069776e-01]),\n", - " array([ 8.70230779e-05, 3.33784104e-01, 1.02215387e+00, -2.63511292e-02,\n", - " 5.39303167e-05, 3.59207416e-06, -9.99652747e-01, 9.82725410e-03,\n", - " -6.26167858e+00, 9.96141957e-04, 1.47672091e-04, -2.04224156e-03,\n", - " -1.21406910e-02, 1.32777358e-03, 2.16487350e+00, 5.18007884e-01,\n", - " -1.42787498e-01, 3.45706274e-04, -8.48876280e-04, 2.97374930e-02,\n", - " -7.93108373e-02, -1.64503821e-03, -1.68340602e-03, -8.91668546e-04,\n", - " -1.61914773e-01]),\n", - " array([ 8.83060218e-05, 3.35919986e-01, 1.02274826e+00, -2.62235353e-02,\n", - " 5.36266914e-05, 4.01230199e-06, -9.99656103e-01, 9.85700545e-03,\n", - " -6.26187143e+00, 9.93522514e-04, 1.45971547e-04, -2.04304546e-03,\n", - " -1.23014947e-02, 1.32445860e-03, 2.16416859e+00, 4.81316001e-01,\n", - " -2.55276058e-01, 5.84337939e-04, -8.42379076e-04, 2.97513538e-02,\n", - " -1.92846485e-01, -2.61944249e-03, -1.70054358e-03, -8.03905213e-04,\n", - " -1.60803702e-01]),\n", - " array([ 8.95916181e-05, 3.38057172e-01, 1.02330627e+00, -2.60421606e-02,\n", - " 5.32073015e-05, 4.42722293e-06, -9.99660844e-01, 9.88677413e-03,\n", - " -6.26217287e+00, 9.89962036e-04, 1.44254126e-04, -2.04376356e-03,\n", - " -1.24612323e-02, 1.32106945e-03, 2.16342224e+00, 4.45580101e-01,\n", - " -3.62873382e-01, 8.15783008e-04, -8.32061180e-04, 2.97686780e-02,\n", - " -3.01445966e-01, -3.56047798e-03, -1.71742119e-03, -7.18093345e-04,\n", - " -1.59737694e-01]),\n", - " array([ 9.08797581e-05, 3.40195616e-01, 1.02382865e+00, -2.58095046e-02,\n", - " 5.26759779e-05, 4.83500325e-06, -9.99666878e-01, 9.91656357e-03,\n", - " -6.26257787e+00, 9.85495346e-04, 1.42520082e-04, -2.04439792e-03,\n", - " -1.26199501e-02, 1.31763705e-03, 2.16264570e+00, 4.10834345e-01,\n", - " -4.65468545e-01, 1.03962989e-03, -8.18146256e-04, 2.97894392e-02,\n", - " -4.04997353e-01, -4.46668978e-03, -1.73404417e-03, -6.34362561e-04,\n", - " -1.58717731e-01]),\n", - " array([ 9.21703254e-05, 3.42335263e-01, 1.02431621e+00, -2.55281139e-02,\n", - " 5.20367413e-05, 5.23393512e-06, -9.99674103e-01, 9.94637713e-03,\n", - " -6.26308127e+00, 9.80158591e-04, 1.40769665e-04, -2.04495075e-03,\n", - " -1.27776947e-02, 1.31419040e-03, 2.16184935e+00, 3.77109281e-01,\n", - " -5.62966823e-01, 1.25549500e-03, -8.00879802e-04, 2.98135596e-02,\n", - " -5.03405067e-01, -5.33675531e-03, -1.75041728e-03, -5.52831683e-04,\n", - " -1.57744650e-01]),\n", - " array([ 9.34631977e-05, 3.44476058e-01, 1.02476979e+00, -2.52005746e-02,\n", - " 5.12937877e-05, 5.62244642e-06, -9.99682414e-01, 9.97621804e-03,\n", - " -6.26367786e+00, 9.73989106e-04, 1.39003120e-04, -2.04542436e-03,\n", - " -1.29345139e-02, 1.31075646e-03, 2.16104269e+00, 3.44431884e-01,\n", - " -6.55289535e-01, 1.46302351e-03, -7.80526650e-04, 2.98409129e-02,\n", - " -5.96589722e-01, -6.16948485e-03, -1.76654480e-03, -4.73608757e-04,\n", - " -1.56819138e-01]),\n", - " array([ 9.47582476e-05, 3.46617943e-01, 1.02519027e+00, -2.48295039e-02,\n", - " 5.04514731e-05, 5.99910923e-06, -9.99691699e-01, 1.00060894e-02,\n", - " -6.26436235e+00, 9.67025285e-04, 1.37220689e-04, -2.04582115e-03,\n", - " -1.30904556e-02, 1.30736016e-03, 2.16023437e+00, 3.12825594e-01,\n", - " -7.42373846e-01, 1.66188986e-03, -7.57368356e-04, 2.98713273e-02,\n", - " -6.84487918e-01, -6.96382131e-03, -1.78243060e-03, -3.96791126e-04,\n", - " -1.55941742e-01]),\n", - " array([ 9.60553437e-05, 3.48760857e-01, 1.02557855e+00, -2.44175426e-02,\n", - " 4.95142991e-05, 6.36264693e-06, -9.99701846e-01, 1.00359940e-02,\n", - " -6.26512940e+00, 9.59306445e-04, 1.35422611e-04, -2.04614362e-03,\n", - " -1.32455685e-02, 1.30402423e-03, 2.15943215e+00, 2.82310370e-01,\n", - " -8.24172512e-01, 1.85179826e-03, -7.31700525e-04, 2.99045893e-02,\n", - " -7.67051992e-01, -7.71883975e-03, -1.79807822e-03, -3.22465551e-04,\n", - " -1.55112866e-01]),\n", - " array([ 9.73543525e-05, 3.50904740e-01, 1.02593557e+00, -2.39673476e-02,\n", - " 4.84868974e-05, 6.71193990e-06, -9.99712741e-01, 1.00659344e-02,\n", - " -6.26597365e+00, 9.50872699e-04, 1.33609120e-04, -2.04639433e-03,\n", - " -1.33999012e-02, 1.30076926e-03, 2.15864296e+00, 2.52902752e-01,\n", - " -9.00653583e-01, 2.03248299e-03, -7.03830108e-04, 2.99404474e-02,\n", - " -8.44249713e-01, -8.43374630e-03, -1.81349092e-03, -2.50708356e-04,\n", - " -1.54332774e-01]),\n", - " array([ 9.86551388e-05, 3.53049529e-01, 1.02626230e+00, -2.34815844e-02,\n", - " 4.73740148e-05, 7.04602989e-06, -9.99724268e-01, 1.00959130e-02,\n", - " -6.26688972e+00, 9.41764822e-04, 1.31780448e-04, -2.04657591e-03,\n", - " -1.35535028e-02, 1.29761360e-03, 2.15787290e+00, 2.24615931e-01,\n", - " -9.71800062e-01, 2.20370862e-03, -6.74072707e-04, 2.99786162e-02,\n", - " -9.16063942e-01, -9.10787668e-03, -1.82867178e-03, -1.81585631e-04,\n", - " -1.53601595e-01]),\n", - " array([ 9.99575674e-05, 3.55195161e-01, 1.02655970e+00, -2.29629195e-02,\n", - " 4.61804976e-05, 7.36412299e-06, -9.99736316e-01, 1.01259318e-02,\n", - " -6.26787221e+00, 9.32024128e-04, 1.29936825e-04, -2.04669107e-03,\n", - " -1.37064222e-02, 1.29457342e-03, 2.15712728e+00, 1.97459825e-01,\n", - " -1.03760953e+00, 2.36527001e-03, -6.42749909e-04, 3.00187806e-02,\n", - " -9.82492242e-01, -9.74069428e-03, -1.84362378e-03, -1.15153449e-04,\n", - " -1.52919326e-01]),\n", - " array([ 1.01261504e-04, 3.57341574e-01, 1.02682879e+00, -2.24140141e-02,\n", - " 4.49112773e-05, 7.66559126e-06, -9.99748773e-01, 1.01559924e-02,\n", - " -6.26891576e+00, 9.21692340e-04, 1.28078475e-04, -2.04674252e-03,\n", - " -1.38587080e-02, 1.29166269e-03, 2.15641062e+00, 1.71441163e-01,\n", - " -1.09809370e+00, 2.51699236e-03, -6.10186685e-04, 3.00606006e-02,\n", - " -1.04354646e+00, -1.03317879e-02, -1.85834986e-03, -5.14581298e-05,\n", - " -1.52285836e-01]),\n", - " array([ 1.02566815e-04, 3.59488706e-01, 1.02707058e+00, -2.18375163e-02,\n", - " 4.35713549e-05, 7.94997315e-06, -9.99761532e-01, 1.01860961e-02,\n", - " -6.27001501e+00, 9.10811471e-04, 1.26205622e-04, -2.04673306e-03,\n", - " -1.40104089e-02, 1.28889324e-03, 2.15572672e+00, 1.46563581e-01,\n", - " -1.15327800e+00, 2.65873100e-03, -5.76708873e-04, 3.01037149e-02,\n", - " -1.09925226e+00, -1.08808692e-02, -1.87285302e-03, 9.46347615e-06,\n", - " -1.51700869e-01]),\n", - " array([ 1.03873372e-04, 3.61636496e-01, 1.02728610e+00, -2.12360553e-02,\n", - " 4.21657866e-05, 8.21697254e-06, -9.99774489e-01, 1.02162439e-02,\n", - " -6.27116466e+00, 8.99423701e-04, 1.24318485e-04, -2.04666548e-03,\n", - " -1.41615729e-02, 1.28627478e-03, 2.15507870e+00, 1.22827719e-01,\n", - " -1.20320106e+00, 2.79037112e-03, -5.42640776e-04, 3.01477461e-02,\n", - " -1.14964863e+00, -1.13877694e-02, -1.88713638e-03, 6.75836722e-05,\n", - " -1.51164050e-01]),\n", - " array([ 1.05181048e-04, 3.63784885e-01, 1.02747639e+00, -2.06122348e-02,\n", - " 4.06996689e-05, 8.46645683e-06, -9.99787544e-01, 1.02464362e-02,\n", - " -6.27235944e+00, 8.87571265e-04, 1.22417282e-04, -2.04654259e-03,\n", - " -1.43122478e-02, 1.28381497e-03, 2.15446900e+00, 1.00231326e-01,\n", - " -1.24791419e+00, 2.91182744e-03, -5.08302875e-04, 3.01923050e-02,\n", - " -1.19478736e+00, -1.18524365e-02, -1.90120330e-03, 1.22883581e-04,\n", - " -1.50674888e-01]),\n", - " array([ 1.06489722e-04, 3.65933815e-01, 1.02764248e+00, -1.99686270e-02,\n", - " 3.91781244e-05, 8.69845373e-06, -9.99800606e-01, 1.02766732e-02,\n", - " -6.27359418e+00, 8.75296334e-04, 1.20502225e-04, -2.04636724e-03,\n", - " -1.44624806e-02, 1.28151951e-03, 2.15389945e+00, 7.87693690e-02,\n", - " -1.28748083e+00, 3.02304376e-03, -4.74009696e-04, 3.02369943e-02,\n", - " -1.23473250e+00, -1.22749311e-02, -1.91505741e-03, 1.75352786e-04,\n", - " -1.50232783e-01]),\n", - " array([ 1.07799278e-04, 3.68083230e-01, 1.02778543e+00, -1.93077665e-02,\n", - " 3.76062879e-05, 8.91314720e-06, -9.99813587e-01, 1.03069546e-02,\n", - " -6.27486374e+00, 8.62640910e-04, 1.18573522e-04, -2.04614225e-03,\n", - " -1.46123176e-02, 1.27939219e-03, 2.15337134e+00, 5.84341553e-02,\n", - " -1.32197602e+00, 3.12399237e-03, -4.40067821e-04, 3.02814136e-02,\n", - " -1.26955975e+00, -1.26554233e-02, -1.92870269e-03, 2.24988962e-04,\n", - " -1.49837031e-01]),\n", - " array([ 1.09109604e-04, 3.70233078e-01, 1.02790628e+00, -1.86321453e-02,\n", - " 3.59892924e-05, 9.11087236e-06, -9.99826406e-01, 1.03372797e-02,\n", - " -6.27616309e+00, 8.49646723e-04, 1.16631378e-04, -2.04587045e-03,\n", - " -1.47618045e-02, 1.27743503e-03, 2.15288541e+00, 3.92154480e-02,\n", - " -1.35148573e+00, 3.21467348e-03, -4.06774050e-04, 3.03251627e-02,\n", - " -1.29935592e+00, -1.29941879e-02, -1.94214357e-03, 2.71797480e-04,\n", - " -1.49486828e-01]),\n", - " array([ 1.10420598e-04, 3.72383309e-01, 1.02800609e+00, -1.79442072e-02,\n", - " 3.43322559e-05, 9.29210958e-06, -9.99838989e-01, 1.03676476e-02,\n", - " -6.27748731e+00, 8.36355122e-04, 1.14675993e-04, -2.04555466e-03,\n", - " -1.49109857e-02, 1.27564833e-03, 2.15244193e+00, 2.11005941e-02,\n", - " -1.37610633e+00, 3.29511450e-03, -3.74413728e-04, 3.03678461e-02,\n", - " -1.32421823e+00, -1.32916005e-02, -1.95538497e-03, 3.15791012e-04,\n", - " -1.49181276e-01]),\n", - " array([ 1.11732162e-04, 3.74533873e-01, 1.02808588e+00, -1.72463433e-02,\n", - " 3.26402686e-05, 9.45747779e-06, -9.99851270e-01, 1.03980567e-02,\n", - " -6.27883156e+00, 8.22806989e-04, 1.12707561e-04, -2.04519767e-03,\n", - " -1.50599051e-02, 1.27403081e-03, 2.15204076e+00, 4.07465306e-03,\n", - " -1.39594391e+00, 3.36536925e-03, -3.43259225e-04, 3.04090760e-02,\n", - " -1.34425378e+00, -1.35481332e-02, -1.96843236e-03, 3.56989118e-04,\n", - " -1.48919389e-01]),\n", - " array([ 1.13044206e-04, 3.76684728e-01, 1.02814669e+00, -1.65408872e-02,\n", - " 3.09183800e-05, 9.60772712e-06, -9.99863190e-01, 1.04285051e-02,\n", - " -6.28019114e+00, 8.09042639e-04, 1.10726269e-04, -2.04480226e-03,\n", - " -1.52086052e-02, 1.27257971e-03, 2.15168136e+00, -1.18794699e-02,\n", - " -1.41111366e+00, 3.42551719e-03, -3.13568553e-04, 3.04484763e-02,\n", - " -1.35957880e+00, -1.37643497e-02, -1.98129183e-03, 3.95417829e-04,\n", - " -1.48700100e-01]),\n", - " array([ 1.14356648e-04, 3.78835830e-01, 1.02818956e+00, -1.58301108e-02,\n", - " 2.91715871e-05, 9.74373087e-06, -9.99874695e-01, 1.04589908e-02,\n", - " -6.28156146e+00, 7.95101739e-04, 1.08732299e-04, -2.04437115e-03,\n", - " -1.53571275e-02, 1.27129089e-03, 2.15136286e+00, -2.67808890e-02,\n", - " -1.42173921e+00, 3.47566248e-03, -2.85584124e-04, 3.04856854e-02,\n", - " -1.37031808e+00, -1.39409007e-02, -1.99397014e-03, 4.31109227e-04,\n", - " -1.48522266e-01]),\n", - " array([ 1.15669414e-04, 3.80987142e-01, 1.02821549e+00, -1.51162203e-02,\n", - " 2.74048226e-05, 9.86647694e-06, -9.99885743e-01, 1.04895112e-02,\n", - " -6.28293807e+00, 7.81023220e-04, 1.06725824e-04, -2.04390705e-03,\n", - " -1.55055122e-02, 1.27015899e-03, 2.15108408e+00, -4.06506001e-02,\n", - " -1.42795201e+00, 3.51593311e-03, -2.59531622e-04, 3.05203594e-02,\n", - " -1.37660427e+00, -1.40785189e-02, -2.00647476e-03, 4.64101018e-04,\n", - " -1.48384672e-01]),\n", - " array([ 1.16982436e-04, 3.83138627e-01, 1.02822548e+00, -1.44013529e-02,\n", - " 2.56229435e-05, 9.97705870e-06, -9.99896295e-01, 1.05200634e-02,\n", - " -6.28431664e+00, 7.66845205e-04, 1.04707011e-04, -2.04341261e-03,\n", - " -1.56537982e-02, 1.26917751e-03, 2.15084362e+00, -5.35113413e-02,\n", - " -1.42989062e+00, 3.54647988e-03, -2.35618975e-04, 3.05521746e-02,\n", - " -1.37857721e+00, -1.41780142e-02, -2.01881389e-03, 4.94436112e-04,\n", - " -1.48286042e-01]),\n", - " array([ 1.18295657e-04, 3.85290255e-01, 1.02822052e+00, -1.36875733e-02,\n", - " 2.38307211e-05, 1.00766654e-05, -9.99906320e-01, 1.05506442e-02,\n", - " -6.28569303e+00, 7.52604937e-04, 1.02676014e-04, -2.04289045e-03,\n", - " -1.58020232e-02, 1.26833895e-03, 2.15063983e+00, -6.53874525e-02,\n", - " -1.42770010e+00, 3.56747547e-03, -2.14035384e-04, 3.05808304e-02,\n", - " -1.37638328e+00, -1.42402686e-02, -2.03099654e-03, 5.22162194e-04,\n", - " -1.48225038e-01]),\n", - " array([ 1.19609025e-04, 3.87441996e-01, 1.02820158e+00, -1.29768708e-02,\n", - " 2.20328298e-05, 1.01665723e-05, -9.99915797e-01, 1.05812502e-02,\n", - " -6.28706320e+00, 7.38338706e-04, 1.00632981e-04, -2.04234312e-03,\n", - " -1.59502235e-02, 1.26763491e-03, 2.15047092e+00, -7.63047342e-02,\n", - " -1.42153132e+00, 3.57911336e-03, -1.94950419e-04, 3.06060515e-02,\n", - " -1.37017474e+00, -1.42662309e-02, -2.04303252e-03, 5.47331314e-04,\n", - " -1.48200274e-01]),\n", - " array([ 1.20922497e-04, 3.89593824e-01, 1.02816961e+00, -1.22711569e-02,\n", - " 2.02338383e-05, 1.02481299e-05, -9.99924706e-01, 1.06118778e-02,\n", - " -6.28842331e+00, 7.24081794e-04, 9.85780490e-05, -2.04177312e-03,\n", - " -1.60984338e-02, 1.26705624e-03, 2.15033494e+00, -8.62903060e-02,\n", - " -1.41154032e+00, 3.58160685e-03, -1.78513103e-04, 3.06275899e-02,\n", - " -1.36010907e+00, -1.42569121e-02, -2.05493249e-03, 5.69999466e-04,\n", - " -1.48210315e-01]),\n", - " array([ 1.22236039e-04, 3.91745716e-01, 1.02812553e+00, -1.15722628e-02,\n", - " 1.84381998e-05, 1.03227532e-05, -9.99933039e-01, 1.06425231e-02,\n", - " -6.28976966e+00, 7.09868414e-04, 9.65113410e-05, -2.04118289e-03,\n", - " -1.62466875e-02, 1.26659313e-03, 2.15022985e+00, -9.53724657e-02,\n", - " -1.39788767e+00, 3.57518799e-03, -1.64850997e-04, 3.06452274e-02,\n", - " -1.34634832e+00, -1.42133795e-02, -2.06670796e-03, 5.90226183e-04,\n", - " -1.48253686e-01]),\n", - " array([ 1.23549622e-04, 3.93897653e-01, 1.02807025e+00, -1.08819374e-02,\n", - " 1.66502435e-05, 1.03919101e-05, -9.99940790e-01, 1.06731818e-02,\n", - " -6.29109872e+00, 6.95731662e-04, 9.44329697e-05, -2.04057482e-03,\n", - " -1.63950164e-02, 1.26623525e-03, 2.15015353e+00, -1.03580549e-01,\n", - " -1.38073783e+00, 3.56010655e-03, -1.54069214e-04, 3.06587772e-02,\n", - " -1.32905844e+00, -1.41367520e-02, -2.07837131e-03, 6.08074140e-04,\n", - " -1.48328878e-01]),\n", - " array([ 1.24863226e-04, 3.96049618e-01, 1.02800466e+00, -1.02018460e-02,\n", - " 1.48741664e-05, 1.04571096e-05, -9.99947960e-01, 1.07038499e-02,\n", - " -6.29240713e+00, 6.81703468e-04, 9.23430339e-05, -2.03995121e-03,\n", - " -1.65434507e-02, 1.26597183e-03, 2.15010384e+00, -1.10944791e-01,\n", - " -1.36025854e+00, 3.53662902e-03, -1.46249350e-04, 3.06680859e-02,\n", - " -1.30840872e+00, -1.40281948e-02, -2.08993577e-03, 6.23608766e-04,\n", - " -1.48434354e-01]),\n", - " array([ 1.26176836e-04, 3.98201596e-01, 1.02792962e+00, -9.53356846e-03,\n", - " 1.31140255e-05, 1.05198894e-05, -9.99954554e-01, 1.07345230e-02,\n", - " -6.29369170e+00, 6.67814553e-04, 9.02416184e-05, -2.03931431e-03,\n", - " -1.66920193e-02, 1.26579181e-03, 2.15007858e+00, -1.17496187e-01,\n", - " -1.33662018e+00, 3.50503756e-03, -1.41448287e-04, 3.06730356e-02,\n", - " -1.28457112e+00, -1.38889143e-02, -2.10141549e-03, 6.36897862e-04,\n", - " -1.48568553e-01]),\n", - " array([ 1.27490445e-04, 4.00353576e-01, 1.02784596e+00, -8.87859864e-03,\n", - " 1.13737307e-05, 1.05818021e-05, -9.99960584e-01, 1.07651965e-02,\n", - " -6.29494942e+00, 6.54094401e-04, 8.81287930e-05, -2.03866630e-03,\n", - " -1.68407492e-02, 1.26568392e-03, 2.15007560e+00, -1.23266360e-01,\n", - " -1.30999523e+00, 3.46562905e-03, -1.39696823e-04, 3.06735452e-02,\n", - " -1.25771967e+00, -1.37201528e-02, -2.11282546e-03, 6.48011236e-04,\n", - " -1.48729896e-01]),\n", - " array([ 1.28804053e-04, 4.02505550e-01, 1.02775449e+00, -8.23834329e-03,\n", - " 9.65703752e-06, 1.06444019e-05, -9.99966064e-01, 1.07958661e-02,\n", - " -6.29617745e+00, 6.40571217e-04, 8.60046114e-05, -2.03800928e-03,\n", - " -1.69896660e-02, 1.26563680e-03, 2.15009275e+00, -1.28287427e-01,\n", - " -1.28055766e+00, 3.41871413e-03, -1.40998114e-04, 3.06695729e-02,\n", - " -1.22802996e+00, -1.35231838e-02, -2.12418155e-03, 6.57020347e-04,\n", - " -1.48916790e-01]),\n", - " array([ 1.30117662e-04, 4.04657509e-01, 1.02765600e+00, -7.61412174e-03,\n", - " 7.96754141e-06, 1.07092292e-05, -9.99971012e-01, 1.08265272e-02,\n", - " -6.29737313e+00, 6.27271910e-04, 8.38691109e-05, -2.03734528e-03,\n", - " -1.71387936e-02, 1.26563912e-03, 2.15012794e+00, -1.32591869e-01,\n", - " -1.24848239e+00, 3.36461627e-03, -1.45325875e-04, 3.06611181e-02,\n", - " -1.19567849e+00, -1.32993064e-02, -2.13550048e-03, 6.63997967e-04,\n", - " -1.49127637e-01]),\n", - " array([ 1.31431282e-04, 4.06809450e-01, 1.02755124e+00, -7.00716560e-03,\n", - " 6.30867119e-06, 1.07777949e-05, -9.99975449e-01, 1.08571754e-02,\n", - " -6.29853397e+00, 6.14222069e-04, 8.17223111e-05, -2.03667626e-03,\n", - " -1.72881545e-02, 1.26567963e-03, 2.15017913e+00, -1.36212404e-01,\n", - " -1.21394476e+00, 3.30367098e-03, -1.52622325e-04, 3.06482230e-02,\n", - " -1.16084224e+00, -1.30498411e-02, -2.14679983e-03, 6.69017845e-04,\n", - " -1.49360834e-01]),\n", - " array([ 1.32744928e-04, 4.08961369e-01, 1.02744094e+00, -6.41861886e-03,\n", - " 4.68368371e-06, 1.08515637e-05, -9.99979400e-01, 1.08878064e-02,\n", - " -6.29965767e+00, 6.01445945e-04, 7.95642131e-05, -2.03600411e-03,\n", - " -1.74377692e-02, 1.26574735e-03, 2.15024437e+00, -1.39181866e-01,\n", - " -1.17712005e+00, 3.23622492e-03, -1.62795847e-04, 3.06309756e-02,\n", - " -1.12369806e+00, -1.27761242e-02, -2.15809800e-03, 6.72154402e-04,\n", - " -1.49614780e-01]),\n", - " array([ 1.34058617e-04, 4.11113265e-01, 1.02732579e+00, -5.84953812e-03,\n", - " 3.09565854e-06, 1.09319348e-05, -9.99982891e-01, 1.09184159e-02,\n", - " -6.30074209e+00, 5.88966441e-04, 7.73947989e-05, -2.03533062e-03,\n", - " -1.75876571e-02, 1.26583160e-03, 2.15032177e+00, -1.41533085e-01,\n", - " -1.13818296e+00, 3.16263521e-03, -1.75718339e-04, 3.06095116e-02,\n", - " -1.08442226e+00, -1.24795038e-02, -2.16941418e-03, 6.73482422e-04,\n", - " -1.49887880e-01]),\n", - " array([ 1.35372372e-04, 4.13265139e-01, 1.02720648e+00, -5.30089309e-03,\n", - " 1.54749303e-06, 1.10202233e-05, -9.99985950e-01, 1.09489999e-02,\n", - " -6.30178528e+00, 5.76805107e-04, 7.52140305e-05, -2.03465755e-03,\n", - " -1.77378357e-02, 1.26592213e-03, 2.15040956e+00, -1.43298771e-01,\n", - " -1.09730716e+00, 3.08326873e-03, -1.91222269e-04, 3.05840173e-02,\n", - " -1.04319011e+00, -1.21613344e-02, -2.18076838e-03, 6.73076773e-04,\n", - " -1.50178549e-01]),\n", - " array([ 1.36686216e-04, 4.15416991e-01, 1.02708364e+00, -4.77356735e-03,\n", - " 4.18976618e-08, 1.11176376e-05, -9.99988606e-01, 1.09795546e-02,\n", - " -6.30278545e+00, 5.64982134e-04, 7.30218492e-05, -2.03398654e-03,\n", - " -1.78883209e-02, 1.26600926e-03, 2.15050606e+00, -1.44511406e-01,\n", - " -1.05466491e+00, 2.99850153e-03, -2.09097406e-04, 3.05547325e-02,\n", - " -1.00017544e+00, -1.18229730e-02, -2.19218135e-03, 6.71012130e-04,\n", - " -1.50485218e-01]),\n", - " array([ 1.38000178e-04, 4.17568826e-01, 1.02695789e+00, -4.26835922e-03,\n", - " -1.41860839e-06, 1.12252572e-05, -9.99990890e-01, 1.10100766e-02,\n", - " -6.30374100e+00, 5.53516360e-04, 7.08181746e-05, -2.03331917e-03,\n", - " -1.80391272e-02, 1.26608393e-03, 2.15060970e+00, -1.45203136e-01,\n", - " -1.01042662e+00, 2.90871825e-03, -2.29087258e-04, 3.05219533e-02,\n", - " -9.55550213e-01, -1.14657744e-02, -2.20367460e-03, 6.67362726e-04,\n", - " -1.50806333e-01]),\n", - " array([ 1.39314288e-04, 4.19720646e-01, 1.02682981e+00, -3.78598291e-03,\n", - " -2.83170146e-06, 1.13440068e-05, -9.99992833e-01, 1.10405626e-02,\n", - " -6.30465049e+00, 5.42425273e-04, 6.86029042e-05, -2.03265697e-03,\n", - " -1.81902676e-02, 1.26613786e-03, 2.15071900e+00, -1.45405673e-01,\n", - " -9.64760487e-01, 2.81431166e-03, -2.50885234e-04, 3.04860355e-02,\n", - " -9.09484174e-01, -1.10910870e-02, -2.21527035e-03, 6.62202101e-04,\n", - " -1.51140362e-01]),\n", - " array([ 1.40628576e-04, 4.21872457e-01, 1.02669997e+00, -3.32706975e-03,\n", - " -4.19525740e-06, 1.14746297e-05, -9.99994465e-01, 1.10710100e-02,\n", - " -6.30551263e+00, 5.31725024e-04, 6.63759127e-05, -2.03200137e-03,\n", - " -1.83417534e-02, 1.26616365e-03, 2.15083261e+00, -1.45150194e-01,\n", - " -9.17832167e-01, 2.71568229e-03, -2.74130579e-04, 3.04473980e-02,\n", - " -8.62144492e-01, -1.07002490e-02, -2.22699151e-03, 6.55602880e-04,\n", - " -1.51485796e-01]),\n", - " array([ 1.41943074e-04, 4.24024263e-01, 1.02656888e+00, -2.89216964e-03,\n", - " -5.50735549e-06, 1.16176581e-05, -9.99995818e-01, 1.11014166e-02,\n", - " -6.30632633e+00, 5.21430440e-04, 6.41370510e-05, -2.03135373e-03,\n", - " -1.84935945e-02, 1.26615489e-03, 2.15094928e+00, -1.44467255e-01,\n", - " -8.69804460e-01, 2.61323801e-03, -2.98404132e-04, 3.04065264e-02,\n", - " -8.13695454e-01, -1.02945840e-02, -2.23886168e-03, 6.47636561e-04,\n", - " -1.51841154e-01]),\n", - " array([ 1.43257816e-04, 4.26176070e-01, 1.02643705e+00, -2.48175262e-03,\n", - " -6.76628217e-06, 1.17733822e-05, -9.99996920e-01, 1.11317805e-02,\n", - " -6.30709063e+00, 5.11555042e-04, 6.18861459e-05, -2.03071536e-03,\n", - " -1.86457995e-02, 1.26610634e-03, 2.15106787e+00, -1.43386704e-01,\n", - " -8.20837030e-01, 2.50739383e-03, -3.23223988e-04, 3.03639764e-02,\n", - " -7.64298184e-01, -9.87539779e-03, -2.25090511e-03, 6.38373312e-04,\n", - " -1.52204984e-01]),\n", - " array([ 1.44572834e-04, 4.28327884e-01, 1.02630496e+00, -2.09621057e-03,\n", - " -7.97053475e-06, 1.19418163e-05, -9.99997803e-01, 1.11621009e-02,\n", - " -6.30780474e+00, 5.02111067e-04, 5.96229993e-05, -2.03008748e-03,\n", - " -1.87983754e-02, 1.26601398e-03, 2.15118735e+00, -1.41937598e-01,\n", - " -7.71086154e-01, 2.39857156e-03, -3.48041180e-04, 3.03203775e-02,\n", - " -7.14110387e-01, -9.44397452e-03, -2.26314666e-03, 6.27881788e-04,\n", - " -1.52575865e-01]),\n", - " array([ 1.45888161e-04, 4.30479712e-01, 1.02617306e+00, -1.73585899e-03,\n", - " -9.11882494e-06, 1.21226635e-05, -9.99998493e-01, 1.11923774e-02,\n", - " -6.30846802e+00, 4.93109494e-04, 5.73473874e-05, -2.02947125e-03,\n", - " -1.89513278e-02, 1.26587526e-03, 2.15130678e+00, -1.40148132e-01,\n", - " -7.20704505e-01, 2.28719969e-03, -3.72235480e-04, 3.02764362e-02,\n", - " -6.63286133e-01, -9.00157367e-03, -2.27561183e-03, 6.16228960e-04,\n", - " -1.52952410e-01]),\n", - " array([ 1.47203828e-04, 4.32631560e-01, 1.02604177e+00, -1.40093894e-03,\n", - " -1.02100824e-05, 1.23152775e-05, -9.99999019e-01, 1.12226103e-02,\n", - " -6.30908000e+00, 4.84560067e-04, 5.50590607e-05, -2.02886777e-03,\n", - " -1.91046611e-02, 1.26568913e-03, 2.15142532e+00, -1.38045565e-01,\n", - " -6.69840961e-01, 2.17371315e-03, -3.95111509e-04, 3.02329391e-02,\n", - " -6.11975660e-01, -8.54942695e-03, -2.28832671e-03, 6.03479956e-04,\n", - " -1.53333267e-01]),\n", - " array([ 1.48519867e-04, 4.34783434e-01, 1.02591147e+00, -1.09161897e-03,\n", - " -1.12434581e-05, 1.25186242e-05, -9.99999404e-01, 1.12528010e-02,\n", - " -6.30964032e+00, 4.76471331e-04, 5.27577428e-05, -2.02827807e-03,\n", - " -1.92583782e-02, 1.26545631e-03, 2.15154225e+00, -1.35656158e-01,\n", - " -6.18640444e-01, 2.05855308e-03, -4.15895295e-04, 3.01907556e-02,\n", - " -5.60325211e-01, -8.08873555e-03, -2.30131795e-03, 5.89697915e-04,\n", - " -1.53717120e-01]),\n", - " array([ 1.49836306e-04, 4.36935339e-01, 1.02578255e+00, -8.07997215e-04,\n", - " -1.22183277e-05, 1.27312404e-05, -9.99999673e-01, 1.12829519e-02,\n", - " -6.31014880e+00, 4.68850663e-04, 5.04431300e-05, -2.02770313e-03,\n", - " -1.94124809e-02, 1.26517937e-03, 2.15165689e+00, -1.33005118e-01,\n", - " -5.67243784e-01, 1.94216669e-03, -4.33731548e-04, 3.01508396e-02,\n", - " -5.08476907e-01, -7.62066774e-03, -2.31461281e-03, 5.74943860e-04,\n", - " -1.54102693e-01]),\n", - " array([ 1.51153172e-04, 4.39087283e-01, 1.02565536e+00, -5.50103475e-04,\n", - " -1.31342946e-05, 1.29511925e-05, -9.99999849e-01, 1.13130661e-02,\n", - " -6.31060537e+00, 4.61704307e-04, 4.81148909e-05, -2.02714385e-03,\n", - " -1.95669696e-02, 1.26486292e-03, 2.15176869e+00, -1.30116537e-01,\n", - " -5.15787619e-01, 1.82500689e-03, -4.47681848e-04, 3.01142308e-02,\n", - " -4.56568631e-01, -7.14635680e-03, -2.32823907e-03, 5.59276572e-04,\n", - " -1.54488745e-01]),\n", - " array([ 1.52470490e-04, 4.41239269e-01, 1.02553022e+00, -3.17901348e-04,\n", - " -1.39911930e-05, 1.31760347e-05, -9.99999949e-01, 1.13431482e-02,\n", - " -6.31101010e+00, 4.55037407e-04, 4.57726658e-05, -2.02660110e-03,\n", - " -1.97218437e-02, 1.26451379e-03, 2.15187714e+00, -1.27013350e-01,\n", - " -4.64404314e-01, 1.70753196e-03, -4.56724051e-04, 3.00820540e-02,\n", - " -4.04733957e-01, -6.66689922e-03, -2.34222511e-03, 5.42752484e-04,\n", - " -1.54874077e-01]),\n", - " array([ 1.53788281e-04, 4.43391304e-01, 1.02540742e+00, -1.11290407e-04,\n", - " -1.47890906e-05, 1.34027675e-05, -9.99999994e-01, 1.13732037e-02,\n", - " -6.31136320e+00, 4.48854054e-04, 4.34160660e-05, -2.02607567e-03,\n", - " -1.98771012e-02, 1.26414120e-03, 2.15198181e+00, -1.23717290e-01,\n", - " -4.13221909e-01, 1.59020503e-03, -4.59753274e-04, 3.00555180e-02,\n", - " -3.53102096e-01, -6.18335345e-03, -2.35659983e-03, 5.25425589e-04,\n", - " -1.55257530e-01]),\n", - " array([ 1.55106566e-04, 4.45543391e-01, 1.02528726e+00, 6.98916324e-05,\n", - " -1.55282907e-05, 1.36277982e-05, -9.99999997e-01, 1.14032396e-02,\n", - " -6.31166500e+00, 4.43157315e-04, 4.10446733e-05, -2.02556832e-03,\n", - " -2.00327392e-02, 1.26375690e-03, 2.15208234e+00, -1.20248851e-01,\n", - " -3.62364092e-01, 1.47349343e-03, -4.55584717e-04, 3.00359114e-02,\n", - " -3.01797863e-01, -5.69673893e-03, -2.37139270e-03, 5.07347350e-04,\n", - " -1.55637984e-01]),\n", - " array([ 1.56425360e-04, 4.47695535e-01, 1.02517000e+00, 2.25866722e-04,\n", - " -1.62093345e-05, 1.38469028e-05, -9.99999974e-01, 1.14332642e-02,\n", - " -6.31191594e+00, 4.37949279e-04, 3.86580395e-05, -2.02507976e-03,\n", - " -2.01887536e-02, 1.26337535e-03, 2.15217843e+00, -1.16627253e-01,\n", - " -3.11950195e-01, 1.35786776e-03, -4.42958787e-04, 3.00245971e-02,\n", - " -2.50941682e-01, -5.20803575e-03, -2.38663375e-03, 4.88566630e-04,\n", - " -1.56014358e-01]),\n", - " array([ 1.57744675e-04, 4.49847739e-01, 1.02505587e+00, 3.56914319e-04,\n", - " -1.68330019e-05, 1.40551935e-05, -9.99999936e-01, 1.14632872e-02,\n", - " -6.31211659e+00, 4.33231094e-04, 3.62556859e-05, -2.02461063e-03,\n", - " -2.03451392e-02, 1.26301387e-03, 2.15226982e+00, -1.12870417e-01,\n", - " -2.62095215e-01, 1.24380075e-03, -4.20549179e-04, 3.00230036e-02,\n", - " -2.00649598e-01, -4.71818475e-03, -2.40235358e-03, 4.69129631e-04,\n", - " -1.56385613e-01]),\n", - " array([ 1.59064522e-04, 4.52000005e-01, 1.02494511e+00, 4.63369228e-04,\n", - " -1.74003118e-05, 1.42470902e-05, -9.99999892e-01, 1.14933198e-02,\n", - " -6.31226763e+00, 4.29003006e-04, 3.38371026e-05, -2.02416155e-03,\n", - " -2.05018899e-02, 1.26269278e-03, 2.15235630e+00, -1.08994942e-01,\n", - " -2.12909847e-01, 1.13176583e-03, -3.86973430e-04, 3.00326140e-02,\n", - " -1.51033316e-01, -4.22808821e-03, -2.41858335e-03, 4.49079839e-04,\n", - " -1.56750748e-01]),\n", - " array([ 1.60384905e-04, 4.54152335e-01, 1.02483792e+00, 5.45619487e-04,\n", - " -1.79125221e-05, 1.44163001e-05, -9.99999851e-01, 1.15233748e-02,\n", - " -6.31236983e+00, 4.25264395e-04, 3.14017477e-05, -2.02373309e-03,\n", - " -2.06589987e-02, 1.26243547e-03, 2.15243770e+00, -1.05016086e-01,\n", - " -1.64500547e-01, 1.02223512e-03, -3.40808616e-04, 3.00549493e-02,\n", - " -1.02200266e-01, -3.73861130e-03, -2.43535483e-03, 4.28457985e-04,\n", - " -1.57108801e-01]),\n", - " array([ 1.61705827e-04, 4.56304732e-01, 1.02473450e+00, 6.04104278e-04,\n", - " -1.83711273e-05, 1.45558065e-05, -9.99999817e-01, 1.15534663e-02,\n", - " -6.31242408e+00, 4.22013811e-04, 2.89490474e-05, -2.02332579e-03,\n", - " -2.08164576e-02, 1.26226853e-03, 2.15251390e+00, -1.00947756e-01,\n", - " -1.16969609e-01, 9.15677335e-04, -2.80608599e-04, 3.00915510e-02,\n", - " -5.42536734e-02, -3.25058390e-03, -2.45270039e-03, 4.07302011e-04,\n", - " -1.57458848e-01]),\n", - " array([ 1.63027286e-04, 4.58457194e-01, 1.02463502e+00, 6.39311892e-04,\n", - " -1.87778551e-05, 1.46578702e-05, -9.99999795e-01, 1.15836103e-02,\n", - " -6.31243137e+00, 4.19249007e-04, 2.64783943e-05, -2.02294014e-03,\n", - " -2.09742576e-02, 1.26222174e-03, 2.15258479e+00, -9.68024932e-02,\n", - " -7.04152507e-02, 8.12554677e-04, -2.04930172e-04, 3.01439548e-02,\n", - " -7.29265293e-03, -2.76480375e-03, -2.47065302e-03, 3.85647056e-04,\n", - " -1.57800003e-01]),\n", - " array([ 1.64349277e-04, 4.60609723e-01, 1.02453965e+00, 6.51777748e-04,\n", - " -1.91346617e-05, 1.47140443e-05, -9.99999787e-01, 1.16138239e-02,\n", - " -6.31239279e+00, 4.16966967e-04, 2.39891480e-05, -2.02257662e-03,\n", - " -2.11323890e-02, 1.26232811e-03, 2.15265028e+00, -9.25914784e-02,\n", - " -2.49317252e-02, 7.13319622e-04, -1.12360269e-04, 3.02136624e-02,\n", - " 3.85876825e-02, -2.28203981e-03, -2.48924634e-03, 3.63525435e-04,\n", - " -1.58131415e-01]),\n", - " array([ 1.65671791e-04, 4.62762318e-01, 1.02444854e+00, 6.42082464e-04,\n", - " -1.94437238e-05, 1.47152071e-05, -9.99999794e-01, 1.16441260e-02,\n", - " -6.31230949e+00, 4.15163931e-04, 2.14806333e-05, -2.02223565e-03,\n", - " -2.12908413e-02, 1.26262374e-03, 2.15271034e+00, -8.83245256e-02,\n", - " 1.93905642e-02, 6.18410802e-04, -1.55144730e-06, 3.03021062e-02,\n", - " 8.32961050e-02, -1.80303684e-03, -2.50851466e-03, 3.40966645e-04,\n", - " -1.58452268e-01]),\n", - " array([ 1.66994815e-04, 4.64914976e-01, 1.02436184e+00, 6.10849997e-04,\n", - " -1.97074296e-05, 1.46516156e-05, -9.99999813e-01, 1.16745366e-02,\n", - " -6.31218274e+00, 4.13835410e-04, 1.89521404e-05, -2.02191765e-03,\n", - " -2.14496030e-02, 1.26314773e-03, 2.15276492e+00, -8.40100904e-02,\n", - " 6.24649352e-02, 5.28248218e-04, 1.28736742e-04, 3.04106076e-02,\n", - " 1.26745142e-01, -1.32852086e-03, -2.52849298e-03, 3.17997368e-04,\n", - " -1.58761781e-01]),\n", - " array([ 1.68318334e-04, 4.67067695e-01, 1.02427966e+00, 5.58745855e-04,\n", - " -1.99283654e-05, 1.45129831e-05, -9.99999844e-01, 1.17050770e-02,\n", - " -6.31201389e+00, 4.12976204e-04, 1.64029234e-05, -2.02162301e-03,\n", - " -2.16086622e-02, 1.26394192e-03, 2.15281400e+00, -7.96552784e-02,\n", - " 1.04208290e-01, 4.43227677e-04, 2.79589396e-04, 3.05403285e-02,\n", - " 1.68850937e-01, -8.59205610e-04, -2.54921700e-03, 2.94641490e-04,\n", - " -1.59059205e-01]),\n", - " array([ 1.69642331e-04, 4.69220473e-01, 1.02420215e+00, 4.86475372e-04,\n", - " -2.01092999e-05, 1.42885847e-05, -9.99999881e-01, 1.17357692e-02,\n", - " -6.31180436e+00, 4.12580404e-04, 1.38322002e-05, -2.02135209e-03,\n", - " -2.17680061e-02, 1.26505055e-03, 2.15285757e+00, -7.52658594e-02,\n", - " 1.44540972e-01, 3.63714378e-04, 4.51880430e-04, 3.06922151e-02,\n", - " 2.09533108e-01, -3.95800013e-04, -2.57072317e-03, 2.70920126e-04,\n", - " -1.59343821e-01]),\n", - " array([ 1.70966784e-04, 4.71373305e-01, 1.02412940e+00, 3.94782063e-04,\n", - " -2.02531646e-05, 1.39673946e-05, -9.99999922e-01, 1.17666361e-02,\n", - " -6.31155565e+00, 4.12641387e-04, 1.12391515e-05, -2.02110524e-03,\n", - " -2.19276210e-02, 1.26651979e-03, 2.15289563e+00, -7.08462847e-02,\n", - " 1.83386619e-01, 2.90035624e-04, 6.46209021e-04, 3.08669345e-02,\n", - " 2.48714598e-01, 6.09832085e-05, -2.59304869e-03, 2.46851656e-04,\n", - " -1.59614942e-01]),\n", - " array([ 1.72291672e-04, 4.73526187e-01, 1.02406154e+00, 2.84446051e-04,\n", - " -2.03630299e-05, 1.35382595e-05, -9.99999959e-01, 1.17977009e-02,\n", - " -6.31126932e+00, 4.13151805e-04, 8.62291991e-06, -2.02088279e-03,\n", - " -2.20874929e-02, 1.26839718e-03, 2.15292820e+00, -6.63997092e-02,\n", - " 2.20672015e-01, 2.22472537e-04, 8.62827321e-04, 3.10648024e-02,\n", - " 2.86321525e-01, 5.10417781e-04, -2.61623158e-03, 2.22451770e-04,\n", - " -1.59871908e-01]),\n", - " array([ 1.73616970e-04, 4.75679115e-01, 1.02399866e+00, 1.56282573e-04,\n", - " -2.04420767e-05, 1.29901123e-05, -9.99999987e-01, 1.18289866e-02,\n", - " -6.31094704e+00, 4.14103558e-04, 5.98260927e-06, -2.02068505e-03,\n", - " -2.22476070e-02, 1.27073086e-03, 2.15295529e+00, -6.19280170e-02,\n", - " 2.56326939e-01, 1.61250779e-04, 1.10155957e-03, 3.12857019e-02,\n", - " 3.22283027e-01, 9.51752942e-04, -2.64031065e-03, 1.97733517e-04,\n", - " -1.60114086e-01]),\n", - " array([ 1.74942656e-04, 4.77832082e-01, 1.02394087e+00, 1.11405500e-05,\n", - " -2.04935627e-05, 1.23122305e-05, -1.00000000e+00, 1.18605156e-02,\n", - " -6.31059051e+00, 4.15487760e-04, 3.31728373e-06, -2.02051235e-03,\n", - " -2.24079479e-02, 1.27356866e-03, 2.15297692e+00, -5.74318511e-02,\n", - " 2.90284018e-01, 1.06530464e-04, 1.36171411e-03, 3.15289959e-02,\n", - " 3.56531123e-01, 1.38420154e-03, -2.66532553e-03, 1.72707373e-04,\n", - " -1.60340870e-01]),\n", - " array([ 1.76268705e-04, 4.79985083e-01, 1.02388826e+00, -1.50098759e-04,\n", - " -2.05207838e-05, 1.14945425e-05, -9.99999988e-01, 1.18923091e-02,\n", - " -6.31020151e+00, 4.17294686e-04, 6.25966994e-07, -2.02036496e-03,\n", - " -2.25684995e-02, 1.27695698e-03, 2.15299312e+00, -5.29106471e-02,\n", - " 3.22478585e-01, 5.83948659e-05, 1.64198496e-03, 3.17934286e-02,\n", - " 3.89000557e-01, 1.80692675e-03, -2.69131674e-03, 1.47381306e-04,\n", - " -1.60551675e-01]),\n", - " array([ 1.77595095e-04, 4.82138109e-01, 1.02384092e+00, -3.26523043e-04,\n", - " -2.05270291e-05, 1.05279883e-05, -9.99999946e-01, 1.19243861e-02,\n", - " -6.30978188e+00, 4.19513714e-04, -2.09235863e-06, -2.02024320e-03,\n", - " -2.27292455e-02, 1.28093947e-03, 2.15300391e+00, -4.83626703e-02,\n", - " 3.52848540e-01, 1.68382744e-05, 1.94034624e-03, 3.20770198e-02,\n", - " 4.19628668e-01, 2.21902788e-03, -2.71832563e-03, 1.21760859e-04,\n", - " -1.60745943e-01]),\n", - " array([ 1.78921807e-04, 4.84291155e-01, 1.02379895e+00, -5.17190160e-04,\n", - " -2.05155299e-05, 9.40493577e-06, -9.99999866e-01, 1.19567630e-02,\n", - " -6.30933353e+00, 4.22133239e-04, -4.83875307e-06, -2.02014735e-03,\n", - " -2.28901686e-02, 1.28555551e-03, 2.15300932e+00, -4.37850571e-02,\n", - " 3.81334222e-01, -1.82470706e-05, 2.25393851e-03, 3.23769515e-02,\n", - " 4.48355256e-01, 2.61952510e-03, -2.74639443e-03, 9.58492368e-05,\n", - " -1.60923135e-01]),\n", - " array([ 1.80248824e-04, 4.86444211e-01, 1.02376245e+00, -7.21129292e-04,\n", - " -2.04894021e-05, 8.11965766e-06, -9.99999740e-01, 1.19894525e-02,\n", - " -6.30885840e+00, 4.25140583e-04, -7.61431934e-06, -2.02007771e-03,\n", - " -2.30512514e-02, 1.29083840e-03, 2.15300939e+00, -3.91738598e-02,\n", - " 4.07878290e-01, -4.70848533e-05, 2.57894838e-03, 3.26894475e-02,\n", - " 4.75122466e-01, 3.00734327e-03, -2.77556628e-03, 6.96474034e-05,\n", - " -1.61082734e-01]),\n", - " array([ 1.81576138e-04, 4.88597270e-01, 1.02373149e+00, -9.37342056e-04,\n", - " -2.04515820e-05, 6.66887195e-06, -9.99999560e-01, 1.20224621e-02,\n", - " -6.30835853e+00, 4.28521878e-04, -1.04202045e-05, -2.02003455e-03,\n", - " -2.32124756e-02, 1.29681333e-03, 2.15300415e+00, -3.45240957e-02,\n", - " 4.32425619e-01, -7.00292231e-05, 2.91048247e-03, 3.30096473e-02,\n", - " 4.99874676e-01, 3.38129516e-03, -2.80588515e-03, 4.31541873e-05,\n", - " -1.61224243e-01]),\n", - " array([ 1.82903742e-04, 4.90750321e-01, 1.02370619e+00, -1.16480356e-03,\n", - " -2.04047550e-05, 5.05234685e-06, -9.99999321e-01, 1.20557936e-02,\n", - " -6.30783597e+00, 4.32261942e-04, -1.32576004e-05, -2.02001819e-03,\n", - " -2.33738228e-02, 1.30349504e-03, 2.15299364e+00, -2.98297990e-02,\n", - " 4.54923202e-01, -8.75798342e-05, 3.24243729e-03, 3.33314765e-02,\n", - " 5.22558408e-01, 3.74006411e-03, -2.83739592e-03, 1.63663965e-05,\n", - " -1.61347181e-01]),\n", - " array([ 1.84231644e-04, 4.92903356e-01, 1.02368663e+00, -1.40246344e-03,\n", - " -2.03512775e-05, 3.27357223e-06, -9.99999016e-01, 1.20894411e-02,\n", - " -6.30729285e+00, 4.36344128e-04, -1.61277447e-05, -2.02002891e-03,\n", - " -2.35352739e-02, 1.31088529e-03, 2.15297790e+00, -2.50840777e-02,\n", - " 4.75320081e-01, -1.00397153e-04, 3.56736715e-03, 3.36475138e-02,\n", - " 5.43122249e-01, 4.08218653e-03, -2.87014429e-03, -1.07210593e-05,\n", - " -1.61451089e-01]),\n", - " array([ 1.85559857e-04, 4.95056365e-01, 1.02367292e+00, -1.64924684e-03,\n", - " -2.02930920e-05, 1.34049683e-06, -9.99998640e-01, 1.21233900e-02,\n", - " -6.30673133e+00, 4.40750163e-04, -1.90319215e-05, -2.02006702e-03,\n", - " -2.36968094e-02, 1.31896989e-03, 2.15295695e+00, -2.02791729e-02,\n", - " 4.93567284e-01, -1.09317744e-04, 3.87635250e-03, 3.39488604e-02,\n", - " 5.61516798e-01, 4.40603451e-03, -2.90417680e-03, -3.81150367e-05,\n", - " -1.61535523e-01]),\n", - " array([ 1.86888410e-04, 4.97209337e-01, 1.02366517e+00, -1.90405537e-03,\n", - " -2.02316358e-05, -7.33670388e-07, -9.99998187e-01, 1.21576150e-02,\n", - " -6.30615364e+00, 4.45459962e-04, -2.19714623e-05, -2.02013285e-03,\n", - " -2.38584094e-02, 1.32771563e-03, 2.15293085e+00, -1.54065236e-02,\n", - " 5.09617791e-01, -1.15369181e-04, 4.15887204e-03, 3.42250110e-02,\n", - " 5.77694620e-01, 4.70979907e-03, -2.93954076e-03, -6.58240183e-05,\n", - " -1.61600056e-01]),\n", - " array([ 1.88217344e-04, 4.99362261e-01, 1.02366347e+00, -2.16576813e-03,\n", - " -2.01677436e-05, -2.92959847e-06, -9.99997655e-01, 1.21920787e-02,\n", - " -6.30556203e+00, 4.50451436e-04, -2.49477465e-05, -2.02022670e-03,\n", - " -2.40200537e-02, 1.33706681e-03, 2.15289964e+00, -1.04568333e-02,\n", - " 5.23426514e-01, -1.19784158e-04, 4.40268210e-03, 3.44637340e-02,\n", - " 5.91610237e-01, 4.99147448e-03, -2.97628423e-03, -9.38579642e-05,\n", - " -1.61644280e-01]),\n", - " array([ 1.89546720e-04, 5.01515127e-01, 1.02366795e+00, -2.43324262e-03,\n", - " -2.01015456e-05, -5.22091826e-06, -9.99997039e-01, 1.22267297e-02,\n", - " -6.30495881e+00, 4.55700281e-04, -2.79622024e-05, -2.02034893e-03,\n", - " -2.41817215e-02, 1.34694155e-03, 2.15286335e+00, -5.42014257e-03,\n", - " 5.34950308e-01, -1.24013307e-04, 4.59370794e-03, 3.46509623e-02,\n", - " 6.03220132e-01, 5.24884421e-03, -3.01445592e-03, -1.22228154e-04,\n", - " -1.61667802e-01]),\n", - " array([ 1.90876615e-04, 5.03667922e-01, 1.02367873e+00, -2.70531577e-03,\n", - " -2.00323599e-05, -7.57326003e-06, -9.99996340e-01, 1.22615004e-02,\n", - " -6.30434632e+00, 4.61179750e-04, -3.10163076e-05, -2.02049988e-03,\n", - " -2.43433918e-02, 1.35722791e-03, 2.15282203e+00, -2.85903595e-04,\n", - " 5.44147996e-01, -1.29736131e-04, 4.71595184e-03, 3.47707010e-02,\n", - " 6.12482778e-01, 5.47946940e-03, -3.05410517e-03, -1.50947023e-04,\n", - " -1.61670247e-01]),\n", - " array([ 1.92207129e-04, 5.05820635e-01, 1.02369593e+00, -2.98080492e-03,\n", - " -1.99585840e-05, -9.94325653e-06, -9.99995557e-01, 1.22963053e-02,\n", - " -6.30372696e+00, 4.66860430e-04, -3.41115894e-05, -2.02067991e-03,\n", - " -2.45050430e-02, 1.36777972e-03, 2.15277572e+00, 4.95693999e-03,\n", - " 5.50980434e-01, -1.38869378e-04, 4.75142414e-03, 3.48049588e-02,\n", - " 6.19358701e-01, 5.68068041e-03, -3.09528179e-03, -1.80027986e-04,\n", - " -1.61651258e-01]),\n", - " array([ 1.93538343e-04, 5.07973253e-01, 1.02371968e+00, -3.25851247e-03,\n", - " -1.98796247e-05, -1.22952448e-05, -9.99994691e-01, 1.23310744e-02,\n", - " -6.30310315e+00, 4.72714269e-04, -3.72496210e-05, -2.02088939e-03,\n", - " -2.46666536e-02, 1.37840812e-03, 2.15272447e+00, 1.03187653e-02,\n", - " 5.55417710e-01, -1.49384275e-04, 4.71552887e-03, 3.47690756e-02,\n", - " 6.23817698e-01, 5.85383897e-03, -3.13803162e-03, -2.09481879e-04,\n", - " -1.61610561e-01]),\n", - " array([ 1.94870322e-04, 5.10125764e-01, 1.02375012e+00, -3.53722689e-03,\n", - " -1.97957996e-05, -1.46004915e-05, -9.99993744e-01, 1.23657513e-02,\n", - " -6.30247732e+00, 4.78714412e-04, -4.04320215e-05, -2.02112871e-03,\n", - " -2.48282015e-02, 1.38895764e-03, 2.15266831e+00, 1.58099756e-02,\n", - " 5.57431964e-01, -1.59442081e-04, 4.62212008e-03, 3.46768431e-02,\n", - " 6.25831636e-01, 6.00014295e-03, -3.18240050e-03, -2.39319385e-04,\n", - " -1.61547902e-01]),\n", - " array([ 1.96203117e-04, 5.12278156e-01, 1.02378738e+00, -3.81572375e-03,\n", - " -1.97082410e-05, -1.68364389e-05, -9.99992720e-01, 1.24002918e-02,\n", - " -6.30185194e+00, 4.84835044e-04, -4.36604556e-05, -2.02139826e-03,\n", - " -2.49896645e-02, 1.39930282e-03, 2.15260728e+00, 2.14409080e-02,\n", - " 5.56997395e-01, -1.67389754e-04, 4.48354238e-03, 3.45405460e-02,\n", - " 6.25374463e-01, 6.12063190e-03, -3.22843415e-03, -2.69550821e-04,\n", - " -1.61463043e-01]),\n", - " array([ 1.97536762e-04, 5.14430414e-01, 1.02383163e+00, -4.09276678e-03,\n", - " -1.96188044e-05, -1.89859794e-05, -9.99991624e-01, 1.24346628e-02,\n", - " -6.30122952e+00, 4.91051239e-04, -4.69366337e-05, -2.02169845e-03,\n", - " -2.51510203e-02, 1.40934497e-03, 2.15254141e+00, 2.72217427e-02,\n", - " 5.54090300e-01, -1.71753481e-04, 4.31068924e-03, 3.43710201e-02,\n", - " 6.22422245e-01, 6.21619467e-03, -3.27617808e-03, -3.00185936e-04,\n", - " -1.61355766e-01]),\n", - " array([ 1.98871284e-04, 5.16582528e-01, 1.02388300e+00, -4.36710893e-03,\n", - " -1.95299809e-05, -2.10367662e-05, -9.99990464e-01, 1.24688405e-02,\n", - " -6.30061257e+00, 4.97338817e-04, -5.02623112e-05, -2.02202968e-03,\n", - " -2.53122462e-02, 1.41900897e-03, 2.15247071e+00, 3.31624128e-02,\n", - " 5.48689124e-01, -1.71230572e-04, 4.11307490e-03, 3.41777244e-02,\n", - " 6.16953217e-01, 6.28757852e-03, -3.32567748e-03, -3.31233714e-04,\n", - " -1.61225870e-01]),\n", - " array([ 2.00206699e-04, 5.18734482e-01, 1.02394165e+00, -4.63749350e-03,\n", - " -1.94448154e-05, -2.29805646e-05, -9.99989246e-01, 1.25028094e-02,\n", - " -6.30000362e+00, 5.03674217e-04, -5.36392883e-05, -2.02239238e-03,\n", - " -2.54733194e-02, 1.42824030e-03, 2.15239520e+00, 3.92725152e-02,\n", - " 5.40774546e-01, -1.64680184e-04, 3.89891608e-03, 3.39688228e-02,\n", - " 6.08947870e-01, 6.33539940e-03, -3.37697711e-03, -3.62702175e-04,\n", - " -1.61073177e-01]),\n", - " array([ 2.01543013e-04, 5.20886264e-01, 1.02400774e+00, -4.90265531e-03,\n", - " -1.93668307e-05, -2.48126477e-05, -9.99987981e-01, 1.25365606e-02,\n", - " -6.29940523e+00, 5.10034370e-04, -5.70694095e-05, -2.02278698e-03,\n", - " -2.56342169e-02, 1.43700224e-03, 2.15231485e+00, 4.55612229e-02,\n", - " 5.30329577e-01, -1.51113253e-04, 3.67522040e-03, 3.37512726e-02,\n", - " 5.98389051e-01, 6.36015297e-03, -3.43012121e-03, -3.94598187e-04,\n", - " -1.60897525e-01]),\n", - " array([ 2.02880228e-04, 5.23037861e-01, 1.02408144e+00, -5.16132191e-03,\n", - " -1.92999562e-05, -2.65312381e-05, -9.99986680e-01, 1.25700916e-02,\n", - " -6.29881997e+00, 5.16396596e-04, -6.05545629e-05, -2.02321391e-03,\n", - " -2.57949157e-02, 1.44527317e-03, 2.15222965e+00, 5.20371981e-02,\n", - " 5.17339691e-01, -1.29681976e-04, 3.44787889e-03, 3.35309174e-02,\n", - " 5.85262092e-01, 6.36222633e-03, -3.48515335e-03, -4.26927274e-04,\n", - " -1.60698778e-01]),\n", - " array([ 2.04218339e-04, 5.25189260e-01, 1.02416290e+00, -5.41221492e-03,\n", - " -1.92484641e-05, -2.81369964e-05, -9.99985353e-01, 1.26034041e-02,\n", - " -6.29825041e+00, 5.22738506e-04, -6.40966792e-05, -2.02367360e-03,\n", - " -2.59553925e-02, 1.45304421e-03, 2.15213954e+00, 5.87085074e-02,\n", - " 5.01792969e-01, -9.96691179e-05, 3.22176021e-03, 3.33125809e-02,\n", - " 5.69554956e-01, 6.34190989e-03, -3.54211633e-03, -4.59693437e-04,\n", - " -1.60476820e-01]),\n", - " array([ 2.05557337e-04, 5.27340447e-01, 1.02425229e+00, -5.65405138e-03,\n", - " -1.92169094e-05, -2.96325572e-05, -9.99984015e-01, 1.26365043e-02,\n", - " -6.29769915e+00, 5.29037916e-04, -6.76977313e-05, -2.02416650e-03,\n", - " -2.61156240e-02, 1.46031694e-03, 2.15204444e+00, 6.55825372e-02,\n", - " 4.83680264e-01, -6.04773753e-05, 3.00080476e-03, 3.31001616e-02,\n", - " 5.51258408e-01, 6.29940949e-03, -3.60105207e-03, -4.92898978e-04,\n", - " -1.60231562e-01]),\n", - " array([ 2.06897210e-04, 5.29491409e-01, 1.02434978e+00, -5.88554525e-03,\n", - " -1.92100773e-05, -3.10221112e-05, -9.99982679e-01, 1.26694010e-02,\n", - " -6.29716879e+00, 5.35272774e-04, -7.13597327e-05, -2.02469304e-03,\n", - " -2.62755870e-02, 1.46710143e-03, 2.15194425e+00, 7.26659117e-02,\n", - " 4.62995389e-01, -1.16189954e-05, 2.78811711e-03, 3.28967249e-02,\n", - " 5.30366199e-01, 6.23485843e-03, -3.66200143e-03, -5.26544324e-04,\n", - " -1.59962939e-01]),\n", - " array([ 2.08237944e-04, 5.31642135e-01, 1.02445555e+00, -6.10540898e-03,\n", - " -1.92329341e-05, -3.23110313e-05, -9.99981361e-01, 1.27021056e-02,\n", - " -6.29666191e+00, 5.41421103e-04, -7.50847368e-05, -2.02525367e-03,\n", - " -2.64352579e-02, 1.47341433e-03, 2.15183883e+00, 7.99644118e-02,\n", - " 4.39735321e-01, 4.72942069e-05, 2.58605550e-03, 3.27045933e-02,\n", - " 5.06875271e-01, 6.14832932e-03, -3.72500410e-03, -5.60627858e-04,\n", - " -1.59670917e-01]),\n", - " array([ 2.09579526e-04, 5.33792610e-01, 1.02456974e+00, -6.31235522e-03,\n", - " -1.92905843e-05, -3.35055426e-05, -9.99980076e-01, 1.27346311e-02,\n", - " -6.29618113e+00, 5.47460949e-04, -7.88748352e-05, -2.02584882e-03,\n", - " -2.65946134e-02, 1.47927731e-03, 2.15172800e+00, 8.74828961e-02,\n", - " 4.13900416e-01, 1.16560310e-04, 2.39631755e-03, 3.25254321e-02,\n", - " 4.80785982e-01, 6.03984576e-03, -3.79009844e-03, -5.95145767e-04,\n", - " -1.59355489e-01]),\n", - " array([ 2.10921939e-04, 5.35942825e-01, 1.02469254e+00, -6.50509860e-03,\n", - " -1.93882313e-05, -3.46124321e-05, -9.99978841e-01, 1.27669914e-02,\n", - " -6.29572902e+00, 5.53370343e-04, -8.27321566e-05, -2.02647891e-03,\n", - " -2.67536301e-02, 1.48471561e-03, 2.15161155e+00, 9.52252233e-02,\n", - " 3.85494646e-01, 1.96396143e-04, 2.22002129e-03, 3.23603306e-02,\n", - " 4.52102337e-01, 5.90939355e-03, -3.85732133e-03, -6.30091873e-04,\n", - " -1.59016683e-01]),\n", - " array([ 2.12265170e-04, 5.38092766e-01, 1.02482409e+00, -6.68235769e-03,\n", - " -1.95311432e-05, -3.56387969e-05, -9.99977672e-01, 1.27992013e-02,\n", - " -6.29530819e+00, 5.59127274e-04, -8.66588646e-05, -2.02714437e-03,\n", - " -2.69122846e-02, 1.48975672e-03, 2.15148922e+00, 1.03194177e-01,\n", - " 3.54525848e-01, 2.86945470e-04, 2.05778123e-03, 3.22098787e-02,\n", - " 4.20832239e-01, 5.75693164e-03, -3.92670800e-03, -6.65457496e-04,\n", - " -1.58654561e-01]),\n", - " array([ 2.13609207e-04, 5.40242424e-01, 1.02496457e+00, -6.84285702e-03,\n", - " -1.97246211e-05, -3.65918271e-05, -9.99976587e-01, 1.28312755e-02,\n", - " -6.29492120e+00, 5.64709677e-04, -9.06571564e-05, -2.02784560e-03,\n", - " -2.70705538e-02, 1.49442933e-03, 2.15136069e+00, 1.11391392e-01,\n", - " 3.21005975e-01, 3.88286481e-04, 1.90977893e-03, 3.20742374e-02,\n", - " 3.86987750e-01, 5.58240251e-03, -3.99829189e-03, -7.01231301e-04,\n", - " -1.58269220e-01]),\n", - " array([ 2.14954039e-04, 5.42391787e-01, 1.02511412e+00, -6.98532930e-03,\n", - " -1.99739719e-05, -3.74786219e-05, -9.99975601e-01, 1.28632287e-02,\n", - " -6.29457062e+00, 5.70095419e-04, -9.47292608e-05, -2.02858300e-03,\n", - " -2.72284146e-02, 1.49876232e-03, 2.15122562e+00, 1.19817283e-01,\n", - " 2.84951370e-01, 5.00438551e-04, 1.77582802e-03, 3.19532046e-02,\n", - " 3.50585359e-01, 5.38574223e-03, -4.07210440e-03, -7.37399167e-04,\n", - " -1.57860799e-01]),\n", - " array([ 2.16299659e-04, 5.44540846e-01, 1.02527290e+00, -7.10851777e-03,\n", - " -2.02844834e-05, -3.83060348e-05, -9.99974733e-01, 1.28950750e-02,\n", - " -6.29425897e+00, 5.75262309e-04, -9.88774356e-05, -2.02935694e-03,\n", - " -2.73858441e-02, 1.50278403e-03, 2.15108359e+00, 1.28470979e-01,\n", - " 2.46383035e-01, 6.23368275e-04, 1.65543359e-03, 3.18462746e-02,\n", - " 3.11646259e-01, 5.16688991e-03, -4.14817480e-03, -7.73944053e-04,\n", - " -1.57429478e-01]),\n", - " array([ 2.17646062e-04, 5.46689593e-01, 1.02544103e+00, -7.21117859e-03,\n", - " -2.06614023e-05, -3.90805462e-05, -9.99973998e-01, 1.29268277e-02,\n", - " -6.29398878e+00, 5.80188106e-04, -1.03103966e-04, -2.03016779e-03,\n", - " -2.75428196e-02, 1.50652152e-03, 2.15093413e+00, 1.37350252e-01,\n", - " 2.05326916e-01, 7.56994801e-04, 1.54784606e-03, 3.17526923e-02,\n", - " 2.70196630e-01, 4.92579674e-03, -4.22652997e-03, -8.10845877e-04,\n", - " -1.56975482e-01]),\n", - " array([ 2.18993247e-04, 5.48838020e-01, 1.02561866e+00, -7.29208355e-03,\n", - " -2.11099140e-05, -3.98081597e-05, -9.99973411e-01, 1.29584992e-02,\n", - " -6.29376251e+00, 5.84850540e-04, -1.07411160e-04, -2.03101587e-03,\n", - " -2.76993187e-02, 1.51000004e-03, 2.15077671e+00, 1.46451457e-01,\n", - " 1.61814180e-01, 9.01194484e-04, 1.45210975e-03, 3.16715022e-02,\n", - " 2.26267924e-01, 4.66243457e-03, -4.30719425e-03, -8.48081400e-04,\n", - " -1.56499082e-01]),\n", - " array([ 2.20341218e-04, 5.50986120e-01, 1.02580590e+00, -7.35002275e-03,\n", - " -2.16351243e-05, -4.04943206e-05, -9.99972987e-01, 1.29901008e-02,\n", - " -6.29358261e+00, 5.89227344e-04, -1.11801349e-04, -2.03190149e-03,\n", - " -2.78553193e-02, 1.51324255e-03, 2.15061075e+00, 1.55769473e-01,\n", - " 1.15881504e-01, 1.05580481e-03, 1.36710556e-03, 3.16015913e-02,\n", - " 1.79897152e-01, 4.37680387e-03, -4.39018922e-03, -8.85624114e-04,\n", - " -1.56000600e-01]),\n", - " array([ 2.21689981e-04, 5.53133886e-01, 1.02600287e+00, -7.38380750e-03,\n", - " -2.22420432e-05, -4.11438524e-05, -9.99972738e-01, 1.30216425e-02,\n", - " -6.29345148e+00, 5.93296285e-04, -1.16276883e-04, -2.03282494e-03,\n", - " -2.80107997e-02, 1.51626941e-03, 2.15043559e+00, 1.65297643e-01,\n", - " 6.75713560e-02, 1.22062770e-03, 1.29158877e-03, 3.15417276e-02,\n", - " 1.31127167e-01, 4.06894127e-03, -4.47553349e-03, -9.23444143e-04,\n", - " -1.55480411e-01]),\n", - " array([ 2.23039550e-04, 5.55281316e-01, 1.02620965e+00, -7.39227339e-03,\n", - " -2.29355692e-05, -4.17609127e-05, -9.99972676e-01, 1.30531331e-02,\n", - " -6.29337148e+00, 5.97035213e-04, -1.20840125e-04, -2.03378644e-03,\n", - " -2.81657386e-02, 1.51909806e-03, 2.15025052e+00, 1.75027724e-01,\n", - " 1.69322743e-02, 1.39543283e-03, 1.22422699e-03, 3.14905977e-02,\n", - " 8.00069508e-02, 3.73892724e-03, -4.56324250e-03, -9.61508151e-04,\n", - " -1.54938943e-01]),\n", - " array([ 2.24389941e-04, 5.57428406e-01, 1.02642632e+00, -7.37428343e-03,\n", - " -2.37204750e-05, -4.23489617e-05, -9.99972808e-01, 1.30845799e-02,\n", - " -6.29334488e+00, 6.00422105e-04, -1.25493453e-04, -2.03478622e-03,\n", - " -2.83201153e-02, 1.52174286e-03, 2.15005477e+00, 1.84949834e-01,\n", - " -3.59808584e-02, 1.57995933e-03, 1.16362495e-03, 3.14468324e-02,\n", - " 2.65918857e-02, 3.38689216e-03, -4.65332834e-03, -9.99779252e-04,\n", - " -1.54376683e-01]),\n", - " array([ 2.25741177e-04, 5.59575153e-01, 1.02665296e+00, -7.32873136e-03,\n", - " -2.46013940e-05, -4.29107437e-05, -9.99973143e-01, 1.31159890e-02,\n", - " -6.29337394e+00, 6.03435128e-04, -1.30239253e-04, -2.03582444e-03,\n", - " -2.84739095e-02, 1.52421499e-03, 2.14984751e+00, 1.95052408e-01,\n", - " -9.11065487e-02, 1.77391785e-03, 1.10835182e-03, 3.14090340e-02,\n", - " -2.90559741e-02, 3.01302285e-03, -4.74579949e-03, -1.03821694e-03,\n", - " -1.53794177e-01]),\n", - " array([ 2.27093284e-04, 5.61721558e-01, 1.02688961e+00, -7.25454509e-03,\n", - " -2.55828068e-05, -4.34482806e-05, -9.99973684e-01, 1.31473648e-02,\n", - " -6.29346081e+00, 6.06052696e-04, -1.35079914e-04, -2.03690122e-03,\n", - " -2.86271015e-02, 1.52652230e-03, 2.14962786e+00, 2.05322156e-01,\n", - " -1.48376437e-01, 1.97699196e-03, 1.05696337e-03, 3.13757985e-02,\n", - " -8.68676457e-02, 2.61756842e-03, -4.84066061e-03, -1.07677701e-03,\n", - " -1.53192036e-01]),\n", - " array([ 2.28446295e-04, 5.63867623e-01, 1.02713629e+00, -7.15069022e-03,\n", - " -2.66690288e-05, -4.39628749e-05, -9.99974432e-01, 1.31787105e-02,\n", - " -6.29360757e+00, 6.08253542e-04, -1.40017826e-04, -2.03801663e-03,\n", - " -2.87796725e-02, 1.52866938e-03, 2.14939487e+00, 2.15744027e-01,\n", - " -2.07715053e-01, 2.18883942e-03, 1.00802262e-03, 3.13457365e-02,\n", - " -1.46766972e-01, 2.20084593e-03, -4.93791238e-03, -1.11541150e-03,\n", - " -1.52570933e-01]),\n", - " array([ 2.29800246e-04, 5.66013349e-01, 1.02739302e+00, -7.01617376e-03,\n", - " -2.78641973e-05, -4.44551189e-05, -9.99975385e-01, 1.32100280e-02,\n", - " -6.29381625e+00, 6.10016787e-04, -1.45055377e-04, -2.03917070e-03,\n", - " -2.89316041e-02, 1.53065757e-03, 2.14914755e+00, 2.26301176e-01,\n", - " -2.69039592e-01, 2.40909241e-03, 9.60111662e-04, 3.13174847e-02,\n", - " -2.08670391e-01, 1.76324496e-03, -5.03755120e-03, -1.15406866e-03,\n", - " -1.51931608e-01]),\n", - " array([ 2.31155181e-04, 5.68158741e-01, 1.02765977e+00, -6.85004786e-03,\n", - " -2.91722596e-05, -4.49249126e-05, -9.99976537e-01, 1.32413177e-02,\n", - " -6.29408873e+00, 6.11322020e-04, -1.50194946e-04, -2.04036339e-03,\n", - " -2.90828789e-02, 1.53248501e-03, 2.14888488e+00, 2.36974937e-01,\n", - " -3.32259695e-01, 2.63735846e-03, 9.11848761e-04, 3.12897233e-02,\n", - " -2.72486722e-01, 1.30523272e-03, -5.13956905e-03, -1.19269288e-03,\n", - " -1.51274871e-01]),\n", - " array([ 2.32511146e-04, 5.70303806e-01, 1.02793650e+00, -6.65141370e-03,\n", - " -3.05969598e-05, -4.53714870e-05, -9.99977878e-01, 1.32725789e-02,\n", - " -6.29442685e+00, 6.12149378e-04, -1.55438899e-04, -2.04159462e-03,\n", - " -2.92334805e-02, 1.53414677e-03, 2.14860579e+00, 2.47744800e-01,\n", - " -3.97277268e-01, 2.87322069e-03, 8.61899639e-04, 3.12611866e-02,\n", - " -3.38116975e-01, 8.27358336e-04, -5.24395323e-03, -1.23122468e-03,\n", - " -1.50601602e-01]),\n", - " array([ 2.33868192e-04, 5.72448552e-01, 1.02822314e+00, -6.41942545e-03,\n", - " -3.21418271e-05, -4.57934325e-05, -9.99979394e-01, 1.33038096e-02,\n", - " -6.29483230e+00, 6.12479635e-04, -1.60789586e-04, -2.04286422e-03,\n", - " -2.93833933e-02, 1.53563496e-03, 2.14830919e+00, 2.58588397e-01,\n", - " -4.63986302e-01, 3.11623798e-03, 8.08987292e-04, 3.12306726e-02,\n", - " -4.05454175e-01, 3.30256814e-04, -5.35068619e-03, -1.26960067e-03,\n", - " -1.49912754e-01]),\n", - " array([ 2.35226377e-04, 5.74592989e-01, 1.02851961e+00, -6.15329427e-03,\n", - " -3.38101631e-05, -4.61887308e-05, -9.99981067e-01, 1.33350066e-02,\n", - " -6.29530669e+00, 6.12294287e-04, -1.66249331e-04, -2.04417197e-03,\n", - " -2.95326027e-02, 1.53693894e-03, 2.14799399e+00, 2.69481490e-01,\n", - " -5.32272733e-01, 3.36594495e-03, 7.51899750e-04, 3.11970505e-02,\n", - " -4.74383219e-01, -1.85347411e-04, -5.45974530e-03, -1.30775356e-03,\n", - " -1.49209352e-01]),\n", - " array([ 2.36585758e-04, 5.76737127e-01, 1.02882577e+00, -5.85229247e-03,\n", - " -3.56050287e-05, -4.65547911e-05, -9.99982873e-01, 1.33661659e-02,\n", - " -6.29585147e+00, 6.11575650e-04, -1.71820434e-04, -2.04551758e-03,\n", - " -2.96810952e-02, 1.53804546e-03, 2.14765908e+00, 2.80397969e-01,\n", - " -6.02014321e-01, 3.62185195e-03, 6.89497331e-04, 3.11592669e-02,\n", - " -5.44780753e-01, -7.18637221e-04, -5.57110265e-03, -1.34561214e-03,\n", - " -1.48492497e-01]),\n", - " array([ 2.37946401e-04, 5.78880980e-01, 1.02914147e+00, -5.51575755e-03,\n", - " -3.75292320e-05, -4.68884885e-05, -9.99984786e-01, 1.33972822e-02,\n", - " -6.29646798e+00, 6.10306950e-04, -1.77505158e-04, -2.04690068e-03,\n", - " -2.98288585e-02, 1.53893890e-03, 2.14730336e+00, 2.91309852e-01,\n", - " -6.73080558e-01, 3.88344500e-03, 6.20718496e-04, 3.11163513e-02,\n", - " -6.16515076e-01, -1.26869997e-03, -5.68472489e-03, -1.38310129e-03,\n", - " -1.47763365e-01]),\n", - " array([ 2.39308370e-04, 5.81024563e-01, 1.02946653e+00, -5.14309645e-03,\n", - " -3.95853150e-05, -4.71862051e-05, -9.99986772e-01, 1.34283496e-02,\n", - " -6.29715743e+00, 6.08472425e-04, -1.83305731e-04, -2.04832083e-03,\n", - " -2.99758817e-02, 1.53960149e-03, 2.14692578e+00, 3.02187294e-01,\n", - " -7.45332603e-01, 4.15018574e-03, 5.44584970e-04, 3.10674200e-02,\n", - " -6.89446083e-01, -1.83452499e-03, -5.80057299e-03, -1.42014204e-03,\n", - " -1.47023208e-01]),\n", - " array([ 2.40671734e-04, 5.83167892e-01, 1.02980071e+00, -4.73378972e-03,\n", - " -4.17755408e-05, -4.74438741e-05, -9.99988794e-01, 1.34593613e-02,\n", - " -6.29792085e+00, 6.06057424e-04, -1.89224334e-04, -2.04977748e-03,\n", - " -3.01221551e-02, 1.54001354e-03, 2.14652529e+00, 3.12998605e-01,\n", - " -8.18623257e-01, 4.42151137e-03, 4.60206184e-04, 3.10116799e-02,\n", - " -7.63425235e-01, -2.41500155e-03, -5.91860213e-03, -1.45665153e-03,\n", - " -1.46273356e-01]),\n", - " array([ 2.42036563e-04, 5.85310986e-01, 1.03014377e+00, -4.28739568e-03,\n", - " -4.41018806e-05, -4.76570243e-05, -9.99990807e-01, 1.34903098e-02,\n", - " -6.29875915e+00, 6.03048507e-04, -1.95263095e-04, -2.05127002e-03,\n", - " -3.02676703e-02, 1.54015369e-03, 2.14610094e+00, 3.23710272e-01,\n", - " -8.92796965e-01, 4.69683477e-03, 3.66783218e-04, 3.09484305e-02,\n", - " -8.38295557e-01, -3.00891709e-03, -6.03876148e-03, -1.49254314e-03,\n", - " -1.45515214e-01]),\n", - " array([ 2.43402926e-04, 5.87453863e-01, 1.03049540e+00, -3.80355461e-03,\n", - " -4.65660010e-05, -4.78208283e-05, -9.99992764e-01, 1.35211868e-02,\n", - " -6.29967304e+00, 5.99433551e-04, -2.01424089e-04, -2.05279775e-03,\n", - " -3.04124206e-02, 1.53999923e-03, 2.14565185e+00, 3.34286992e-01,\n", - " -9.67689857e-01, 4.97554451e-03, 2.63612351e-04, 3.08770668e-02,\n", - " -9.13891685e-01, -3.61495602e-03, -6.16099407e-03, -1.52772647e-03,\n", - " -1.44750264e-01]),\n", - " array([ 2.44770894e-04, 5.89596544e-01, 1.03085529e+00, -3.28199285e-03,\n", - " -4.91692510e-05, -4.79301502e-05, -9.99994612e-01, 1.35519839e-02,\n", - " -6.30066308e+00, 5.95201852e-04, -2.07709326e-04, -2.05435985e-03,\n", - " -3.05564006e-02, 1.53952631e-03, 2.14517721e+00, 3.44691706e-01,\n", - " -1.04312982e+00, 5.25700518e-03, 1.50088354e-04, 3.07970808e-02,\n", - " -9.90039939e-01, -4.23169885e-03, -6.28523664e-03, -1.56210748e-03,\n", - " -1.43980063e-01]),\n", - " array([ 2.46140534e-04, 5.91739050e-01, 1.03122304e+00, -2.72252694e-03,\n", - " -5.19126495e-05, -4.79795971e-05, -9.99996291e-01, 1.35826920e-02,\n", - " -6.30172964e+00, 5.90344230e-04, -2.14120745e-04, -2.05595544e-03,\n", - " -3.06996069e-02, 1.53871028e-03, 2.14467636e+00, 3.54885648e-01,\n", - " -1.11893663e+00, 5.54055769e-03, 2.57075587e-05, 3.07080625e-02,\n", - " -1.06655844e+00, -4.85762179e-03, -6.41141953e-03, -1.59558855e-03,\n", - " -1.43206243e-01]),\n", - " array([ 2.47511914e-04, 5.93881406e-01, 1.03159826e+00, -2.12506753e-03,\n", - " -5.47968729e-05, -4.79635700e-05, -9.99997739e-01, 1.36133017e-02,\n", - " -6.30287290e+00, 5.84853133e-04, -2.20660212e-04, -2.05758351e-03,\n", - " -3.08420374e-02, 1.53752600e-03, 2.14414877e+00, 3.64828402e-01,\n", - " -1.19492206e+00, 5.82551978e-03, -1.09929218e-04, 3.06097018e-02,\n", - " -1.14325727e+00, -5.49109685e-03, -6.53946655e-03, -1.62806857e-03,\n", - " -1.42430511e-01]),\n", - " array([ 2.48885094e-04, 5.96023632e-01, 1.03198048e+00, -1.48962335e-03,\n", - " -5.78222430e-05, -4.78763174e-05, -9.99998888e-01, 1.36438035e-02,\n", - " -6.30409283e+00, 5.78722741e-04, -2.27329507e-04, -2.05924295e-03,\n", - " -3.09836920e-02, 1.53594811e-03, 2.14359407e+00, 3.74477960e-01,\n", - " -1.27089016e+00, 6.11118662e-03, -2.57113862e-04, 3.05017887e-02,\n", - " -1.21993867e+00, -6.13039232e-03, -6.66929488e-03, -1.65944306e-03,\n", - " -1.41654642e-01]),\n", - " array([ 2.50260133e-04, 5.98165753e-01, 1.03236921e+00, -8.16304948e-04,\n", - " -6.09887157e-05, -4.77119899e-05, -9.99999664e-01, 1.36741877e-02,\n", - " -6.30538923e+00, 5.71949067e-04, -2.34130322e-04, -2.06093256e-03,\n", - " -3.11245725e-02, 1.53395136e-03, 2.14301209e+00, 3.83790795e-01,\n", - " -1.34663740e+00, 6.39683162e-03, -4.16028260e-04, 3.03842141e-02,\n", - " -1.29639726e+00, -6.77367391e-03, -6.80081501e-03, -1.68960434e-03,\n", - " -1.40880483e-01]),\n", - " array([ 2.51637079e-04, 6.00307793e-01, 1.03276391e+00, -1.05328357e-04,\n", - " -6.42958700e-05, -4.74646958e-05, -9.99999991e-01, 1.37044446e-02,\n", - " -6.30676165e+00, 5.64530061e-04, -2.41064252e-04, -2.06265100e-03,\n", - " -3.12646824e-02, 1.53151097e-03, 2.14240285e+00, 3.92721942e-01,\n", - " -1.42195301e+00, 6.68170740e-03, -5.86741705e-04, 3.02569704e-02,\n", - " -1.37242037e+00, -7.41900626e-03, -6.93393065e-03, -1.71844165e-03,\n", - " -1.40109948e-01]),\n", - " array([ 2.53015975e-04, 6.02449775e-01, 1.03316398e+00, 6.42981438e-04,\n", - " -6.77428973e-05, -4.71285584e-05, -9.99999790e-01, 1.37345648e-02,\n", - " -6.30820944e+00, 5.56465705e-04, -2.48132791e-04, -2.06439684e-03,\n", - " -3.14040275e-02, 1.52860293e-03, 2.14176661e+00, 4.01225082e-01,\n", - " -1.49661930e+00, 6.96504680e-03, -7.69208437e-04, 3.01201514e-02,\n", - " -1.44778829e+00, -8.06435506e-03, -7.06853871e-03, -1.74584131e-03,\n", - " -1.39345013e-01]),\n", - " array([ 2.54396854e-04, 6.04591722e-01, 1.03356880e+00, 1.42818720e-03,\n", - " -7.13285921e-05, -4.66977739e-05, -9.99998977e-01, 1.37645387e-02,\n", - " -6.30973172e+00, 5.47758116e-04, -2.55337320e-04, -2.06616853e-03,\n", - " -3.15426152e-02, 1.52520432e-03, 2.14110390e+00, 4.09252643e-01,\n", - " -1.57041201e+00, 7.24606424e-03, -9.63265340e-04, 2.99739525e-02,\n", - " -1.52227474e+00, -8.70758970e-03, -7.20452931e-03, -1.77168694e-03,\n", - " -1.38587717e-01]),\n", - " array([ 2.55779736e-04, 6.06733656e-01, 1.03397768e+00, 2.24973636e-03,\n", - " -7.50513432e-05, -4.61666711e-05, -9.99997465e-01, 1.37943574e-02,\n", - " -6.31132736e+00, 5.38411629e-04, -2.62679106e-04, -2.06796439e-03,\n", - " -3.16804553e-02, 1.52129366e-03, 2.14041549e+00, 4.16755902e-01,\n", - " -1.64310071e+00, 7.52395703e-03, -1.16862987e-03, 2.98186702e-02,\n", - " -1.59564717e+00, -9.34648647e-03, -7.34178572e-03, -1.79585966e-03,\n", - " -1.37840154e-01]),\n", - " array([ 2.57164627e-04, 6.08875597e-01, 1.03438990e+00, 3.10695813e-03,\n", - " -7.89091257e-05, -4.55297711e-05, -9.99995169e-01, 1.38240121e-02,\n", - " -6.31299503e+00, 5.28432897e-04, -2.70159291e-04, -2.06978263e-03,\n", - " -3.18175598e-02, 1.51685128e-03, 2.13970249e+00, 4.23685100e-01,\n", - " -1.71444928e+00, 7.79790699e-03, -1.38489823e-03, 2.96547018e-02,\n", - " -1.66766734e+00, -9.97873238e-03, -7.48018442e-03, -1.81823830e-03,\n", - " -1.37104472e-01]),\n", - " array([ 2.58551521e-04, 6.11017565e-01, 1.03480468e+00, 3.99906092e-03,\n", - " -8.28994943e-05, -4.47818484e-05, -9.99991999e-01, 1.38534947e-02,\n", - " -6.31473312e+00, 5.17830967e-04, -2.77778886e-04, -2.07162133e-03,\n", - " -3.19539427e-02, 1.51185959e-03, 2.13896629e+00, 4.29989564e-01,\n", - " -1.78421641e+00, 8.06708210e-03, -1.61154393e-03, 2.94825440e-02,\n", - " -1.73809171e+00, -1.06019295e-02, -7.61959517e-03, -1.83869965e-03,\n", - " -1.36382868e-01]),\n", - " array([ 2.59940392e-04, 6.13159575e-01, 1.03522120e+00, 4.92512998e-03,\n", - " -8.70195776e-05, -4.39179924e-05, -9.99987867e-01, 1.38827975e-02,\n", - " -6.31653979e+00, 5.06617368e-04, -2.85538767e-04, -2.07347844e-03,\n", - " -3.20896203e-02, 1.50630344e-03, 2.13820865e+00, 4.35617836e-01,\n", - " -1.85215612e+00, 8.33063832e-03, -1.84791671e-03, 2.93027921e-02,\n", - " -1.80667207e+00, -1.12135999e-02, -7.75988106e-03, -1.85711879e-03,\n", - " -1.35677581e-01]),\n", - " array([ 2.61331195e-04, 6.15301644e-01, 1.03563858e+00, 5.88412538e-03,\n", - " -9.12660731e-05, -4.29336688e-05, -9.99982683e-01, 1.39119136e-02,\n", - " -6.31841295e+00, 4.94806176e-04, -2.93439665e-04, -2.07535181e-03,\n", - " -3.22246111e-02, 1.50017045e-03, 2.13743165e+00, 4.40517811e-01,\n", - " -1.91801833e+00, 8.58772153e-03, -2.09324199e-03, 2.91161379e-02,\n", - " -1.87315606e+00, -1.18111912e-02, -7.90089862e-03, -1.87336927e-03,\n", - " -1.34990890e-01]),\n", - " array([ 2.62723864e-04, 6.17443780e-01, 1.03605592e+00, 6.87488024e-03,\n", - " -9.56352443e-05, -4.18247816e-05, -9.99976362e-01, 1.39408370e-02,\n", - " -6.32035024e+00, 4.82414094e-04, -3.01482163e-04, -2.07723914e-03,\n", - " -3.23589362e-02, 1.49345132e-03, 2.13663773e+00, 4.44636887e-01,\n", - " -1.98154955e+00, 8.83746954e-03, -2.34662085e-03, 2.89233680e-02,\n", - " -1.93728788e+00, -1.23920828e-02, -8.04249796e-03, -1.88732356e-03,\n", - " -1.34325104e-01]),\n", - " array([ 2.64118309e-04, 6.19585993e-01, 1.03647225e+00, 7.89609938e-03,\n", - " -1.00122919e-04, -4.05877341e-05, -9.99968819e-01, 1.39695623e-02,\n", - " -6.32234905e+00, 4.69460501e-04, -3.09666686e-04, -2.07913799e-03,\n", - " -3.24926188e-02, 1.48614013e-03, 2.13582973e+00, 4.47922114e-01,\n", - " -2.04249345e+00, 9.07901425e-03, -2.60703072e-03, 2.87253605e-02,\n", - " -1.99880887e+00, -1.29535924e-02, -8.18452291e-03, -1.89885327e-03,\n", - " -1.33682561e-01]),\n", - " array([ 2.65514417e-04, 6.21728285e-01, 1.03688655e+00, 8.94635824e-03,\n", - " -1.04724486e-04, -3.92194899e-05, -9.99959974e-01, 1.39980854e-02,\n", - " -6.32440650e+00, 4.55967518e-04, -3.17993497e-04, -2.08104582e-03,\n", - " -3.26256844e-02, 1.47823461e-03, 2.13501085e+00, 4.50320357e-01,\n", - " -2.10059165e+00, 9.31148383e-03, -2.87332669e-03, 2.85230825e-02,\n", - " -2.05745827e+00, -1.34929833e-02, -8.32681125e-03, -1.90782960e-03,\n", - " -1.33065619e-01]),\n", - " array([ 2.66912045e-04, 6.23870655e-01, 1.03729776e+00, 1.00241022e-02,\n", - " -1.09434901e-04, -3.77176323e-05, -9.99949751e-01, 1.40264030e-02,\n", - " -6.32651948e+00, 4.41960045e-04, -3.26462692e-04, -2.08295994e-03,\n", - " -3.27581611e-02, 1.46973646e-03, 2.13418465e+00, 4.51778463e-01,\n", - " -2.15558440e+00, 9.53400500e-03, -3.14424374e-03, 2.83175858e-02,\n", - " -2.11297399e+00, -1.40074724e-02, -8.46919487e-03, -1.91412368e-03,\n", - " -1.32476647e-01]),\n", - " array([ 2.68311020e-04, 6.26013098e-01, 1.03770478e+00, 1.11276465e-02,\n", - " -1.14248682e-04, -3.60804227e-05, -9.99938079e-01, 1.40545130e-02,\n", - " -6.32868457e+00, 4.27465807e-04, -3.35074192e-04, -2.08487755e-03,\n", - " -3.28900791e-02, 1.46065153e-03, 2.13335511e+00, 4.52243439e-01,\n", - " -2.20721137e+00, 9.74570530e-03, -3.41839976e-03, 2.81100030e-02,\n", - " -2.16509332e+00, -1.44942384e-02, -8.61150004e-03, -1.91760701e-03,\n", - " -1.31918024e-01]),\n", - " array([ 2.69711139e-04, 6.28155602e-01, 1.03810646e+00, 1.22551760e-02,\n", - " -1.19159920e-04, -3.43068561e-05, -9.99924895e-01, 1.40824145e-02,\n", - " -6.33089813e+00, 4.12515376e-04, -3.43827740e-04, -2.08679570e-03,\n", - " -3.30214712e-02, 1.45099013e-03, 2.13252655e+00, 4.51662627e-01,\n", - " -2.25521247e+00, 9.94571549e-03, -3.69429950e-03, 2.79015421e-02,\n", - " -2.21355379e+00, -1.49504307e-02, -8.75354772e-03, -1.91815187e-03,\n", - " -1.31392126e-01]),\n", - " array([ 2.71112166e-04, 6.30298149e-01, 1.03850160e+00, 1.34047461e-02,\n", - " -1.24162275e-04, -3.23967152e-05, -9.99910144e-01, 1.41101080e-02,\n", - " -6.33315622e+00, 3.97142198e-04, -3.52722894e-04, -2.08871133e-03,\n", - " -3.31523725e-02, 1.44076714e-03, 2.13170364e+00, 4.49983893e-01,\n", - " -2.29932868e+00, 1.01331719e-02, -3.97033955e-03, 2.76934814e-02,\n", - " -2.25809403e+00, -1.53731785e-02, -8.89515381e-03, -1.91563181e-03,\n", - " -1.30901320e-01]),\n", - " array([ 2.72513828e-04, 6.32440715e-01, 1.03888896e+00, 1.45742834e-02,\n", - " -1.29248992e-04, -3.03506208e-05, -9.99893781e-01, 1.41375952e-02,\n", - " -6.33545467e+00, 3.81382597e-04, -3.61759023e-04, -2.09062126e-03,\n", - " -3.32828205e-02, 1.43000228e-03, 2.13089142e+00, 4.47155816e-01,\n", - " -2.33930289e+00, 1.03072188e-02, -4.24481429e-03, 2.74871628e-02,\n", - " -2.29845459e+00, -1.57596010e-02, -9.03612951e-03, -1.90992211e-03,\n", - " -1.30447958e-01]),\n", - " array([ 2.73915816e-04, 6.34583271e-01, 1.03926728e+00, 1.57615876e-02,\n", - " -1.34412902e-04, -2.81700792e-05, -9.99875769e-01, 1.41648792e-02,\n", - " -6.33778905e+00, 3.65275780e-04, -3.70935305e-04, -2.09252216e-03,\n", - " -3.34128549e-02, 1.41872015e-03, 2.13009523e+00, 4.43127883e-01,\n", - " -2.37488084e+00, 1.04670108e-02, -4.51592296e-03, 2.72839853e-02,\n", - " -2.33437887e+00, -1.61068173e-02, -9.17628167e-03, -1.90090031e-03,\n", - " -1.30034368e-01]),\n", - " array([ 2.75317783e-04, 6.36725778e-01, 1.03963522e+00, 1.69643329e-02,\n", - " -1.39646431e-04, -2.58575248e-05, -9.99856085e-01, 1.41919646e-02,\n", - " -6.34015467e+00, 3.48863823e-04, -3.80250718e-04, -2.09441060e-03,\n", - " -3.35425177e-02, 1.40695041e-03, 2.12932070e+00, 4.37850690e-01,\n", - " -2.40581198e+00, 1.06117151e-02, -4.78177775e-03, 2.70853975e-02,\n", - " -2.36561405e+00, -1.64119570e-02, -9.31541323e-03, -1.88844670e-03,\n", - " -1.29662842e-01]),\n", - " array([ 2.76719341e-04, 6.38868192e-01, 1.03999143e+00, 1.81800708e-02,\n", - " -1.44941617e-04, -2.34163593e-05, -9.99834718e-01, 1.42188575e-02,\n", - " -6.34254658e+00, 3.32191652e-04, -3.89704042e-04, -2.09628305e-03,\n", - " -3.36718533e-02, 1.39472781e-03, 2.12857371e+00, 4.31276138e-01,\n", - " -2.43185043e+00, 1.07405140e-02, -5.04041299e-03, 2.68928892e-02,\n", - " -2.39191201e+00, -1.66721708e-02, -9.45332356e-03, -1.87244494e-03,\n", - " -1.29335634e-01]),\n", - " array([ 2.78120061e-04, 6.41010458e-01, 1.04033453e+00, 1.94062326e-02,\n", - " -1.50290111e-04, -2.08509844e-05, -9.99811670e-01, 1.42455654e-02,\n", - " -6.34495961e+00, 3.15307010e-04, -3.99293851e-04, -2.09813583e-03,\n", - " -3.38009083e-02, 1.38209222e-03, 2.12786035e+00, 4.23357642e-01,\n", - " -2.45275590e+00, 1.08526070e-02, -5.28979551e-03, 2.67079832e-02,\n", - " -2.41303026e+00, -1.68846422e-02, -9.58980896e-03, -1.85278256e-03,\n", - " -1.29054948e-01]),\n", - " array([ 2.79519473e-04, 6.43152517e-01, 1.04066307e+00, 2.06401329e-02,\n", - " -1.55683201e-04, -1.81668298e-05, -9.99786957e-01, 1.42720977e-02,\n", - " -6.34738834e+00, 2.98260412e-04, -4.09018514e-04, -2.09996518e-03,\n", - " -3.39297312e-02, 1.36908862e-03, 2.12718689e+00, 4.14050329e-01,\n", - " -2.46829467e+00, 1.09472133e-02, -5.52783592e-03, 2.65322259e-02,\n", - " -2.42873298e+00, -1.70465980e-02, -9.72466311e-03, -1.82935159e-03,\n", - " -1.28822927e-01]),\n", - " array([ 2.80917063e-04, 6.45294298e-01, 1.04097562e+00, 2.18789736e-02,\n", - " -1.61111816e-04, -1.53703750e-05, -9.99760614e-01, 1.42984648e-02,\n", - " -6.34982713e+00, 2.81105091e-04, -4.18876192e-04, -2.10176723e-03,\n", - " -3.40583729e-02, 1.35576702e-03, 2.12655969e+00, 4.03311251e-01,\n", - " -2.47824057e+00, 1.10235737e-02, -5.75240108e-03, 2.63671777e-02,\n", - " -2.43879189e+00, -1.71553205e-02, -9.85767756e-03, -1.80204916e-03,\n", - " -1.28641650e-01]),\n", - " array([ 2.82312275e-04, 6.47435725e-01, 1.04127068e+00, 2.31198478e-02,\n", - " -1.66566550e-04, -1.24691638e-05, -9.99732687e-01, 1.43246792e-02,\n", - " -6.35227012e+00, 2.63896933e-04, -4.28864834e-04, -2.10353801e-03,\n", - " -3.41868860e-02, 1.34218239e-03, 2.12598518e+00, 3.91099582e-01,\n", - " -2.48237588e+00, 1.10809531e-02, -5.96132738e-03, 2.62144030e-02,\n", - " -2.44298732e+00, -1.72081585e-02, -9.98864229e-03, -1.77077810e-03,\n", - " -1.28513116e-01]),\n", - " array([ 2.83704509e-04, 6.49576711e-01, 1.04154674e+00, 2.43597450e-02,\n", - " -1.72037669e-04, -9.47181262e-06, -9.99703243e-01, 1.43507547e-02,\n", - " -6.35471123e+00, 2.46694393e-04, -4.38982180e-04, -2.10527346e-03,\n", - " -3.43153252e-02, 1.32839444e-03, 2.12546974e+00, 3.77376826e-01,\n", - " -2.48049238e+00, 1.11186423e-02, -6.15243515e-03, 2.60754597e-02,\n", - " -2.44110914e+00, -1.72025393e-02, -1.01173461e-02, -1.73544762e-03,\n", - " -1.28439242e-01]),\n", - " array([ 2.85093122e-04, 6.51717162e-01, 1.04180228e+00, 2.55955559e-02,\n", - " -1.77515135e-04, -6.38801032e-06, -9.99672364e-01, 1.43767066e-02,\n", - " -6.35714419e+00, 2.29558413e-04, -4.49225757e-04, -2.10696943e-03,\n", - " -3.44437471e-02, 1.31446750e-03, 2.12501968e+00, 3.62107019e-01,\n", - " -2.47239226e+00, 1.11359602e-02, -6.32354371e-03, 2.59518886e-02,\n", - " -2.43295772e+00, -1.71359800e-02, -1.02435775e-02, -1.69597390e-03,\n", - " -1.28421850e-01]),\n", - " array([ 2.86477426e-04, 6.53856976e-01, 1.04203572e+00, 2.68240788e-02,\n", - " -1.82988620e-04, -3.22851103e-06, -9.99640153e-01, 1.44025518e-02,\n", - " -6.35956253e+00, 2.12552314e-04, -4.59592882e-04, -2.10862171e-03,\n", - " -3.45722097e-02, 1.30047017e-03, 2.12464116e+00, 3.45256925e-01,\n", - " -2.45788908e+00, 1.11322558e-02, -6.47248737e-03, 2.58452022e-02,\n", - " -2.41834495e+00, -1.70060991e-02, -1.03671248e-02, -1.65228077e-03,\n", - " -1.28462659e-01]),\n", - " array([ 2.87856695e-04, 6.55996041e-01, 1.04224552e+00, 2.80420251e-02,\n", - " -1.88447524e-04, -5.11826141e-09, -9.99606727e-01, 1.44283087e-02,\n", - " -6.36195963e+00, 1.95741686e-04, -4.70080659e-04, -2.11022601e-03,\n", - " -3.47007730e-02, 1.28647512e-03, 2.12434006e+00, 3.26796232e-01,\n", - " -2.43680876e+00, 1.11069102e-02, -6.59713194e-03, 2.57568741e-02,\n", - " -2.39709514e+00, -1.68106281e-02, -1.04877771e-02, -1.60430035e-03,\n", - " -1.28563278e-01]),\n", - " array([ 2.89230160e-04, 6.58134240e-01, 1.04243007e+00, 2.92460266e-02,\n", - " -1.93880998e-04, 3.26933932e-06, -9.99572225e-01, 1.44539970e-02,\n", - " -6.36432867e+00, 1.79194264e-04, -4.80685984e-04, -2.11177799e-03,\n", - " -3.48294982e-02, 1.27255863e-03, 2.12412192e+00, 3.06697742e-01,\n", - " -2.40899044e+00, 1.10593381e-02, -6.69539190e-03, 2.56883276e-02,\n", - " -2.36904597e+00, -1.65474220e-02, -1.06053246e-02, -1.55197371e-03,\n", - " -1.28725195e-01]),\n", - " array([ 2.90597013e-04, 6.60271446e-01, 1.04258780e+00, 3.04326423e-02,\n", - " -1.99277958e-04, 6.58104074e-06, -9.99536800e-01, 1.44796379e-02,\n", - " -6.36666272e+00, 1.62979793e-04, -4.91405543e-04, -2.11327324e-03,\n", - " -3.49584480e-02, 1.25880029e-03, 2.12399187e+00, 2.84937558e-01,\n", - " -2.37428746e+00, 1.09889904e-02, -6.76524793e-03, 2.56409247e-02,\n", - " -2.33404942e+00, -1.62144710e-02, -1.07195595e-02, -1.49525153e-03,\n", - " -1.28949770e-01]),\n", - " array([ 2.91956408e-04, 6.62407527e-01, 1.04271711e+00, 3.15983658e-02,\n", - " -2.04627108e-04, 9.91521443e-06, -9.99500626e-01, 1.45052539e-02,\n", - " -6.36895470e+00, 1.47169883e-04, -5.02235820e-04, -2.11470733e-03,\n", - " -3.50876862e-02, 1.24528249e-03, 2.12395449e+00, 2.61495261e-01,\n", - " -2.33256816e+00, 1.08953552e-02, -6.80476478e-03, 2.56159552e-02,\n", - " -2.29197266e+00, -1.58099107e-02, -1.08302764e-02, -1.43409472e-03,\n", - " -1.29238229e-01]),\n", - " array([ 2.93307467e-04, 6.64542342e-01, 1.04281639e+00, 3.27396338e-02,\n", - " -2.09916958e-04, 1.32561888e-05, -9.99463892e-01, 1.45308685e-02,\n", - " -6.37119740e+00, 1.31837850e-04, -5.13173093e-04, -2.11607581e-03,\n", - " -3.52172779e-02, 1.23208993e-03, 2.12401375e+00, 2.36354079e-01,\n", - " -2.28371682e+00, 1.07779599e-02, -6.81210929e-03, 2.56146257e-02,\n", - " -2.24269889e+00, -1.53320323e-02, -1.09372728e-02, -1.36847506e-03,\n", - " -1.29591651e-01]),\n", - " array([ 2.94649277e-04, 6.66675748e-01, 1.04288405e+00, 3.38528340e-02,\n", - " -2.15135848e-04, 1.65874515e-05, -9.99426805e-01, 1.45565065e-02,\n", - " -6.37338352e+00, 1.17058558e-04, -5.24213443e-04, -2.11737418e-03,\n", - " -3.53472888e-02, 1.21930911e-03, 2.12417289e+00, 2.09501059e-01,\n", - " -2.22763440e+00, 1.06363728e-02, -6.78556836e-03, 2.56380499e-02,\n", - " -2.18612817e+00, -1.47792927e-02, -1.10403501e-02, -1.29837581e-03,\n", - " -1.30010967e-01]),\n", - " array([ 2.95980898e-04, 6.68807594e-01, 1.04291850e+00, 3.49343140e-02,\n", - " -2.20271967e-04, 1.98917180e-05, -9.99389586e-01, 1.45821938e-02,\n", - " -6.37550570e+00, 1.02908233e-04, -5.35352756e-04, -2.11859798e-03,\n", - " -3.54777858e-02, 1.20702773e-03, 2.12443433e+00, 1.80927211e-01,\n", - " -2.16423938e+00, 1.04702050e-02, -6.72356692e-03, 2.56872378e-02,\n", - " -2.12217824e+00, -1.41503241e-02, -1.11393138e-02, -1.22379234e-03,\n", - " -1.30496948e-01]),\n", - " array([ 2.97301365e-04, 6.70937726e-01, 1.04291816e+00, 3.59803906e-02,\n", - " -2.25313371e-04, 2.31510079e-05, -9.99352470e-01, 1.46079569e-02,\n", - " -6.37755649e+00, 8.94642909e-05, -5.46586731e-04, -2.11974271e-03,\n", - " -3.56088360e-02, 1.19533406e-03, 2.12479955e+00, 1.50627665e-01,\n", - " -2.09346850e+00, 1.02791117e-02, -6.62468548e-03, 2.57630865e-02,\n", - " -2.05078523e+00, -1.34439425e-02, -1.12339743e-02, -1.14473265e-03,\n", - " -1.31050198e-01]),\n", - " array([ 2.98609691e-04, 6.73065985e-01, 1.04288148e+00, 3.69873590e-02,\n", - " -2.30248008e-04, 2.63467310e-05, -9.99315707e-01, 1.46338232e-02,\n", - " -6.37952839e+00, 7.68051342e-05, -5.57910879e-04, -2.12080393e-03,\n", - " -3.57405071e-02, 1.18431633e-03, 2.12526902e+00, 1.18601802e-01,\n", - " -2.01527739e+00, 1.00627938e-02, -6.48767729e-03, 2.58663711e-02,\n", - " -1.97190440e+00, -1.26591567e-02, -1.13241477e-02, -1.06121796e-03,\n", - " -1.31671151e-01]),\n", - " array([ 2.99904872e-04, 6.75192212e-01, 1.04280689e+00, 3.79515027e-02,\n", - " -2.35063737e-04, 2.94597796e-05, -9.99279554e-01, 1.46598210e-02,\n", - " -6.38141390e+00, 6.50099584e-05, -5.69320534e-04, -2.12177721e-03,\n", - " -3.58728672e-02, 1.17406197e-03, 2.12584208e+00, 8.48533808e-02,\n", - " -1.92964130e+00, 9.82099981e-03, -6.31148490e-03, 2.59977364e-02,\n", - " -1.88551076e+00, -1.17951758e-02, -1.14096559e-02, -9.73283200e-04,\n", - " -1.32360064e-01]),\n", - " array([ 3.01185895e-04, 6.77316245e-01, 1.04269290e+00, 3.88691034e-02,\n", - " -2.39748349e-04, 3.24706306e-05, -9.99244282e-01, 1.46859787e-02,\n", - " -6.38320550e+00, 5.41585413e-05, -5.80810862e-04, -2.12265819e-03,\n", - " -3.60059842e-02, 1.16465697e-03, 2.12651684e+00, 4.93906547e-02,\n", - " -1.83655567e+00, 9.55352686e-03, -6.09525597e-03, 2.61576892e-02,\n", - " -1.79159968e+00, -1.08514171e-02, -1.14903274e-02, -8.80977473e-04,\n", - " -1.33117011e-01]),\n", - " array([ 3.02451738e-04, 6.79437923e-01, 1.04253800e+00, 3.97364515e-02,\n", - " -2.44289590e-04, 3.53594533e-05, -9.99210165e-01, 1.47123253e-02,\n", - " -6.38489569e+00, 4.43310287e-05, -5.92376860e-04, -2.12344255e-03,\n", - " -3.61399261e-02, 1.15618506e-03, 2.12729014e+00, 1.22264748e-02,\n", - " -1.73603663e+00, 9.26022249e-03, -5.83835809e-03, 2.63465911e-02,\n", - " -1.69018746e+00, -9.82751265e-03, -1.15659981e-02, -7.84364516e-04,\n", - " -1.33941875e-01]),\n", - " array([ 3.03701378e-04, 6.81557085e-01, 1.04234074e+00, 4.05498566e-02,\n", - " -2.48675177e-04, 3.81062246e-05, -9.99177485e-01, 1.47388899e-02,\n", - " -6.38647700e+00, 3.56077133e-05, -6.04013371e-04, -2.12412607e-03,\n", - " -3.62747604e-02, 1.14872701e-03, 2.12815740e+00, -2.66216170e-02,\n", - " -1.62812155e+00, 8.94098597e-03, -5.54039267e-03, 2.65646526e-02,\n", - " -1.58131179e+00, -8.72331541e-03, -1.16365114e-02, -6.83523066e-04,\n", - " -1.34834350e-01]),\n", - " array([ 3.04933798e-04, 6.83673574e-01, 1.04209970e+00, 4.13056579e-02,\n", - " -2.52892826e-04, 4.06908502e-05, -9.99146524e-01, 1.47657018e-02,\n", - " -6.38794203e+00, 2.80688081e-05, -6.15715090e-04, -2.12470462e-03,\n", - " -3.64105544e-02, 1.14235981e-03, 2.12911259e+00, -6.71313078e-02,\n", - " -1.51286940e+00, 8.59576967e-03, -5.20120751e-03, 2.68119278e-02,\n", - " -1.46503217e+00, -7.53890521e-03, -1.17017190e-02, -5.78547204e-04,\n", - " -1.35793932e-01]),\n", - " array([ 3.06147991e-04, 6.85787235e-01, 1.04181350e+00, 4.20002356e-02,\n", - " -2.56930267e-04, 4.30932916e-05, -9.99117567e-01, 1.47927902e-02,\n", - " -6.38928346e+00, 2.17942144e-05, -6.27476572e-04, -2.12517417e-03,\n", - " -3.65473743e-02, 1.13715588e-03, 2.13014814e+00, -1.09275446e-01,\n", - " -1.39036112e+00, 8.22458041e-03, -4.82090804e-03, 2.70883097e-02,\n", - " -1.34143028e+00, -6.27459361e-03, -1.17614812e-02, -4.69546632e-04,\n", - " -1.36819918e-01]),\n", - " array([ 3.07342968e-04, 6.87897919e-01, 1.04148082e+00, 4.26300213e-02,\n", - " -2.60775269e-04, 4.52936972e-05, -9.99090892e-01, 1.48201837e-02,\n", - " -6.39049407e+00, 1.68632860e-05, -6.39292239e-04, -2.12553082e-03,\n", - " -3.66852857e-02, 1.13318228e-03, 2.13125492e+00, -1.53021984e-01,\n", - " -1.26069995e+00, 7.82748070e-03, -4.39986714e-03, 2.73935272e-02,\n", - " -1.21061029e+00, -4.93092844e-03, -1.18156674e-02, -3.56646898e-04,\n", - " -1.37911401e-01]),\n", - " array([ 3.08517764e-04, 6.90005482e-01, 1.04110038e+00, 4.31915098e-02,\n", - " -2.64415658e-04, 4.72725379e-05, -9.99066775e-01, 1.48479108e-02,\n", - " -6.39156677e+00, 1.33545884e-05, -6.51156396e-04, -2.12577081e-03,\n", - " -3.68243530e-02, 1.13049992e-03, 2.13242213e+00, -1.98333939e-01,\n", - " -1.12401158e+00, 7.40458997e-03, -3.93873324e-03, 2.77271422e-02,\n", - " -1.07269903e+00, -3.50869759e-03, -1.18641566e-02, -2.39989558e-04,\n", - " -1.39067272e-01]),\n", - " array([ 3.09671442e-04, 6.92109790e-01, 1.04067095e+00, 4.36812695e-02,\n", - " -2.67839342e-04, 4.90107457e-05, -9.99045481e-01, 1.48759994e-02,\n", - " -6.39249462e+00, 1.13456562e-05, -6.63063233e-04, -2.12589054e-03,\n", - " -3.69646392e-02, 1.12916274e-03, 2.13363731e+00, -2.45169361e-01,\n", - " -9.80444335e-01, 6.95608564e-03, -3.43843677e-03, 2.80885483e-02,\n", - " -9.27846172e-01, -2.00893225e-03, -1.19068378e-02, -1.19732265e-04,\n", - " -1.40286216e-01]),\n", - " array([ 3.10803107e-04, 6.94210715e-01, 1.04019139e+00, 4.40959544e-02,\n", - " -2.71034328e-04, 5.04898541e-05, -9.99027262e-01, 1.49044763e-02,\n", - " -6.39327084e+00, 1.09127466e-05, -6.75006843e-04, -2.12588659e-03,\n", - " -3.71062059e-02, 1.12921692e-03, 2.13488633e+00, -2.93481315e-01,\n", - " -8.30169256e-01, 6.48220421e-03, -2.90019472e-03, 2.84769703e-02,\n", - " -7.76224306e-01, -4.32909564e-04, -1.19436101e-02, 3.95119752e-06,\n", - " -1.41566710e-01]),\n", - " array([ 3.11911904e-04, 6.96308143e-01, 1.03966059e+00, 4.44323146e-02,\n", - " -2.73988750e-04, 5.16921406e-05, -9.99012358e-01, 1.49333678e-02,\n", - " -6.39388887e+00, 1.21305920e-05, -6.86981227e-04, -2.12575572e-03,\n", - " -3.72491129e-02, 1.13070014e-03, 2.13615332e+00, -3.43217883e-01,\n", - " -6.73380065e-01, 5.98324218e-03, -2.32551328e-03, 2.88914648e-02,\n", - " -6.18028915e-01, 1.21784541e-03, -1.19743831e-02, 1.30870970e-04,\n", - " -1.42907026e-01]),\n", - " array([ 3.12997030e-04, 6.98401968e-01, 1.03907753e+00, 4.46872078e-02,\n", - " -2.76690886e-04, 5.26007687e-05, -9.99000988e-01, 1.49626987e-02,\n", - " -6.39434235e+00, 1.50721503e-05, -6.98980304e-04, -2.12549489e-03,\n", - " -3.73934181e-02, 1.13364083e-03, 2.13742076e+00, -3.94322168e-01,\n", - " -5.10293106e-01, 5.45955686e-03, -1.71618837e-03, 2.93309216e-02,\n", - " -4.53478306e-01, 2.94155829e-03, -1.19990774e-02, 2.60821233e-04,\n", - " -1.44305229e-01]),\n", - " array([ 3.14057741e-04, 7.00492101e-01, 1.03844128e+00, 4.48576103e-02,\n", - " -2.79129180e-04, 5.31999293e-05, -9.98993350e-01, 1.49924928e-02,\n", - " -6.39462516e+00, 1.98083549e-05, -7.10997929e-04, -2.12510131e-03,\n", - " -3.75391773e-02, 1.13805742e-03, 2.13866944e+00, -4.46732322e-01,\n", - " -3.41147178e-01, 4.91156715e-03, -1.07430412e-03, 2.97940668e-02,\n", - " -2.82813448e-01, 4.73620459e-03, -1.20176246e-02, 3.93580410e-04,\n", - " -1.45759181e-01]),\n", - " array([ 3.15093357e-04, 7.02578464e-01, 1.03775095e+00, 4.49406281e-02,\n", - " -2.81292272e-04, 5.34749806e-05, -9.98989619e-01, 1.50227723e-02,\n", - " -6.39473146e+00, 2.64078645e-05, -7.23027896e-04, -2.12457240e-03,\n", - " -3.76864439e-02, 1.14395770e-03, 2.13987851e+00, -5.00381584e-01,\n", - " -1.66203299e-01, 4.33975411e-03, -4.02229073e-04, 3.02794659e-02,\n", - " -1.06297730e-01, 6.59950959e-03, -1.20299674e-02, 5.28911445e-04,\n", - " -1.47266541e-01]),\n", - " array([ 3.16103267e-04, 7.04660995e-01, 1.03700576e+00, 4.49335074e-02,\n", - " -2.83169012e-04, 5.34125848e-05, -9.98989938e-01, 1.50535578e-02,\n", - " -6.39465568e+00, 3.49368132e-05, -7.35063956e-04, -2.12390584e-03,\n", - " -3.78352686e-02, 1.15133818e-03, 2.14102556e+00, -5.55198326e-01,\n", - " 1.42556110e-02, 3.74466141e-03, 2.97389462e-04, 3.07855291e-02,\n", - " 7.57833588e-02, 8.52894872e-03, -1.20360599e-02, 6.66562158e-04,\n", - " -1.48824769e-01]),\n", - " array([ 3.17086939e-04, 7.06739648e-01, 1.03620502e+00, 4.48336453e-02,\n", - " -2.84748493e-04, 5.30008407e-05, -9.98994425e-01, 1.50848683e-02,\n", - " -6.39439256e+00, 4.54585620e-05, -7.47099824e-04, -2.12309957e-03,\n", - " -3.79856997e-02, 1.16018351e-03, 2.14208667e+00, -6.11106125e-01,\n", - " 1.99925131e-01, 3.12689576e-03, 1.02163469e-03, 3.13105170e-02,\n", - " 2.63122631e-01, 1.05217488e-02, -1.20358678e-02, 8.06265692e-04,\n", - " -1.50431128e-01]),\n", - " array([ 3.18043921e-04, 7.08814397e-01, 1.03534812e+00, 4.46386006e-02,\n", - " -2.86020070e-04, 5.22294112e-05, -9.99003159e-01, 1.51167209e-02,\n", - " -6.39393716e+00, 5.80334514e-05, -7.59129192e-04, -2.12215183e-03,\n", - " -3.81377824e-02, 1.17046595e-03, 2.14303653e+00, -6.68023836e-01,\n", - " 3.90479818e-01, 2.48712696e-03, 1.76732969e-03, 3.18525473e-02,\n", - " 4.55391683e-01, 1.25748894e-02, -1.20293680e-02, 9.47741031e-04,\n", - " -1.52082691e-01]),\n", - " array([ 3.18973850e-04, 7.10885231e-01, 1.03443455e+00, 4.43461032e-02,\n", - " -2.86973391e-04, 5.10896444e-05, -9.99016185e-01, 1.51491305e-02,\n", - " -6.39328492e+00, 7.27185574e-05, -7.71145741e-04, -2.12106114e-03,\n", - " -3.82915588e-02, 1.18214494e-03, 2.14384850e+00, -7.25865686e-01,\n", - " 5.85573760e-01, 1.82608811e-03, 2.53105204e-03, 3.24096034e-02,\n", - " 6.52241463e-01, 1.46851060e-02, -1.20165490e-02, 1.09069361e-03,\n", - " -1.53776343e-01]),\n", - " array([ 3.19876458e-04, 7.12952158e-01, 1.03346389e+00, 4.39540648e-02,\n", - " -2.87598419e-04, 4.95746873e-05, -9.99033510e-01, 1.51821100e-02,\n", - " -6.39243162e+00, 8.95674495e-05, -7.83143151e-04, -2.11982632e-03,\n", - " -3.84470676e-02, 1.19516672e-03, 2.14449478e+00, -7.84541384e-01,\n", - " 7.84841224e-01, 1.14457544e-03, 3.30914807e-03, 3.29795430e-02,\n", - " 8.53302911e-01, 1.68488921e-02, -1.19974107e-02, 1.23481601e-03,\n", - " -1.55508790e-01]),\n", - " array([ 3.20751569e-04, 7.15015205e-01, 1.03243584e+00, 4.34605876e-02,\n", - " -2.87885463e-04, 4.76795906e-05, -9.99055100e-01, 1.52156701e-02,\n", - " -6.39137343e+00, 1.08629953e-04, -7.95115116e-04, -2.11844654e-03,\n", - " -3.86043441e-02, 1.20946405e-03, 2.14494654e+00, -8.43956239e-01,\n", - " 9.87897367e-01, 4.43448014e-04, 4.09775092e-03, 3.35601079e-02,\n", - " 1.05818769e+00, 1.90625034e-02, -1.19719643e-02, 1.37978872e-03,\n", - " -1.57276561e-01]),\n", - " array([ 3.21599112e-04, 7.17074421e-01, 1.03135019e+00, 4.28639739e-02,\n", - " -2.87825205e-04, 4.54014042e-05, -9.99080875e-01, 1.52498190e-02,\n", - " -6.39010694e+00, 1.29951915e-04, -8.07055348e-04, -2.11692125e-03,\n", - " -3.87634202e-02, 1.22495600e-03, 2.14517408e+00, -9.04011295e-01,\n", - " 1.19433904e+00, -2.76372593e-04, 4.89280078e-03, 3.41489350e-02,\n", - " 1.26648897e+00, 2.13219626e-02, -1.19402319e-02, 1.52528098e-03,\n", - " -1.59076021e-01]),\n", - " array([ 3.22419118e-04, 7.19129870e-01, 1.03020684e+00, 4.21627349e-02,\n", - " -2.87408732e-04, 4.27392613e-05, -9.99110714e-01, 1.52845626e-02,\n", - " -6.38862916e+00, 1.53574979e-04, -8.18957594e-04, -2.11525030e-03,\n", - " -3.89243235e-02, 1.24154790e-03, 2.14514700e+00, -9.64603486e-01,\n", - " 1.40374564e+00, -1.01390286e-03, 5.69006726e-03, 3.47435689e-02,\n", - " 1.47778236e+00, 2.36230637e-02, -1.19022468e-02, 1.67095176e-03,\n", - " -1.60903372e-01]),\n", - " array([ 3.23211723e-04, 7.21181640e-01, 1.02900581e+00, 4.13555987e-02,\n", - " -2.86627565e-04, 3.96944506e-05, -9.99144449e-01, 1.53199041e-02,\n", - " -6.38693753e+00, 1.79536358e-04, -8.30815647e-04, -2.11343385e-03,\n", - " -3.90870782e-02, 1.25913131e-03, 2.14483440e+00, -1.02562580e+00,\n", - " 1.61568010e+00, -1.76809796e-03, 6.48517407e-03, 3.53414744e-02,\n", - " 1.69162679e+00, 2.59613789e-02, -1.18580526e-02, 1.81645071e-03,\n", - " -1.62754670e-01]),\n", - " array([ 3.23977172e-04, 7.23229835e-01, 1.02774724e+00, 4.04415182e-02,\n", - " -2.85473693e-04, 3.62704756e-05, -9.99181866e-01, 1.53558441e-02,\n", - " -6.38502997e+00, 2.07868623e-04, -8.42623350e-04, -2.11147243e-03,\n", - " -3.92517040e-02, 1.27758420e-03, 2.14420508e+00, -1.08696744e+00,\n", - " 1.82968989e+00, -2.53785258e-03, 7.27362576e-03, 3.59400504e-02,\n", - " 1.90756562e+00, 2.83322647e-02, -1.18077034e-02, 1.96141927e-03,\n", - " -1.64625824e-01]),\n", - " array([ 3.24715816e-04, 7.25274579e-01, 1.02643136e+00, 3.94196788e-02,\n", - " -2.83939604e-04, 3.24730998e-05, -9.99222702e-01, 1.53923808e-02,\n", - " -6.38290484e+00, 2.38599493e-04, -8.54374613e-04, -2.10936694e-03,\n", - " -3.94182166e-02, 1.29677121e-03, 2.14322778e+00, -1.14851407e+00,\n", - " 2.04530807e+00, -3.32200181e-03, 8.05083651e-03, 3.65366447e-02,\n", - " 2.12512768e+00, 3.07308699e-02, -1.17512631e-02, 2.10549184e-03,\n", - " -1.66512616e-01]),\n", - " array([ 3.25428117e-04, 7.27316014e-01, 1.02505855e+00, 3.82895045e-02,\n", - " -2.82018321e-04, 2.83103766e-05, -9.99266648e-01, 1.54295093e-02,\n", - " -6.38056101e+00, 2.71751636e-04, -8.66063419e-04, -2.10711864e-03,\n", - " -3.95866273e-02, 1.31654403e-03, 2.14187137e+00, -1.21014797e+00,\n", - " 2.26205454e+00, -4.11932220e-03, 8.81216082e-03, 3.71285695e-02,\n", - " 2.34382849e+00, 3.31521436e-02, -1.16888052e-02, 2.24829696e-03,\n", - " -1.68410705e-01]),\n", - " array([ 3.26114640e-04, 7.29354299e-01, 1.02362929e+00, 3.70506647e-02,\n", - " -2.79703437e-04, 2.37926638e-05, -9.99313349e-01, 1.54672225e-02,\n", - " -6.37799784e+00, 3.07342482e-04, -8.77683831e-04, -2.10472918e-03,\n", - " -3.97569430e-02, 1.33674194e-03, 2.14010512e+00, -1.27174829e+00,\n", - " 2.47943719e+00, -4.92853283e-03, 9.55292579e-03, 3.77131177e-02,\n", - " 2.56317149e+00, 3.55908452e-02, -1.16204122e-02, 2.38945863e-03,\n", - " -1.70315639e-01]),\n", - " array([ 3.26776059e-04, 7.31389609e-01, 1.02214419e+00, 3.57030794e-02,\n", - " -2.76989152e-04, 1.89326209e-05, -9.99362403e-01, 1.55055100e-02,\n", - " -6.37521519e+00, 3.45384035e-04, -8.89230006e-04, -2.10220059e-03,\n", - " -3.99291658e-02, 1.35719249e-03, 2.13789896e+00, -1.33319129e+00,\n", - " 2.69695325e+00, -5.74829655e-03, 1.02684651e-02, 3.82875798e-02,\n", - " 2.78264933e+00, 3.80415539e-02, -1.15461750e-02, 2.52859762e-03,\n", - " -1.72222869e-01]),\n", - " array([ 3.27413147e-04, 7.33422133e-01, 1.02060398e+00, 3.42469242e-02,\n", - " -2.73870308e-04, 1.37451901e-05, -9.99413364e-01, 1.55443593e-02,\n", - " -6.37221345e+00, 3.85882716e-04, -9.00696198e-04, -2.09953525e-03,\n", - " -4.01032936e-02, 1.37771230e-03, 2.13522369e+00, -1.39435061e+00,\n", - " 2.91409062e+00, -6.57722124e-03, 1.09541540e-02, 3.88492612e-02,\n", - " 3.00174524e+00, 4.04986807e-02, -1.14661924e-02, 2.66533288e-03,\n", - " -1.74127761e-01]),\n", - " array([ 3.28026775e-04, 7.35452073e-01, 1.01900953e+00, 3.26826349e-02,\n", - " -2.70342430e-04, 8.24755781e-06, -9.99465743e-01, 1.55837548e-02,\n", - " -6.36899351e+00, 4.28839196e-04, -9.12076769e-04, -2.09673597e-03,\n", - " -4.02793192e-02, 1.39810806e-03, 2.13205128e+00, -1.45509752e+00,\n", - " 3.13032925e+00, -7.41386116e-03, 1.16054458e-02, 3.93955005e-02,\n", - " 3.21993447e+00, 4.29564800e-02, -1.13805708e-02, 2.79928295e-03,\n", - " -1.76025605e-01]),\n", - " array([ 3.28617909e-04, 7.37479644e-01, 1.01736181e+00, 3.10109106e-02,\n", - " -2.66401762e-04, 2.45909978e-06, -9.99519011e-01, 1.56236785e-02,\n", - " -6.36555683e+00, 4.74248260e-04, -9.23366192e-04, -2.09380590e-03,\n", - " -4.04572308e-02, 1.41817761e-03, 2.12835511e+00, -1.51530124e+00,\n", - " 3.34514265e+00, -8.25671838e-03, 1.22179086e-02, 3.99236875e-02,\n", - " 3.43668575e+00, 4.54090635e-02, -1.12894230e-02, 2.93006743e-03,\n", - " -1.77911633e-01]),\n", - " array([ 3.29187601e-04, 7.39505069e-01, 1.01566193e+00, 2.92327168e-02,\n", - " -2.62045308e-04, -3.59869386e-06, -9.99572598e-01, 1.56641098e-02,\n", - " -6.36190536e+00, 5.22098673e-04, -9.34559060e-04, -2.09074860e-03,\n", - " -4.06370119e-02, 1.43771121e-03, 2.12411025e+00, -1.57482922e+00,\n", - " 3.55799940e+00, -9.10424417e-03, 1.27872628e-02, 4.04312818e-02,\n", - " 3.65146281e+00, 4.78504136e-02, -1.11928678e-02, 3.05730852e-03,\n", - " -1.79781031e-01]),\n", - " array([ 3.29736986e-04, 7.41528576e-01, 1.01391113e+00, 2.73492872e-02,\n", - " -2.57270868e-04, -9.90231142e-06, -9.99625905e-01, 1.57050256e-02,\n", - " -6.35804164e+00, 5.72373073e-04, -9.45650089e-04, -2.08756796e-03,\n", - " -4.08186408e-02, 1.45649294e-03, 2.11929368e+00, -1.63354749e+00,\n", - " 3.76836463e+00, -9.95484054e-03, 1.33094191e-02, 4.09158316e-02,\n", - " 3.86372594e+00, 5.02743996e-02, -1.10910293e-02, 3.18063246e-03,\n", - " -1.81628950e-01]),\n", - " array([ 3.30267269e-04, 7.43550402e-01, 1.01211077e+00, 2.53621255e-02,\n", - " -2.52077082e-04, -1.64263314e-05, -9.99678298e-01, 1.57464006e-02,\n", - " -6.35396870e+00, 6.25047866e-04, -9.56634125e-04, -2.08426829e-03,\n", - " -4.10020914e-02, 1.47430223e-03, 2.11388457e+00, -1.69132097e+00,\n", - " 3.97570171e+00, -1.08068618e-02, 1.37805152e-02, 4.13749922e-02,\n", - " 4.07293363e+00, 5.26747933e-02, -1.09840362e-02, 3.29967113e-03,\n", - " -1.83450527e-01]),\n", - " array([ 3.30779722e-04, 7.45570782e-01, 1.01026234e+00, 2.32730051e-02,\n", - " -2.46463462e-04, -2.31435526e-05, -9.99729116e-01, 1.57882071e-02,\n", - " -6.34969016e+00, 6.80093153e-04, -9.67506146e-04, -2.08085423e-03,\n", - " -4.11873322e-02, 1.49091549e-03, 2.10786451e+00, -1.74801386e+00,\n", - " 4.17947379e+00, -1.16586160e-02, 1.41969534e-02, 4.18065444e-02,\n", - " 4.27854416e+00, 5.50452868e-02, -1.08720209e-02, 3.41406355e-03,\n", - " -1.85240892e-01]),\n", - " array([ 3.31275673e-04, 7.47589953e-01, 1.00836745e+00, 2.10839695e-02,\n", - " -2.40430436e-04, -3.00251423e-05, -9.99777679e-01, 1.58304156e-02,\n", - " -6.34521014e+00, 7.37472663e-04, -9.78261265e-04, -2.07733077e-03,\n", - " -4.13743274e-02, 1.50610794e-03, 2.10121775e+00, -1.80348996e+00,\n", - " 4.37914548e+00, -1.25083669e-02, 1.45554362e-02, 4.22084126e-02,\n", - " 4.48001728e+00, 5.73795104e-02, -1.07551188e-02, 3.52345739e-03,\n", - " -1.86995190e-01]),\n", - " array([ 3.31756495e-04, 7.49608149e-01, 1.00642782e+00, 1.87973306e-02,\n", - " -2.33979380e-04, -3.70408017e-05, -9.99823287e-01, 1.58729942e-02,\n", - " -6.34053333e+00, 7.97143716e-04, -9.88894732e-04, -2.07370326e-03,\n", - " -4.15630360e-02, 1.51965544e-03, 2.09393141e+00, -1.85761311e+00,\n", - " 4.57418453e+00, -1.33543351e-02, 1.48530012e-02, 4.25786823e-02,\n", - " 4.67681591e+00, 5.96710522e-02, -1.06334673e-02, 3.62751052e-03,\n", - " -1.88708591e-01]),\n", - " array([ 3.32223597e-04, 7.51625594e-01, 1.00444531e+00, 1.64156667e-02,\n", - " -2.27112657e-04, -4.41589486e-05, -9.99865227e-01, 1.59159099e-02,\n", - " -6.33566492e+00, 8.59057194e-04, -9.99401937e-04, -2.06997737e-03,\n", - " -4.17534123e-02, 1.53133647e-03, 2.08599568e+00, -1.91024754e+00,\n", - " 4.76406351e+00, -1.41947006e-02, 1.50870536e-02, 4.29156166e-02,\n", - " 4.86840783e+00, 6.19134782e-02, -1.05072053e-02, 3.72589243e-03,\n", - " -1.90376308e-01]),\n", - " array([ 3.32678411e-04, 7.53642507e-01, 1.00242190e+00, 1.39418196e-02,\n", - " -2.19833649e-04, -5.13469145e-05, -9.99902783e-01, 1.59591275e-02,\n", - " -6.33061065e+00, 9.23157547e-04, -1.00977841e-03, -2.06615908e-03,\n", - " -4.19454059e-02, 1.54093415e-03, 2.07740401e+00, -1.96125830e+00,\n", - " 4.94826146e+00, -1.50276038e-02, 1.52553975e-02, 4.32176728e-02,\n", - " 5.05426735e+00, 6.41003530e-02, -1.03764725e-02, 3.81828573e-03,\n", - " -1.91993611e-01]),\n", - " array([ 3.33122382e-04, 7.55659091e-01, 1.00035968e+00, 1.13788909e-02,\n", - " -2.12146787e-04, -5.85711576e-05, -9.99935234e-01, 1.60026110e-02,\n", - " -6.32537677e+00, 9.89382809e-04, -1.02001982e-03, -2.06225469e-03,\n", - " -4.21389618e-02, 1.54823836e-03, 2.06815326e+00, -2.01051165e+00,\n", - " 5.12626564e+00, -1.58511484e-02, 1.53562639e-02, 4.34835165e-02,\n", - " 5.23387709e+00, 6.62252622e-02, -1.02414080e-02, 3.90438748e-03,\n", - " -1.93555844e-01]),\n", - " array([ 3.33556954e-04, 7.57675537e-01, 9.98260831e-01, 8.73023690e-03,\n", - " -2.04057585e-04, -6.57974873e-05, -9.99961868e-01, 1.60463231e-02,\n", - " -6.31997004e+00, 1.05766464e-03, -1.03012197e-03, -2.05827078e-03,\n", - " -4.23340202e-02, 1.55304778e-03, 2.05824385e+00, -2.05787552e+00,\n", - " 5.29757318e+00, -1.66634027e-02, 1.53883361e-02, 4.37120356e-02,\n", - " 5.40672961e+00, 6.82818341e-02, -1.01021503e-02, 3.98391056e-03,\n", - " -1.95058440e-01]),\n", - " array([ 3.33983559e-04, 7.59692013e-01, 9.96127681e-01, 5.99946335e-03,\n", - " -1.95572657e-04, -7.29913017e-05, -9.99981981e-01, 1.60902254e-02,\n", - " -6.31439772e+00, 1.12792841e-03, -1.04008080e-03, -2.05421420e-03,\n", - " -4.25305172e-02, 1.55517209e-03, 2.04767986e+00, -2.10321992e+00,\n", - " 5.46169276e+00, -1.74624028e-02, 1.53507717e-02, 4.39023523e-02,\n", - " 5.57232914e+00, 7.02637631e-02, -9.95883591e-03, 4.05658491e-03,\n", - " -1.96496933e-01]),\n", - " array([ 3.34403603e-04, 7.61708669e-01, 9.93962642e-01, 3.19041869e-03,\n", - " -1.86699747e-04, -8.01178334e-05, -9.99994890e-01, 1.61342793e-02,\n", - " -6.30866752e+00, 1.20009324e-03, -1.04989240e-03, -2.05009204e-03,\n", - " -4.27283841e-02, 1.55443396e-03, 2.03646912e+00, -2.14641739e+00,\n", - " 5.61814628e+00, -1.82461543e-02, 1.52432213e-02, 4.40538335e-02,\n", - " 5.73019324e+00, 7.21648332e-02, -9.81159923e-03, 4.12215874e-03,\n", - " -1.97866979e-01]),\n", - " array([ 3.34818455e-04, 7.63725626e-01, 9.91768233e-01, 3.07186762e-04,\n", - " -1.77447746e-04, -8.71424032e-05, -9.99999933e-01, 1.61784454e-02,\n", - " -6.30278767e+00, 1.27407218e-03, -1.05955297e-03, -2.04591164e-03,\n", - " -4.29275485e-02, 1.55067119e-03, 2.02462329e+00, -2.18734341e+00,\n", - " 5.76647046e+00, -1.90126359e-02, 1.50658425e-02, 4.41660997e-02,\n", - " 5.87985442e+00, 7.39789416e-02, -9.66057145e-03, 4.18039953e-03,\n", - " -1.99164365e-01]),\n", - " array([ 3.35229431e-04, 7.65742982e-01, 9.89547071e-01, -2.64592148e-03,\n", - " -1.67826703e-04, -9.40306801e-05, -9.99996481e-01, 1.62226844e-02,\n", - " -6.29676681e+00, 1.34977230e-03, -1.06905885e-03, -2.04168055e-03,\n", - " -4.31279335e-02, 1.54373860e-03, 2.01215783e+00, -2.22587688e+00,\n", - " 5.90621844e+00, -1.97598023e-02, 1.48193101e-02, 4.42390315e-02,\n", - " 6.02086178e+00, 7.57001226e-02, -9.50588014e-03, 4.23109515e-03,\n", - " -2.00385028e-01]),\n", - " array([ 3.35637781e-04, 7.67760799e-01, 9.87301865e-01, -5.66437707e-03,\n", - " -1.57847837e-04, -1.00748944e-04, -9.99983940e-01, 1.62669572e-02,\n", - " -6.29061402e+00, 1.42709488e-03, -1.07840650e-03, -2.03740649e-03,\n", - " -4.33294586e-02, 1.53350989e-03, 1.99909203e+00, -2.26190055e+00,\n", - " 6.03696133e+00, -2.04855876e-02, 1.45048216e-02, 4.42727743e-02,\n", - " 6.15278254e+00, 7.73225714e-02, -9.34764869e-03, 4.27405459e-03,\n", - " -2.01525066e-01]),\n", - " array([ 3.36044680e-04, 7.69779108e-01, 9.85035410e-01, -8.74344294e-03,\n", - " -1.47523538e-04, -1.07264347e-04, -9.99961759e-01, 1.63112249e-02,\n", - " -6.28433882e+00, 1.50593554e-03, -1.08759250e-03, -2.03309738e-03,\n", - " -4.35320394e-02, 1.51987942e-03, 1.98544897e+00, -2.29530142e+00,\n", - " 6.15828972e+00, -2.11879095e-02, 1.41240978e-02, 4.42677405e-02,\n", - " 6.27520358e+00, 7.88406682e-02, -9.18599578e-03, 4.30910884e-03,\n", - " -2.02580753e-01]),\n", - " array([ 3.36451210e-04, 7.71797904e-01, 9.82750585e-01, -1.18781847e-02,\n", - " -1.36867374e-04, -1.13545178e-04, -9.99929436e-01, 1.63554495e-02,\n", - " -6.27795109e+00, 1.58618454e-03, -1.09661353e-03, -2.02876127e-03,\n", - " -4.37355879e-02, 1.50276373e-03, 1.97125544e+00, -2.32597120e+00,\n", - " 6.26981512e+00, -2.18646734e-02, 1.36793781e-02, 4.42246094e-02,\n", - " 6.38773287e+00, 8.02490014e-02, -9.02103497e-03, 4.33611147e-03,\n", - " -2.03548553e-01]),\n", - " array([ 3.36858353e-04, 7.73817143e-01, 9.80450344e-01, -1.50634821e-02,\n", - " -1.25894073e-04, -1.19561118e-04, -9.99886524e-01, 1.63995938e-02,\n", - " -6.27146109e+00, 1.66772693e-03, -1.10546641e-03, -2.02440633e-03,\n", - " -4.39400130e-02, 1.48210292e-03, 1.95654183e+00, -2.35380674e+00,\n", - " 6.37117130e+00, -2.25137775e-02, 1.31734116e-02, 4.41443249e-02,\n", - " 6.49000089e+00, 8.15423902e-02, -8.85287438e-03, 4.35493914e-03,\n", - " -2.04425130e-01]),\n", - " array([ 3.37266975e-04, 7.75836738e-01, 9.78137711e-01, -1.82940412e-02,\n", - " -1.14619521e-04, -1.25283492e-04, -9.99832636e-01, 1.64436219e-02,\n", - " -6.26487942e+00, 1.75044284e-03, -1.11414803e-03, -2.02004084e-03,\n", - " -4.41452204e-02, 1.45786182e-03, 1.94134198e+00, -2.37871039e+00,\n", - " 6.46201566e+00, -2.31331185e-02, 1.26094412e-02, 4.40280897e-02,\n", - " 6.58166191e+00, 8.27159074e-02, -8.68161636e-03, 4.36549198e-03,\n", - " -2.05207364e-01]),\n", - " array([ 3.37677817e-04, 7.77856563e-01, 9.75815771e-01, -2.15644074e-02,\n", - " -1.03060735e-04, -1.30685506e-04, -9.99767447e-01, 1.64874993e-02,\n", - " -6.25821703e+00, 1.83420774e-03, -1.12265538e-03, -2.01567315e-03,\n", - " -4.43511128e-02, 1.43003096e-03, 1.92569303e+00, -2.40059042e+00,\n", - " 6.54203043e+00, -2.37205972e-02, 1.19911845e-02, 4.38773581e-02,\n", - " 6.66239529e+00, 8.37649001e-02, -8.50735737e-03, 4.36769382e-03,\n", - " -2.05892358e-01]),\n", - " array([ 3.38091483e-04, 7.79876445e-01, 9.73487669e-01, -2.48689790e-02,\n", - " -9.12358449e-05, -1.35742478e-04, -9.99690706e-01, 1.65311931e-02,\n", - " -6.25148512e+00, 1.91889275e-03, -1.13098557e-03, -2.01131165e-03,\n", - " -4.45575902e-02, 1.39862720e-03, 1.90963521e+00, -2.41936140e+00,\n", - " 6.61092383e+00, -2.42741250e-02, 1.13228078e-02, 4.36938248e-02,\n", - " 6.73190660e+00, 8.46850103e-02, -8.33018778e-03, 4.36149229e-03,\n", - " -2.06477452e-01]),\n", - " array([ 3.38508433e-04, 7.81896167e-01, 9.71156597e-01, -2.82020211e-02,\n", - " -7.91640565e-05, -1.40432051e-04, -9.99602231e-01, 1.65746725e-02,\n", - " -6.24469519e+00, 2.00436495e-03, -1.13913576e-03, -2.00696479e-03,\n", - " -4.47645504e-02, 1.36369417e-03, 1.89321157e+00, -2.43494453e+00,\n", - " 6.66843113e+00, -2.47916320e-02, 1.06088960e-02, 4.34794121e-02,\n", - " 6.78992871e+00, 8.54721938e-02, -8.15019191e-03, 4.34685879e-03,\n", - " -2.06960229e-01]),\n", - " array([ 3.38928970e-04, 7.83915463e-01, 9.68825790e-01, -3.15576804e-02,\n", - " -6.68656180e-05, -1.44734386e-04, -9.99501920e-01, 1.66179088e-02,\n", - " -6.23785897e+00, 2.09048768e-03, -1.14710321e-03, -2.00264101e-03,\n", - " -4.49718890e-02, 1.32530239e-03, 1.87646778e+00, -2.44726795e+00,\n", - " 6.71431562e+00, -2.52710737e-02, 9.85441694e-03, 4.32362539e-02,\n", - " 6.83622275e+00, 8.61227377e-02, -7.96744801e-03, 4.32378827e-03,\n", - " -2.07338529e-01]),\n", - " array([ 3.39353236e-04, 7.85934023e-01, 9.66498519e-01, -3.49300007e-02,\n", - " -5.43617742e-05, -1.48632340e-04, -9.99389749e-01, 1.66608755e-02,\n", - " -6.23098839e+00, 2.17712096e-03, -1.15488524e-03, -1.99834871e-03,\n", - " -4.51794994e-02, 1.28354914e-03, 1.85945177e+00, -2.45626711e+00,\n", - " 6.74836948e+00, -2.57104405e-02, 9.06468147e-03, 4.29666769e-02,\n", - " 6.87057903e+00, 8.66332765e-02, -7.78202843e-03, 4.29229894e-03,\n", - " -2.07610453e-01]),\n", - " array([ 3.39781205e-04, 7.87951486e-01, 9.64178081e-01, -3.83129377e-02,\n", - " -4.16747172e-05, -1.52111618e-04, -9.99265777e-01, 1.67035486e-02,\n", - " -6.22409557e+00, 2.26412177e-03, -1.16247924e-03, -1.99409628e-03,\n", - " -4.53872738e-02, 1.23855796e-03, 1.84221346e+00, -2.46188497e+00,\n", - " 6.77041456e+00, -2.61077661e-02, 8.24529906e-03, 4.26731802e-02,\n", - " 6.89281778e+00, 8.70008061e-02, -7.59399977e-03, 4.25243179e-03,\n", - " -2.07774370e-01]),\n", - " array([ 3.40212674e-04, 7.89967447e-01, 9.61867793e-01, -4.17003756e-02,\n", - " -2.88275304e-05, -1.55160900e-04, -9.99130149e-01, 1.67459071e-02,\n", - " -6.21719278e+00, 2.35134446e-03, -1.16988266e-03, -1.98989203e-03,\n", - " -4.55951027e-02, 1.19047792e-03, 1.82480439e+00, -2.46407228e+00,\n", - " 6.78030305e+00, -2.64611377e-02, 7.40212937e-03, 4.23584113e-02,\n", - " 6.90278984e+00, 8.72226970e-02, -7.40342313e-03, 4.20425001e-03,\n", - " -2.07828925e-01]),\n", - " array([ 3.40647262e-04, 7.91981450e-01, 9.59570984e-01, -4.50861429e-02,\n", - " -1.58441273e-05, -1.57771946e-04, -9.98983090e-01, 1.67879322e-02,\n", - " -6.21029241e+00, 2.43864117e-03, -1.17709302e-03, -1.98574419e-03,\n", - " -4.58028758e-02, 1.13948257e-03, 1.80727740e+00, -2.46278779e+00,\n", - " 6.77791802e+00, -2.67687057e-02, 6.54123049e-03, 4.20251415e-02,\n", - " 6.90037721e+00, 8.72967038e-02, -7.21035445e-03, 4.14783831e-03,\n", - " -2.07773045e-01]),\n", - " array([ 3.41084407e-04, 7.93992996e-01, 9.57290988e-01, -4.84640290e-02,\n", - " -2.74918452e-06, -1.59939671e-04, -9.98824916e-01, 1.68296084e-02,\n", - " -6.20340691e+00, 2.52586214e-03, -1.18410786e-03, -1.98166089e-03,\n", - " -4.60104817e-02, 1.08576860e-03, 1.78968621e+00, -2.45799843e+00,\n", - " 6.76317388e+00, -2.70286946e-02, 5.66880411e-03, 4.16762378e-02,\n", - " 6.88549353e+00, 8.72209748e-02, -7.01484487e-03, 4.08330206e-03,\n", - " -2.07605939e-01]),\n", - " array([ 3.41523364e-04, 7.96001540e-01, 9.55031135e-01, -5.18278006e-02,\n", - " 1.04319298e-05, -1.61662190e-04, -9.98656023e-01, 1.68709231e-02,\n", - " -6.19654883e+00, 2.61285620e-03, -1.19092480e-03, -1.97765012e-03,\n", - " -4.62178088e-02, 1.02955427e-03, 1.77208508e+00, -2.44967944e+00,\n", - " 6.73601671e+00, -2.72394143e-02, 4.79113847e-03, 4.13146348e-02,\n", - " 6.85808439e+00, 8.69940575e-02, -6.81694112e-03, 4.01076638e-03,\n", - " -2.07327104e-01]),\n", - " array([ 3.41963202e-04, 7.98006492e-01, 9.52794744e-01, -5.51712184e-02,\n", - " 2.36732320e-05, -1.62940832e-04, -9.98476895e-01, 1.69118664e-02,\n", - " -6.18973070e+00, 2.69947110e-03, -1.19754149e-03, -1.97371974e-03,\n", - " -4.64247451e-02, 9.71077475e-04, 1.75452837e+00, -2.43781450e+00,\n", - " 6.69642449e+00, -2.73992709e-02, 3.91454962e-03, 4.09433044e-02,\n", - " 6.81812755e+00, 8.66149038e-02, -6.61668596e-03, 3.93037515e-03,\n", - " -2.06936329e-01]),\n", - " array([ 3.42402811e-04, 8.00007221e-01, 9.50585114e-01, -5.84880536e-02,\n", - " 3.69482029e-05, -1.63780129e-04, -9.98288094e-01, 1.69524316e-02,\n", - " -6.18296507e+00, 2.78555398e-03, -1.20395561e-03, -1.96987745e-03,\n", - " -4.66311788e-02, 9.10593744e-04, 1.73707019e+00, -2.42239577e+00,\n", - " 6.64440721e+00, -2.75067787e-02, 3.04532165e-03, 4.05652248e-02,\n", - " 6.76563308e+00, 8.60828716e-02, -6.41411871e-03, 3.84228985e-03,\n", - " -2.06433691e-01]),\n", - " array([ 3.42840898e-04, 8.02003059e-01, 9.48405519e-01, -6.17721046e-02,\n", - " 5.02298711e-05, -1.64187769e-04, -9.98090265e-01, 1.69926149e-02,\n", - " -6.17626443e+00, 2.87095170e-03, -1.21016488e-03, -1.96613077e-03,\n", - " -4.68369984e-02, 8.48373874e-04, 1.71976394e+00, -2.40342398e+00,\n", - " 6.58000684e+00, -2.75605716e-02, 2.18964682e-03, 4.01833496e-02,\n", - " 6.70064333e+00, 8.53977255e-02, -6.20927566e-03, 3.74668842e-03,\n", - " -2.05819557e-01]),\n", - " array([ 3.43275997e-04, 8.03993299e-01, 9.46259198e-01, -6.50172133e-02,\n", - " 6.34908993e-05, -1.64174520e-04, -9.97884127e-01, 1.70324155e-02,\n", - " -6.16964119e+00, 2.95551134e-03, -1.21616707e-03, -1.96248700e-03,\n", - " -4.70420930e-02, 7.84701472e-04, 1.70266196e+00, -2.38090837e+00,\n", - " 6.50329725e+00, -2.75594147e-02, 1.35356612e-03, 3.98005761e-02,\n", - " 6.62323284e+00, 8.45596348e-02, -6.00219063e-03, 3.64376404e-03,\n", - " -2.05094587e-01]),\n", - " array([ 3.43706474e-04, 8.05977201e-01, 9.44149346e-01, -6.82172817e-02,\n", - " 7.67036724e-05, -1.63754126e-04, -9.97670472e-01, 1.70718352e-02,\n", - " -6.16310768e+00, 3.03908051e-03, -1.22195997e-03, -1.95895328e-03,\n", - " -4.72463527e-02, 7.19870315e-04, 1.68581510e+00, -2.35486670e+00,\n", - " 6.41438396e+00, -2.75022156e-02, 5.42911256e-04, 3.94197152e-02,\n", - " 6.53350808e+00, 8.35691695e-02, -5.79289544e-03, 3.53372381e-03,\n", - " -2.04259724e-01]),\n", - " array([ 3.44130529e-04, 8.07953995e-01, 9.42079112e-01, -7.13662871e-02,\n", - " 8.98403874e-05, -1.62943174e-04, -9.97450158e-01, 1.71108787e-02,\n", - " -6.15667608e+00, 3.12150780e-03, -1.22754139e-03, -1.95553649e-03,\n", - " -4.74496689e-02, 6.54181599e-04, 1.66927237e+00, -2.32532515e+00,\n", - " 6.31340383e+00, -2.73880357e-02, -2.36751312e-04, 3.90434613e-02,\n", - " 6.43160712e+00, 8.24272955e-02, -5.58142043e-03, 3.41678748e-03,\n", - " -2.03316198e-01]),\n", - " array([ 3.44546213e-04, 8.09922883e-01, 9.40051589e-01, -7.44582985e-02,\n", - " 1.02873144e-04, -1.61760928e-04, -9.97224110e-01, 1.71495531e-02,\n", - " -6.15035838e+00, 3.20264317e-03, -1.23290918e-03, -1.95224330e-03,\n", - " -4.76519344e-02, 5.87941104e-04, 1.65308054e+00, -2.29231824e+00,\n", - " 6.20052457e+00, -2.72161006e-02, -9.80173409e-04, 3.86743640e-02,\n", - " 6.31769920e+00, 8.11353666e-02, -5.36779490e-03, 3.29318611e-03,\n", - " -2.02265520e-01]),\n", - " array([ 3.44951429e-04, 8.11883046e-01, 9.38069804e-01, -7.74874916e-02,\n", - " 1.15774038e-04, -1.60229149e-04, -9.96993305e-01, 1.71878679e-02,\n", - " -6.14416639e+00, 3.28233828e-03, -1.23806123e-03, -1.94908014e-03,\n", - " -4.78530439e-02, 5.21456313e-04, 1.63728380e+00, -2.25588866e+00,\n", - " 6.07594426e+00, -2.69858100e-02, -1.68247463e-03, 3.83148025e-02,\n", - " 6.19198419e+00, 7.96951160e-02, -5.15204761e-03, 3.16316072e-03,\n", - " -2.01109473e-01]),\n", - " array([ 3.45343953e-04, 8.13833645e-01, 9.36136719e-01, -8.04481634e-02,\n", - " 1.28515247e-04, -1.58371878e-04, -9.96758773e-01, 1.72258348e-02,\n", - " -6.13811170e+00, 3.36044693e-03, -1.24299544e-03, -1.94605318e-03,\n", - " -4.80528940e-02, 4.55033511e-04, 1.62192342e+00, -2.21608713e+00,\n", - " 5.93989066e+00, -2.66967469e-02, -2.33918751e-03, 3.79669611e-02,\n", - " 6.05469191e+00, 7.81086464e-02, -4.93420718e-03, 3.02696098e-03,\n", - " -1.99850112e-01]),\n", - " array([ 3.45721437e-04, 8.15773826e-01, 9.34255216e-01, -8.33347468e-02,\n", - " 1.41069126e-04, -1.56215211e-04, -9.96521588e-01, 1.72634676e-02,\n", - " -6.13220562e+00, 3.43682535e-03, -1.24770974e-03, -1.94316834e-03,\n", - " -4.82513837e-02, 3.88974920e-04, 1.60703745e+00, -2.17297221e+00,\n", - " 5.79262052e+00, -2.63486863e-02, -2.94629791e-03, 3.76328089e-02,\n", - " 5.90608142e+00, 7.63784182e-02, -4.71430252e-03, 2.88484393e-03,\n", - " -1.98489754e-01]),\n", - " array([ 3.46081432e-04, 8.17702726e-01, 9.32428097e-01, -8.61418246e-02,\n", - " 1.53408295e-04, -1.53787045e-04, -9.96282861e-01, 1.73007817e-02,\n", - " -6.12645918e+00, 3.51133259e-03, -1.25220210e-03, -1.94043127e-03,\n", - " -4.84484147e-02, 3.23575882e-04, 1.59266044e+00, -2.12661005e+00,\n", - " 5.63441871e+00, -2.59416019e-02, -3.50027987e-03, 3.73140814e-02,\n", - " 5.74644016e+00, 7.45072374e-02, -4.49236318e-03, 2.73707265e-03,\n", - " -1.97030970e-01]),\n", - " array([ 3.46421397e-04, 8.19619476e-01, 9.30658076e-01, -8.88641423e-02,\n", - " 1.65505723e-04, -1.51116816e-04, -9.96043731e-01, 1.73377940e-02,\n", - " -6.12088310e+00, 3.58383083e-03, -1.25647052e-03, -1.93784735e-03,\n", - " -4.86438913e-02, 2.59122133e-04, 1.57882317e+00, -2.07707414e+00,\n", - " 5.46559732e+00, -2.54756726e-02, -3.99812478e-03, 3.70122668e-02,\n", - " 5.57608308e+00, 7.24982423e-02, -4.26841969e-03, 2.58391510e-03,\n", - " -1.95476580e-01]),\n", - " array([ 3.46738715e-04, 8.21523206e-01, 9.28947775e-01, -9.14966210e-02,\n", - " 1.77334817e-04, -1.48235222e-04, -9.95805360e-01, 1.73745226e-02,\n", - " -6.11548775e+00, 3.65418572e-03, -1.26051303e-03, -1.93542171e-03,\n", - " -4.88377209e-02, 1.95887208e-04, 1.56555242e+00, -2.02444506e+00,\n", - " 5.28649473e+00, -2.49512875e-02, -4.43736434e-03, 3.67285948e-02,\n", - " 5.39535159e+00, 7.03548894e-02, -4.04250387e-03, 2.42564292e-03,\n", - " -1.93829640e-01]),\n", - " array([ 3.47030715e-04, 8.23413049e-01, 9.27299715e-01, -9.40343695e-02,\n", - " 1.88869503e-04, -1.45173938e-04, -9.95568923e-01, 1.74109866e-02,\n", - " -6.11028313e+00, 3.72226666e-03, -1.26432768e-03, -1.93315918e-03,\n", - " -4.90298144e-02, 1.34129985e-04, 1.55287083e+00, -1.96881017e+00,\n", - " 5.09747444e+00, -2.43690494e-02, -4.81608715e-03, 3.64640306e-02,\n", - " 5.20461250e+00, 6.80809392e-02, -3.81464905e-03, 2.26253033e-03,\n", - " -1.92093434e-01]),\n", - " array([ 3.47294683e-04, 8.25288148e-01, 9.25716317e-01, -9.64726954e-02,\n", - " 2.00084305e-04, -1.41965325e-04, -9.95335601e-01, 1.74472059e-02,\n", - " -6.10527888e+00, 3.78794710e-03, -1.26791257e-03, -1.93106432e-03,\n", - " -4.92200858e-02, 7.40924138e-05, 1.54079668e+00, -1.91026333e+00,\n", - " 4.89892405e+00, -2.37297769e-02, -5.13294893e-03, 3.62192712e-02,\n", - " 5.00425691e+00, 6.56804416e-02, -3.58489033e-03, 2.09485311e-03,\n", - " -1.90271465e-01]),\n", - " array([ 3.47527885e-04, 8.27147659e-01, 9.24199890e-01, -9.88071161e-02,\n", - " 2.10954420e-04, -1.38642136e-04, -9.95106572e-01, 1.74832006e-02,\n", - " -6.10048418e+00, 3.85110482e-03, -1.27126583e-03, -1.92914144e-03,\n", - " -4.94084533e-02, 1.59974412e-05, 1.52934381e+00, -1.84890453e+00,\n", - " 4.69125398e+00, -2.30345052e-02, -5.38717620e-03, 3.59947471e-02,\n", - " 4.79469899e+00, 6.31577205e-02, -3.35326474e-03, 1.92288762e-03,\n", - " -1.88367441e-01]),\n", - " array([ 3.47727583e-04, 8.28990755e-01, 9.22752635e-01, -1.01033368e-01,\n", - " 2.21455797e-04, -1.35237226e-04, -9.94883004e-01, 1.75189913e-02,\n", - " -6.09590780e+00, 3.91162218e-03, -1.27438564e-03, -1.92739453e-03,\n", - " -4.95948385e-02, -3.99528460e-05, 1.51852154e+00, -1.78483959e+00,\n", - " 4.47489627e+00, -2.22844860e-02, -5.57856378e-03, 3.57906266e-02,\n", - " 4.57637467e+00, 6.05173592e-02, -3.11981138e-03, 1.74690998e-03,\n", - " -1.86385267e-01]),\n", - " array([ 3.47891056e-04, 8.30816634e-01, 9.21376636e-01, -1.03147418e-01,\n", - " 2.31565200e-04, -1.31783262e-04, -9.94666044e-01, 1.75545981e-02,\n", - " -6.09155806e+00, 3.96938636e-03, -1.27727021e-03, -1.92582733e-03,\n", - " -4.97791676e-02, -9.35788425e-05, 1.50833459e+00, -1.71817983e+00,\n", - " 4.25030325e+00, -2.14811844e-02, -5.70746609e-03, 3.56068244e-02,\n", - " 4.34974040e+00, 5.77641856e-02, -2.88457154e-03, 1.56719525e-03,\n", - " -1.84329030e-01]),\n", - " array([ 3.48015615e-04, 8.32624518e-01, 9.20073856e-01, -1.05145468e-01,\n", - " 2.41260279e-04, -1.28312443e-04, -9.94456815e-01, 1.75900411e-02,\n", - " -6.08744279e+00, 4.02428962e-03, -1.27991780e-03, -1.92444331e-03,\n", - " -4.99613706e-02, -1.44724799e-04, 1.49878313e+00, -1.64904165e+00,\n", - " 4.01794622e+00, -2.06262763e-02, -5.77478286e-03, 3.54430128e-02,\n", - " 4.11527176e+00, 5.49032568e-02, -2.64758876e-03, 1.38401679e-03,\n", - " -1.82202989e-01]),\n", - " array([ 3.48098626e-04, 8.34413665e-01, 9.18846137e-01, -1.07023966e-01,\n", - " 2.50519629e-04, -1.24856229e-04, -9.94256402e-01, 1.76253397e-02,\n", - " -6.08356933e+00, 4.07622946e-03, -1.28232671e-03, -1.92324567e-03,\n", - " -5.01413821e-02, -1.93259941e-04, 1.48986274e+00, -1.57754625e+00,\n", - " 3.77831402e+00, -1.97216424e-02, -5.78193936e-03, 3.52986365e-02,\n", - " 3.87346202e+00, 5.19398451e-02, -2.40890889e-03, 1.19764566e-03,\n", - " -1.80011562e-01]),\n", - " array([ 3.48137527e-04, 8.36183364e-01, 9.17695196e-01, -1.08779613e-01,\n", - " 2.59322853e-04, -1.21445084e-04, -9.94065850e-01, 1.76605127e-02,\n", - " -6.07994451e+00, 4.12510889e-03, -1.28449529e-03, -1.92223732e-03,\n", - " -5.03191414e-02, -2.39079328e-04, 1.48156455e+00, -1.50381923e+00,\n", - " 3.53191165e+00, -1.87693626e-02, -5.73086186e-03, 3.51729295e-02,\n", - " 3.62482078e+00, 4.88794233e-02, -2.16858010e-03, 1.00835012e-03,\n", - " -1.77759310e-01]),\n", - " array([ 3.48129843e-04, 8.37932948e-01, 9.16622621e-01, -1.10409368e-01,\n", - " 2.67650614e-04, -1.18108228e-04, -9.93886153e-01, 1.76955776e-02,\n", - " -6.07657464e+00, 4.17083654e-03, -1.28642195e-03, -1.92142092e-03,\n", - " -5.04945924e-02, -2.82104445e-04, 1.47387528e+00, -1.42799021e+00,\n", - " 3.27925878e+00, -1.77717077e-02, -5.62394875e-03, 3.50649345e-02,\n", - " 3.36987242e+00, 4.57276509e-02, -1.92665282e-03, 8.16395267e-04,\n", - " -1.75450931e-01]),\n", - " array([ 3.48073212e-04, 8.39661790e-01, 9.15629869e-01, -1.11910452e-01,\n", - " 2.75484689e-04, -1.14873413e-04, -9.93718251e-01, 1.77305511e-02,\n", - " -6.07346548e+00, 4.21332690e-03, -1.28810513e-03, -1.92079888e-03,\n", - " -5.06676836e-02, -3.22283536e-04, 1.46677741e+00, -1.35019252e+00,\n", - " 3.02088831e+00, -1.67311302e-02, -5.46403785e-03, 3.49735232e-02,\n", - " 3.10915469e+00, 4.24903604e-02, -1.68317977e-03, 6.22042695e-04,\n", - " -1.73091237e-01]),\n", - " array([ 3.47965391e-04, 8.41369314e-01, 9.14718266e-01, -1.13280359e-01,\n", - " 2.82808014e-04, -1.11766713e-04, -9.93563017e-01, 1.77654485e-02,\n", - " -6.07062226e+00, 4.25250044e-03, -1.28954334e-03, -1.92037333e-03,\n", - " -5.08383688e-02, -3.59591676e-04, 1.46024937e+00, -1.27056281e+00,\n", - " 2.75734484e+00, -1.56502544e-02, -5.25437053e-03, 3.48974191e-02,\n", - " 2.84321715e+00, 3.91735432e-02, -1.43821581e-03, 4.25550325e-04,\n", - " -1.70685149e-01]),\n", - " array([ 3.47804280e-04, 8.43054989e-01, 9.13889003e-01, -1.14516853e-01,\n", - " 2.89604732e-04, -1.08812331e-04, -9.93421257e-01, 1.78002838e-02,\n", - " -6.06804964e+00, 4.28828378e-03, -1.29073516e-03, -1.92014616e-03,\n", - " -5.10066064e-02, -3.94030588e-04, 1.45426567e+00, -1.18924070e+00,\n", - " 2.48918318e+00, -1.45318649e-02, -4.99855329e-03, 3.48352201e-02,\n", - " 2.57261965e+00, 3.57833372e-02, -1.19181789e-03, 2.27172261e-04,\n", - " -1.68237678e-01]),\n", - " array([ 3.47587935e-04, 8.44718343e-01, 9.13143136e-01, -1.15617974e-01,\n", - " 2.95860231e-04, -1.06032436e-04, -9.93293705e-01, 1.78350692e-02,\n", - " -6.06575171e+00, 4.32060979e-03, -1.29167920e-03, -1.92011900e-03,\n", - " -5.11723603e-02, -4.25628224e-04, 1.44879721e+00, -1.10636843e+00,\n", - " 2.21696685e+00, -1.33788939e-02, -4.70051721e-03, 3.47854218e-02,\n", - " 2.29793082e+00, 3.23260135e-02, -9.44044944e-04, 2.71587519e-05,\n", - " -1.65753913e-01]),\n", - " array([ 3.47314581e-04, 8.46358956e-01, 9.12481586e-01, -1.16582045e-01,\n", - " 3.01561180e-04, -1.03447008e-04, -9.93181013e-01, 1.78698156e-02,\n", - " -6.06373199e+00, 4.34941776e-03, -1.29237416e-03, -1.92029324e-03,\n", - " -5.13355994e-02, -4.54438100e-04, 1.44381150e+00, -1.02209052e+00,\n", - " 1.94126651e+00, -1.21944081e-02, -4.36447600e-03, 3.47464407e-02,\n", - " 2.01972654e+00, 2.88079633e-02, -6.94957705e-04, -1.74243778e-04,\n", - " -1.63239007e-01]),\n", - " array([ 3.46982622e-04, 8.47976467e-01, 9.11905133e-01, -1.17407666e-01,\n", - " 3.06695567e-04, -1.01073720e-04, -9.93083751e-01, 1.79045323e-02,\n", - " -6.06199340e+00, 4.37465344e-03, -1.29281878e-03, -1.92067004e-03,\n", - " -5.14962975e-02, -4.80538420e-04, 1.43927294e+00, -9.36553426e-01,\n", - " 1.66265848e+00, -1.09815941e-02, -3.99488302e-03, 3.47166371e-02,\n", - " 1.73858835e+00, 2.52356856e-02, -4.44618591e-04, -3.76792628e-04,\n", - " -1.60698165e-01]),\n", - " array([ 3.46590658e-04, 8.49570574e-01, 9.11414423e-01, -1.18093723e-01,\n", - " 3.11252720e-04, -9.89278280e-05, -9.93002400e-01, 1.79392266e-02,\n", - " -6.06053830e+00, 4.39626922e-03, -1.29301187e-03, -1.92125028e-03,\n", - " -5.16544341e-02, -5.04030989e-04, 1.43514313e+00, -8.49905220e-01,\n", - " 1.38172319e+00, -9.74374422e-03, -3.59638789e-03, 3.46943372e-02,\n", - " 1.45510197e+00, 2.16157745e-02, -1.93091521e-04, -5.80248661e-04,\n", - " -1.58136627e-01]),\n", - " array([ 3.46137490e-04, 8.51141038e-01, 9.11009961e-01, -1.18639382e-01,\n", - " 3.15223343e-04, -9.70220935e-05, -9.92937354e-01, 1.79739044e-02,\n", - " -6.05936844e+00, 4.41422412e-03, -1.29295231e-03, -1.92203466e-03,\n", - " -5.18099938e-02, -5.25039933e-04, 1.43138121e+00, -7.62295253e-01,\n", - " 1.09904368e+00, -8.48424034e-03, -3.17379302e-03, 3.46778542e-02,\n", - " 1.16985574e+00, 1.79549067e-02, 5.95582720e-05, -7.84376096e-04,\n", - " -1.55559655e-01]),\n", - " array([ 3.45622129e-04, 8.52687681e-01, 9.10692115e-01, -1.19044096e-01,\n", - " 3.18599529e-04, -9.53667239e-05, -9.92888912e-01, 1.80085700e-02,\n", - " -6.05848500e+00, 4.42848395e-03, -1.29263905e-03, -1.92302360e-03,\n", - " -5.19629663e-02, -5.43710245e-04, 1.42794417e+00, -6.73873846e-01,\n", - " 8.15204075e-01, -7.20653830e-03, -2.73201051e-03, 3.46655083e-02,\n", - " 8.83439110e-01, 1.42598287e-02, 3.13264432e-04, -9.88942248e-04,\n", - " -1.52972524e-01]),\n", - " array([ 3.45043804e-04, 8.54210389e-01, 9.10461114e-01, -1.19307600e-01,\n", - " 3.21374782e-04, -9.39693352e-05, -9.92857283e-01, 1.80432256e-02,\n", - " -6.05788856e+00, 4.43902130e-03, -1.29207109e-03, -1.92421732e-03,\n", - " -5.21133468e-02, -5.60206168e-04, 1.42478722e+00, -5.84791977e-01,\n", - " 5.30788139e-01, -5.91415148e-03, -2.27601975e-03, 3.46556450e-02,\n", - " 5.96441152e-01, 1.05373445e-02, 5.67959685e-04, -1.19371725e-03,\n", - " -1.50380500e-01]),\n", - " array([ 3.44401962e-04, 8.55709110e-01, 9.10317050e-01, -1.19429908e-01,\n", - " 3.23544032e-04, -9.28349365e-05, -9.92842578e-01, 1.80778723e-02,\n", - " -6.05757911e+00, 4.44581560e-03, -1.29124751e-03, -1.92561579e-03,\n", - " -5.22611357e-02, -5.74709445e-04, 1.42186417e+00, -4.95200978e-01,\n", - " 2.46377752e-01, -4.61063427e-03, -1.81082597e-03, 3.46466520e-02,\n", - " 3.09449039e-01, 6.79430267e-03, 8.23576050e-04, -1.39847372e-03,\n", - " -1.47788834e-01]),\n", - " array([ 3.43696278e-04, 8.57183859e-01, 9.10259877e-01, -1.19411318e-01,\n", - " 3.25103642e-04, -9.19659355e-05, -9.92844813e-01, 1.81125092e-02,\n", - " -6.05755606e+00, 4.44885318e-03, -1.29016747e-03, -1.92721878e-03,\n", - " -5.24063384e-02, -5.87417439e-04, 1.41912775e+00, -4.05252239e-01,\n", - " -3.74485190e-02, -3.29956542e-03, -1.34142009e-03, 3.46369752e-02,\n", - " 2.30466036e-02, 3.03758320e-03, 1.08004505e-03, -1.60298646e-03,\n", - " -1.45202748e-01]),\n", - " array([ 3.42926651e-04, 8.58634711e-01, 9.10289412e-01, -1.19252404e-01,\n", - " 3.26051416e-04, -9.13621633e-05, -9.92863913e-01, 1.81471344e-02,\n", - " -6.05781825e+00, 4.44812727e-03, -1.28883017e-03, -1.92902581e-03,\n", - " -5.25489658e-02, -5.98541152e-04, 1.41653005e+00, -3.15096913e-01,\n", - " -3.20116857e-01, -1.98453134e-03, -8.72739947e-04, 3.46251316e-02,\n", - " -2.62187118e-01, -7.25915249e-04, 1.33729792e-03, -1.80703208e-03,\n", - " -1.42627418e-01]),\n", - " array([ 3.42093205e-04, 8.60061804e-01, 9.10405338e-01, -1.18954013e-01,\n", - " 3.26386601e-04, -9.10209196e-05, -9.92899707e-01, 1.81817441e-02,\n", - " -6.05836393e+00, 4.44363798e-03, -1.28723490e-03, -1.93103620e-03,\n", - " -5.26890338e-02, -6.08303156e-04, 1.41402284e+00, -2.24885635e-01,\n", - " -6.01059601e-01, -6.69109590e-04, -4.09633196e-04, 3.46097221e-02,\n", - " -5.45679301e-01, -4.48928883e-03, 1.59526581e-03, -2.01038873e-03,\n", - " -1.40067964e-01]),\n", - " array([ 3.41196284e-04, 8.61465339e-01, 9.10607203e-01, -1.18517267e-01,\n", - " 3.26109883e-04, -9.09370352e-05, -9.92951934e-01, 1.82163335e-02,\n", - " -6.05919080e+00, 4.43539234e-03, -1.28538102e-03, -1.93324904e-03,\n", - " -5.28265632e-02, -6.16935466e-04, 1.41155798e+00, -1.34768236e-01,\n", - " -8.79716623e-01, 6.43147455e-04, 4.31781002e-05, 3.45894417e-02,\n", - " -8.26864723e-01, -8.24564207e-03, 1.85388000e-03, -2.21283570e-03,\n", - " -1.37529438e-01]),\n", - " array([ 3.40236455e-04, 8.62845574e-01, 9.10894421e-01, -1.17943551e-01,\n", - " 3.25223384e-04, -9.11029530e-05, -9.93020244e-01, 1.82508966e-02,\n", - " -6.06029598e+00, 4.42340423e-03, -1.28326795e-03, -1.93566319e-03,\n", - " -5.29615800e-02, -6.24677353e-04, 1.40908778e+00, -4.48934684e-02,\n", - " -1.15553668e+00, 1.94872858e-03, 4.81130950e-04, 3.45630888e-02,\n", - " -1.10518713e+00, -1.19881016e-02, 2.11307208e-03, -2.41415317e-03,\n", - " -1.35016813e-01]),\n", - " array([ 3.39214494e-04, 8.64202827e-01, 9.11266277e-01, -1.17234514e-01,\n", - " 3.23730646e-04, -9.15088248e-05, -9.93104202e-01, 1.82854262e-02,\n", - " -6.06167608e+00, 4.40769440e-03, -1.28089518e-03, -1.93827731e-03,\n", - " -5.30941150e-02, -6.31773144e-04, 1.40656534e+00, 4.45912687e-02,\n", - " -1.42797871e+00, 3.24417927e-03, 8.99853000e-04, 3.45295728e-02,\n", - " -1.38010054e+00, -1.57098303e-02, 2.37277410e-03, -2.61412192e-03,\n", - " -1.32534966e-01]),\n", - " array([ 3.38131385e-04, 8.65537472e-01, 9.11721925e-01, -1.16392065e-01,\n", - " 3.21636620e-04, -9.21426240e-05, -9.93203290e-01, 1.83199141e-02,\n", - " -6.06332715e+00, 4.38829036e-03, -1.27826226e-03, -1.94108984e-03,\n", - " -5.32242037e-02, -6.38469998e-04, 1.40394493e+00, 1.33540199e-01,\n", - " -1.69651315e+00, 4.52611662e-03, 1.29519204e-03, 3.44879201e-02,\n", - " -1.65107058e+00, -1.94040412e-02, 2.63291877e-03, -2.81252309e-03,\n", - " -1.30088672e-01]),\n", - " array([ 3.36988308e-04, 8.66849936e-01, 9.12260394e-01, -1.15418360e-01,\n", - " 3.18947648e-04, -9.29902724e-05, -9.93316914e-01, 1.83543514e-02,\n", - " -6.06524473e+00, 4.36522635e-03, -1.27536882e-03, -1.94409897e-03,\n", - " -5.33518863e-02, -6.45015705e-04, 1.40118233e+00, 2.21809436e-01,\n", - " -1.96062312e+00, 5.79124373e-03, 1.66324344e-03, 3.44372794e-02,\n", - " -1.91757569e+00, -2.30640125e-02, 2.89343954e-03, -3.00913799e-03,\n", - " -1.27682591e-01]),\n", - " array([ 3.35786630e-04, 8.68140696e-01, 9.12880586e-01, -1.14315803e-01,\n", - " 3.15671433e-04, -9.40357801e-05, -9.93444406e-01, 1.83887283e-02,\n", - " -6.06742384e+00, 4.33854325e-03, -1.27221455e-03, -1.94730272e-03,\n", - " -5.34772075e-02, -6.51656504e-04, 1.39823511e+00, 3.09257251e-01,\n", - " -2.21980569e+00, 7.03636320e-03, 2.00037536e-03, 3.43769258e-02,\n", - " -2.17910834e+00, -2.66831016e-02, 3.15427077e-03, -3.20374794e-03,\n", - " -1.25321255e-01]),\n", - " array([ 3.34527896e-04, 8.69410278e-01, 9.13581281e-01, -1.13087037e-01,\n", - " 3.11817018e-04, -9.52613982e-05, -9.93585032e-01, 1.84230346e-02,\n", - " -6.06985901e+00, 4.30828849e-03, -1.26879920e-03, -1.95069886e-03,\n", - " -5.36002166e-02, -6.58634948e-04, 1.39506299e+00, 3.95744332e-01,\n", - " -2.47357295e+00, 8.25838990e-03, 2.30325179e-03, 3.43062631e-02,\n", - " -2.43517623e+00, -3.02547601e-02, 3.41534774e-03, -3.39613419e-03,\n", - " -1.23009063e-01]),\n", - " array([ 3.33213811e-04, 8.70659252e-01, 9.14361141e-01, -1.11734934e-01,\n", - " 3.07394751e-04, -9.66477819e-05, -9.93737994e-01, 1.84572594e-02,\n", - " -6.07254432e+00, 4.27451594e-03, -1.26512259e-03, -1.95428493e-03,\n", - " -5.37209668e-02, -6.66187838e-04, 1.39162806e+00, 4.81134049e-01,\n", - " -2.72145323e+00, 9.45436279e-03, 2.56885324e-03, 3.42248264e-02,\n", - " -2.68530337e+00, -3.37725491e-02, 3.67660679e-03, -3.58607790e-03,\n", - " -1.20750263e-01]),\n", - " array([ 3.31846232e-04, 8.71888228e-01, 9.15218708e-01, -1.10262592e-01,\n", - " 3.02416248e-04, -9.81741630e-05, -9.93902440e-01, 1.84913917e-02,\n", - " -6.07547335e+00, 4.23728579e-03, -1.26118461e-03, -1.95805829e-03,\n", - " -5.38395158e-02, -6.74544230e-04, 1.38789511e+00, 5.65292707e-01,\n", - " -2.96299204e+00, 1.06214557e-02, 2.79449515e-03, 3.41322827e-02,\n", - " -2.92903120e+00, -3.72301533e-02, 3.93798525e-03, -3.77336012e-03,\n", - " -1.18548950e-01]),\n", - " array([ 3.30427152e-04, 8.73097856e-01, 9.16152414e-01, -1.08673323e-01,\n", - " 2.96894355e-04, -9.98185316e-05, -9.94077467e-01, 1.85254201e-02,\n", - " -6.07863927e+00, 4.19666439e-03, -1.25698519e-03, -1.96201606e-03,\n", - " -5.39559249e-02, -6.83923538e-04, 1.38383182e+00, 6.48089810e-01,\n", - " -3.19775319e+00, 1.17569873e-02, 2.97784382e-03, 3.40284310e-02,\n", - " -3.16591954e+00, -4.06213966e-02, 4.19942148e-03, -3.95776193e-03,\n", - " -1.16409053e-01]),\n", - " array([ 3.28958681e-04, 8.74288818e-01, 9.17160579e-01, -1.06970647e-01,\n", - " 2.90843104e-04, -1.01557824e-04, -9.94262131e-01, 1.85593333e-02,\n", - " -6.08203482e+00, 4.15272413e-03, -1.25252433e-03, -1.96615512e-03,\n", - " -5.40702592e-02, -6.94533757e-04, 1.37940897e+00, 7.29398308e-01,\n", - " -3.42531969e+00, 1.28584296e-02, 3.11692984e-03, 3.39132027e-02,\n", - " -3.39554763e+00, -4.39402570e-02, 4.46085483e-03, -4.13906460e-03,\n", - " -1.14334327e-01]),\n", - " array([ 3.27443039e-04, 8.75461826e-01, 9.18241417e-01, -1.05158280e-01,\n", - " 2.84277662e-04, -1.03368118e-04, -9.94455451e-01, 1.85931200e-02,\n", - " -6.08565233e+00, 4.10554325e-03, -1.24780211e-03, -1.97047217e-03,\n", - " -5.41825875e-02, -7.06569799e-04, 1.37460066e+00, 8.09094852e-01,\n", - " -3.64529466e+00, 1.39234154e-02, 3.21015904e-03, 3.37866593e-02,\n", - " -3.61751502e+00, -4.71808811e-02, 4.72222553e-03, -4.31704978e-03,\n", - " -1.12328346e-01]),\n", - " array([ 3.25882531e-04, 8.76617618e-01, 9.19393037e-01, -1.03240127e-01,\n", - " 2.77214286e-04, -1.05224830e-04, -9.94656417e-01, 1.86267690e-02,\n", - " -6.08948377e+00, 4.05520565e-03, -1.24281863e-03, -1.97496367e-03,\n", - " -5.42929820e-02, -7.20211977e-04, 1.36938442e+00, 8.87060041e-01,\n", - " -3.85730218e+00, 1.49497452e-02, 3.25632072e-03, 3.36489914e-02,\n", - " -3.83144238e+00, -5.03375988e-02, 4.98347460e-03, -4.49149985e-03,\n", - " -1.10394491e-01]),\n", - " array([ 3.24279534e-04, 8.77756953e-01, 9.20613452e-01, -1.01220270e-01,\n", - " 2.69670260e-04, -1.07102917e-04, -9.94863997e-01, 1.86602695e-02,\n", - " -6.09352075e+00, 4.00180072e-03, -1.23757409e-03, -1.97962587e-03,\n", - " -5.44015180e-02, -7.35624632e-04, 1.36374138e+00, 9.63178664e-01,\n", - " -4.06098810e+00, 1.59353919e-02, 3.25459323e-03, 3.35005157e-02,\n", - " -4.03697236e+00, -5.34049380e-02, 5.24454367e-03, -4.66219826e-03,\n", - " -1.08535950e-01]),\n", - " array([ 3.22636483e-04, 8.78880609e-01, 9.21900579e-01, -9.91029603e-02,\n", - " 2.61663846e-04, -1.08977080e-04, -9.95077144e-01, 1.86936112e-02,\n", - " -6.09775452e+00, 3.94542308e-03, -1.23206871e-03, -1.98445480e-03,\n", - " -5.45082737e-02, -7.52954927e-04, 1.35765632e+00, 1.03733993e+00,\n", - " -4.25602071e+00, 1.68785048e-02, 3.20454684e-03, 3.33416721e-02,\n", - " -4.23377027e+00, -5.63776384e-02, 5.50537484e-03, -4.82892997e-03,\n", - " -1.06755707e-01]),\n", - " array([ 3.20955850e-04, 8.79989376e-01, 9.23252245e-01, -9.68926044e-02,\n", - " 2.53214216e-04, -1.10821965e-04, -9.95294804e-01, 1.87267842e-02,\n", - " -6.10217604e+00, 3.88617241e-03, -1.22630280e-03, -1.98944628e-03,\n", - " -5.46133302e-02, -7.72331809e-04, 1.35111779e+00, 1.10943773e+00,\n", - " -4.44209146e+00, 1.77774131e-02, 3.10614370e-03, 3.31730197e-02,\n", - " -4.42152477e+00, -5.92506653e-02, 5.76591044e-03, -4.99148194e-03,\n", - " -1.05056533e-01]),\n", - " array([ 3.19240129e-04, 8.81084054e-01, 9.24666189e-01, -9.45937554e-02,\n", - " 2.44341393e-04, -1.12612370e-04, -9.95515921e-01, 1.87597794e-02,\n", - " -6.10677599e+00, 3.82415319e-03, -1.22027671e-03, -1.99459592e-03,\n", - " -5.47167712e-02, -7.93865143e-04, 1.34411810e+00, 1.17937080e+00,\n", - " -4.61891551e+00, 1.86306265e-02, 2.95973504e-03, 3.29952325e-02,\n", - " -4.59994845e+00, -6.20192231e-02, 6.02609281e-03, -5.14964373e-03,\n", - " -1.03440990e-01]),\n", - " array([ 3.17491822e-04, 8.82165449e-01, 9.26140074e-01, -9.22111001e-02,\n", - " 2.35066182e-04, -1.14323436e-04, -9.95739446e-01, 1.87925885e-02,\n", - " -6.11154477e+00, 3.75947442e-03, -1.21399085e-03, -1.99989913e-03,\n", - " -5.48186826e-02, -8.17645039e-04, 1.33665334e+00, 1.24704300e+00,\n", - " -4.78623225e+00, 1.94368368e-02, 2.76605553e-03, 3.28090942e-02,\n", - " -4.76877839e+00, -6.46787678e-02, 6.28586399e-03, -5.30320802e-03,\n", - " -1.01911416e-01]),\n", - " array([ 3.15713420e-04, 8.83234366e-01, 9.27671482e-01, -8.97494482e-02,\n", - " 2.25410105e-04, -1.15930848e-04, -9.95964343e-01, 1.88252040e-02,\n", - " -6.11647254e+00, 3.69224940e-03, -1.20744568e-03, -2.00535110e-03,\n", - " -5.49191525e-02, -8.43741354e-04, 1.32872339e+00, 1.31236349e+00,\n", - " -4.94380580e+00, 2.01949164e-02, 2.52621471e-03, 3.26154924e-02,\n", - " -4.92777657e+00, -6.72250190e-02, 6.54516553e-03, -5.45197139e-03,\n", - " -1.00469927e-01]),\n", - " array([ 3.13907388e-04, 8.84291609e-01, 9.29257927e-01, -8.72137197e-02,\n", - " 2.15395329e-04, -1.17411019e-04, -9.96189594e-01, 1.88576194e-02,\n", - " -6.12154927e+00, 3.62259543e-03, -1.20064174e-03, -2.01094684e-03,\n", - " -5.50182710e-02, -8.72203396e-04, 1.32033179e+00, 1.37524693e+00,\n", - " -5.09142532e+00, 2.09039173e-02, 2.24168561e-03, 3.24154121e-02,\n", - " -5.07673029e+00, -6.96539718e-02, 6.80393806e-03, -5.59573493e-03,\n", - " -9.91184127e-02]),\n", - " array([ 3.12076154e-04, 8.85337975e-01, 9.30896856e-01, -8.46089325e-02,\n", - " 2.05044594e-04, -1.18741271e-04, -9.96414207e-01, 1.88898293e-02,\n", - " -6.12676473e+00, 3.55063352e-03, -1.19357962e-03, -2.01668114e-03,\n", - " -5.51161295e-02, -9.03059806e-04, 1.31148576e+00, 1.43561363e+00,\n", - " -5.22890539e+00, 2.15630679e-02, 1.91429060e-03, 3.22099287e-02,\n", - " -5.21545245e+00, -7.19619074e-02, 7.06212107e-03, -5.73430502e-03,\n", - " -9.78585319e-02]),\n", - " array([ 3.10222088e-04, 8.86374249e-01, 9.32585657e-01, -8.19401906e-02,\n", - " 1.94381143e-04, -1.19900010e-04, -9.96637222e-01, 1.89218295e-02,\n", - " -6.13210851e+00, 3.47648812e-03, -1.18625997e-03, -2.02254864e-03,\n", - " -5.52128212e-02, -9.36318636e-04, 1.30219599e+00, 1.49338977e+00,\n", - " -5.35608618e+00, 2.21717698e-02, 1.54618455e-03, 3.20001999e-02,\n", - " -5.34378181e+00, -7.41454028e-02, 7.31965255e-03, -5.86749411e-03,\n", - " -9.66917118e-02]),\n", - " array([ 3.08347496e-04, 8.87401206e-01, 9.34321664e-01, -7.92126709e-02,\n", - " 1.83428645e-04, -1.20866887e-04, -9.96857715e-01, 1.89536170e-02,\n", - " -6.13757009e+00, 3.40028678e-03, -1.17868350e-03, -2.02854376e-03,\n", - " -5.53084403e-02, -9.71967604e-04, 1.29247659e+00, 1.54850752e+00,\n", - " -5.47283365e+00, 2.27295933e-02, 1.13983528e-03, 3.17874574e-02,\n", - " -5.46158315e+00, -7.62013399e-02, 7.57646864e-03, -5.99512152e-03,\n", - " -9.56191463e-02]),\n", - " array([ 3.06454603e-04, 8.88419600e-01, 9.36102160e-01, -7.64316105e-02,\n", - " 1.72211124e-04, -1.21622946e-04, -9.97074804e-01, 1.89851900e-02,\n", - " -6.14313884e+00, 3.32215987e-03, -1.17085100e-03, -2.03466077e-03,\n", - " -5.54030821e-02, -1.00997453e-03, 1.28234487e+00, 1.60090520e+00,\n", - " -5.57903960e+00, 2.32362717e-02, 6.98001685e-04, 3.15729976e-02,\n", - " -5.56874733e+00, -7.81269138e-02, 7.83250331e-03, -6.11701420e-03,\n", - " -9.46417950e-02]),\n", - " array([ 3.04545543e-04, 8.89430168e-01, 9.37924386e-01, -7.36022940e-02,\n", - " 1.60752881e-04, -1.22150764e-04, -9.97287652e-01, 1.90165482e-02,\n", - " -6.14880403e+00, 3.24224023e-03, -1.16276331e-03, -2.04089378e-03,\n", - " -5.54968425e-02, -1.05028796e-03, 1.27182121e+00, 1.65052733e+00,\n", - " -5.67462169e+00, 2.36916961e-02, 2.23709434e-04, 3.13581724e-02,\n", - " -5.66519128e+00, -7.99196397e-02, 8.08768805e-03, -6.23300762e-03,\n", - " -9.37603835e-02]),\n", - " array([ 3.02622350e-04, 8.90433621e-01, 9.39785547e-01, -7.07300406e-02,\n", - " 1.49078423e-04, -1.22434576e-04, -9.97495476e-01, 1.90476925e-02,\n", - " -6.15455489e+00, 3.16066287e-03, -1.15442136e-03, -2.04723673e-03,\n", - " -5.55898179e-02, -1.09283788e-03, 1.26092882e+00, 1.69732484e+00,\n", - " -5.75952337e+00, 2.40959083e-02, -2.79775359e-04, 3.11443782e-02,\n", - " -5.75085798e+00, -8.15773588e-02, 8.34195151e-03, -6.34294650e-03,\n", - " -9.29754037e-02]),\n", - " array([ 3.00686946e-04, 8.91430646e-01, 9.41682816e-01, -6.78201909e-02,\n", - " 1.37212390e-04, -1.22460383e-04, -9.97697543e-01, 1.90786256e-02,\n", - " -6.16038060e+00, 3.07756462e-03, -1.14582614e-03, -2.05368341e-03,\n", - " -5.56821050e-02, -1.13753673e-03, 1.24969355e+00, 1.74125504e+00,\n", - " -5.83371372e+00, 2.44490938e-02, -8.08974379e-04, 3.09330457e-02,\n", - " -5.82571625e+00, -8.30982435e-02, 8.59521923e-03, -6.44668567e-03,\n", - " -9.22871154e-02]),\n", - " array([ 2.98741135e-04, 8.92421902e-01, 9.43613340e-01, -6.48780943e-02,\n", - " 1.25179479e-04, -1.22216048e-04, -9.97893182e-01, 1.91093512e-02,\n", - " -6.16627037e+00, 2.99308382e-03, -1.13697873e-03, -2.06022750e-03,\n", - " -5.57738006e-02, -1.18428034e-03, 1.23814364e+00, 1.78228174e+00,\n", - " -5.89718721e+00, 2.47515746e-02, -1.36022697e-03, 3.07256287e-02,\n", - " -5.88976057e+00, -8.44808008e-02, 8.84741334e-03, -6.54409082e-03,\n", - " -9.16955481e-02]),\n", - " array([ 2.96786594e-04, 8.93408017e-01, 9.45574248e-01, -6.19090962e-02,\n", - " 1.13004374e-04, -1.21691373e-04, -9.98081778e-01, 1.91398748e-02,\n", - " -6.17221338e+00, 2.90735995e-03, -1.12788027e-03, -2.06686254e-03,\n", - " -5.58650011e-02, -1.23294923e-03, 1.22630945e+00, 1.82037529e+00,\n", - " -5.94996343e+00, 2.50038011e-02, -1.92972137e-03, 3.05235926e-02,\n", - " -5.94301072e+00, -8.57238750e-02, 9.09845228e-03, -6.63503926e-03,\n", - " -9.12005041e-02]),\n", - " array([ 2.94824868e-04, 8.94389587e-01, 9.47562657e-01, -5.89185251e-02,\n", - " 1.00711676e-04, -1.20878160e-04, -9.98262782e-01, 1.91702032e-02,\n", - " -6.17819889e+00, 2.82053330e-03, -1.11853202e-03, -2.07358196e-03,\n", - " -5.59558027e-02, -1.28340981e-03, 1.21422325e+00, 1.85551256e+00,\n", - " -5.99208672e+00, 2.52063442e-02, -2.51352693e-03, 3.03284028e-02,\n", - " -5.98551149e+00, -8.68266492e-02, 9.34825060e-03, -6.71942062e-03,\n", - " -9.08015614e-02]),\n", - " array([ 2.92857367e-04, 8.95367175e-01, 9.49575674e-01, -5.59116804e-02,\n", - " 8.83258366e-05, -1.19770258e-04, -9.98435707e-01, 1.92003447e-02,\n", - " -6.18421622e+00, 2.73274465e-03, -1.10893530e-03, -2.08037910e-03,\n", - " -5.60463007e-02, -1.33551578e-03, 1.20191891e+00, 1.88767695e+00,\n", - " -6.02362567e+00, 2.53598872e-02, -3.10762718e-03, 3.01415129e-02,\n", - " -6.01733211e+00, -8.77886452e-02, 9.59671872e-03, -6.79713754e-03,\n", - " -9.04980782e-02]),\n", - " array([ 2.90885360e-04, 8.96341308e-01, 9.51610408e-01, -5.28938198e-02,\n", - " 7.58710882e-05, -1.18363588e-04, -9.98600132e-01, 1.92303091e-02,\n", - " -6.19025479e+00, 2.64413493e-03, -1.09909154e-03, -2.08724721e-03,\n", - " -5.61365899e-02, -1.38910963e-03, 1.18943165e+00, 1.91685836e+00,\n", - " -6.04467266e+00, 2.54652172e-02, -3.70795324e-03, 2.99643531e-02,\n", - " -6.03856585e+00, -8.86097223e-02, 9.84376278e-03, -6.86810627e-03,\n", - " -9.02891972e-02]),\n", - " array([ 2.88909971e-04, 8.97312478e-01, 9.53663970e-01, -4.98701473e-02,\n", - " 6.33713843e-05, -1.16656154e-04, -9.98755701e-01, 1.92601074e-02,\n", - " -6.19630411e+00, 2.55484486e-03, -1.08900226e-03, -2.09417946e-03,\n", - " -5.62267638e-02, -1.44402410e-03, 1.17679775e+00, 1.94305315e+00,\n", - " -6.05534327e+00, 2.55232174e-02, -4.31041730e-03, 2.97983186e-02,\n", - " -6.04932934e+00, -8.92900752e-02, 1.00892845e-02, -6.93225723e-03,\n", - " -9.01738514e-02]),\n", - " array([ 2.86932184e-04, 8.98281139e-01, 9.55733486e-01, -4.68458018e-02,\n", - " 5.08503371e-05, -1.14648037e-04, -9.98902125e-01, 1.92897522e-02,\n", - " -6.20235388e+00, 2.46501463e-03, -1.07866908e-03, -2.10116900e-03,\n", - " -5.63169145e-02, -1.50008376e-03, 1.16405424e+00, 1.96626405e+00,\n", - " -6.05577558e+00, 2.55348585e-02, -4.91094593e-03, 2.96447582e-02,\n", - " -6.04976198e+00, -8.98302302e-02, 1.03331811e-02, -6.98953550e-03,\n", - " -9.01507693e-02]),\n", - " array([ 2.84952833e-04, 8.99247709e-01, 9.57816094e-01, -4.38258452e-02,\n", - " 3.83311602e-05, -1.12341370e-04, -9.99039179e-01, 1.93192571e-02,\n", - " -6.20839390e+00, 2.37478359e-03, -1.06809373e-03, -2.10820890e-03,\n", - " -5.64071330e-02, -1.55710658e-03, 1.15123869e+00, 1.98650004e+00,\n", - " -6.04612955e+00, 2.55011911e-02, -5.50551271e-03, 2.95049635e-02,\n", - " -6.04002518e+00, -9.02310403e-02, 1.05753451e-02, -7.03990129e-03,\n", - " -9.02184821e-02]),\n", - " array([ 2.82972614e-04, 9.00212568e-01, 9.59908958e-01, -4.08152516e-02,\n", - " 2.58366139e-05, -1.09740302e-04, -9.99166704e-01, 1.93486373e-02,\n", - " -6.21441420e+00, 2.28428991e-03, -1.05727807e-03, -2.11529223e-03,\n", - " -5.64975084e-02, -1.61490554e-03, 1.13838887e+00, 2.00377630e+00,\n", - " -6.02658616e+00, 2.54233377e-02, -6.09017001e-03, 2.93801582e-02,\n", - " -6.02030160e+00, -9.04936796e-02, 1.08156647e-02, -7.08333021e-03,\n", - " -9.03753302e-02]),\n", - " array([ 2.80992075e-04, 9.01176059e-01, 9.62009267e-01, -3.78188967e-02,\n", - " 1.33889543e-05, -1.06850936e-04, -9.99284604e-01, 1.93779088e-02,\n", - " -6.22040500e+00, 2.19367027e-03, -1.04622404e-03, -2.12241204e-03,\n", - " -5.65881278e-02, -1.67329016e-03, 1.12554249e+00, 2.01811399e+00,\n", - " -5.99734665e+00, 2.53024856e-02, -6.66107956e-03, 2.92714886e-02,\n", - " -5.99079434e+00, -9.06196356e-02, 1.10540233e-02, -7.11981361e-03,\n", - " -9.06194709e-02]),\n", - " array([ 2.79011629e-04, 9.02138487e-01, 9.64114245e-01, -3.48415476e-02,\n", - " 1.00988573e-06, -1.03681268e-04, -9.99392844e-01, 1.94070888e-02,\n", - " -6.22635672e+00, 2.10305957e-03, -1.03493374e-03, -2.12956140e-03,\n", - " -5.66790767e-02, -1.73206810e-03, 1.11273698e+00, 2.02954016e+00,\n", - " -5.95863161e+00, 2.51398792e-02, -7.21454145e-03, 2.91800144e-02,\n", - " -5.95172600e+00, -9.06107014e-02, 1.12903001e-02, -7.14935877e-03,\n", - " -9.09488864e-02]),\n", - " array([ 2.77031550e-04, 9.03100120e-01, 9.66221154e-01, -3.18878527e-02,\n", - " -1.12794832e-05, -1.00241095e-04, -9.99491448e-01, 1.94361955e-02,\n", - " -6.23226006e+00, 2.01259060e-03, -1.02340937e-03, -2.13673339e-03,\n", - " -5.67704381e-02, -1.79104661e-03, 1.10000918e+00, 2.03808753e+00,\n", - " -5.91068009e+00, 2.49368140e-02, -7.74702138e-03, 2.91067005e-02,\n", - " -5.90333782e+00, -9.04689660e-02, 1.15243696e-02, -7.17198896e-03,\n", - " -9.13613921e-02]),\n", - " array([ 2.75051983e-04, 9.04061192e-01, 9.68327299e-01, -2.89623332e-02,\n", - " -2.34586799e-05, -9.65419253e-05, -9.99580499e-01, 1.94652479e-02,\n", - " -6.23810595e+00, 1.92239380e-03, -1.01165327e-03, -2.14392114e-03,\n", - " -5.68622928e-02, -1.85003406e-03, 1.08739515e+00, 2.04379431e+00,\n", - " -5.85374861e+00, 2.46946296e-02, -8.25517590e-03, 2.90524095e-02,\n", - " -5.84588868e+00, -9.01968045e-02, 1.17561026e-02, -7.18774352e-03,\n", - " -9.18546455e-02]),\n", - " array([ 2.73072943e-04, 9.05021902e-01, 9.70430034e-01, -2.60693736e-02,\n", - " -3.55079038e-05, -9.25968653e-05, -9.99660131e-01, 1.94942658e-02,\n", - " -6.24388560e+00, 1.83259693e-03, -9.99667905e-04, -2.15111781e-03,\n", - " -5.69547189e-02, -1.90884123e-03, 1.07492989e+00, 2.04670397e+00,\n", - " -5.78811015e+00, 2.44147039e-02, -8.73587536e-03, 2.90178953e-02,\n", - " -5.77965404e+00, -8.97968666e-02, 1.19853656e-02, -7.19667779e-03,\n", - " -9.24261553e-02]),\n", - " array([ 2.71094327e-04, 9.05982413e-01, 9.72526765e-01, -2.32132143e-02,\n", - " -4.74080593e-05, -8.84205046e-05, -9.99730532e-01, 1.95232696e-02,\n", - " -6.24959053e+00, 1.74332487e-03, -9.87455883e-04, -2.15831668e-03,\n", - " -5.70477922e-02, -1.96728270e-03, 1.06264717e+00, 2.04686507e+00,\n", - " -5.71405315e+00, 2.40984479e-02, -9.18622446e-03, 2.90037982e-02,\n", - " -5.70492499e+00, -8.92720643e-02, 1.22120216e-02, -7.19886295e-03,\n", - " -9.30732909e-02]),\n", - " array([ 2.69115917e-04, 9.06942857e-01, 9.74614955e-01, -2.03979433e-02,\n", - " -5.91407844e-05, -8.40287876e-05, -9.99791935e-01, 1.95522802e-02,\n", - " -6.25521254e+00, 1.65469931e-03, -9.75019953e-04, -2.16551106e-03,\n", - " -5.71415855e-02, -2.02517805e-03, 1.05057932e+00, 2.04433094e+00,\n", - " -5.63188041e+00, 2.37473000e-02, -9.60358019e-03, 2.90106403e-02,\n", - " -5.62200709e+00, -8.86255597e-02, 1.24359301e-02, -7.19438581e-03,\n", - " -9.37932920e-02]),\n", - " array([ 2.67137387e-04, 9.07903335e-01, 9.76692130e-01, -1.76274898e-02,\n", - " -7.06884757e-05, -7.94388782e-05, -9.99844618e-01, 1.95813190e-02,\n", - " -6.26074376e+00, 1.56683856e-03, -9.62363005e-04, -2.17269441e-03,\n", - " -5.72361688e-02, -2.08235293e-03, 1.03875705e+00, 2.03915950e+00,\n", - " -5.54190801e+00, 2.33627219e-02, -9.98556711e-03, 2.90388225e-02,\n", - " -5.53121929e+00, -8.78607510e-02, 1.26569477e-02, -7.18334854e-03,\n", - " -9.45832790e-02]),\n", - " array([ 2.65158312e-04, 9.08863920e-01, 9.78755880e-01, -1.49056174e-02,\n", - " -8.20343096e-05, -7.46690197e-05, -9.99888899e-01, 1.96104077e-02,\n", - " -6.26617665e+00, 1.47985730e-03, -9.49488077e-04, -2.17986028e-03,\n", - " -5.73316090e-02, -2.13864016e-03, 1.02720927e+00, 2.03141294e+00,\n", - " -5.44446420e+00, 2.29461937e-02, -1.03300898e-02, 2.90886226e-02,\n", - " -5.43289283e+00, -8.69812587e-02, 1.28749283e-02, -7.16586823e-03,\n", - " -9.54402625e-02]),\n", - " array([ 2.63178176e-04, 9.09824655e-01, 9.80803863e-01, -1.22359187e-02,\n", - " -9.31622604e-05, -6.97383882e-05, -9.99925132e-01, 1.96395679e-02,\n", - " -6.27150402e+00, 1.39386639e-03, -9.36398354e-04, -2.18700236e-03,\n", - " -5.74279702e-02, -2.19388060e-03, 1.01596298e+00, 2.02115751e+00,\n", - " -5.33988827e+00, 2.24992104e-02, -1.06353427e-02, 2.91601944e-02,\n", - " -5.32737009e+00, -8.59909106e-02, 1.30897234e-02, -7.14207648e-03,\n", - " -9.63611542e-02]),\n", - " array([ 2.61196377e-04, 9.10785559e-01, 9.82833811e-01, -9.62180962e-03,\n", - " -1.04057114e-04, -6.46669436e-05, -9.99953702e-01, 1.96688214e-02,\n", - " -6.27671902e+00, 1.30897266e-03, -9.23097171e-04, -2.19411447e-03,\n", - " -5.75253130e-02, -2.24792398e-03, 1.00504314e+00, 2.00846319e+00,\n", - " -5.22852941e+00, 2.20232782e-02, -1.08998168e-02, 2.92535681e-02,\n", - " -5.21500343e+00, -8.48937272e-02, 1.33011829e-02, -7.11211890e-03,\n", - " -9.73427770e-02]),\n", - " array([ 2.59212241e-04, 9.11746626e-01, 9.84843531e-01, -7.06652525e-03,\n", - " -1.14704481e-04, -5.94752788e-05, -9.99975023e-01, 1.96981901e-02,\n", - " -6.28181518e+00, 1.22527875e-03, -9.09588016e-04, -2.20119063e-03,\n", - " -5.76236948e-02, -2.30062957e-03, 9.94472538e-01, 1.99340344e+00,\n", - " -5.11074555e+00, 2.15199113e-02, -1.11223036e-02, 2.93686514e-02,\n", - " -5.09615405e+00, -8.36939061e-02, 1.35091552e-02, -7.07615445e-03,\n", - " -9.83818753e-02]),\n", - " array([ 2.57225026e-04, 9.12707830e-01, 9.86830907e-01, -4.57311574e-03,\n", - " -1.25090800e-04, -5.41844676e-05, -9.99989534e-01, 1.97276953e-02,\n", - " -6.28678637e+00, 1.14288295e-03, -8.95874528e-04, -2.20822498e-03,\n", - " -5.77231700e-02, -2.35186679e-03, 9.84271741e-01, 1.97605489e+00,\n", - " -4.98690226e+00, 2.09906289e-02, -1.13018968e-02, 2.95052322e-02,\n", - " -4.97119082e+00, -8.23958063e-02, 1.37134880e-02, -7.03435487e-03,\n", - " -9.94751259e-02]),\n", - " array([ 2.55233932e-04, 9.13669123e-01, 9.88793904e-01, -2.14444302e-03,\n", - " -1.35203347e-04, -4.88159140e-05, -9.99997690e-01, 1.97573583e-02,\n", - " -6.29162686e+00, 1.06187902e-03, -8.81960499e-04, -2.21521189e-03,\n", - " -5.78237891e-02, -2.40151567e-03, 9.74459014e-01, 1.95649709e+00,\n", - " -4.85737154e+00, 2.04369529e-02, -1.14379907e-02, 2.96629815e-02,\n", - " -4.84048914e+00, -8.10039328e-02, 1.39140286e-02, -6.98690394e-03,\n", - " -1.00619148e-01]),\n", - " array([ 2.53238113e-04, 9.14630440e-01, 9.90730572e-01, 2.16821954e-04,\n", - " -1.45030236e-04, -4.33912037e-05, -9.99999965e-01, 1.97871998e-02,\n", - " -6.29633129e+00, 9.82356095e-04, -8.67849875e-04, -2.22214588e-03,\n", - " -5.79255996e-02, -2.44946723e-03, 9.65050280e-01, 1.93481218e+00,\n", - " -4.72253075e+00, 1.98604050e-02, -1.15302767e-02, 2.98414579e-02,\n", - " -4.70442977e+00, -7.95229201e-02, 1.41106244e-02, -6.93399675e-03,\n", - " -1.01810514e-01]),\n", - " array([ 2.51236681e-04, 9.15591703e-01, 9.92639043e-01, 2.50820127e-03,\n", - " -1.54560418e-04, -3.79319577e-05, -9.99996842e-01, 1.98172399e-02,\n", - " -6.30089468e+00, 9.04398579e-04, -8.53546751e-04, -2.22902172e-03,\n", - " -5.80286454e-02, -2.49562373e-03, 9.56059094e-01, 1.91108462e+00,\n", - " -4.58276142e+00, 1.92625051e-02, -1.15787366e-02, 3.00401127e-02,\n", - " -4.56339771e+00, -7.79575168e-02, 1.43031238e-02, -6.87583889e-03,\n", - " -1.03045759e-01]),\n", - " array([ 2.49228718e-04, 9.16552816e-01, 9.94517538e-01, 4.72741159e-03,\n", - " -1.63783678e-04, -3.24596914e-05, -9.99988812e-01, 1.98474982e-02,\n", - " -6.30531246e+00, 8.28086009e-04, -8.39055375e-04, -2.23583437e-03,\n", - " -5.81329668e-02, -2.53989883e-03, 9.47496637e-01, 1.88540091e+00,\n", - " -4.43844817e+00, 1.86447689e-02, -1.15836348e-02, 3.02582954e-02,\n", - " -4.41778107e+00, -7.63125697e-02, 1.44913761e-02, -6.81264565e-03,\n", - " -1.04321392e-01]),\n", - " array([ 2.47213286e-04, 9.17513674e-01, 9.96364366e-01, 6.87236512e-03,\n", - " -1.72690631e-04, -2.69956788e-05, -9.99976370e-01, 1.98779934e-02,\n", - " -6.30958043e+00, 7.53493001e-04, -8.24380142e-04, -2.24257901e-03,\n", - " -5.82386007e-02, -2.58221769e-03, 9.39371726e-01, 1.85784931e+00,\n", - " -4.28997762e+00, 1.80087063e-02, -1.15455073e-02, 3.04952601e-02,\n", - " -4.26796997e+00, -7.45930079e-02, 1.46752329e-02, -6.74464112e-03,\n", - " -1.05633906e-01]),\n", - " array([ 2.45189431e-04, 9.18474162e-01, 9.98177923e-01, 8.94116992e-03,\n", - " -1.81272713e-04, -2.15608219e-05, -9.99960010e-01, 1.99087436e-02,\n", - " -6.31369479e+00, 6.80689173e-04, -8.09525594e-04, -2.24925107e-03,\n", - " -5.83455805e-02, -2.62251691e-03, 9.31690840e-01, 1.82851955e+00,\n", - " -4.13773729e+00, 1.73558196e-02, -1.14651498e-02, 3.07501726e-02,\n", - " -4.11435544e+00, -7.28038277e-02, 1.48545477e-02, -6.67205736e-03,\n", - " -1.06979785e-01]),\n", - " array([ 2.43156195e-04, 9.19434157e-01, 9.99956700e-01, 1.09321298e-02,\n", - " -1.89522175e-04, -1.61755288e-05, -9.99940224e-01, 1.99397657e-02,\n", - " -6.31765212e+00, 6.09739096e-04, -7.94496417e-04, -2.25584620e-03,\n", - " -5.84539360e-02, -2.66074446e-03, 9.24458168e-01, 1.79750256e+00,\n", - " -3.98211457e+00, 1.66876018e-02, -1.13436035e-02, 3.10221176e-02,\n", - " -3.95732840e+00, -7.09500770e-02, 1.50291775e-02, -6.59513347e-03,\n", - " -1.08355518e-01]),\n", - " array([ 2.41112624e-04, 9.20393532e-01, 1.00169927e+00, 1.28437434e-02,\n", - " -1.97432067e-04, -1.08595980e-05, -9.99917496e-01, 1.99710758e-02,\n", - " -6.32144940e+00, 5.40702256e-04, -7.79297434e-04, -2.26236032e-03,\n", - " -5.85636936e-02, -2.69685947e-03, 9.17675663e-01, 1.76489022e+00,\n", - " -3.82349572e+00, 1.60055352e-02, -1.11821401e-02, 3.13101065e-02,\n", - " -3.79727857e+00, -6.90368407e-02, 1.51989822e-02, -6.51411466e-03,\n", - " -1.09757605e-01]),\n", - " array([ 2.39057772e-04, 9.21352153e-01, 1.00340432e+00, 1.46747033e-02,\n", - " -2.04996233e-04, -5.63211183e-06, -9.99892300e-01, 2.00026889e-02,\n", - " -6.32508399e+00, 4.73633030e-04, -7.63933608e-04, -2.26878957e-03,\n", - " -5.86748762e-02, -2.73083201e-03, 9.11343114e-01, 1.73077508e+00,\n", - " -3.66226483e+00, 1.53110898e-02, -1.09822446e-02, 3.16130852e-02,\n", - " -3.63459353e+00, -6.70692258e-02, 1.53638263e-02, -6.42925139e-03,\n", - " -1.11182565e-01]),\n", - " array([ 2.36990715e-04, 9.22309886e-01, 1.00507059e+00, 1.64238942e-02,\n", - " -2.12209293e-04, -5.11338593e-07, -9.99865096e-01, 2.00346188e-02,\n", - " -6.32855365e+00, 4.08580682e-04, -7.48410030e-04, -2.27513037e-03,\n", - " -5.87875031e-02, -2.76264279e-03, 9.05458234e-01, 1.69525015e+00,\n", - " -3.49880289e+00, 1.46057218e-02, -1.07455985e-02, 3.19299423e-02,\n", - " -3.46965774e+00, -6.50523479e-02, 1.55235784e-02, -6.34079838e-03,\n", - " -1.12626951e-01]),\n", - " array([ 2.34910549e-04, 9.23266597e-01, 1.00669695e+00, 1.80903903e-02,\n", - " -2.19066629e-04, 4.48535638e-06, -9.99836331e-01, 2.00668784e-02,\n", - " -6.33185650e+00, 3.45589365e-04, -7.32731917e-04, -2.28137938e-03,\n", - " -5.89015905e-02, -2.79228276e-03, 9.00016750e-01, 1.65840861e+00,\n", - " -3.33348689e+00, 1.38908719e-02, -1.04740608e-02, 3.22595174e-02,\n", - " -3.30285157e+00, -6.29913166e-02, 1.56781124e-02, -6.24901375e-03,\n", - " -1.14087349e-01]),\n", - " array([ 2.32816406e-04, 9.24222150e-01, 1.00828235e+00, 1.96734533e-02,\n", - " -2.25564372e-04, 9.34158998e-06, -9.99806433e-01, 2.00994790e-02,\n", - " -6.33499105e+00, 2.84698142e-04, -7.16904610e-04, -2.28753354e-03,\n", - " -5.90171509e-02, -2.81975274e-03, 8.95012514e-01, 1.62034362e+00,\n", - " -3.16668888e+00, 1.31679645e-02, -1.01696492e-02, 3.26006090e-02,\n", - " -3.13455045e+00, -6.08912233e-02, 1.58273076e-02, -6.15415809e-03,\n", - " -1.15560395e-01]),\n", - " array([ 2.30707452e-04, 9.25176415e-01, 1.00982582e+00, 2.11725291e-02,\n", - " -2.31699382e-04, 1.40420311e-05, -9.99775810e-01, 2.01324310e-02,\n", - " -6.33795617e+00, 2.25941014e-04, -7.00933560e-04, -2.29359003e-03,\n", - " -5.91341936e-02, -2.84506293e-03, 8.90437610e-01, 1.58114806e+00,\n", - " -2.99877520e+00, 1.24384052e-02, -9.83452079e-03, 3.29519831e-02,\n", - " -2.96512403e+00, -5.87571277e-02, 1.59710494e-02, -6.05649357e-03,\n", - " -1.17042775e-01]),\n", - " array([ 2.28582896e-04, 9.26129263e-01, 1.01132648e+00, 2.25872440e-02,\n", - " -2.37469234e-04, 1.85724604e-05, -9.99744847e-01, 2.01657433e-02,\n", - " -6.34075111e+00, 1.69346968e-04, -6.84824331e-04, -2.29954631e-03,\n", - " -5.92527249e-02, -2.86823245e-03, 8.86282483e-01, 1.54091437e+00,\n", - " -2.83010561e+00, 1.17035801e-02, -9.47095245e-03, 3.33123805e-02,\n", - " -2.79493532e+00, -5.65940457e-02, 1.61092295e-02, -5.95628307e-03,\n", - " -1.18531240e-01]),\n", - " array([ 2.26441996e-04, 9.27080570e-01, 1.01278356e+00, 2.39174014e-02,\n", - " -2.42872201e-04, 2.29198210e-05, -9.99713908e-01, 2.01994239e-02,\n", - " -6.34337545e+00, 1.14940030e-04, -6.68582584e-04, -2.30540010e-03,\n", - " -5.93727475e-02, -2.88928883e-03, 8.82536058e-01, 1.49973431e+00,\n", - " -2.66103257e+00, 1.09648539e-02, -9.08132124e-03, 3.36805253e-02,\n", - " -2.62433997e+00, -5.44069382e-02, 1.62417466e-02, -5.85378934e-03,\n", - " -1.20022604e-01]),\n", - " array([ 2.24284061e-04, 9.28030220e-01, 1.01419637e+00, 2.51629772e-02,\n", - " -2.47907230e-04, 2.70722585e-05, -9.99683331e-01, 2.02334790e-02,\n", - " -6.34582914e+00, 6.27393307e-05, -6.52214078e-04, -2.31114938e-03,\n", - " -5.94942612e-02, -2.90826745e-03, 8.79185879e-01, 1.45769879e+00,\n", - " -2.49190050e+00, 1.02235682e-02, -8.66808490e-03, 3.40551321e-02,\n", - " -2.45368550e+00, -5.22006996e-02, 1.63685064e-02, -5.74927416e-03,\n", - " -1.21513758e-01]),\n", - " array([ 2.22108456e-04, 9.28978101e-01, 1.01556430e+00, 2.63241156e-02,\n", - " -2.52573933e-04, 3.10191528e-05, -9.99653428e-01, 2.02679139e-02,\n", - " -6.34811245e+00, 1.27591837e-05, -6.35724656e-04, -2.31679238e-03,\n", - " -5.96172629e-02, -2.92521099e-03, 8.76218235e-01, 1.41489766e+00,\n", - " -2.32304513e+00, 9.48104039e-03, -8.23376266e-03, 3.44349129e-02,\n", - " -2.28331067e+00, -4.99801470e-02, 1.64894223e-02, -5.64299759e-03,\n", - " -1.23001674e-01]),\n", - " array([ 2.19914605e-04, 9.29924112e-01, 1.01688682e+00, 2.74011240e-02,\n", - " -2.56872559e-04, 3.47511392e-05, -9.99624485e-01, 2.03027325e-02,\n", - " -6.35022599e+00, -3.49908271e-05, -6.19120240e-04, -2.32232759e-03,\n", - " -5.97417463e-02, -2.94016889e-03, 8.73618309e-01, 1.37141961e+00,\n", - " -2.15479284e+00, 8.73856146e-03, -7.78091653e-03, 3.48185849e-02,\n", - " -2.11354482e+00, -4.77500108e-02, 1.66044155e-02, -5.53521715e-03,\n", - " -1.24483408e-01]),\n", - " array([ 2.17701995e-04, 9.30868158e-01, 1.01816351e+00, 2.83944680e-02,\n", - " -2.60803981e-04, 3.82601219e-05, -9.99596761e-01, 2.03379374e-02,\n", - " -6.35217070e+00, -8.05057520e-05, -6.02406825e-04, -2.32775378e-03,\n", - " -5.98677024e-02, -2.95319674e-03, 8.71370303e-01, 1.32735192e+00,\n", - " -1.98746011e+00, 7.99739483e-03, -7.31213306e-03, 3.52048760e-02,\n", - " -1.94470729e+00, -4.55149249e-02, 1.67134153e-02, -5.42618712e-03,\n", - " -1.25956106e-01]),\n", - " array([ 2.15470175e-04, 9.31810153e-01, 1.01939401e+00, 2.93047661e-02,\n", - " -2.64369671e-04, 4.15392779e-05, -9.99570487e-01, 2.03735299e-02,\n", - " -6.35394780e+00, -1.23785170e-04, -5.85590465e-04, -2.33306994e-03,\n", - " -5.99951194e-02, -2.96435572e-03, 8.69457588e-01, 1.28278039e+00,\n", - " -1.82135297e+00, 7.25877459e-03, -6.83000578e-03, 3.55925320e-02,\n", - " -1.77710685e+00, -4.32794179e-02, 1.68163596e-02, -5.31615790e-03,\n", - " -1.27417014e-01]),\n", - " array([ 2.13218762e-04, 9.32750021e-01, 1.02057805e+00, 3.01327841e-02,\n", - " -2.67571688e-04, 4.45830529e-05, -9.99545868e-01, 2.04095102e-02,\n", - " -6.35555885e+00, -1.64833075e-04, -5.68677270e-04, -2.33827531e-03,\n", - " -6.01239829e-02, -2.97371206e-03, 8.67862832e-01, 1.23778917e+00,\n", - " -1.65676651e+00, 6.52390391e-03, -6.33711849e-03, 3.59803217e-02,\n", - " -1.61104126e+00, -4.10479047e-02, 1.69131948e-02, -5.20537528e-03,\n", - " -1.28863475e-01]),\n", - " array([ 2.10947438e-04, 9.33687698e-01, 1.02171544e+00, 3.08794293e-02,\n", - " -2.70412649e-04, 4.73871497e-05, -9.99523079e-01, 2.04458773e-02,\n", - " -6.35700564e+00, -2.03657754e-04, -5.51673394e-04, -2.34336939e-03,\n", - " -6.02542758e-02, -2.98133638e-03, 8.66568138e-01, 1.19246061e+00,\n", - " -1.49398444e+00, 5.79395354e-03, -5.83602924e-03, 3.63670426e-02,\n", - " -1.44679678e+00, -3.88246790e-02, 1.70038759e-02, -5.09407992e-03,\n", - " -1.30292936e-01]),\n", - " array([ 2.08655953e-04, 9.34623126e-01, 1.02280608e+00, 3.15457444e-02,\n", - " -2.72895718e-04, 4.99485084e-05, -9.99502271e-01, 2.04826288e-02,\n", - " -6.35829029e+00, -2.40271659e-04, -5.34585027e-04, -2.34835190e-03,\n", - " -6.03859788e-02, -2.98730321e-03, 8.65555178e-01, 1.14687521e+00,\n", - " -1.33327867e+00, 5.07006024e-03, -5.32925539e-03, 3.67515257e-02,\n", - " -1.28464779e+00, -3.66139056e-02, 1.70883670e-02, -4.98250671e-03,\n", - " -1.31702954e-01]),\n", - " array([ 2.06344125e-04, 9.35556259e-01, 1.02384992e+00, 3.21329016e-02,\n", - " -2.75024579e-04, 5.22652807e-05, -9.99483566e-01, 2.05197614e-02,\n", - " -6.35941515e+00, -2.74691274e-04, -5.17418386e-04, -2.35322278e-03,\n", - " -6.05190700e-02, -2.99169041e-03, 8.64805317e-01, 1.10111143e+00,\n", - " -1.17490901e+00, 4.35332531e-03, -4.81925954e-03, 3.71326403e-02,\n", - " -1.12485642e+00, -3.44196145e-02, 1.71666414e-02, -4.87088431e-03,\n", - " -1.33091196e-01]),\n", - " array([ 2.04011840e-04, 9.36487064e-01, 1.02484700e+00, 3.26421961e-02,\n", - " -2.76803420e-04, 5.43367969e-05, -9.99467062e-01, 2.05572707e-02,\n", - " -6.36038282e+00, -3.06936968e-04, -5.00179705e-04, -2.35798222e-03,\n", - " -6.06535254e-02, -2.99457860e-03, 8.64299737e-01, 1.05524567e+00,\n", - " -1.01912279e+00, 3.64481320e-03, -4.30843649e-03, 3.75092981e-02,\n", - " -9.67672235e-01, -3.22456942e-02, 1.72386812e-02, -4.75943464e-03,\n", - " -1.34455441e-01]),\n", - " array([ 2.01659048e-04, 9.37415514e-01, 1.02579742e+00, 3.30750400e-02,\n", - " -2.78236910e-04, 5.61635274e-05, -9.99452831e-01, 2.05951512e-02,\n", - " -6.36119615e+00, -3.37032854e-04, -4.82875227e-04, -2.36263059e-03,\n", - " -6.07893190e-02, -2.99605068e-03, 8.64019557e-01, 1.00935210e+00,\n", - " -8.66154665e-01, 2.94555015e-03, -3.79910136e-03, 3.78804568e-02,\n", - " -8.13331996e-01, -3.00958864e-02, 1.73044777e-02, -4.64837247e-03,\n", - " -1.35793587e-01]),\n", - " array([ 1.99285766e-04, 9.38341595e-01, 1.02670137e+00, 3.34329555e-02,\n", - " -2.79330183e-04, 5.77470390e-05, -9.99440922e-01, 2.06333963e-02,\n", - " -6.36185821e+00, -3.65006635e-04, -4.65511195e-04, -2.36716850e-03,\n", - " -6.09264227e-02, -2.99619129e-03, 8.63945944e-01, 9.63502661e-01,\n", - " -7.16226347e-01, 2.25652292e-03, -3.29347864e-03, 3.82451236e-02,\n", - " -6.62059413e-01, -2.79737809e-02, 1.73640317e-02, -4.53790501e-03,\n", - " -1.37103648e-01]),\n", - " array([ 1.96892076e-04, 9.39265301e-01, 1.02755908e+00, 3.37175685e-02,\n", - " -2.80088814e-04, 5.90899461e-05, -9.99431360e-01, 2.06719987e-02,\n", - " -6.36237228e+00, -3.90889446e-04, -4.48093843e-04, -2.37159673e-03,\n", - " -6.10648064e-02, -2.99508631e-03, 8.64060216e-01, 9.17766930e-01,\n", - " -5.69546456e-01, 1.57867762e-03, -2.79369250e-03, 3.86023581e-02,\n", - " -5.14064977e-01, -2.58828111e-02, 1.74173526e-02, -4.42823159e-03,\n", - " -1.38383758e-01]),\n", - " array([ 1.94478117e-04, 9.40186638e-01, 1.02837086e+00, 3.39306020e-02,\n", - " -2.80518798e-04, 6.01958577e-05, -9.99424150e-01, 2.07109499e-02,\n", - " -6.36274182e+00, -4.14715696e-04, -4.30629383e-04, -2.37591627e-03,\n", - " -6.12044386e-02, -2.99282243e-03, 8.64343947e-01, 8.72212088e-01,\n", - " -4.26310370e-01, 9.12918655e-04, -2.30175807e-03, 3.89512752e-02,\n", - " -3.69545822e-01, -2.38262499e-02, 1.74644593e-02, -4.31954333e-03,\n", - " -1.39632170e-01]),\n", - " array([ 1.92044092e-04, 9.41105618e-01, 1.02913707e+00, 3.40738694e-02,\n", - " -2.80626533e-04, 6.10693206e-05, -9.99419276e-01, 2.07502410e-02,\n", - " -6.36297051e+00, -4.36522903e-04, -4.13124004e-04, -2.38012829e-03,\n", - " -6.13452859e-02, -2.98948665e-03, 8.64779051e-01, 8.26902852e-01,\n", - " -2.86700138e-01, 2.60107708e-04, -1.81957395e-03, 3.92910466e-02,\n", - " -2.28685628e-01, -2.18072063e-02, 1.75053795e-02, -4.21202292e-03,\n", - " -1.40847262e-01]),\n", - " array([ 1.89590257e-04, 9.42022265e-01, 1.02985815e+00, 3.41492679e-02,\n", - " -2.80418800e-04, 6.17157596e-05, -9.99416702e-01, 2.07898619e-02,\n", - " -6.36306216e+00, -4.56351525e-04, -3.95583854e-04, -2.38423414e-03,\n", - " -6.14873134e-02, -2.98516588e-03, 8.65347874e-01, 7.81901431e-01,\n", - " -1.50884424e-01, -3.78937094e-04, -1.34891575e-03, 3.96209036e-02,\n", - " -9.16545692e-02, -1.98286225e-02, 1.75401498e-02, -4.10584436e-03,\n", - " -1.42027529e-01]),\n", - " array([ 1.87116924e-04, 9.42936610e-01, 1.03053458e+00, 3.41587718e-02,\n", - " -2.79902737e-04, 6.21414147e-05, -9.99416378e-01, 2.08298020e-02,\n", - " -6.36302077e+00, -4.74244796e-04, -3.78015039e-04, -2.38823531e-03,\n", - " -6.16304850e-02, -2.97994652e-03, 8.66033265e-01, 7.37267481e-01,\n", - " -1.90184868e-02, -1.00344186e-03, -8.91430082e-04, 3.99401385e-02,\n", - " 4.13907036e-02, -1.78932710e-02, 1.75688155e-02, -4.00117282e-03,\n", - " -1.43171592e-01]),\n", - " array([ 1.84624454e-04, 9.43848692e-01, 1.03116689e+00, 3.41044257e-02,\n", - " -2.79085827e-04, 6.23532767e-05, -9.99418234e-01, 2.08700501e-02,\n", - " -6.36285046e+00, -4.90248549e-04, -3.60423608e-04, -2.39213348e-03,\n", - " -6.17747632e-02, -2.97391410e-03, 8.66818648e-01, 6.93058075e-01,\n", - " 1.08755793e-01, -1.61267780e-03, -4.48632083e-04, 4.02481044e-02,\n", - " 1.70307043e-01, -1.60037529e-02, 1.75914306e-02, -3.89816450e-03,\n", - " -1.44278192e-01]),\n", - " array([ 1.82113257e-04, 9.44758558e-01, 1.03175566e+00, 3.39883382e-02,\n", - " -2.77975870e-04, 6.23590208e-05, -9.99422189e-01, 2.09105943e-02,\n", - " -6.36255550e+00, -5.04411045e-04, -3.42815551e-04, -2.39593044e-03,\n", - " -6.19201094e-02, -2.96715287e-03, 8.67688084e-01, 6.49327668e-01,\n", - " 2.32309861e-01, -2.20596148e-03, -2.19003924e-05, 4.05442176e-02,\n", - " 2.94964747e-01, -1.41624963e-02, 1.76080572e-02, -3.79696651e-03,\n", - " -1.45346191e-01]),\n", - " array([ 1.79583784e-04, 9.45666261e-01, 1.03230154e+00, 3.38126750e-02,\n", - " -2.76580967e-04, 6.21669387e-05, -9.99428148e-01, 2.09514223e-02,\n", - " -6.36214025e+00, -5.16782800e-04, -3.25196785e-04, -2.39962816e-03,\n", - " -6.20664839e-02, -2.95974552e-03, 8.68626321e-01, 6.06128083e-01,\n", - " 3.51528394e-01, -2.78265531e-03, 3.87524766e-04, 4.08279581e-02,\n", - " 4.15247467e-01, -1.23717549e-02, 1.76187658e-02, -3.69771684e-03,\n", - " -1.46374571e-01]),\n", - " array([ 1.77036529e-04, 9.46571860e-01, 1.03280520e+00, 3.35796529e-02,\n", - " -2.74909499e-04, 6.17858708e-05, -9.99436005e-01, 2.09925212e-02,\n", - " -6.36160920e+00, -5.27416408e-04, -3.07573150e-04, -2.40322870e-03,\n", - " -6.22138464e-02, -2.95177286e-03, 8.69618843e-01, 5.63508491e-01,\n", - " 4.66309180e-01, -3.34216787e-03, 7.78542152e-04, 4.10988689e-02,\n", - " 5.31052080e-01, -1.06336076e-02, 1.76236347e-02, -3.60054430e-03,\n", - " -1.47362433e-01]),\n", - " array([ 1.74472019e-04, 9.47475420e-01, 1.03326736e+00, 3.32915325e-02,\n", - " -2.72970106e-04, 6.12251377e-05, -9.99445644e-01, 2.10338777e-02,\n", - " -6.36096691e+00, -5.36366366e-04, -2.89950401e-04, -2.40673427e-03,\n", - " -6.23621554e-02, -2.94331348e-03, 8.70651908e-01, 5.21515406e-01,\n", - " 5.76562958e-01, -3.88395401e-03, 1.15019057e-03, 4.13565568e-02,\n", - " 6.42288536e-01, -8.94995806e-03, 1.76227499e-02, -3.50556858e-03,\n", - " -1.48308997e-01]),\n", - " array([ 1.71890817e-04, 9.48377012e-01, 1.03368879e+00, 3.29506130e-02,\n", - " -2.70771666e-04, 6.04944718e-05, -9.99456943e-01, 2.10754784e-02,\n", - " -6.36021803e+00, -5.43688901e-04, -2.72334196e-04, -2.41014717e-03,\n", - " -6.25113690e-02, -2.93444358e-03, 8.71712580e-01, 4.80192677e-01,\n", - " 6.82213237e-01, -4.40751485e-03, 1.50164811e-03, 4.16006920e-02,\n", - " 7.48879667e-01, -7.32253523e-03, 1.76162046e-02, -3.41290023e-03,\n", - " -1.49213597e-01]),\n", - " array([ 1.69293511e-04, 9.49276710e-01, 1.03407028e+00, 3.25592250e-02,\n", - " -2.68323277e-04, 5.96039497e-05, -9.99469770e-01, 2.11173094e-02,\n", - " -6.35936727e+00, -5.49441795e-04, -2.54730097e-04, -2.41346981e-03,\n", - " -6.26614446e-02, -2.92523664e-03, 8.72788747e-01, 4.39581496e-01,\n", - " 7.83196077e-01, -4.91239781e-03, 1.83223078e-03, 4.18310071e-02,\n", - " 8.50760972e-01, -5.75289359e-03, 1.76040994e-02, -3.32264079e-03,\n", - " -1.50075681e-01]),\n", - " array([ 1.66680717e-04, 9.50174592e-01, 1.03441268e+00, 3.21197250e-02,\n", - " -2.65634236e-04, 5.85639257e-05, -9.99483992e-01, 2.11593567e-02,\n", - " -6.35841939e+00, -5.53684209e-04, -2.37143555e-04, -2.41670470e-03,\n", - " -6.28123395e-02, -2.91576331e-03, 8.73869148e-01, 3.99720401e-01,\n", - " 8.79459850e-01, -5.39819634e-03, 2.14139033e-03, 4.20472970e-02,\n", - " 9.47880374e-01, -4.24241442e-03, 1.75865413e-02, -3.23488282e-03,\n", - " -1.50894810e-01]),\n", - " array([ 1.64053070e-04, 9.51070738e-01, 1.03471684e+00, 3.16344891e-02,\n", - " -2.62714016e-04, 5.73849667e-05, -9.99499468e-01, 2.12016061e-02,\n", - " -6.35737919e+00, -5.56476516e-04, -2.19579911e-04, -2.41985441e-03,\n", - " -6.29640101e-02, -2.90609112e-03, 8.74943372e-01, 3.60645290e-01,\n", - " 9.70964975e-01, -5.86454968e-03, 2.42871137e-03, 4.22494170e-02,\n", - " 1.04019795e+00, -2.79230719e-03, 1.75636441e-02, -3.14971011e-03,\n", - " -1.51670651e-01]),\n", - " array([ 1.61411222e-04, 9.51965233e-01, 1.03498366e+00, 3.11059074e-02,\n", - " -2.59572250e-04, 5.60777883e-05, -9.99516059e-01, 2.12440434e-02,\n", - " -6.35625151e+00, -5.57880128e-04, -2.02044384e-04, -2.42292160e-03,\n", - " -6.31164131e-02, -2.89628441e-03, 8.76001873e-01, 3.22389441e-01,\n", - " 1.05768363e+00, -6.31114246e-03, 2.69390780e-03, 4.24372822e-02,\n", - " 1.12768564e+00, -1.40361145e-03, 1.75355274e-02, -3.06719776e-03,\n", - " -1.52402982e-01]),\n", - " array([ 1.58755839e-04, 9.52858162e-01, 1.03521407e+00, 3.05363782e-02,\n", - " -2.56218710e-04, 5.46531936e-05, -9.99533622e-01, 2.12866543e-02,\n", - " -6.35504118e+00, -5.57957327e-04, -1.84542067e-04, -2.42590902e-03,\n", - " -6.32695048e-02, -2.88640414e-03, 8.77035960e-01, 2.84983533e-01,\n", - " 1.13959942e+00, -6.73770426e-03, 2.93681854e-03, 4.26108657e-02,\n", - " 1.21032693e+00, -7.71989778e-05, 1.75023167e-02, -2.98741239e-03,\n", - " -1.53091680e-01]),\n", - " array([ 1.56087597e-04, 9.53749611e-01, 1.03540900e+00, 2.99283026e-02,\n", - " -2.52663283e-04, 5.31220140e-05, -9.99552015e-01, 2.13294245e-02,\n", - " -6.35375306e+00, -5.56771103e-04, -1.67077924e-04, -2.42881943e-03,\n", - " -6.34232415e-02, -2.87650780e-03, 8.78037794e-01, 2.48455676e-01,\n", - " 1.21670709e+00, -7.14400900e-03, 3.15740281e-03, 4.27701967e-02,\n", - " 1.28811651e+00, 1.18622356e-03, 1.74641430e-02, -2.91041232e-03,\n", - " -1.53736726e-01]),\n", - " array([ 1.53407177e-04, 9.54639667e-01, 1.03556944e+00, 2.92840789e-02,\n", - " -2.48915959e-04, 5.14950521e-05, -9.99571097e-01, 2.13723398e-02,\n", - " -6.35239200e+00, -5.54384991e-04, -1.49656782e-04, -2.43165568e-03,\n", - " -6.35775797e-02, -2.86664932e-03, 8.79000374e-01, 2.12831438e-01,\n", - " 1.28901211e+00, -7.52987430e-03, 3.35573481e-03, 4.29153589e-02,\n", - " 1.36105994e+00, 2.38611168e-03, 1.74211422e-02, -2.83624779e-03,\n", - " -1.54338195e-01]),\n", - " array([ 1.50715264e-04, 9.55528418e-01, 1.03569636e+00, 2.86060977e-02,\n", - " -2.44986803e-04, 4.97830287e-05, -9.99590731e-01, 2.14153863e-02,\n", - " -6.35096283e+00, -5.50862912e-04, -1.32283327e-04, -2.43442064e-03,\n", - " -6.37324759e-02, -2.85687899e-03, 8.79917521e-01, 1.78133886e-01,\n", - " 1.35653038e+00, -7.89516080e-03, 3.53199791e-03, 4.30464882e-02,\n", - " 1.42917327e+00, 3.52207978e-03, 1.73734548e-02, -2.76496118e-03,\n", - " -1.54896259e-01]),\n", - " array([ 1.48012541e-04, 9.56415951e-01, 1.03579076e+00, 2.78967368e-02,\n", - " -2.40885942e-04, 4.79965309e-05, -9.99610780e-01, 2.14585501e-02,\n", - " -6.34947035e+00, -5.46269014e-04, -1.14962101e-04, -2.43711722e-03,\n", - " -6.38878871e-02, -2.84724344e-03, 8.80783856e-01, 1.44383624e-01,\n", - " 1.41928777e+00, -8.23977131e-03, 3.68647855e-03, 4.31637703e-02,\n", - " 1.49248262e+00, 4.59389751e-03, 1.73212259e-02, -2.69658726e-03,\n", - " -1.55411178e-01]),\n", - " array([ 1.45299690e-04, 9.57302352e-01, 1.03585368e+00, 2.71583567e-02,\n", - " -2.36623541e-04, 4.61459653e-05, -9.99631115e-01, 2.15018175e-02,\n", - " -6.34791932e+00, -5.40667528e-04, -9.76974969e-05, -2.43974838e-03,\n", - " -6.40437704e-02, -2.83778562e-03, 8.81594775e-01, 1.11598838e-01,\n", - " 1.47731978e+00, -8.56364998e-03, 3.81955973e-03, 4.32674383e-02,\n", - " 1.55102383e+00, 5.60148585e-03, 1.72646042e-02, -2.63115346e-03,\n", - " -1.55883300e-01]),\n", - " array([ 1.42577383e-04, 9.58187705e-01, 1.03588613e+00, 2.63932953e-02,\n", - " -2.32209790e-04, 4.42415129e-05, -9.99651608e-01, 2.15451753e-02,\n", - " -6.34631448e+00, -5.34122615e-04, -8.04937546e-05, -2.44231706e-03,\n", - " -6.42000835e-02, -2.82854475e-03, 8.82346422e-01, 7.97953433e-02,\n", - " 1.53067111e+00, -8.86678138e-03, 3.93171416e-03, 4.33577704e-02,\n", - " 1.60484201e+00, 6.54491283e-03, 1.72037422e-02, -2.56868012e-03,\n", - " -1.56313055e-01]),\n", - " array([ 1.39846286e-04, 9.59072094e-01, 1.03588915e+00, 2.56038644e-02,\n", - " -2.27654876e-04, 4.22930884e-05, -9.99672141e-01, 2.15886104e-02,\n", - " -6.34466049e+00, -5.26698226e-04, -6.33549592e-05, -2.44482624e-03,\n", - " -6.43567844e-02, -2.81955641e-03, 8.83035655e-01, 4.89866368e-02,\n", - " 1.57939523e+00, -9.14918951e-03, 4.02349735e-03, 4.34350866e-02,\n", - " 1.65399114e+00, 7.42438904e-03, 1.71387954e-02, -2.50918076e-03,\n", - " -1.56700954e-01]),\n", - " array([ 1.37107052e-04, 9.59955598e-01, 1.03586379e+00, 2.47923449e-02,\n", - " -2.22968974e-04, 4.03103027e-05, -9.99692597e-01, 2.16321101e-02,\n", - " -6.34296196e+00, -5.18457964e-04, -4.62850370e-05, -2.44727890e-03,\n", - " -6.45138320e-02, -2.81085253e-03, 8.83660014e-01, 1.91839510e-02,\n", - " 1.62355396e+00, -9.41093675e-03, 4.09554032e-03, 4.34997461e-02,\n", - " 1.69853361e+00, 8.24026284e-03, 1.70699222e-02, -2.45266241e-03,\n", - " -1.57047581e-01]),\n", - " array([ 1.34360318e-04, 9.60838297e-01, 1.03581110e+00, 2.39609833e-02,\n", - " -2.18162223e-04, 3.83024290e-05, -9.99712870e-01, 2.16756623e-02,\n", - " -6.34122342e+00, -5.09464948e-04, -2.92877538e-05, -2.44967803e-03,\n", - " -6.46711856e-02, -2.80246146e-03, 8.84217683e-01, -9.60368801e-03,\n", - " 1.66321703e+00, -9.65212280e-03, 4.14854236e-03, 4.35521444e-02,\n", - " 1.73853980e+00, 8.99301535e-03, 1.69972832e-02, -2.39912585e-03,\n", - " -1.57353592e-01]),\n", - " array([ 1.31606708e-04, 9.61720266e-01, 1.03573214e+00, 2.31119875e-02,\n", - " -2.13244711e-04, 3.62783722e-05, -9.99732859e-01, 2.17192550e-02,\n", - " -6.33944933e+00, -4.99781693e-04, -1.23667124e-05, -2.45202659e-03,\n", - " -6.48288053e-02, -2.79440804e-03, 8.84707454e-01, -3.73693994e-02,\n", - " 1.69846166e+00, -9.87288356e-03, 4.18326364e-03, 4.35927101e-02,\n", - " 1.77408762e+00, 9.68325515e-03, 1.69210414e-02, -2.34856594e-03,\n", - " -1.57619710e-01]),\n", - " array([ 1.28846825e-04, 9.62601577e-01, 1.03562796e+00, 2.22475237e-02,\n", - " -2.08226454e-04, 3.42466428e-05, -9.99752471e-01, 2.17628769e-02,\n", - " -6.33764407e+00, -4.89469980e-04, 4.47464862e-06, -2.45432756e-03,\n", - " -6.49866520e-02, -2.78671368e-03, 8.85128689e-01, -6.41083842e-02,\n", - " 1.72937204e+00, -1.00733900e-02, 4.20051786e-03, 4.36219018e-02,\n", - " 1.80526207e+00, 1.03117129e-02, 1.68413611e-02, -2.30097193e-03,\n", - " -1.57846722e-01]),\n", - " array([ 1.26081254e-04, 9.63482299e-01, 1.03549962e+00, 2.13697128e-02,\n", - " -2.03117384e-04, 3.22153329e-05, -9.99771620e-01, 2.18065171e-02,\n", - " -6.33581191e+00, -4.78590745e-04, 2.12330567e-05, -2.45658389e-03,\n", - " -6.51446875e-02, -2.77939648e-03, 8.85481275e-01, -8.98178594e-02,\n", - " 1.75603899e+00, -1.02538467e-02, 4.20116485e-03, 4.36402048e-02,\n", - " 1.83215477e+00, 1.08792356e-02, 1.67584080e-02, -2.25632772e-03,\n", - " -1.58035473e-01]),\n", - " array([ 1.23310558e-04, 9.64362498e-01, 1.03534816e+00, 2.04806276e-02,\n", - " -1.97927327e-04, 3.01920976e-05, -9.99790230e-01, 2.18501652e-02,\n", - " -6.33395705e+00, -4.67203964e-04, 3.79054057e-05, -2.45879850e-03,\n", - " -6.53028744e-02, -2.77247132e-03, 8.85765588e-01, -1.14496990e-01,\n", - " 1.77855938e+00, -1.04144911e-02, 4.18610337e-03, 4.36481282e-02,\n", - " 1.85486351e+00, 1.13867810e-02, 1.66723490e-02, -2.21461219e-03,\n", - " -1.58186862e-01]),\n", - " array([ 1.20535275e-04, 9.65242237e-01, 1.03517464e+00, 1.95822898e-02,\n", - " -1.92665992e-04, 2.81841383e-05, -9.99808230e-01, 2.18938114e-02,\n", - " -6.33208356e+00, -4.55368552e-04, 5.44887570e-05, -2.46097430e-03,\n", - " -6.54611762e-02, -2.76595001e-03, 8.85982451e-01, -1.38146817e-01,\n", - " 1.79703580e+00, -1.05555919e-02, 4.15626396e-03, 4.36462011e-02,\n", - " 1.87349179e+00, 1.18354112e-02, 1.65833513e-02, -2.17579953e-03,\n", - " -1.58301841e-01]),\n", - " array([ 1.17755922e-04, 9.66121571e-01, 1.03498009e+00, 1.86766673e-02,\n", - " -1.87342952e-04, 2.61981904e-05, -9.99825558e-01, 2.19374464e-02,\n", - " -6.33019541e+00, -4.43142265e-04, 7.09803394e-05, -2.46311416e-03,\n", - " -6.56195576e-02, -2.75984140e-03, 8.86133091e-01, -1.60770189e-01,\n", - " 1.81157602e+00, -1.06774475e-02, 4.11260194e-03, 4.36349701e-02,\n", - " 1.88814838e+00, 1.22262873e-02, 1.64915824e-02, -2.13985947e-03,\n", - " -1.58381406e-01]),\n", - " array([ 1.14972991e-04, 9.67000557e-01, 1.03476555e+00, 1.77656721e-02,\n", - " -1.81967630e-04, 2.42405143e-05, -9.99842161e-01, 2.19810614e-02,\n", - " -6.32829646e+00, -4.30581603e-04, 8.73775493e-05, -2.46522092e-03,\n", - " -6.57779842e-02, -2.75415155e-03, 8.86219102e-01, -1.82371683e-01,\n", - " 1.82229256e+00, -1.07803852e-02, 4.05609072e-03, 4.36149954e-02,\n", - " 1.89894683e+00, 1.25606624e-02, 1.63972099e-02, -2.10675763e-03,\n", - " -1.58426598e-01]),\n", - " array([ 1.12186945e-04, 9.67879244e-01, 1.03453204e+00, 1.68511578e-02,\n", - " -1.76549283e-04, 2.23168885e-05, -9.99857993e-01, 2.20246483e-02,\n", - " -6.32639046e+00, -4.17741726e-04, 1.03677950e-04, -2.46729738e-03,\n", - " -6.59364227e-02, -2.74888384e-03, 8.86242400e-01, -2.02957537e-01,\n", - " 1.82930228e+00, -1.08647597e-02, 3.98771524e-03, 4.35868478e-02,\n", - " 1.90600507e+00, 1.28398763e-02, 1.63004006e-02, -2.07645582e-03,\n", - " -1.58438493e-01]),\n", - " array([ 1.09398226e-04, 9.68757678e-01, 1.03428057e+00, 1.59349178e-02,\n", - " -1.71096990e-04, 2.04326077e-05, -9.99873016e-01, 2.20681994e-02,\n", - " -6.32448101e+00, -4.04676378e-04, 1.19879271e-04, -2.46934629e-03,\n", - " -6.60948409e-02, -2.74403920e-03, 8.86205190e-01, -2.22535564e-01,\n", - " 1.83272590e+00, -1.09309513e-02, 3.90846571e-03, 4.35511059e-02,\n", - " 1.90944491e+00, 1.30653483e-02, 1.62013211e-02, -2.04891228e-03,\n", - " -1.58418206e-01]),\n", - " array([ 1.06607244e-04, 9.69635901e-01, 1.03401215e+00, 1.50186836e-02,\n", - " -1.65619641e-04, 1.85924820e-05, -9.99887199e-01, 2.21117077e-02,\n", - " -6.32257162e+00, -3.91437807e-04, 1.35979408e-04, -2.47137037e-03,\n", - " -6.62532078e-02, -2.73961620e-03, 8.86109923e-01, -2.41115084e-01,\n", - " 1.83268756e+00, -1.09793651e-02, 3.81933172e-03, 4.35083525e-02,\n", - " 1.90939163e+00, 1.32385714e-02, 1.61001365e-02, -2.02408200e-03,\n", - " -1.58366878e-01]),\n", - " array([ 1.03814386e-04, 9.70513951e-01, 1.03372776e+00, 1.41041232e-02,\n", - " -1.60125918e-04, 1.68008402e-05, -9.99900519e-01, 2.21551669e-02,\n", - " -6.32066565e+00, -3.78076700e-04, 1.51976418e-04, -2.47337229e-03,\n", - " -6.64114935e-02, -2.73561124e-03, 8.85959261e-01, -2.58706842e-01,\n", - " 1.82931444e+00, -1.10104292e-02, 3.72129659e-03, 4.34591722e-02,\n", - " 1.90597356e+00, 1.33611062e-02, 1.59970109e-02, -2.00191698e-03,\n", - " -1.58285679e-01]),\n", - " array([ 1.01020012e-04, 9.71391862e-01, 1.03342836e+00, 1.31928398e-02,\n", - " -1.54624287e-04, 1.50615348e-05, -9.99912959e-01, 2.21985710e-02,\n", - " -6.31876632e+00, -3.64642127e-04, 1.67868525e-04, -2.47535465e-03,\n", - " -6.65696693e-02, -2.73201875e-03, 8.85756042e-01, -2.75322929e-01,\n", - " 1.82273627e+00, -1.10245933e-02, 3.61533213e-03, 4.34041480e-02,\n", - " 1.89932162e+00, 1.34345739e-02, 1.58921066e-02, -1.98236650e-03,\n", - " -1.58175801e-01]),\n", - " array([ 9.82244530e-05, 9.72269664e-01, 1.03311492e+00, 1.22863708e-02,\n", - " -1.49122990e-04, 1.33779500e-05, -9.99924508e-01, 2.22419149e-02,\n", - " -6.31687676e+00, -3.51181476e-04, 1.83654109e-04, -2.47732003e-03,\n", - " -6.67277077e-02, -2.72883132e-03, 8.85503246e-01, -2.90976707e-01,\n", - " 1.81308497e+00, -1.10223273e-02, 3.50239367e-03, 4.33438589e-02,\n", - " 1.88956893e+00, 1.34606505e-02, 1.57855842e-02, -1.96537739e-03,\n", - " -1.58038454e-01]),\n", - " array([ 9.54280154e-05, 9.73147385e-01, 1.03278837e+00, 1.13861866e-02,\n", - " -1.43630027e-04, 1.17530119e-05, -9.99935165e-01, 2.22851938e-02,\n", - " -6.31499991e+00, -3.37740415e-04, 1.99331711e-04, -2.47927093e-03,\n", - " -6.68855826e-02, -2.72603987e-03, 8.85203963e-01, -3.05682728e-01,\n", - " 1.80049424e+00, -1.10041198e-02, 3.38341561e-03, 4.32788770e-02,\n", - " 1.87685039e+00, 1.34410607e-02, 1.56776020e-02, -1.95089426e-03,\n", - " -1.57874865e-01]),\n", - " array([ 9.26309790e-05, 9.74025045e-01, 1.03244963e+00, 1.04936903e-02,\n", - " -1.38153153e-04, 1.01892004e-05, -9.99944930e-01, 2.23284035e-02,\n", - " -6.31313860e+00, -3.24362844e-04, 2.14900028e-04, -2.48120979e-03,\n", - " -6.70432689e-02, -2.72363384e-03, 8.84861362e-01, -3.19456656e-01,\n", - " 1.78509913e+00, -1.09704765e-02, 3.25930724e-03, 4.32097655e-02,\n", - " 1.86130230e+00, 1.33775713e-02, 1.55683162e-02, -1.93885977e-03,\n", - " -1.57686272e-01]),\n", - " array([ 8.98335979e-05, 9.74902664e-01, 1.03209960e+00, 9.61021695e-03,\n", - " -1.32699867e-04, 8.68856352e-06, -9.99953812e-01, 2.23715406e-02,\n", - " -6.31129554e+00, -3.11090859e-04, 2.30357908e-04, -2.48313900e-03,\n", - " -6.72007428e-02, -2.72160136e-03, 8.84478665e-01, -3.32315190e-01,\n", - " 1.76703571e+00, -1.09219191e-02, 3.13094900e-03, 4.31370755e-02,\n", - " 1.84306196e+00, 1.32719855e-02, 1.54578800e-02, -1.92921484e-03,\n", - " -1.57473921e-01]),\n", - " array([ 8.70361014e-05, 9.75780258e-01, 1.03173917e+00, 8.73703324e-03,\n", - " -1.27277400e-04, 7.25273270e-06, -9.99961823e-01, 2.24146020e-02,\n", - " -6.30947327e+00, -2.97964722e-04, 2.45704352e-04, -2.48506090e-03,\n", - " -6.73579819e-02, -2.71992939e-03, 8.84059118e-01, -3.44275989e-01,\n", - " 1.74644068e+00, -1.08589834e-02, 2.99918915e-03, 4.30613450e-02,\n", - " 1.82226729e+00, 1.31261368e-02, 1.53464442e-02, -1.92189888e-03,\n", - " -1.57239063e-01]),\n", - " array([ 8.42386942e-05, 9.76657839e-01, 1.03136918e+00, 7.87533737e-03,\n", - " -1.21892716e-04, 5.88294034e-06, -9.99968982e-01, 2.24575850e-02,\n", - " -6.30767422e+00, -2.85022839e-04, 2.60938508e-04, -2.48697775e-03,\n", - " -6.75149648e-02, -2.71860388e-03, 8.83605966e-01, -3.55357590e-01,\n", - " 1.72345099e+00, -1.07822177e-02, 2.86484082e-03, 4.29830956e-02,\n", - " 1.79905651e+00, 1.29418831e-02, 1.52341563e-02, -1.91685002e-03,\n", - " -1.56982951e-01]),\n", - " array([ 8.14415578e-05, 9.77535416e-01, 1.03099048e+00, 7.02625907e-03,\n", - " -1.16552497e-04, 4.58003802e-06, -9.99975309e-01, 2.25004879e-02,\n", - " -6.30590065e+00, -2.72301737e-04, 2.76059669e-04, -2.48889176e-03,\n", - " -6.76716716e-02, -2.71760995e-03, 8.83122435e-01, -3.65579340e-01,\n", - " 1.69820353e+00, -1.06921819e-02, 2.72867944e-03, 4.29028319e-02,\n", - " 1.77356775e+00, 1.27211015e-02, 1.51211608e-02, -1.91400530e-03,\n", - " -1.56706835e-01]),\n", - " array([ 7.86448506e-05, 9.78412994e-01, 1.03060389e+00, 6.19085981e-03,\n", - " -1.11263143e-04, 3.34451612e-06, -9.99980830e-01, 2.25433089e-02,\n", - " -6.30415471e+00, -2.59836055e-04, 2.91067268e-04, -2.49080506e-03,\n", - " -6.78280836e-02, -2.71693200e-03, 8.82611707e-01, -3.74961317e-01,\n", - " 1.67083481e+00, -1.05894454e-02, 2.59144065e-03, 4.28210389e-02,\n", - " 1.74593873e+00, 1.24656820e-02, 1.50075988e-02, -1.91330087e-03,\n", - " -1.56411963e-01]),\n", - " array([ 7.58487097e-05, 9.79290579e-01, 1.03021019e+00, 5.37013314e-03,\n", - " -1.06030764e-04, 2.17652422e-06, -9.99985575e-01, 2.25860471e-02,\n", - " -6.30243840e+00, -2.47658532e-04, 3.05960875e-04, -2.49271973e-03,\n", - " -6.79841832e-02, -2.71655389e-03, 8.82076905e-01, -3.83524258e-01,\n", - " 1.64148058e+00, -1.04745858e-02, 2.45381845e-03, 4.27381811e-02,\n", - " 1.71630647e+00, 1.21775228e-02, 1.48936078e-02, -1.91467217e-03,\n", - " -1.56099574e-01]),\n", - " array([ 7.30532512e-05, 9.80168169e-01, 1.02981017e+00, 4.56500518e-03,\n", - " -1.00861178e-04, 1.07589221e-06, -9.99989575e-01, 2.26287018e-02,\n", - " -6.30075360e+00, -2.35800008e-04, 3.20740197e-04, -2.49463778e-03,\n", - " -6.81399541e-02, -2.71645906e-03, 8.81521075e-01, -3.91289489e-01,\n", - " 1.61027562e+00, -1.03481875e-02, 2.31646388e-03, 4.26547010e-02,\n", - " 1.68480693e+00, 1.18585249e-02, 1.47793216e-02, -1.91805414e-03,\n", - " -1.55770897e-01]),\n", - " array([ 7.02585712e-05, 9.81045763e-01, 1.02940455e+00, 3.77633527e-03,\n", - " -9.57599080e-05, 4.21519723e-08, -9.99992865e-01, 2.26712728e-02,\n", - " -6.29910202e+00, -2.24289421e-04, 3.35405067e-04, -2.49656116e-03,\n", - " -6.82953812e-02, -2.71663064e-03, 8.80947169e-01, -3.98278856e-01,\n", - " 1.57735337e+00, -1.02108402e-02, 2.17998392e-03, 4.25710181e-02,\n", - " 1.65157480e+00, 1.15105870e-02, 1.46648703e-02, -1.92338131e-03,\n", - " -1.55427150e-01]),\n", - " array([ 6.74647477e-05, 9.81923357e-01, 1.02899408e+00, 3.00491677e-03,\n", - " -9.07321759e-05, -9.25440594e-07, -9.99995481e-01, 2.27137603e-02,\n", - " -6.29748528e+00, -2.13153819e-04, 3.49955447e-04, -2.49849175e-03,\n", - " -6.84504508e-02, -2.71705160e-03, 8.80358038e-01, -4.04514655e-01,\n", - " 1.54284573e+00, -1.00631374e-02, 2.04494087e-03, 4.24875279e-02,\n", - " 1.61674313e+00, 1.11356011e-02, 1.45503800e-02, -1.93058806e-03,\n", - " -1.55069535e-01]),\n", - " array([ 6.46718404e-05, 9.82800946e-01, 1.02857944e+00, 2.25147793e-03,\n", - " -8.57829053e-05, -1.82788339e-06, -9.99997462e-01, 2.27561649e-02,\n", - " -6.29590484e+00, -2.02418372e-04, 3.64391420e-04, -2.50043136e-03,\n", - " -6.86051500e-02, -2.71770486e-03, 8.79756419e-01, -4.10019568e-01,\n", - " 1.50688273e+00, -9.90567487e-03, 1.91185194e-03, 4.24046012e-02,\n", - " 1.58044317e+00, 1.07354474e-02, 1.44359727e-02, -1.93960867e-03,\n", - " -1.54699236e-01]),\n", - " array([ 6.18798932e-05, 9.83678522e-01, 1.02816131e+00, 1.51668299e-03,\n", - " -8.09167185e-05, -2.66640585e-06, -9.99998847e-01, 2.27984875e-02,\n", - " -6.29436203e+00, -1.92106382e-04, 3.78713187e-04, -2.50238174e-03,\n", - " -6.87594674e-02, -2.71857335e-03, 8.79144922e-01, -4.14816597e-01,\n", - " 1.46959236e+00, -9.73904951e-03, 1.78118924e-03, 4.23225838e-02,\n", - " 1.54280404e+00, 1.03119903e-02, 1.43217665e-02, -1.95037753e-03,\n", - " -1.54317417e-01]),\n", - " array([ 5.90889341e-05, 9.84556074e-01, 1.02774035e+00, 8.01133253e-04,\n", - " -7.61379366e-05, -3.44244684e-06, -9.99999676e-01, 2.28407293e-02,\n", - " -6.29285808e+00, -1.82239307e-04, 3.92921062e-04, -2.50434457e-03,\n", - " -6.89133926e-02, -2.71964019e-03, 8.78526029e-01, -4.18929004e-01,\n", - " 1.43110031e+00, -9.56385772e-03, 1.65337998e-03, 4.22417956e-02,\n", - " 1.50395258e+00, 9.86707449e-03, 1.42078751e-02, -1.96282922e-03,\n", - " -1.53925223e-01]),\n", - " array([ 5.62989770e-05, 9.85433593e-01, 1.02731718e+00, 1.05368382e-04,\n", - " -7.14505805e-05, -4.15763273e-06, -9.99999992e-01, 2.28828919e-02,\n", - " -6.29139407e+00, -1.72836787e-04, 4.07015470e-04, -2.50632147e-03,\n", - " -6.90669164e-02, -2.72088868e-03, 8.77902085e-01, -4.22380252e-01,\n", - " 1.39152977e+00, -9.38069415e-03, 1.52880708e-03, 4.21625309e-02,\n", - " 1.46401308e+00, 9.40252053e-03, 1.40944079e-02, -1.97689868e-03,\n", - " -1.53523773e-01]),\n", - " array([ 5.35100229e-05, 9.86311066e-01, 1.02689239e+00, -5.70132259e-04,\n", - " -6.68583720e-05, -4.81375592e-06, -9.99999835e-01, 2.29249769e-02,\n", - " -6.28997096e+00, -1.63916665e-04, 4.20996940e-04, -2.50831399e-03,\n", - " -6.92200306e-02, -2.72230247e-03, 8.77275292e-01, -4.25193945e-01,\n", - " 1.35100121e+00, -9.19015040e-03, 1.40780985e-03, 4.20850583e-02,\n", - " 1.42310711e+00, 8.92012155e-03, 1.39814701e-02, -1.99252126e-03,\n", - " -1.53114162e-01]),\n", - " array([ 5.07220605e-05, 9.87188479e-01, 1.02646657e+00, -1.22494817e-03,\n", - " -6.23647361e-05, -5.41275378e-06, -9.99999248e-01, 2.29669865e-02,\n", - " -6.28858961e+00, -1.55495025e-04, 4.34866102e-04, -2.51032362e-03,\n", - " -6.93727280e-02, -2.72386556e-03, 8.76647710e-01, -4.27393776e-01,\n", - " 1.30963224e+00, -8.99281371e-03, 1.29068506e-03, 4.20096205e-02,\n", - " 1.38135334e+00, 8.42163977e-03, 1.38691626e-02, -2.00963290e-03,\n", - " -1.52697459e-01]),\n", - " array([ 4.79350677e-05, 9.88065819e-01, 1.02604027e+00, -1.85871618e-03,\n", - " -5.79728035e-05, -5.95668825e-06, -9.99998271e-01, 2.30089230e-02,\n", - " -6.28725074e+00, -1.47586222e-04, 4.48623684e-04, -2.51235179e-03,\n", - " -6.95250027e-02, -2.72556242e-03, 8.76021252e-01, -4.29003470e-01,\n", - " 1.26753743e+00, -8.78926572e-03, 1.17768811e-03, 4.19364349e-02,\n", - " 1.33886738e+00, 7.90880324e-03, 1.37575815e-02, -2.02817016e-03,\n", - " -1.52274702e-01]),\n", - " array([ 4.51490124e-05, 9.88943071e-01, 1.02561402e+00, -2.47112886e-03,\n", - " -5.36854141e-05, -6.44772607e-06, -9.99996945e-01, 2.30507887e-02,\n", - " -6.28595498e+00, -1.40202919e-04, 4.62270503e-04, -2.51439986e-03,\n", - " -6.96768496e-02, -2.72737800e-03, 8.75397687e-01, -4.30046739e-01,\n", - " 1.22482815e+00, -8.58008133e-03, 1.06903445e-03, 4.18656937e-02,\n", - " 1.29576160e+00, 7.38330296e-03, 1.36468190e-02, -2.04807033e-03,\n", - " -1.51846903e-01]),\n", - " array([ 4.23638540e-05, 9.89820218e-01, 1.02518832e+00, -3.06193288e-03,\n", - " -4.95051211e-05, -6.88811982e-06, -9.99995311e-01, 2.30925862e-02,\n", - " -6.28470283e+00, -1.33356129e-04, 4.75807465e-04, -2.51646913e-03,\n", - " -6.98282647e-02, -2.72929782e-03, 8.74778636e-01, -4.30547231e-01,\n", - " 1.18161246e+00, -8.36582752e-03, 9.64901144e-04, 4.17975649e-02,\n", - " 1.25214504e+00, 6.84679014e-03, 1.35369626e-02, -2.06927154e-03,\n", - " -1.51415040e-01]),\n", - " array([ 3.95795438e-05, 9.90697245e-01, 1.02476365e+00, -3.63092722e-03,\n", - " -4.54341956e-05, -7.28018976e-06, -9.99993407e-01, 2.31343184e-02,\n", - " -6.28349471e+00, -1.27055255e-04, 4.89235561e-04, -2.51856084e-03,\n", - " -6.99792447e-02, -2.73130797e-03, 8.74165580e-01, -4.30528483e-01,\n", - " 1.13799498e+00, -8.14706228e-03, 8.65428549e-04, 4.17321922e-02,\n", - " 1.20812325e+00, 6.30087372e-03, 1.34280952e-02, -2.09171279e-03,\n", - " -1.50980061e-01]),\n", - " array([ 3.67960263e-05, 9.91574136e-01, 1.02434047e+00, -4.17796147e-03,\n", - " -4.14746317e-05, -7.62630660e-06, -9.99991271e-01, 2.31759881e-02,\n", - " -6.28233091e+00, -1.21308137e-04, 5.02555856e-04, -2.52067618e-03,\n", - " -7.01297876e-02, -2.73339516e-03, 8.73559855e-01, -4.30013881e-01,\n", - " 1.09407676e+00, -7.92433357e-03, 7.70722153e-04, 4.16696966e-02,\n", - " 1.16379821e+00, 5.74711810e-03, 1.33202956e-02, -2.11533405e-03,\n", - " -1.50542881e-01]),\n", - " array([ 3.40132405e-05, 9.92450875e-01, 1.02391921e+00, -4.70293395e-03,\n", - " -3.76281520e-05, -7.92887521e-06, -9.99988940e-01, 2.32175983e-02,\n", - " -6.28121164e+00, -1.16121096e-04, 5.15769494e-04, -2.52281626e-03,\n", - " -7.02798920e-02, -2.73554677e-03, 8.72962662e-01, -4.29026621e-01,\n", - " 1.04995524e+00, -7.69817833e-03, 6.80854488e-04, 4.16101766e-02,\n", - " 1.11926822e+00, 5.18704116e-03, 1.32136379e-02, -2.14007631e-03,\n", - " -1.50104382e-01]),\n", - " array([ 3.12311198e-05, 9.93327444e-01, 1.02350029e+00, -5.20578987e-03,\n", - " -3.38962138e-05, -8.19031930e-06, -9.99986449e-01, 2.32591520e-02,\n", - " -6.28013701e+00, -1.11498984e-04, 5.28877686e-04, -2.52498214e-03,\n", - " -7.04295574e-02, -2.73775083e-03, 8.72375067e-01, -4.27589666e-01,\n", - " 1.00572413e+00, -7.46912160e-03, 5.95867127e-04, 4.15537093e-02,\n", - " 1.07462786e+00, 4.62211243e-03, 1.31081922e-02, -2.16588163e-03,\n", - " -1.49665410e-01]),\n", - " array([ 2.84495941e-05, 9.94203827e-01, 1.02308409e+00, -5.68651947e-03,\n", - " -3.02800162e-05, -8.41306716e-06, -9.99983831e-01, 2.33006524e-02,\n", - " -6.27910705e+00, -1.07445232e-04, 5.41881710e-04, -2.52717483e-03,\n", - " -7.05787842e-02, -2.73999605e-03, 8.71798007e-01, -4.25725713e-01,\n", - " 9.61473378e-01, -7.23767563e-03, 5.15772744e-04, 4.15003515e-02,\n", - " 1.02996787e+00, 4.05375154e-03, 1.30040239e-02, -2.19269320e-03,\n", - " -1.49226777e-01]),\n", - " array([ 2.56685895e-05, 9.95080008e-01, 1.02267097e+00, -6.14515602e-03,\n", - " -2.67805062e-05, -8.59953839e-06, -9.99981118e-01, 2.33421025e-02,\n", - " -6.27812167e+00, -1.03961905e-04, 5.54782904e-04, -2.52939529e-03,\n", - " -7.07275734e-02, -2.74227186e-03, 8.71232296e-01, -4.23457161e-01,\n", - " 9.17289092e-01, -7.00433907e-03, 4.40557197e-04, 4.14501407e-02,\n", - " 9.85375131e-01, 3.48332679e-03, 1.29011942e-02, -2.22045539e-03,\n", - " -1.48789261e-01]),\n", - " array([ 2.28880299e-05, 9.95955972e-01, 1.02226128e+00, -6.58177397e-03,\n", - " -2.33983869e-05, -8.75213170e-06, -9.99978340e-01, 2.33835056e-02,\n", - " -6.27718074e+00, -1.01049751e-04, 5.67582665e-04, -2.53164440e-03,\n", - " -7.08759270e-02, -2.74456836e-03, 8.70678629e-01, -4.20806078e-01,\n", - " 8.73253515e-01, -6.76959629e-03, 3.70181656e-04, 4.14030962e-02,\n", - " 9.40932635e-01, 2.91215407e-03, 1.27997602e-02, -2.24911377e-03,\n", - " -1.48353603e-01]),\n", - " array([ 2.01078372e-05, 9.96831702e-01, 1.02185533e+00, -6.99648694e-03,\n", - " -2.01341247e-05, -8.87321378e-06, -9.99975524e-01, 2.34248648e-02,\n", - " -6.27628402e+00, -9.87082554e-05, 5.80282439e-04, -2.53392301e-03,\n", - " -7.10238476e-02, -2.74687635e-03, 8.70137589e-01, -4.17794176e-01,\n", - " 8.29445001e-01, -6.53391664e-03, 3.04584713e-04, 4.13592201e-02,\n", - " 8.96719437e-01, 2.34149585e-03, 1.26997746e-02, -2.27861516e-03,\n", - " -1.47920510e-01]),\n", - " array([ 1.73279322e-05, 9.97707183e-01, 1.02145344e+00, -7.38944580e-03,\n", - " -1.69879578e-05, -8.96510920e-06, -9.99972697e-01, 2.34661833e-02,\n", - " -6.27543121e+00, -9.69356950e-05, 5.92883726e-04, -2.53623192e-03,\n", - " -7.11713382e-02, -2.74918731e-03, 8.69609650e-01, -4.14442779e-01,\n", - " 7.85937993e-01, -6.29775390e-03, 2.43684498e-04, 4.13184987e-02,\n", - " 8.52810652e-01, 1.77256042e-03, 1.26012862e-02, -2.30890764e-03,\n", - " -1.47490649e-01]),\n", - " array([ 1.45482351e-05, 9.98582402e-01, 1.02105589e+00, -7.76083668e-03,\n", - " -1.39599040e-05, -9.03009131e-06, -9.99969884e-01, 2.35074642e-02,\n", - " -6.27462193e+00, -9.57291937e-05, 6.05388065e-04, -2.53857186e-03,\n", - " -7.13184029e-02, -2.75149341e-03, 8.69095191e-01, -4.10772806e-01,\n", - " 7.42803026e-01, -6.06154571e-03, 1.87380759e-04, 4.12809036e-02,\n", - " 8.09277446e-01, 1.20650133e-03, 1.25043396e-02, -2.33994060e-03,\n", - " -1.47064657e-01]),\n", - " array([ 1.17686662e-05, 9.99457344e-01, 1.02066292e+00, -8.11087905e-03,\n", - " -1.10497693e-05, -9.07037426e-06, -9.99967106e-01, 2.35487106e-02,\n", - " -6.27385574e+00, -9.50847767e-05, 6.17797041e-04, -2.54094353e-03,\n", - " -7.14650460e-02, -2.75378748e-03, 8.68594493e-01, -4.06804746e-01,\n", - " 7.00106727e-01, -5.82571310e-03, 1.35556915e-04, 4.12463929e-02,\n", - " 7.66187047e-01, 6.44416962e-04, 1.24089755e-02, -2.37166477e-03,\n", - " -1.46643130e-01]),\n", - " array([ 8.98914642e-06, 1.00033199e+00, 1.02027478e+00, -8.43982372e-03,\n", - " -8.25715724e-06, -9.08810587e-06, -9.99964384e-01, 2.35899255e-02,\n", - " -6.27313214e+00, -9.49974264e-05, 6.30112271e-04, -2.54334756e-03,\n", - " -7.16112726e-02, -2.75606299e-03, 8.68107753e-01, -4.02558636e-01,\n", - " 6.57911836e-01, -5.59066007e-03, 8.80820425e-05, 4.12149123e-02,\n", - " 7.23602758e-01, 8.73503118e-05, 1.23152306e-02, -2.40403219e-03,\n", - " -1.46226632e-01]),\n", - " array([ 6.20959758e-06, 1.00120634e+00, 1.01989170e+00, -8.74795098e-03,\n", - " -5.58147693e-06, -9.08536159e-06, -9.99961736e-01, 2.36311119e-02,\n", - " -6.27245056e+00, -9.54611375e-05, 6.42335409e-04, -2.54578456e-03,\n", - " -7.17570883e-02, -2.75831406e-03, 8.67635086e-01, -3.98054050e-01,\n", - " 6.16277233e-01, -5.35677327e-03, 4.48128207e-05, 4.11863964e-02,\n", - " 6.81583986e-01, -4.63711076e-04, 1.22231380e-02, -2.43699625e-03,\n", - " -1.45815690e-01]),\n", - " array([ 3.42994307e-06, 1.00208038e+00, 1.01951387e+00, -9.03556862e-03,\n", - " -3.02195268e-06, -9.06413932e-06, -9.99959178e-01, 2.36722727e-02,\n", - " -6.27181037e+00, -9.64689725e-05, 6.54468136e-04, -2.54825507e-03,\n", - " -7.19024991e-02, -2.76053539e-03, 8.67176535e-01, -3.93310078e-01,\n", - " 5.75257969e-01, -5.12442167e-03, 5.59539280e-06, 4.11607701e-02,\n", - " 6.40186276e-01, -1.00783503e-03, 1.21327270e-02, -2.47051174e-03,\n", - " -1.45410795e-01]),\n", - " array([ 6.50108120e-07, 1.00295408e+00, 1.01914149e+00, -9.30301005e-03,\n", - " -5.77632874e-07, -9.02635511e-06, -9.99956726e-01, 2.37134106e-02,\n", - " -6.27121091e+00, -9.80131170e-05, 6.66512159e-04, -2.55075960e-03,\n", - " -7.20475115e-02, -2.76272227e-03, 8.66732075e-01, -3.88345316e-01,\n", - " 5.34905313e-01, -4.89395635e-03, -2.97328452e-05, 4.11379491e-02,\n", - " 5.99461357e-01, -1.54414451e-03, 1.20440232e-02, -2.50453478e-03,\n", - " -1.45012406e-01]),\n", - " array([-2.12997985e-06, 1.00382746e+00, 1.01877471e+00, -9.55063247e-03,\n", - " 1.75260079e-06, -8.97383977e-06, -9.99954392e-01, 2.37545285e-02,\n", - " -6.27065145e+00, -1.00084934e-04, 6.78469208e-04, -2.55329863e-03,\n", - " -7.21921325e-02, -2.76487056e-03, 8.66301619e-01, -3.83177855e-01,\n", - " 4.95266805e-01, -4.66571037e-03, -6.13415403e-05, 4.11178418e-02,\n", - " 5.59457193e-01, -2.07181725e-03, 1.19570489e-02, -2.53902288e-03,\n", - " -1.44620945e-01]),\n", - " array([-4.91039088e-06, 1.00470048e+00, 1.01841369e+00, -9.77881499e-03,\n", - " 3.97002407e-06, -8.90833623e-06, -9.99952186e-01, 2.37956288e-02,\n", - " -6.27013124e+00, -1.02675019e-04, 6.90341031e-04, -2.55587256e-03,\n", - " -7.23363693e-02, -2.76697664e-03, 8.65885026e-01, -3.77825266e-01,\n", - " 4.56386309e-01, -4.43999860e-03, -8.94057691e-05, 4.11003498e-02,\n", - " 5.20218042e-01, -2.59008525e-03, 1.18718227e-02, -2.57393493e-03,\n", - " -1.44236804e-01]),\n", - " array([-7.69119228e-06, 1.00557315e+00, 1.01805856e+00, -9.98795684e-03,\n", - " 6.07606093e-06, -8.83149763e-06, -9.99950119e-01, 2.38367142e-02,\n", - " -6.26964945e+00, -1.05773254e-04, 7.02129391e-04, -2.55848179e-03,\n", - " -7.24802296e-02, -2.76903739e-03, 8.65482108e-01, -3.72304600e-01,\n", - " 4.18304085e-01, -4.21711775e-03, -1.14104520e-04, 4.10853694e-02,\n", - " 4.81784522e-01, -3.09823416e-03, 1.17883603e-02, -2.60923118e-03,\n", - " -1.43860339e-01]),\n", - " array([-1.04724484e-05, 1.00644546e+00, 1.01770945e+00, -1.01784756e-02,\n", - " 8.07227432e-06, -8.74488622e-06, -9.99948198e-01, 2.38777870e-02,\n", - " -6.26920526e+00, -1.09368856e-04, 7.13836065e-04, -2.56112666e-03,\n", - " -7.26237215e-02, -2.77105017e-03, 8.65092632e-01, -3.66632377e-01,\n", - " 3.81056860e-01, -3.99734629e-03, -1.35619274e-04, 4.10727922e-02,\n", - " 4.44193688e-01, -3.59560256e-03, 1.17066738e-02, -2.64487326e-03,\n", - " -1.43491874e-01]),\n", - " array([-1.32542202e-05, 1.00731740e+00, 1.01736645e+00, -1.03508055e-02,\n", - " 9.96035706e-06, -8.64997278e-06, -9.99946429e-01, 2.39188495e-02,\n", - " -6.26879778e+00, -1.13450437e-04, 7.25462838e-04, -2.56380749e-03,\n", - " -7.27668532e-02, -2.77301277e-03, 8.64716328e-01, -3.60824582e-01,\n", - " 3.44677903e-01, -3.78094459e-03, -1.54132683e-04, 4.10625063e-02,\n", - " 4.07479105e-01, -4.08158107e-03, 1.16267726e-02, -2.68082417e-03,\n", - " -1.43131703e-01]),\n", - " array([-1.60365656e-05, 1.00818897e+00, 1.01702966e+00, -1.05053957e-02,\n", - " 1.17421226e-05, -8.54813677e-06, -9.99944817e-01, 2.39599039e-02,\n", - " -6.26842611e+00, -1.18006049e-04, 7.37011500e-04, -2.56652454e-03,\n", - " -7.29096333e-02, -2.77492343e-03, 8.64352894e-01, -3.54896663e-01,\n", - " 3.09197113e-01, -3.56815497e-03, -1.69827354e-04, 4.10543973e-02,\n", - " 3.71670939e-01, -4.55561149e-03, 1.15486628e-02, -2.71704824e-03,\n", - " -1.42780089e-01]),\n", - " array([-1.88195390e-05, 1.00906016e+00, 1.01669915e+00, -1.06427085e-02,\n", - " 1.34194963e-05, -8.44066693e-06, -9.99943365e-01, 2.40009522e-02,\n", - " -6.26808931e+00, -1.23023234e-04, 7.48483848e-04, -2.56927805e-03,\n", - " -7.30520705e-02, -2.77678072e-03, 8.64002000e-01, -3.48863529e-01,\n", - " 2.74641104e-01, -3.35920188e-03, -1.82884736e-04, 4.10483488e-02,\n", - " 3.36796037e-01, -5.01718571e-03, 1.14723478e-02, -2.75351118e-03,\n", - " -1.42437264e-01]),\n", - " array([-2.16031911e-05, 1.00993096e+00, 1.01637497e+00, -1.07632183e-02,\n", - " 1.49945061e-05, -8.32876246e-06, -9.99942075e-01, 2.40419965e-02,\n", - " -6.26778643e+00, -1.28489079e-04, 7.59881677e-04, -2.57206823e-03,\n", - " -7.31941740e-02, -2.77858363e-03, 8.63663295e-01, -3.42739550e-01,\n", - " 2.41033299e-01, -3.15429212e-03, -1.93484102e-04, 4.10442436e-02,\n", - " 3.02878032e-01, -5.46584464e-03, 1.13978283e-02, -2.79017999e-03,\n", - " -1.42103432e-01]),\n", - " array([-2.43875691e-05, 1.01080137e+00, 1.01605719e+00, -1.08674092e-02,\n", - " 1.64692742e-05, -8.21353462e-06, -9.99940948e-01, 2.40830385e-02,\n", - " -6.26751650e+00, -1.34390256e-04, 7.71206779e-04, -2.57489525e-03,\n", - " -7.33359527e-02, -2.78033143e-03, 8.63336410e-01, -3.36538558e-01,\n", - " 2.08394025e-01, -2.95361506e-03, -2.01801644e-04, 4.10419643e-02,\n", - " 2.69937431e-01, -5.90117704e-03, 1.13251023e-02, -2.82702303e-03,\n", - " -1.41778768e-01]),\n", - " array([-2.71727166e-05, 1.01167139e+00, 1.01574582e+00, -1.09557743e-02,\n", - " 1.78460080e-05, -8.09600871e-06, -9.99939984e-01, 2.41240798e-02,\n", - " -6.26727850e+00, -1.40713074e-04, 7.82460944e-04, -2.57775926e-03,\n", - " -7.34774162e-02, -2.78202372e-03, 8.63020959e-01, -3.30273850e-01,\n", - " 1.76740618e-01, -2.75734293e-03, -2.08009663e-04, 4.10413936e-02,\n", - " 2.37991718e-01, -6.32281821e-03, 1.12541653e-02, -2.86400992e-03,\n", - " -1.41463422e-01]),\n", - " array([-2.99586736e-05, 1.01254102e+00, 1.01544091e+00, -1.10288137e-02,\n", - " 1.91269924e-05, -7.97712644e-06, -9.99939181e-01, 2.41651223e-02,\n", - " -6.26707145e+00, -1.47443523e-04, 7.93645954e-04, -2.58066037e-03,\n", - " -7.36185737e-02, -2.78366035e-03, 8.62716550e-01, -3.23958190e-01,\n", - " 1.46087519e-01, -2.56563117e-03, -2.12275838e-04, 4.10424157e-02,\n", - " 2.07055464e-01, -6.73044877e-03, 1.11850104e-02, -2.90111159e-03,\n", - " -1.41157513e-01]),\n", - " array([-3.27454763e-05, 1.01341026e+00, 1.01514245e+00, -1.10870333e-02,\n", - " 2.03145807e-05, -7.85774861e-06, -9.99938537e-01, 2.42061672e-02,\n", - " -6.26689431e+00, -1.54567316e-04, 8.04763583e-04, -2.58359867e-03,\n", - " -7.37594348e-02, -2.78524143e-03, 8.62422781e-01, -3.17603815e-01,\n", - " 1.16446384e-01, -2.37861875e-03, -2.14762613e-04, 4.10449162e-02,\n", - " 1.77140424e-01, -7.12379323e-03, 1.11176286e-02, -2.93830023e-03,\n", - " -1.40861140e-01]),\n", - " array([-3.55331574e-05, 1.01427910e+00, 1.01485046e+00, -1.11309437e-02,\n", - " 2.14111870e-05, -7.73865807e-06, -9.99938049e-01, 2.42472160e-02,\n", - " -6.26674605e+00, -1.62069935e-04, 8.15815591e-04, -2.58657422e-03,\n", - " -7.39000092e-02, -2.78676729e-03, 8.62139248e-01, -3.11222441e-01,\n", - " 8.78261899e-02, -2.19642858e-03, -2.15626601e-04, 4.10487829e-02,\n", - " 1.48255653e-01, -7.50261863e-03, 1.10520084e-02, -2.97554927e-03,\n", - " -1.40574375e-01]),\n", - " array([-3.83217460e-05, 1.01514755e+00, 1.01456492e+00, -1.11610585e-02,\n", - " 2.24192787e-05, -7.62056276e-06, -9.99937713e-01, 2.42882699e-02,\n", - " -6.26662564e+00, -1.69936668e-04, 8.26803728e-04, -2.58958706e-03,\n", - " -7.40403064e-02, -2.78823845e-03, 8.61865546e-01, -3.04825267e-01,\n", - " 6.02333454e-02, -2.01916796e-03, -2.15018350e-04, 4.10539063e-02,\n", - " 1.20407611e-01, -7.86673308e-03, 1.09881366e-02, -3.01283336e-03,\n", - " -1.40297267e-01]),\n", - " array([-4.11112679e-05, 1.01601560e+00, 1.01428582e+00, -1.11778934e-02,\n", - " 2.33413683e-05, -7.50409913e-06, -9.99937525e-01, 2.43293300e-02,\n", - " -6.26653204e+00, -1.78152652e-04, 8.37729726e-04, -2.59263718e-03,\n", - " -7.41803363e-02, -2.78965562e-03, 8.61601273e-01, -2.98422986e-01,\n", - " 3.36717986e-02, -1.84692896e-03, -2.13081759e-04, 4.10601797e-02,\n", - " 9.36002789e-02, -8.21598425e-03, 1.09259977e-02, -3.05012834e-03,\n", - " -1.40029843e-01]),\n", - " array([-4.39017452e-05, 1.01688326e+00, 1.01401313e+00, -1.11819647e-02,\n", - " 2.41800063e-05, -7.38983553e-06, -9.99937480e-01, 2.43703975e-02,\n", - " -6.26646421e+00, -1.86702910e-04, 8.48595301e-04, -2.59572460e-03,\n", - " -7.43201084e-02, -2.79101963e-03, 8.61346029e-01, -2.92025790e-01,\n", - " 8.14315077e-03, -1.67978896e-03, -2.09953869e-04, 4.10675000e-02,\n", - " 6.78352679e-02, -8.55025793e-03, 1.08655748e-02, -3.08741125e-03,\n", - " -1.39772108e-01]),\n", - " array([-4.66931969e-05, 1.01775053e+00, 1.01374680e+00, -1.11737886e-02,\n", - " 2.49377744e-05, -7.27827588e-06, -9.99937571e-01, 2.44114733e-02,\n", - " -6.26642110e+00, -1.95572387e-04, 8.59402150e-04, -2.59884926e-03,\n", - " -7.44596324e-02, -2.79233146e-03, 8.61099423e-01, -2.85643382e-01,\n", - " -1.63532329e-02, -1.51781107e-03, -2.05764648e-04, 4.10757677e-02,\n", - " 4.31119331e-02, -8.86947642e-03, 1.08068490e-02, -3.12466026e-03,\n", - " -1.39524048e-01]),\n", - " array([-4.94856387e-05, 1.01861741e+00, 1.01348681e+00, -1.11538798e-02,\n", - " 2.56172782e-05, -7.16986319e-06, -9.99937793e-01, 2.44525582e-02,\n", - " -6.26640167e+00, -2.04745984e-04, 8.70151949e-04, -2.60201111e-03,\n", - " -7.45989181e-02, -2.79359221e-03, 8.60861071e-01, -2.79284981e-01,\n", - " -3.98201108e-02, -1.36104470e-03, -2.00636847e-04, 4.10848870e-02,\n", - " 1.94274871e-02, -9.17359706e-03, 1.07497998e-02, -3.16185466e-03,\n", - " -1.39285629e-01]),\n", - " array([-5.22790832e-05, 1.01948391e+00, 1.01323309e+00, -1.11227506e-02,\n", - " 2.62211411e-05, -7.06498333e-06, -9.99938140e-01, 2.44936530e-02,\n", - " -6.26640489e+00, -2.14208594e-04, 8.80846355e-04, -2.60521009e-03,\n", - " -7.47379749e-02, -2.79480305e-03, 8.60630598e-01, -2.72959338e-01,\n", - " -6.22622530e-02, -1.20952604e-03, -1.94685919e-04, 4.10947665e-02,\n", - " -3.22288742e-03, -9.46261059e-03, 1.06944053e-02, -3.19897486e-03,\n", - " -1.39056800e-01]),\n", - " array([-5.50735401e-05, 1.02035002e+00, 1.01298558e+00, -1.10809100e-02,\n", - " 2.67519975e-05, -6.96396868e-06, -9.99938604e-01, 2.45347583e-02,\n", - " -6.26642974e+00, -2.23945134e-04, 8.91486997e-04, -2.60844609e-03,\n", - " -7.48768124e-02, -2.79596522e-03, 8.60407644e-01, -2.66674742e-01,\n", - " -8.36863297e-02, -1.06327865e-03, -1.88019993e-04, 4.11053189e-02,\n", - " -2.48459250e-02, -9.73653967e-03, 1.06406423e-02, -3.23600231e-03,\n", - " -1.38837490e-01]),\n", - " array([-5.78690162e-05, 1.02121576e+00, 1.01274422e+00, -1.10288628e-02,\n", - " 2.72124872e-05, -6.86710178e-06, -9.99939180e-01, 2.45758747e-02,\n", - " -6.26647519e+00, -2.33940571e-04, 9.02075483e-04, -2.61171901e-03,\n", - " -7.50154400e-02, -2.79708005e-03, 8.60191856e-01, -2.60439032e-01,\n", - " -1.04100801e-01, -9.22313915e-04, -1.80739902e-04, 4.11164614e-02,\n", - " -4.54501657e-02, -9.99543724e-03, 1.05884861e-02, -3.27291952e-03,\n", - " -1.38627616e-01]),\n", - " array([-6.06655155e-05, 1.02208113e+00, 1.01250894e+00, -1.09671086e-02,\n", - " 2.76052495e-05, -6.77461898e-06, -9.99939859e-01, 2.46170029e-02,\n", - " -6.26654023e+00, -2.44179956e-04, 9.12613394e-04, -2.61502872e-03,\n", - " -7.51538671e-02, -2.79814888e-03, 8.59982898e-01, -2.54259613e-01,\n", - " -1.23515805e-01, -7.86631709e-04, -1.72939260e-04, 4.11281156e-02,\n", - " -6.50458444e-02, -1.02393850e-02, 1.05379109e-02, -3.30971001e-03,\n", - " -1.38427076e-01]),\n", - " array([-6.34630396e-05, 1.02294613e+00, 1.01227965e+00, -1.08961414e-02,\n", - " 2.79329178e-05, -6.68671401e-06, -9.99940635e-01, 2.46581431e-02,\n", - " -6.26662388e+00, -2.54648448e-04, 9.23102284e-04, -2.61837508e-03,\n", - " -7.52921028e-02, -2.79917310e-03, 8.59780447e-01, -2.48143460e-01,\n", - " -1.41943054e-01, -6.56220876e-04, -1.64704582e-04, 4.11402076e-02,\n", - " -8.36447814e-02, -1.04684918e-02, 1.04888900e-02, -3.34635828e-03,\n", - " -1.38235757e-01]),\n", - " array([-6.62615875e-05, 1.02381077e+00, 1.01205627e+00, -1.08164482e-02,\n", - " 2.81981142e-05, -6.60354152e-06, -9.99941500e-01, 2.46992957e-02,\n", - " -6.26672514e+00, -2.65331340e-04, 9.33543679e-04, -2.62175792e-03,\n", - " -7.54301563e-02, -2.80015411e-03, 8.59584193e-01, -2.42097138e-01,\n", - " -1.59395722e-01, -5.31059819e-04, -1.56115327e-04, 4.11526682e-02,\n", - " -1.01260274e-01, -1.06828921e-02, 1.04413954e-02, -3.38284977e-03,\n", - " -1.38053531e-01]),\n", - " array([-6.90611559e-05, 1.02467505e+00, 1.01183872e+00, -1.07285091e-02,\n", - " 2.84034450e-05, -6.52522029e-06, -9.99942447e-01, 2.47404612e-02,\n", - " -6.26684305e+00, -2.76214085e-04, 9.43939078e-04, -2.62517710e-03,\n", - " -7.55680366e-02, -2.80109331e-03, 8.59393844e-01, -2.36126810e-01,\n", - " -1.75888343e-01, -4.11117096e-04, -1.47244473e-04, 4.11654324e-02,\n", - " -1.17906992e-01, -1.08827445e-02, 1.03953984e-02, -3.41917088e-03,\n", - " -1.37880257e-01]),\n", - " array([-7.18617395e-05, 1.02553898e+00, 1.01162688e+00, -1.06327962e-02,\n", - " 2.85514958e-05, -6.45183665e-06, -9.99943470e-01, 2.47816396e-02,\n", - " -6.26697665e+00, -2.87282315e-04, 9.54289947e-04, -2.62863240e-03,\n", - " -7.57057524e-02, -2.80199212e-03, 8.59209120e-01, -2.30238251e-01,\n", - " -1.91436707e-01, -2.96351943e-04, -1.38158291e-04, 4.11784399e-02,\n", - " -1.33600869e-01, -1.10682303e-02, 1.03508696e-02, -3.45530887e-03,\n", - " -1.37715787e-01]),\n", - " array([-7.46633309e-05, 1.02640257e+00, 1.01142067e+00, -1.05297731e-02,\n", - " 2.86448272e-05, -6.38344763e-06, -9.99944560e-01, 2.48228312e-02,\n", - " -6.26712501e+00, -2.98521866e-04, 9.64597726e-04, -2.63212366e-03,\n", - " -7.58433124e-02, -2.80285193e-03, 8.59029759e-01, -2.24436860e-01,\n", - " -2.06057758e-01, -1.86714843e-04, -1.28916712e-04, 4.11916346e-02,\n", - " -1.48359008e-01, -1.12395514e-02, 1.03077786e-02, -3.49125186e-03,\n", - " -1.37559958e-01]),\n", - " array([-7.74659206e-05, 1.02726582e+00, 1.01121999e+00, -1.04198944e-02,\n", - " 2.86859707e-05, -6.32008393e-06, -9.99945711e-01, 2.48640362e-02,\n", - " -6.26728721e+00, -3.09918796e-04, 9.74863821e-04, -2.63565065e-03,\n", - " -7.59807249e-02, -2.80367411e-03, 8.58855513e-01, -2.18727675e-01,\n", - " -2.19769496e-01, -8.21481024e-05, -1.19573675e-04, 4.12049650e-02,\n", - " -1.62199574e-01, -1.13969299e-02, 1.02660947e-02, -3.52698884e-03,\n", - " -1.37412599e-01]),\n", - " array([-8.02694977e-05, 1.02812873e+00, 1.01102471e+00, -1.03036052e-02,\n", - " 2.86774251e-05, -6.26175287e-06, -9.99946916e-01, 2.49052546e-02,\n", - " -6.26746235e+00, -3.21459402e-04, 9.85089607e-04, -2.63921315e-03,\n", - " -7.61179985e-02, -2.80446001e-03, 8.58686148e-01, -2.13115385e-01,\n", - " -2.32590880e-01, 1.74136049e-05, -1.10177376e-04, 4.12183835e-02,\n", - " -1.75141701e-01, -1.15406055e-02, 1.02257864e-02, -3.56250955e-03,\n", - " -1.37273532e-01]),\n", - " array([-8.30740495e-05, 1.02899133e+00, 1.01083474e+00, -1.01813408e-02,\n", - " 2.86216530e-05, -6.20844104e-06, -9.99948168e-01, 2.49464864e-02,\n", - " -6.26764955e+00, -3.33130237e-04, 9.95276429e-04, -2.64281096e-03,\n", - " -7.62551411e-02, -2.80521094e-03, 8.58521446e-01, -2.07604343e-01,\n", - " -2.44541736e-01, 1.12042690e-04, -1.00770541e-04, 4.12318467e-02,\n", - " -1.87205396e-01, -1.16708349e-02, 1.01868219e-02, -3.59780455e-03,\n", - " -1.37142570e-01]),\n", - " array([-8.58795618e-05, 1.02985360e+00, 1.01064995e+00, -1.00535260e-02,\n", - " 2.85210773e-05, -6.16011691e-06, -9.99949462e-01, 2.49877318e-02,\n", - " -6.26784796e+00, -3.44918127e-04, 1.00542560e-03, -2.64644382e-03,\n", - " -7.63921606e-02, -2.80592819e-03, 8.58361204e-01, -2.02198577e-01,\n", - " -2.55642664e-01, 2.01818111e-04, -9.13907562e-05, 4.12453152e-02,\n", - " -1.98411448e-01, -1.17878901e-02, 1.01491689e-02, -3.63286511e-03,\n", - " -1.37019520e-01]),\n", - " array([-8.86860191e-05, 1.03071557e+00, 1.01047022e+00, -9.92057514e-03,\n", - " 2.83780783e-05, -6.11673327e-06, -9.99950789e-01, 2.50289905e-02,\n", - " -6.26805675e+00, -3.56810184e-04, 1.01553839e-03, -2.65011151e-03,\n", - " -7.65290648e-02, -2.80661298e-03, 8.58205233e-01, -1.96901808e-01,\n", - " -2.65914948e-01, 2.86824848e-04, -8.20707263e-05, 4.12587531e-02,\n", - " -2.08781337e-01, -1.18920569e-02, 1.01127949e-02, -3.66768322e-03,\n", - " -1.36904181e-01]),\n", - " array([-9.14934048e-05, 1.03157724e+00, 1.01029545e+00, -9.78289159e-03,\n", - " 2.81949913e-05, -6.07822950e-06, -9.99952146e-01, 2.50702626e-02,\n", - " -6.26827508e+00, -3.68793817e-04, 1.02561606e-03, -2.65381376e-03,\n", - " -7.66658611e-02, -2.80726652e-03, 8.58053357e-01, -1.91717460e-01,\n", - " -2.75380476e-01, 3.67153383e-04, -7.28386254e-05, 4.12721285e-02,\n", - " -2.18337152e-01, -1.19836338e-02, 1.00776672e-02, -3.70225154e-03,\n", - " -1.36796350e-01]),\n", - " array([-9.43017010e-05, 1.03243860e+00, 1.01012550e+00, -9.64086746e-03,\n", - " 2.79741037e-05, -6.04453364e-06, -9.99953525e-01, 2.51115481e-02,\n", - " -6.26850218e+00, -3.80856748e-04, 1.03565981e-03, -2.65755032e-03,\n", - " -7.68025569e-02, -2.80788994e-03, 8.57905413e-01, -1.86648672e-01,\n", - " -2.84061655e-01, 4.42899204e-04, -6.37183577e-05, 4.12854125e-02,\n", - " -2.27101502e-01, -1.20629306e-02, 1.00437529e-02, -3.73656339e-03,\n", - " -1.36695817e-01]),\n", - " array([-9.71108889e-05, 1.03329969e+00, 1.00996025e+00, -9.49488347e-03,\n", - " 2.77176528e-05, -6.01556442e-06, -9.99954922e-01, 2.51528466e-02,\n", - " -6.26873728e+00, -3.92987015e-04, 1.04567083e-03, -2.66132094e-03,\n", - " -7.69391593e-02, -2.80848434e-03, 8.57761253e-01, -1.81698312e-01,\n", - " -2.91981329e-01, 5.14162305e-04, -5.47299215e-05, 4.12985799e-02,\n", - " -2.35097443e-01, -1.21302672e-02, 1.00110188e-02, -3.77061270e-03,\n", - " -1.36602368e-01]),\n", - " array([-9.99209490e-05, 1.03416049e+00, 1.00979957e+00, -9.34530876e-03,\n", - " 2.74278242e-05, -5.99123299e-06, -9.99956331e-01, 2.51941582e-02,\n", - " -6.26897963e+00, -4.05172987e-04, 1.05565026e-03, -2.66512533e-03,\n", - " -7.70756751e-02, -2.80905077e-03, 8.57620739e-01, -1.76868991e-01,\n", - " -2.99162707e-01, 5.81046712e-04, -4.58896650e-05, 4.13116084e-02,\n", - " -2.42348394e-01, -1.21859723e-02, 9.97943197e-03, -3.80439401e-03,\n", - " -1.36515788e-01]),\n", - " array([-1.02731861e-04, 1.03502101e+00, 1.00964333e+00, -9.19250068e-03,\n", - " 2.71067496e-05, -5.97144465e-06, -9.99957748e-01, 2.52354827e-02,\n", - " -6.26922851e+00, -4.17403370e-04, 1.06559922e-03, -2.66896323e-03,\n", - " -7.72121109e-02, -2.80959022e-03, 8.57483744e-01, -1.72163073e-01,\n", - " -3.05629289e-01, 6.43660022e-04, -3.72106188e-05, 4.13244785e-02,\n", - " -2.48878070e-01, -1.22303824e-02, 9.94895935e-03, -3.83790240e-03,\n", - " -1.36435859e-01]),\n", - " array([-1.05543603e-04, 1.03588128e+00, 1.00949140e+00, -9.03680474e-03,\n", - " 2.67565054e-05, -5.95610030e-06, -9.99959167e-01, 2.52768199e-02,\n", - " -6.26948322e+00, -4.29667210e-04, 1.07551879e-03, -2.67283437e-03,\n", - " -7.73484733e-02, -2.81010364e-03, 8.57350153e-01, -1.67582687e-01,\n", - " -3.11404795e-01, 7.02112952e-04, -2.87027689e-05, 4.13371736e-02,\n", - " -2.54710409e-01, -1.22638403e-02, 9.91956799e-03, -3.87113349e-03,\n", - " -1.36362359e-01]),\n", - " array([-1.08356154e-04, 1.03674128e+00, 1.00934365e+00, -8.87855454e-03,\n", - " 2.63791116e-05, -5.94509784e-06, -9.99960584e-01, 2.53181696e-02,\n", - " -6.26974309e+00, -4.41953905e-04, 1.08541002e-03, -2.67673845e-03,\n", - " -7.74847684e-02, -2.81059191e-03, 8.57219861e-01, -1.63129745e-01,\n", - " -3.16513100e-01, 7.56518912e-04, -2.03733330e-05, 4.13496796e-02,\n", - " -2.59869501e-01, -1.22866945e-02, 9.89122507e-03, -3.90408341e-03,\n", - " -1.36295068e-01]),\n", - " array([-1.11169492e-04, 1.03760104e+00, 1.00919995e+00, -8.71807167e-03,\n", - " 2.59765302e-05, -5.93833340e-06, -9.99961997e-01, 2.53595316e-02,\n", - " -6.27000747e+00, -4.54253202e-04, 1.09527391e-03, -2.68067520e-03,\n", - " -7.76210021e-02, -2.81105587e-03, 8.57092774e-01, -1.58805944e-01,\n", - " -3.20978171e-01, 8.06993590e-04, -1.22270392e-05, 4.13619848e-02,\n", - " -2.64379533e-01, -1.22992978e-02, 9.86389795e-03, -3.93674875e-03,\n", - " -1.36233763e-01]),\n", - " array([-1.13983595e-04, 1.03846055e+00, 1.00906017e+00, -8.55566572e-03,\n", - " 2.55506647e-05, -5.93570242e-06, -9.99963399e-01, 2.54009056e-02,\n", - " -6.27027573e+00, -4.66555209e-04, 1.10511147e-03, -2.68464432e-03,\n", - " -7.77571803e-02, -2.81149631e-03, 8.56968803e-01, -1.54612786e-01,\n", - " -3.24824006e-01, 8.53654548e-04, -4.26638137e-06, 4.13740798e-02,\n", - " -2.68264719e-01, -1.23020063e-02, 9.83755426e-03, -3.96912657e-03,\n", - " -1.36178222e-01]),\n", - " array([-1.16798438e-04, 1.03931982e+00, 1.00892416e+00, -8.39163432e-03,\n", - " 2.51033590e-05, -5.93710067e-06, -9.99964789e-01, 2.54422916e-02,\n", - " -6.27054728e+00, -4.78850387e-04, 1.11492363e-03, -2.68864554e-03,\n", - " -7.78933086e-02, -2.81191398e-03, 8.56847871e-01, -1.50551584e-01,\n", - " -3.28074576e-01, 8.96620848e-04, 3.50813288e-06, 4.13859570e-02,\n", - " -2.71549251e-01, -1.22951787e-02, 9.81216187e-03, -4.00121434e-03,\n", - " -1.36128224e-01]),\n", - " array([-1.19614001e-04, 1.04017887e+00, 1.00879179e+00, -8.22626314e-03,\n", - " 2.46363973e-05, -5.94242510e-06, -9.99966163e-01, 2.54836892e-02,\n", - " -6.27082154e+00, -4.91129562e-04, 1.12471132e-03, -2.69267855e-03,\n", - " -7.80293921e-02, -2.81230956e-03, 8.56729907e-01, -1.46623478e-01,\n", - " -3.30753774e-01, 9.36012683e-04, 1.10977587e-05, 4.13976108e-02,\n", - " -2.74257239e-01, -1.22791750e-02, 9.78768900e-03, -4.03300993e-03,\n", - " -1.36083548e-01]),\n", - " array([-1.22430259e-04, 1.04103770e+00, 1.00866293e+00, -8.05982597e-03,\n", - " 2.41515030e-05, -5.95157456e-06, -9.99967519e-01, 2.55250982e-02,\n", - " -6.27109795e+00, -5.03383918e-04, 1.13447542e-03, -2.69674306e-03,\n", - " -7.81654361e-02, -2.81268369e-03, 8.56614846e-01, -1.42829440e-01,\n", - " -3.32885365e-01, 9.71951034e-04, 1.85052762e-05, 4.14090374e-02,\n", - " -2.76412663e-01, -1.22543560e-02, 9.76410422e-03, -4.06451159e-03,\n", - " -1.36043974e-01]),\n", - " array([-1.25247189e-04, 1.04189631e+00, 1.00853744e+00, -7.89258482e-03,\n", - " 2.36503394e-05, -5.96445048e-06, -9.99968853e-01, 2.55665185e-02,\n", - " -6.27137599e+00, -5.15605001e-04, 1.14421680e-03, -2.70083878e-03,\n", - " -7.83014454e-02, -2.81303699e-03, 8.56502632e-01, -1.39170288e-01,\n", - " -3.34492936e-01, 1.00455734e-03, 2.57347892e-05, 4.14202343e-02,\n", - " -2.78039323e-01, -1.22210822e-02, 9.74137649e-03, -4.09571791e-03,\n", - " -1.36009285e-01]),\n", - " array([-1.28064768e-04, 1.04275472e+00, 1.00841518e+00, -7.72479001e-03,\n", - " 2.31345089e-05, -5.98095741e-06, -9.99970163e-01, 2.56079497e-02,\n", - " -6.27165515e+00, -5.27784714e-04, 1.15393628e-03, -2.70496541e-03,\n", - " -7.84374246e-02, -2.81337001e-03, 8.56393213e-01, -1.35646696e-01,\n", - " -3.35599852e-01, 1.03395317e-03, 3.27915422e-05, 4.14312008e-02,\n", - " -2.79160799e-01, -1.21797133e-02, 9.71947522e-03, -4.12662780e-03,\n", - " -1.35979265e-01]),\n", - " array([-1.30882973e-04, 1.04361293e+00, 1.00829603e+00, -7.55668030e-03,\n", - " 2.26055531e-05, -6.00100349e-06, -9.99971448e-01, 2.56493916e-02,\n", - " -6.27193495e+00, -5.39915321e-04, 1.16363465e-03, -2.70912265e-03,\n", - " -7.85733783e-02, -2.81368326e-03, 8.56286541e-01, -1.32259202e-01,\n", - " -3.36229219e-01, 1.06025997e-03, 3.96817201e-05, 4.14419371e-02,\n", - " -2.79800405e-01, -1.21306070e-02, 9.69837028e-03, -4.15724048e-03,\n", - " -1.35953702e-01]),\n", - " array([-1.33701781e-04, 1.04447094e+00, 1.00817983e+00, -7.38848307e-03,\n", - " 2.20649537e-05, -6.02450080e-06, -9.99972705e-01, 2.56908441e-02,\n", - " -6.27221493e+00, -5.51989440e-04, 1.17331268e-03, -2.71331020e-03,\n", - " -7.87093107e-02, -2.81397724e-03, 8.56182576e-01, -1.29008219e-01,\n", - " -3.36403840e-01, 1.08359873e-03, 4.64123067e-05, 4.14524447e-02,\n", - " -2.79981152e-01, -1.20741187e-02, 9.67803203e-03, -4.18755545e-03,\n", - " -1.35932386e-01]),\n", - " array([-1.36521168e-04, 1.04532877e+00, 1.00806645e+00, -7.22041446e-03,\n", - " 2.15141318e-05, -6.05136569e-06, -9.99973932e-01, 2.57323068e-02,\n", - " -6.27249466e+00, -5.64000040e-04, 1.18297111e-03, -2.71752777e-03,\n", - " -7.88452258e-02, -2.81425238e-03, 8.56081278e-01, -1.25894044e-01,\n", - " -3.36146186e-01, 1.10408977e-03, 5.29909058e-05, 4.14627261e-02,\n", - " -2.79725713e-01, -1.20106009e-02, 9.65843135e-03, -4.21757245e-03,\n", - " -1.35915110e-01]),\n", - " array([-1.39341113e-04, 1.04618642e+00, 1.00795577e+00, -7.05267955e-03,\n", - " 2.09544495e-05, -6.08151900e-06, -9.99975129e-01, 2.57737796e-02,\n", - " -6.27277372e+00, -5.75940443e-04, 1.19261065e-03, -2.72177507e-03,\n", - " -7.89811275e-02, -2.81450909e-03, 8.55982613e-01, -1.22916865e-01,\n", - " -3.35478357e-01, 1.12185247e-03, 5.94256185e-05, 4.14727847e-02,\n", - " -2.79056389e-01, -1.19404020e-02, 9.63953967e-03, -4.24729148e-03,\n", - " -1.35901672e-01]),\n", - " array([-1.42161592e-04, 1.04704390e+00, 1.00784763e+00, -6.88547258e-03,\n", - " 2.03872095e-05, -6.11488620e-06, -9.99976295e-01, 2.58152622e-02,\n", - " -6.27305171e+00, -5.87804309e-04, 1.20223198e-03, -2.72605178e-03,\n", - " -7.91170194e-02, -2.81474776e-03, 8.55886550e-01, -1.20076773e-01,\n", - " -3.34422058e-01, 1.13700506e-03, 6.57249118e-05, 4.14826245e-02,\n", - " -2.77995083e-01, -1.18638666e-02, 9.62132898e-03, -4.27671272e-03,\n", - " -1.35891872e-01]),\n", - " array([-1.44982583e-04, 1.04790121e+00, 1.00774191e+00, -6.71897714e-03,\n", - " 1.98136563e-05, -6.15139755e-06, -9.99977427e-01, 2.58567544e-02,\n", - " -6.27332827e+00, -5.99585643e-04, 1.21183575e-03, -2.73035761e-03,\n", - " -7.92529049e-02, -2.81496874e-03, 8.55793061e-01, -1.17373765e-01,\n", - " -3.32998568e-01, 1.14966439e-03, 7.18975022e-05, 4.14922504e-02,\n", - " -2.76563266e-01, -1.17813341e-02, 9.60377186e-03, -4.30583660e-03,\n", - " -1.35885514e-01]),\n", - " array([-1.47804065e-04, 1.04875836e+00, 1.00763847e+00, -6.55336642e-03,\n", - " 1.92349769e-05, -6.19098811e-06, -9.99978526e-01, 2.58982561e-02,\n", - " -6.27360306e+00, -6.11278782e-04, 1.22142259e-03, -2.73469228e-03,\n", - " -7.93887873e-02, -2.81517234e-03, 8.55702118e-01, -1.14807757e-01,\n", - " -3.31228721e-01, 1.15994575e-03, 7.79522530e-05, 4.15016679e-02,\n", - " -2.74781959e-01, -1.16931388e-02, 9.58684148e-03, -4.33466368e-03,\n", - " -1.35882409e-01]),\n", - " array([-1.50626015e-04, 1.04961535e+00, 1.00753717e+00, -6.38880343e-03,\n", - " 1.86523016e-05, -6.23359778e-06, -9.99979591e-01, 2.59397670e-02,\n", - " -6.27387573e+00, -6.22878391e-04, 1.23099310e-03, -2.73905547e-03,\n", - " -7.95246697e-02, -2.81535888e-03, 8.55613697e-01, -1.12378589e-01,\n", - " -3.29132878e-01, 1.16796268e-03, 8.38980742e-05, 4.15108827e-02,\n", - " -2.72671709e-01, -1.15996093e-02, 9.57051164e-03, -4.36319470e-03,\n", - " -1.35882369e-01]),\n", - " array([-1.53448413e-04, 1.05047220e+00, 1.00743789e+00, -6.22544121e-03,\n", - " 1.80667049e-05, -6.27917124e-06, -9.99980622e-01, 2.59812869e-02,\n", - " -6.27414598e+00, -6.34379459e-04, 1.24054786e-03, -2.74344690e-03,\n", - " -7.96605549e-02, -2.81552861e-03, 8.55527776e-01, -1.10086031e-01,\n", - " -3.26730913e-01, 1.17382683e-03, 8.97438526e-05, 4.15199011e-02,\n", - " -2.70252568e-01, -1.15010681e-02, 9.55475677e-03, -4.39143054e-03,\n", - " -1.35885213e-01]),\n", - " array([-1.56271238e-04, 1.05132891e+00, 1.00734048e+00, -6.06342317e-03,\n", - " 1.74792068e-05, -6.32765792e-06, -9.99981617e-01, 2.60228156e-02,\n", - " -6.27441352e+00, -6.45777290e-04, 1.25008741e-03, -2.74786628e-03,\n", - " -7.97964457e-02, -2.81568181e-03, 8.55444331e-01, -1.07929792e-01,\n", - " -3.24042190e-01, 1.17764778e-03, 9.54983780e-05, 4.15287297e-02,\n", - " -2.67544078e-01, -1.13978309e-02, 9.53955195e-03, -4.41937221e-03,\n", - " -1.35890763e-01]),\n", - " array([-1.59094470e-04, 1.05218548e+00, 1.00724481e+00, -5.90288326e-03,\n", - " 1.68907736e-05, -6.37901189e-06, -9.99982578e-01, 2.60643530e-02,\n", - " -6.27467809e+00, -6.57067497e-04, 1.25961228e-03, -2.75231330e-03,\n", - " -7.99323445e-02, -2.81581871e-03, 8.55363342e-01, -1.05909523e-01,\n", - " -3.21085558e-01, 1.17953290e-03, 1.01170278e-04, 4.15373755e-02,\n", - " -2.64565255e-01, -1.12902069e-02, 9.52487289e-03, -4.44702084e-03,\n", - " -1.35898848e-01]),\n", - " array([-1.61918087e-04, 1.05304192e+00, 1.00715075e+00, -5.74394629e-03,\n", - " 1.63023190e-05, -6.43319173e-06, -9.99983503e-01, 2.61058988e-02,\n", - " -6.27493942e+00, -6.68245995e-04, 1.26912298e-03, -2.75678767e-03,\n", - " -8.00682538e-02, -2.81593952e-03, 8.55284788e-01, -1.04024830e-01,\n", - " -3.17879329e-01, 1.17958728e-03, 1.06767971e-04, 4.15458453e-02,\n", - " -2.61334578e-01, -1.11784979e-02, 9.51069597e-03, -4.47437764e-03,\n", - " -1.35909300e-01]),\n", - " array([-1.64742072e-04, 1.05389823e+00, 1.00705817e+00, -5.58672817e-03,\n", - " 1.57147057e-05, -6.49016041e-06, -9.99984394e-01, 2.61474530e-02,\n", - " -6.27519729e+00, -6.79308993e-04, 1.27861998e-03, -2.76128912e-03,\n", - " -8.02041758e-02, -2.81604446e-03, 8.55208649e-01, -1.02275271e-01,\n", - " -3.14441271e-01, 1.17791356e-03, 1.12299617e-04, 4.15541464e-02,\n", - " -2.57869977e-01, -1.10629983e-02, 9.49699825e-03, -4.50144391e-03,\n", - " -1.35921956e-01]),\n", - " array([-1.67566404e-04, 1.05475442e+00, 1.00696694e+00, -5.43133622e-03,\n", - " 1.51287462e-05, -6.54988509e-06, -9.99985250e-01, 2.61890153e-02,\n", - " -6.27545148e+00, -6.90252988e-04, 1.28810374e-03, -2.76581734e-03,\n", - " -8.03401124e-02, -2.81613372e-03, 8.55134904e-01, -1.00660367e-01,\n", - " -3.10788605e-01, 1.17461188e-03, 1.17773070e-04, 4.15622860e-02,\n", - " -2.54188825e-01, -1.09439951e-02, 9.48375745e-03, -4.52822104e-03,\n", - " -1.35936661e-01]),\n", - " array([-1.70391066e-04, 1.05561050e+00, 1.00687692e+00, -5.27786943e-03,\n", - " 1.45452046e-05, -6.61233697e-06, -9.99986072e-01, 2.62305855e-02,\n", - " -6.27570179e+00, -7.01074756e-04, 1.29757469e-03, -2.77037205e-03,\n", - " -8.04760657e-02, -2.81620747e-03, 8.55063533e-01, -9.91796079e-02,\n", - " -3.06937988e-01, 1.16977977e-03, 1.23195858e-04, 4.15702713e-02,\n", - " -2.50307933e-01, -1.08217671e-02, 9.47095195e-03, -4.55471044e-03,\n", - " -1.35953262e-01]),\n", - " array([-1.73216039e-04, 1.05646646e+00, 1.00678799e+00, -5.12641871e-03,\n", - " 1.39647972e-05, -6.67749111e-06, -9.99986860e-01, 2.62721637e-02,\n", - " -6.27594803e+00, -7.11771341e-04, 1.30703325e-03, -2.77495296e-03,\n", - " -8.06120373e-02, -2.81626590e-03, 8.54994516e-01, -9.78324523e-02,\n", - " -3.02905519e-01, 1.16351209e-03, 1.28575169e-04, 4.15781098e-02,\n", - " -2.46243542e-01, -1.06965854e-02, 9.45856083e-03, -4.58091360e-03,\n", - " -1.35971613e-01]),\n", - " array([-1.76041305e-04, 1.05732232e+00, 1.00670002e+00, -4.97706725e-03,\n", - " 1.33881947e-05, -6.74532619e-06, -9.99987614e-01, 2.63137495e-02,\n", - " -6.27619005e+00, -7.22340054e-04, 1.31647981e-03, -2.77955980e-03,\n", - " -8.07480289e-02, -2.81630916e-03, 8.54927831e-01, -9.66183371e-02,\n", - " -2.98706729e-01, 1.15590098e-03, 1.33917816e-04, 4.15858085e-02,\n", - " -2.42011324e-01, -1.05687127e-02, 9.44656381e-03, -4.60683204e-03,\n", - " -1.35991572e-01]),\n", - " array([-1.78866848e-04, 1.05817808e+00, 1.00661287e+00, -4.82989072e-03,\n", - " 1.28160230e-05, -6.81582436e-06, -9.99988336e-01, 2.63553428e-02,\n", - " -6.27642767e+00, -7.32778457e-04, 1.32591475e-03, -2.78419226e-03,\n", - " -8.08840419e-02, -2.81633741e-03, 8.54863455e-01, -9.55366791e-02,\n", - " -2.94356583e-01, 1.14703577e-03, 1.39230231e-04, 4.15933746e-02,\n", - " -2.37626378e-01, -1.04384034e-02, 9.43494133e-03, -4.63246729e-03,\n", - " -1.36013003e-01]),\n", - " array([-1.81692651e-04, 1.05903375e+00, 1.00652642e+00, -4.68495762e-03,\n", - " 1.22488649e-05, -6.88897098e-06, -9.99989025e-01, 2.63969437e-02,\n", - " -6.27666078e+00, -7.43084361e-04, 1.33533843e-03, -2.78885008e-03,\n", - " -8.10200776e-02, -2.81635080e-03, 8.54801368e-01, -9.45868799e-02,\n", - " -2.89869479e-01, 1.13700300e-03, 1.44518454e-04, 4.16008151e-02,\n", - " -2.33103234e-01, -1.03059039e-02, 9.42367446e-03, -4.65782092e-03,\n", - " -1.36035777e-01]),\n", - " array([-1.84518698e-04, 1.05988932e+00, 1.00644054e+00, -4.54232950e-03,\n", - " 1.16872612e-05, -6.96475447e-06, -9.99989683e-01, 2.64385518e-02,\n", - " -6.27688923e+00, -7.53255813e-04, 1.34475117e-03, -2.79353298e-03,\n", - " -8.11561374e-02, -2.81634947e-03, 8.54741545e-01, -9.37683291e-02,\n", - " -2.85259251e-01, 1.12588636e-03, 1.49788126e-04, 4.16081370e-02,\n", - " -2.28455848e-01, -1.01714519e-02, 9.41274496e-03, -4.68289449e-03,\n", - " -1.36059767e-01]),\n", - " array([-1.87344973e-04, 1.06074480e+00, 1.00635511e+00, -4.40206132e-03,\n", - " 1.11317126e-05, -7.04316603e-06, -9.99990311e-01, 2.64801671e-02,\n", - " -6.27711293e+00, -7.63291089e-04, 1.35415331e-03, -2.79824067e-03,\n", - " -8.12922223e-02, -2.81633358e-03, 8.54683962e-01, -9.30804084e-02,\n", - " -2.80539170e-01, 1.11376667e-03, 1.55044500e-04, 4.16153469e-02,\n", - " -2.23697612e-01, -1.00352766e-02, 9.40213524e-03, -4.70768957e-03,\n", - " -1.36084853e-01]),\n", - " array([-1.90171461e-04, 1.06160020e+00, 1.00627000e+00, -4.26420163e-03,\n", - " 1.05826807e-05, -7.12419949e-06, -9.99990908e-01, 2.65217896e-02,\n", - " -6.27733177e+00, -7.73188689e-04, 1.36354514e-03, -2.80297288e-03,\n", - " -8.14283332e-02, -2.81630325e-03, 8.54628594e-01, -9.25224942e-02,\n", - " -2.75721952e-01, 1.10072185e-03, 1.60292433e-04, 4.16224515e-02,\n", - " -2.18841356e-01, -9.89759908e-03, 9.39182838e-03, -4.73220771e-03,\n", - " -1.36110920e-01]),\n", - " array([-1.92998147e-04, 1.06245552e+00, 1.00618508e+00, -4.12879294e-03,\n", - " 1.00405897e-05, -7.20785110e-06, -9.99991476e-01, 2.65634190e-02,\n", - " -6.27754567e+00, -7.82947320e-04, 1.37292694e-03, -2.80772933e-03,\n", - " -8.15644710e-02, -2.81625863e-03, 8.54575415e-01, -9.20939610e-02,\n", - " -2.70819759e-01, 1.08682697e-03, 1.65536402e-04, 4.16294570e-02,\n", - " -2.13899350e-01, -9.75863167e-03, 9.38180812e-03, -4.75645047e-03,\n", - " -1.36137858e-01]),\n", - " array([-1.95825018e-04, 1.06331076e+00, 1.00610023e+00, -3.99587193e-03,\n", - " 9.50582768e-06, -7.29411929e-06, -9.99992016e-01, 2.66050554e-02,\n", - " -6.27775455e+00, -7.92565899e-04, 1.38229900e-03, -2.81250975e-03,\n", - " -8.17006366e-02, -2.81619985e-03, 8.54524398e-01, -9.17941835e-02,\n", - " -2.65844208e-01, 1.07215423e-03, 1.70780497e-04, 4.16363696e-02,\n", - " -2.08883317e-01, -9.61857846e-03, 9.37205881e-03, -4.78041938e-03,\n", - " -1.36165563e-01]),\n", - " array([-1.98652060e-04, 1.06416593e+00, 1.00601533e+00, -3.86546974e-03,\n", - " 8.97874823e-06, -7.38300452e-06, -9.99992529e-01, 2.66466986e-02,\n", - " -6.27795836e+00, -8.02043534e-04, 1.39166157e-03, -2.81731386e-03,\n", - " -8.18368305e-02, -2.81612704e-03, 8.54475513e-01, -9.16225398e-02,\n", - " -2.60806381e-01, 1.05677292e-03, 1.76028438e-04, 4.16431954e-02,\n", - " -2.03804436e-01, -9.47763518e-03, 9.36256547e-03, -4.80411592e-03,\n", - " -1.36193933e-01]),\n", - " array([-2.01479260e-04, 1.06502103e+00, 1.00593025e+00, -3.73761225e-03,\n", - " 8.45967163e-06, -7.47450906e-06, -9.99993015e-01, 2.66883486e-02,\n", - " -6.27815703e+00, -8.11379523e-04, 1.40101488e-03, -2.82214140e-03,\n", - " -8.19730534e-02, -2.81604035e-03, 8.54428732e-01, -9.15784131e-02,\n", - " -2.55716826e-01, 1.04074954e-03, 1.81283581e-04, 4.16499400e-02,\n", - " -1.98673352e-01, -9.33598926e-03, 9.35331374e-03, -4.82754158e-03,\n", - " -1.36222875e-01]),\n", - " array([-2.04306605e-04, 1.06587606e+00, 1.00584487e+00, -3.61232030e-03,\n", - " 7.94888639e-06, -7.56863682e-06, -9.99993475e-01, 2.67300052e-02,\n", - " -6.27835053e+00, -8.20573343e-04, 1.41035917e-03, -2.82699210e-03,\n", - " -8.21093057e-02, -2.81593991e-03, 8.54384025e-01, -9.16611940e-02,\n", - " -2.50585577e-01, 1.02414775e-03, 1.86548948e-04, 4.16566090e-02,\n", - " -1.93500188e-01, -9.19381999e-03, 9.34428987e-03, -4.85069778e-03,\n", - " -1.36252298e-01]),\n", - " array([-2.07134083e-04, 1.06673103e+00, 1.00575907e+00, -3.48960999e-03,\n", - " 7.44665064e-06, -7.66539318e-06, -9.99993911e-01, 2.67716684e-02,\n", - " -6.27853883e+00, -8.29624642e-04, 1.41969465e-03, -2.83186569e-03,\n", - " -8.22455878e-02, -2.81582585e-03, 8.54341359e-01, -9.18702820e-02,\n", - " -2.45422154e-01, 1.00702841e-03, 1.91827210e-04, 4.16632075e-02,\n", - " -1.88294549e-01, -9.05129855e-03, 9.33548072e-03, -4.87358593e-03,\n", - " -1.36282116e-01]),\n", - " array([-2.09961683e-04, 1.06758595e+00, 1.00567272e+00, -3.36949290e-03,\n", - " 6.95319346e-06, -7.76478481e-06, -9.99994323e-01, 2.68133381e-02,\n", - " -6.27872189e+00, -8.38533230e-04, 1.42902153e-03, -2.83676189e-03,\n", - " -8.23819001e-02, -2.81569832e-03, 8.54300702e-01, -9.22050875e-02,\n", - " -2.40235580e-01, 9.89449650e-04, 1.97120732e-04, 4.16697407e-02,\n", - " -1.83065539e-01, -8.90858819e-03, 9.32687376e-03, -4.89620738e-03,\n", - " -1.36312249e-01]),\n", - " array([-2.12789393e-04, 1.06844080e+00, 1.00558572e+00, -3.25197635e-03,\n", - " 6.46871627e-06, -7.86681952e-06, -9.99994712e-01, 2.68550143e-02,\n", - " -6.27889971e+00, -8.47299074e-04, 1.43833998e-03, -2.84168046e-03,\n", - " -8.25182427e-02, -2.81555746e-03, 8.54262021e-01, -9.26650330e-02,\n", - " -2.35034391e-01, 9.71466887e-04, 2.02431570e-04, 4.16762132e-02,\n", - " -1.77821771e-01, -8.76584434e-03, 9.31845704e-03, -4.91856343e-03,\n", - " -1.36342620e-01]),\n", - " array([-2.15617202e-04, 1.06929561e+00, 1.00549793e+00, -3.13706361e-03,\n", - " 5.99339413e-06, -7.97150611e-06, -9.99995079e-01, 2.68966970e-02,\n", - " -6.27907228e+00, -8.55922289e-04, 1.44765020e-03, -2.84662111e-03,\n", - " -8.26546159e-02, -2.81540340e-03, 8.54225280e-01, -9.32495545e-02,\n", - " -2.29826647e-01, 9.53132874e-04, 2.07761485e-04, 4.16826298e-02,\n", - " -1.72571376e-01, -8.62321475e-03, 9.31021917e-03, -4.94065536e-03,\n", - " -1.36373157e-01]),\n", - " array([-2.18445101e-04, 1.07015036e+00, 1.00540924e+00, -3.02475416e-03,\n", - " 5.52737707e-06, -8.07885419e-06, -9.99995425e-01, 2.69383859e-02,\n", - " -6.27923961e+00, -8.64403129e-04, 1.45695235e-03, -2.85158360e-03,\n", - " -8.27910196e-02, -2.81523630e-03, 8.54190445e-01, -9.39581021e-02,\n", - " -2.24619946e-01, 9.34497752e-04, 2.13111972e-04, 4.16889946e-02,\n", - " -1.67322020e-01, -8.48083966e-03, 9.30214935e-03, -4.96248437e-03,\n", - " -1.36403791e-01]),\n", - " array([-2.21273079e-04, 1.07100507e+00, 1.00531952e+00, -2.91504392e-03,\n", - " 5.07079135e-06, -8.18887411e-06, -9.99995751e-01, 2.69800813e-02,\n", - " -6.27940169e+00, -8.72741981e-04, 1.46624659e-03, -2.85656765e-03,\n", - " -8.29274541e-02, -2.81505630e-03, 8.54157478e-01, -9.47901415e-02,\n", - " -2.19421436e-01, 9.15609107e-04, 2.18484264e-04, 4.16953117e-02,\n", - " -1.62080914e-01, -8.33885198e-03, 9.29423733e-03, -4.98405162e-03,\n", - " -1.36434461e-01]),\n", - " array([-2.24101128e-04, 1.07185973e+00, 1.00522866e+00, -2.80792544e-03,\n", - " 4.62374070e-06, -8.30157678e-06, -9.99996058e-01, 2.70217828e-02,\n", - " -6.27955854e+00, -8.80939358e-04, 1.47553306e-03, -2.86157301e-03,\n", - " -8.30639192e-02, -2.81486355e-03, 8.54126343e-01, -9.57451544e-02,\n", - " -2.14237827e-01, 8.96512025e-04, 2.23879367e-04, 4.17015851e-02,\n", - " -1.56854828e-01, -8.19737742e-03, 9.28647339e-03, -5.00535823e-03,\n", - " -1.36465105e-01]),\n", - " array([-2.26929238e-04, 1.07271434e+00, 1.00513655e+00, -2.70338813e-03,\n", - " 4.18630758e-06, -8.41697357e-06, -9.99996346e-01, 2.70634907e-02,\n", - " -6.27971019e+00, -8.88995893e-04, 1.48481191e-03, -2.86659941e-03,\n", - " -8.32004149e-02, -2.81465820e-03, 8.54097002e-01, -9.68226392e-02,\n", - " -2.09075407e-01, 8.77249154e-04, 2.29298043e-04, 4.17078183e-02,\n", - " -1.51650108e-01, -8.05653473e-03, 9.27884832e-03, -5.02640525e-03,\n", - " -1.36495668e-01]),\n", - " array([-2.29757400e-04, 1.07356892e+00, 1.00504306e+00, -2.60141846e-03,\n", - " 3.75855433e-06, -8.53507621e-06, -9.99996616e-01, 2.71052047e-02,\n", - " -6.27985666e+00, -8.96912329e-04, 1.49408327e-03, -2.87164661e-03,\n", - " -8.33369410e-02, -2.81444041e-03, 8.54069415e-01, -9.80221112e-02,\n", - " -2.03940055e-01, 8.57860765e-04, 2.34740856e-04, 4.17140147e-02,\n", - " -1.46472682e-01, -7.91643584e-03, 9.27135347e-03, -5.04719367e-03,\n", - " -1.36526098e-01]),\n", - " array([-2.32585606e-04, 1.07442346e+00, 1.00494808e+00, -2.50200015e-03,\n", - " 3.34052430e-06, -8.65589666e-06, -9.99996870e-01, 2.71469249e-02,\n", - " -6.27999799e+00, -9.04689515e-04, 1.50334725e-03, -2.87671433e-03,\n", - " -8.34734973e-02, -2.81421033e-03, 8.54043543e-01, -9.93431033e-02,\n", - " -1.98837252e-01, 8.38384816e-04, 2.40208151e-04, 4.17201775e-02,\n", - " -1.41328083e-01, -7.77718612e-03, 9.26398066e-03, -5.06772446e-03,\n", - " -1.36556347e-01]),\n", - " array([-2.35413850e-04, 1.07527796e+00, 1.00485148e+00, -2.40511439e-03,\n", - " 2.93224306e-06, -8.77944704e-06, -9.99997108e-01, 2.71886512e-02,\n", - " -6.28013421e+00, -9.12328399e-04, 1.51260397e-03, -2.88180233e-03,\n", - " -8.36100837e-02, -2.81396813e-03, 8.54019345e-01, -1.00785166e-01,\n", - " -1.93772102e-01, 8.18857025e-04, 2.45700116e-04, 4.17263097e-02,\n", - " -1.36221457e-01, -7.63888453e-03, 9.25672219e-03, -5.08799851e-03,\n", - " -1.36586369e-01]),\n", - " array([-2.38242123e-04, 1.07613243e+00, 1.00475316e+00, -2.31073998e-03,\n", - " 2.53371940e-06, -8.90573951e-06, -9.99997330e-01, 2.72303836e-02,\n", - " -6.28026537e+00, -9.19830023e-04, 1.52185354e-03, -2.88691035e-03,\n", - " -8.37466998e-02, -2.81371396e-03, 8.53996782e-01, -1.02347866e-01,\n", - " -1.88749338e-01, 7.99310938e-04, 2.51216773e-04, 4.17324139e-02,\n", - " -1.31157581e-01, -7.50162381e-03, 9.24957087e-03, -5.10801666e-03,\n", - " -1.36616123e-01]),\n", - " array([-2.41070418e-04, 1.07698687e+00, 1.00465300e+00, -2.21885354e-03,\n", - " 2.14494640e-06, -9.03478625e-06, -9.99997538e-01, 2.72721221e-02,\n", - " -6.28039151e+00, -9.27195514e-04, 1.53109606e-03, -2.89203813e-03,\n", - " -8.38833454e-02, -2.81344800e-03, 8.53975812e-01, -1.04030790e-01,\n", - " -1.83773341e-01, 7.79777997e-04, 2.56758020e-04, 4.17384929e-02,\n", - " -1.26140874e-01, -7.36549078e-03, 9.24251994e-03, -5.12777970e-03,\n", - " -1.36645572e-01]),\n", - " array([-2.43898729e-04, 1.07784128e+00, 1.00455088e+00, -2.12942967e-03,\n", - " 1.76590248e-06, -9.16659937e-06, -9.99997733e-01, 2.73138666e-02,\n", - " -6.28051269e+00, -9.34426080e-04, 1.54033162e-03, -2.89718541e-03,\n", - " -8.40200201e-02, -2.81317039e-03, 8.53956394e-01, -1.05833541e-01,\n", - " -1.78848154e-01, 7.60287613e-04, 2.62323597e-04, 4.17445489e-02,\n", - " -1.21175414e-01, -7.23056645e-03, 9.23556310e-03, -5.14728837e-03,\n", - " -1.36674679e-01]),\n", - " array([-2.46727050e-04, 1.07869566e+00, 1.00444669e+00, -2.04244111e-03,\n", - " 1.39655234e-06, -9.30119079e-06, -9.99997914e-01, 2.73556172e-02,\n", - " -6.28062895e+00, -9.41523007e-04, 1.54956032e-03, -2.90235196e-03,\n", - " -8.41567235e-02, -2.81288132e-03, 8.53938484e-01, -1.07755737e-01,\n", - " -1.73977495e-01, 7.40867237e-04, 2.67913125e-04, 4.17505843e-02,\n", - " -1.16264953e-01, -7.09692631e-03, 9.22869450e-03, -5.16654336e-03,\n", - " -1.36703413e-01]),\n", - " array([-2.49555374e-04, 1.07955002e+00, 1.00434031e+00, -1.95785889e-03,\n", - " 1.03684791e-06, -9.43857227e-06, -9.99998083e-01, 2.73973738e-02,\n", - " -6.28074037e+00, -9.48487647e-04, 1.55878223e-03, -2.90753750e-03,\n", - " -8.42934552e-02, -2.81258096e-03, 8.53922041e-01, -1.09797016e-01,\n", - " -1.69164771e-01, 7.21542435e-04, 2.73526146e-04, 4.17566009e-02,\n", - " -1.11412927e-01, -6.96464047e-03, 9.22190869e-03, -5.18554532e-03,\n", - " -1.36731744e-01]),\n", - " array([-2.52383697e-04, 1.08040434e+00, 1.00423163e+00, -1.87565249e-03,\n", - " 6.86729293e-07, -9.57875535e-06, -9.99998241e-01, 2.74391364e-02,\n", - " -6.28084699e+00, -9.55321421e-04, 1.56799743e-03, -2.91274180e-03,\n", - " -8.44302149e-02, -2.81226947e-03, 8.53907023e-01, -1.11957030e-01,\n", - " -1.64413092e-01, 7.02336966e-04, 2.79162137e-04, 4.17626008e-02,\n", - " -1.06622474e-01, -6.83377396e-03, 9.21520064e-03, -5.20429483e-03,\n", - " -1.36759645e-01]),\n", - " array([-2.55212012e-04, 1.08125865e+00, 1.00412053e+00, -1.79578998e-03,\n", - " 3.46125564e-07, -9.72175127e-06, -9.99998388e-01, 2.74809050e-02,\n", - " -6.28094888e+00, -9.62025808e-04, 1.57720599e-03, -2.91796459e-03,\n", - " -8.45670020e-02, -2.81194702e-03, 8.53893386e-01, -1.14235447e-01,\n", - " -1.59725286e-01, 6.83272849e-04, 2.84820509e-04, 4.17685858e-02,\n", - " -1.01896446e-01, -6.70438688e-03, 9.20856571e-03, -5.22279247e-03,\n", - " -1.36787093e-01]),\n", - " array([-2.58040315e-04, 1.08211294e+00, 1.00400690e+00, -1.71823814e-03,\n", - " 1.49556604e-08, -9.86757099e-06, -9.99998524e-01, 2.75226796e-02,\n", - " -6.28104612e+00, -9.68602342e-04, 1.58640799e-03, -2.92320563e-03,\n", - " -8.47038160e-02, -2.81161380e-03, 8.53881088e-01, -1.16631950e-01,\n", - " -1.55103912e-01, 6.64370438e-04, 2.90500598e-04, 4.17745574e-02,\n", - " -9.72374237e-02, -6.57653462e-03, 9.20199965e-03, -5.24103873e-03,\n", - " -1.36814065e-01]),\n", - " array([-2.60868601e-04, 1.08296720e+00, 1.00389062e+00, -1.64296261e-03,\n", - " -3.06870852e-07, -1.00162252e-05, -9.99998650e-01, 2.75644601e-02,\n", - " -6.28113877e+00, -9.75052611e-04, 1.59560349e-03, -2.92846466e-03,\n", - " -8.48406566e-02, -2.81126997e-03, 8.53870085e-01, -1.19146236e-01,\n", - " -1.50551272e-01, 6.45648498e-04, 2.96201757e-04, 4.17805173e-02,\n", - " -9.26477296e-02, -6.45026810e-03, 9.19549858e-03, -5.25903409e-03,\n", - " -1.36840543e-01]),\n", - " array([-2.63696867e-04, 1.08382145e+00, 1.00377159e+00, -1.56992799e-03,\n", - " -6.19453011e-07, -1.01677242e-05, -9.99998768e-01, 2.76062465e-02,\n", - " -6.28122690e+00, -9.81378245e-04, 1.60479255e-03, -2.93374144e-03,\n", - " -8.49775231e-02, -2.81091572e-03, 8.53860335e-01, -1.21778016e-01,\n", - " -1.46069425e-01, 6.27124279e-04, 3.01923311e-04, 4.17864669e-02,\n", - " -8.81294409e-02, -6.32563397e-03, 9.18905895e-03, -5.27677898e-03,\n", - " -1.36866509e-01]),\n", - " array([-2.66525107e-04, 1.08467568e+00, 1.00364968e+00, -1.49909797e-03,\n", - " -9.22897740e-07, -1.03220781e-05, -9.99998876e-01, 2.76480389e-02,\n", - " -6.28131058e+00, -9.87580919e-04, 1.61397523e-03, -2.93903572e-03,\n", - " -8.51144150e-02, -2.81055122e-03, 8.53851795e-01, -1.24527014e-01,\n", - " -1.41660201e-01, 6.08813586e-04, 3.07664613e-04, 4.17924076e-02,\n", - " -8.36844029e-02, -6.20267477e-03, 9.18267759e-03, -5.29427381e-03,\n", - " -1.36891948e-01]),\n", - " array([-2.69353319e-04, 1.08552989e+00, 1.00352479e+00, -1.43043543e-03,\n", - " -1.21731916e-06, -1.04792965e-05, -9.99998977e-01, 2.76898373e-02,\n", - " -6.28138990e+00, -9.93662349e-04, 1.62315158e-03, -2.94434723e-03,\n", - " -8.52513319e-02, -2.81017664e-03, 8.53844421e-01, -1.27392964e-01,\n", - " -1.37325212e-01, 5.90730850e-04, 3.13425057e-04, 4.17983408e-02,\n", - " -7.93142418e-02, -6.08142921e-03, 9.17635165e-03, -5.31151894e-03,\n", - " -1.36916848e-01]),\n", - " array([-2.72181498e-04, 1.08638409e+00, 1.00339680e+00, -1.36390256e-03,\n", - " -1.50283795e-06, -1.06393891e-05, -9.99999070e-01, 2.77316416e-02,\n", - " -6.28146492e+00, -9.99624281e-04, 1.63232166e-03, -2.94967575e-03,\n", - " -8.53882731e-02, -2.80979216e-03, 8.53838172e-01, -1.30375611e-01,\n", - " -1.33065866e-01, 5.72889206e-04, 3.19204103e-04, 4.18042679e-02,\n", - " -7.50203767e-02, -5.96193229e-03, 9.17007857e-03, -5.32851472e-03,\n", - " -1.36941197e-01]),\n", - " array([-2.75009642e-04, 1.08723828e+00, 1.00326560e+00, -1.29946093e-03,\n", - " -1.77958071e-06, -1.08023651e-05, -9.99999156e-01, 2.77734517e-02,\n", - " -6.28153572e+00, -1.00546850e-03, 1.64148551e-03, -2.95502101e-03,\n", - " -8.55252381e-02, -2.80939796e-03, 8.53833004e-01, -1.33474711e-01,\n", - " -1.28883377e-01, 5.55300554e-04, 3.25001289e-04, 4.18101902e-02,\n", - " -7.08040319e-02, -5.84421553e-03, 9.16385614e-03, -5.34526147e-03,\n", - " -1.36964985e-01]),\n", - " array([-2.77837747e-04, 1.08809245e+00, 1.00313108e+00, -1.23707159e-03,\n", - " -2.04767940e-06, -1.09682337e-05, -9.99999235e-01, 2.78152679e-02,\n", - " -6.28160239e+00, -1.01119680e-03, 1.65064320e-03, -2.96038277e-03,\n", - " -8.56622263e-02, -2.80899422e-03, 8.53828876e-01, -1.36690027e-01,\n", - " -1.24778777e-01, 5.37975633e-04, 3.30816262e-04, 4.18161090e-02,\n", - " -6.66662488e-02, -5.72830719e-03, 9.15768240e-03, -5.36175947e-03,\n", - " -1.36988205e-01]),\n", - " array([-2.80665812e-04, 1.08894661e+00, 1.00299312e+00, -1.17669516e-03,\n", - " -2.30727079e-06, -1.11370038e-05, -9.99999308e-01, 2.78570899e-02,\n", - " -6.28166500e+00, -1.01681104e-03, 1.65979475e-03, -2.96576078e-03,\n", - " -8.57992371e-02, -2.80858110e-03, 8.53825746e-01, -1.40021331e-01,\n", - " -1.20752930e-01, 5.20924088e-04, 3.36648807e-04, 4.18220260e-02,\n", - " -6.26078969e-02, -5.61423238e-03, 9.15155570e-03, -5.37800901e-03,\n", - " -1.37010851e-01]),\n", - " array([-2.83493832e-04, 1.08980076e+00, 1.00285161e+00, -1.11829193e-03,\n", - " -2.55849593e-06, -1.13086844e-05, -9.99999375e-01, 2.78989178e-02,\n", - " -6.28172363e+00, -1.02231305e-03, 1.66894023e-03, -2.97115479e-03,\n", - " -8.59362700e-02, -2.80815878e-03, 8.53823571e-01, -1.43468398e-01,\n", - " -1.16806538e-01, 5.04154536e-04, 3.42498875e-04, 4.18279425e-02,\n", - " -5.86296849e-02, -5.50201329e-03, 9.14547463e-03, -5.39401036e-03,\n", - " -1.37032918e-01]),\n", - " array([-2.86321807e-04, 1.09065490e+00, 1.00270644e+00, -1.06182188e-03,\n", - " -2.80149970e-06, -1.14832848e-05, -9.99999436e-01, 2.79407517e-02,\n", - " -6.28177836e+00, -1.02770472e-03, 1.67807966e-03, -2.97656455e-03,\n", - " -8.60733244e-02, -2.80772744e-03, 8.53822311e-01, -1.47031012e-01,\n", - " -1.12940156e-01, 4.87674632e-04, 3.48366611e-04, 4.18338602e-02,\n", - " -5.47321717e-02, -5.39166935e-03, 9.13943807e-03, -5.40976376e-03,\n", - " -1.37054402e-01]),\n", - " array([-2.89149733e-04, 1.09150904e+00, 1.00255750e+00, -1.00724481e-03,\n", - " -3.03643033e-06, -1.16608141e-05, -9.99999493e-01, 2.79825915e-02,\n", - " -6.28182927e+00, -1.03298794e-03, 1.68721311e-03, -2.98198982e-03,\n", - " -8.62103997e-02, -2.80728724e-03, 8.53821925e-01, -1.50708958e-01,\n", - " -1.09154200e-01, 4.71491129e-04, 3.54252383e-04, 4.18397809e-02,\n", - " -5.09157760e-02, -5.28321740e-03, 9.13344512e-03, -5.42526945e-03,\n", - " -1.37075302e-01]),\n", - " array([-2.91977610e-04, 1.09236316e+00, 1.00240467e+00, -9.54520357e-04,\n", - " -3.26343899e-06, -1.18412819e-05, -9.99999544e-01, 2.80244372e-02,\n", - " -6.28187645e+00, -1.03816461e-03, 1.69634060e-03, -2.98743035e-03,\n", - " -8.63474954e-02, -2.80683834e-03, 8.53822373e-01, -1.54502024e-01,\n", - " -1.05448956e-01, 4.55609943e-04, 3.60156802e-04, 4.18457067e-02,\n", - " -4.71807868e-02, -5.17667182e-03, 9.12749512e-03, -5.44052768e-03,\n", - " -1.37095615e-01]),\n", - " array([-2.94805435e-04, 1.09321728e+00, 1.00224785e+00, -9.03608081e-04,\n", - " -3.48267940e-06, -1.20246984e-05, -9.99999592e-01, 2.80662888e-02,\n", - " -6.28191998e+00, -1.04323665e-03, 1.70546219e-03, -2.99288589e-03,\n", - " -8.64846107e-02, -2.80638093e-03, 8.53823615e-01, -1.58409998e-01,\n", - " -1.01824592e-01, 4.40036209e-04, 3.66080758e-04, 4.18516395e-02,\n", - " -4.35273722e-02, -5.07204474e-03, 9.12158763e-03, -5.45553869e-03,\n", - " -1.37115342e-01]),\n", - " array([-2.97633207e-04, 1.09407139e+00, 1.00208692e+00, -8.54467515e-04,\n", - " -3.69430750e-06, -1.22110740e-05, -9.99999635e-01, 2.81081464e-02,\n", - " -6.28195994e+00, -1.04820600e-03, 1.71457791e-03, -2.99835619e-03,\n", - " -8.66217452e-02, -2.80591514e-03, 8.53825612e-01, -1.62432671e-01,\n", - " -9.82811661e-02, 4.24774341e-04, 3.72025438e-04, 4.18575819e-02,\n", - " -3.99555889e-02, -4.96934614e-03, 9.11572242e-03, -5.47030273e-03,\n", - " -1.37134485e-01]),\n", - " array([-3.00460925e-04, 1.09492549e+00, 1.00192177e+00, -8.07058213e-04,\n", - " -3.89848105e-06, -1.24004204e-05, -9.99999674e-01, 2.81500099e-02,\n", - " -6.28199640e+00, -1.05307458e-03, 1.72368781e-03, -3.00384101e-03,\n", - " -8.67588982e-02, -2.80544115e-03, 8.53828325e-01, -1.66569829e-01,\n", - " -9.48186316e-02, 4.09828085e-04, 3.77992359e-04, 4.18635366e-02,\n", - " -3.64653908e-02, -4.86858399e-03, 9.10989946e-03, -5.48482004e-03,\n", - " -1.37153044e-01]),\n", - " array([-3.03288587e-04, 1.09577959e+00, 1.00175228e+00, -7.61339801e-04,\n", - " -4.09535940e-06, -1.25927497e-05, -9.99999710e-01, 2.81918794e-02,\n", - " -6.28202946e+00, -1.05784435e-03, 1.73279193e-03, -3.00934010e-03,\n", - " -8.68960692e-02, -2.80495911e-03, 8.53831716e-01, -1.70821256e-01,\n", - " -9.14368502e-02, 3.95200573e-04, 3.83983384e-04, 4.18695063e-02,\n", - " -3.30566370e-02, -4.76976443e-03, 9.10411891e-03, -5.49909089e-03,\n", - " -1.37171023e-01]),\n", - " array([-3.06116194e-04, 1.09663368e+00, 1.00157836e+00, -7.17272013e-04,\n", - " -4.28510313e-06, -1.27880755e-05, -9.99999743e-01, 2.82337549e-02,\n", - " -6.28205919e+00, -1.06251724e-03, 1.74189031e-03, -3.01485322e-03,\n", - " -8.70332577e-02, -2.80446916e-03, 8.53835748e-01, -1.75186731e-01,\n", - " -8.81355967e-02, 3.80894374e-04, 3.90000749e-04, 4.18754945e-02,\n", - " -2.97290996e-02, -4.67289184e-03, 9.09838110e-03, -5.51311557e-03,\n", - " -1.37188426e-01]),\n", - " array([-3.08943743e-04, 1.09748777e+00, 1.00139988e+00, -6.74814738e-04,\n", - " -4.46787386e-06, -1.29864125e-05, -9.99999772e-01, 2.82756364e-02,\n", - " -6.28208567e+00, -1.06709521e-03, 1.75098300e-03, -3.02038011e-03,\n", - " -8.71704629e-02, -2.80397145e-03, 8.53840383e-01, -1.79666028e-01,\n", - " -8.49145673e-02, 3.66911541e-04, 3.96047072e-04, 4.18815046e-02,\n", - " -2.64824715e-02, -4.57796901e-03, 9.09268654e-03, -5.52689437e-03,\n", - " -1.37205255e-01]),\n", - " array([-3.11771235e-04, 1.09834186e+00, 1.00121674e+00, -6.33928052e-04,\n", - " -4.64383400e-06, -1.31877770e-05, -9.99999799e-01, 2.83175240e-02,\n", - " -6.28210899e+00, -1.07158021e-03, 1.76007004e-03, -3.02592054e-03,\n", - " -8.73076844e-02, -2.80346612e-03, 8.53845587e-01, -1.84258913e-01,\n", - " -8.17733864e-02, 3.53253655e-04, 4.02125369e-04, 4.18875407e-02,\n", - " -2.33163730e-02, -4.48499723e-03, 9.08703588e-03, -5.54042761e-03,\n", - " -1.37221517e-01]),\n", - " array([-3.14598668e-04, 1.09919594e+00, 1.00102883e+00, -5.94572252e-04,\n", - " -4.81314648e-06, -1.33921869e-05, -9.99999823e-01, 2.83594176e-02,\n", - " -6.28212922e+00, -1.07597418e-03, 1.76915147e-03, -3.03147426e-03,\n", - " -8.74449217e-02, -2.80295330e-03, 8.53851324e-01, -1.88965142e-01,\n", - " -7.87116129e-02, 3.39921872e-04, 4.08239054e-04, 4.18936068e-02,\n", - " -2.02303584e-02, -4.39397639e-03, 9.08142994e-03, -5.55371566e-03,\n", - " -1.37237217e-01]),\n", - " array([-3.17426044e-04, 1.10005002e+00, 1.00083602e+00, -5.56707883e-04,\n", - " -4.97597465e-06, -1.35996623e-05, -9.99999845e-01, 2.84013173e-02,\n", - " -6.28214644e+00, -1.08027909e-03, 1.77822734e-03, -3.03704101e-03,\n", - " -8.75821740e-02, -2.80243312e-03, 8.53857559e-01, -1.93784463e-01,\n", - " -7.57287467e-02, 3.26916955e-04, 4.14391943e-04, 4.18997077e-02,\n", - " -1.72239225e-02, -4.30490511e-03, 9.07586965e-03, -5.56675889e-03,\n", - " -1.37252359e-01]),\n", - " array([-3.20253361e-04, 1.10090410e+00, 1.00063823e+00, -5.20295770e-04,\n", - " -5.13248201e-06, -1.38102250e-05, -9.99999865e-01, 2.84432231e-02,\n", - " -6.28216074e+00, -1.08449687e-03, 1.78729769e-03, -3.04262057e-03,\n", - " -8.77194410e-02, -2.80190569e-03, 8.53864259e-01, -1.98716610e-01,\n", - " -7.28242343e-02, 3.14239317e-04, 4.20588232e-04, 4.19058483e-02,\n", - " -1.42965063e-02, -4.21778083e-03, 9.07035609e-03, -5.57955774e-03,\n", - " -1.37266952e-01]),\n", - " array([-3.23080619e-04, 1.10175817e+00, 1.00043533e+00, -4.85297037e-04,\n", - " -5.28283213e-06, -1.40238994e-05, -9.99999882e-01, 2.84851352e-02,\n", - " -6.28217219e+00, -1.08862947e-03, 1.79636258e-03, -3.04821268e-03,\n", - " -8.78567220e-02, -2.80137113e-03, 8.53871391e-01, -2.03761303e-01,\n", - " -6.99974743e-02, 3.01889051e-04, 4.26832483e-04, 4.19120338e-02,\n", - " -1.14475021e-02, -4.13259987e-03, 9.06489045e-03, -5.59211265e-03,\n", - " -1.37281002e-01]),\n", - " array([-3.25907820e-04, 1.10261225e+00, 1.00022721e+00, -4.51673129e-04,\n", - " -5.42718846e-06, -1.42407121e-05, -9.99999898e-01, 2.85270534e-02,\n", - " -6.28218086e+00, -1.09267882e-03, 1.80542206e-03, -3.05381711e-03,\n", - " -8.79940165e-02, -2.80082954e-03, 8.53878922e-01, -2.08918247e-01,\n", - " -6.72478219e-02, 2.89865956e-04, 4.33129582e-04, 4.19182697e-02,\n", - " -8.67625901e-03, -4.04935755e-03, 9.05947402e-03, -5.60442415e-03,\n", - " -1.37294515e-01]),\n", - " array([-3.28734961e-04, 1.10346632e+00, 1.00001376e+00, -4.19385834e-04,\n", - " -5.56571418e-06, -1.44606925e-05, -9.99999912e-01, 2.85689780e-02,\n", - " -6.28218684e+00, -1.09664687e-03, 1.81447616e-03, -3.05943360e-03,\n", - " -8.81313240e-02, -2.80028102e-03, 8.53886823e-01, -2.14187133e-01,\n", - " -6.45745944e-02, 2.78169567e-04, 4.39484689e-04, 4.19245619e-02,\n", - " -5.98208736e-03, -3.96804828e-03, 9.05410822e-03, -5.61649278e-03,\n", - " -1.37307500e-01]),\n", - " array([-3.31562046e-04, 1.10432039e+00, 9.99794886e-01, -3.88397298e-04,\n", - " -5.69857213e-06, -1.46838725e-05, -9.99999924e-01, 2.86109089e-02,\n", - " -6.28219021e+00, -1.10053554e-03, 1.82352496e-03, -3.06506192e-03,\n", - " -8.82686440e-02, -2.79972566e-03, 8.53895061e-01, -2.19567631e-01,\n", - " -6.19770744e-02, 2.66799174e-04, 4.45903175e-04, 4.19309162e-02,\n", - " -3.36426299e-03, -3.88866560e-03, 9.04879452e-03, -5.62831917e-03,\n", - " -1.37319964e-01]),\n", - " array([-3.34389072e-04, 1.10517446e+00, 9.99570465e-01, -3.58670042e-04,\n", - " -5.82592467e-06, -1.49102868e-05, -9.99999936e-01, 2.86528463e-02,\n", - " -6.28219103e+00, -1.10434674e-03, 1.83256849e-03, -3.07070182e-03,\n", - " -8.84059759e-02, -2.79916353e-03, 8.53903609e-01, -2.25059391e-01,\n", - " -5.94545147e-02, 2.55753836e-04, 4.52390528e-04, 4.19373386e-02,\n", - " -8.22031278e-04, -3.81120225e-03, 9.04353450e-03, -5.63990398e-03,\n", - " -1.37331914e-01]),\n", - " array([-3.37216042e-04, 1.10602854e+00, 9.99340391e-01, -3.30166973e-04,\n", - " -5.94793356e-06, -1.51399729e-05, -9.99999945e-01, 2.86947901e-02,\n", - " -6.28218939e+00, -1.10808239e-03, 1.84160682e-03, -3.07635307e-03,\n", - " -8.85433192e-02, -2.79859470e-03, 8.53912438e-01, -2.30662043e-01,\n", - " -5.70061413e-02, 2.45032398e-04, 4.58952253e-04, 4.19438351e-02,\n", - " 1.64538933e-03, -3.73565030e-03, 9.03832982e-03, -5.65124795e-03,\n", - " -1.37343361e-01]),\n", - " array([-3.40042955e-04, 1.10688261e+00, 9.99104557e-01, -3.02851396e-04,\n", - " -6.06475988e-06, -1.53729709e-05, -9.99999954e-01, 2.87367405e-02,\n", - " -6.28218535e+00, -1.11174439e-03, 1.85064001e-03, -3.08201542e-03,\n", - " -8.86806735e-02, -2.79801923e-03, 8.53921519e-01, -2.36375193e-01,\n", - " -5.46311565e-02, 2.34633494e-04, 4.65593734e-04, 4.19504116e-02,\n", - " 4.03880404e-03, -3.66200114e-03, 9.03318218e-03, -5.66235188e-03,\n", - " -1.37354310e-01]),\n", - " array([-3.42869813e-04, 1.10773668e+00, 9.98862853e-01, -2.76687025e-04,\n", - " -6.17656391e-06, -1.56093237e-05, -9.99999962e-01, 2.87786976e-02,\n", - " -6.28217899e+00, -1.11533464e-03, 1.85966810e-03, -3.08768864e-03,\n", - " -8.88180383e-02, -2.79743716e-03, 8.53930828e-01, -2.42198423e-01,\n", - " -5.23287425e-02, 2.24555553e-04, 4.72320082e-04, 4.19570735e-02,\n", - " 6.35903878e-03, -3.59024557e-03, 9.02809337e-03, -5.67321663e-03,\n", - " -1.37364773e-01]),\n", - " array([-3.45696616e-04, 1.10859075e+00, 9.98615173e-01, -2.51637994e-04,\n", - " -6.28350501e-06, -1.58490760e-05, -9.99999968e-01, 2.88206614e-02,\n", - " -6.28217038e+00, -1.11885501e-03, 1.86869116e-03, -3.09337248e-03,\n", - " -8.89554131e-02, -2.79684855e-03, 8.53940337e-01, -2.48131287e-01,\n", - " -5.00980630e-02, 2.14796791e-04, 4.79135944e-04, 4.19638259e-02,\n", - " 8.60693762e-03, -3.52037387e-03, 9.02306520e-03, -5.68384315e-03,\n", - " -1.37374756e-01]),\n", - " array([-3.48523366e-04, 1.10944482e+00, 9.98361409e-01, -2.27668862e-04,\n", - " -6.38574157e-06, -1.60922751e-05, -9.99999974e-01, 2.88626321e-02,\n", - " -6.28215960e+00, -1.12230739e-03, 1.87770926e-03, -3.09906672e-03,\n", - " -8.90927973e-02, -2.79625343e-03, 8.53950023e-01, -2.54173313e-01,\n", - " -4.79382665e-02, 2.05355208e-04, 4.86045291e-04, 4.19706731e-02,\n", - " 1.07833605e-02, -3.45237586e-03, 9.01809955e-03, -5.69423248e-03,\n", - " -1.37384269e-01]),\n", - " array([-3.51350062e-04, 1.11029889e+00, 9.98101455e-01, -2.04744619e-04,\n", - " -6.48343082e-06, -1.63389694e-05, -9.99999979e-01, 2.89046097e-02,\n", - " -6.28214671e+00, -1.12569363e-03, 1.88672246e-03, -3.10477110e-03,\n", - " -8.92301907e-02, -2.79565181e-03, 8.53959862e-01, -2.60323998e-01,\n", - " -4.58484874e-02, 1.96228570e-04, 4.93051167e-04, 4.19776184e-02,\n", - " 1.28891810e-02, -3.38624091e-03, 9.01319833e-03, -5.70438573e-03,\n", - " -1.37393321e-01]),\n", - " array([-3.54176706e-04, 1.11115297e+00, 9.97835203e-01, -1.82830695e-04,\n", - " -6.57672876e-06, -1.65892084e-05, -9.99999983e-01, 2.89465944e-02,\n", - " -6.28213178e+00, -1.12901559e-03, 1.89573082e-03, -3.11048541e-03,\n", - " -8.93675926e-02, -2.79504370e-03, 8.53969831e-01, -2.66582810e-01,\n", - " -4.38278482e-02, 1.87414388e-04, 5.00155403e-04, 4.19846641e-02,\n", - " 1.49252851e-02, -3.32195804e-03, 9.00836346e-03, -5.71430409e-03,\n", - " -1.37401921e-01]),\n", - " array([-3.57003300e-04, 1.11200704e+00, 9.97562548e-01, -1.61892965e-04,\n", - " -6.66578998e-06, -1.68430416e-05, -9.99999987e-01, 2.89885862e-02,\n", - " -6.28211489e+00, -1.13227510e-03, 1.90473442e-03, -3.11620940e-03,\n", - " -8.95050027e-02, -2.79442913e-03, 8.53979910e-01, -2.72949180e-01,\n", - " -4.18754610e-02, 1.78909897e-04, 5.07358301e-04, 4.19918105e-02,\n", - " 1.68925693e-02, -3.25951595e-03, 9.00359691e-03, -5.72398886e-03,\n", - " -1.37410078e-01]),\n", - " array([-3.59829844e-04, 1.11286111e+00, 9.97283385e-01, -1.41897751e-04,\n", - " -6.75076755e-06, -1.71005178e-05, -9.99999990e-01, 2.90305852e-02,\n", - " -6.28209610e+00, -1.13547401e-03, 1.91373332e-03, -3.12194284e-03,\n", - " -8.96424205e-02, -2.79380809e-03, 8.53990077e-01, -2.79422509e-01,\n", - " -3.99904283e-02, 1.70712017e-04, 5.14658271e-04, 4.19990565e-02,\n", - " 1.87919395e-02, -3.19890307e-03, 8.99890065e-03, -5.73344144e-03,\n", - " -1.37417801e-01]),\n", - " array([-3.62656340e-04, 1.11371519e+00, 9.96997609e-01, -1.22811830e-04,\n", - " -6.83181279e-06, -1.73616839e-05, -9.99999992e-01, 2.90725916e-02,\n", - " -6.28207547e+00, -1.13861411e-03, 1.92272760e-03, -3.12768550e-03,\n", - " -8.97798456e-02, -2.79318057e-03, 8.54000313e-01, -2.86002158e-01,\n", - " -3.81718440e-02, 1.62817317e-04, 5.22051439e-04, 4.20063982e-02,\n", - " 2.06243104e-02, -3.14010762e-03, 8.99427666e-03, -5.74266332e-03,\n", - " -1.37425099e-01]),\n", - " array([-3.65482789e-04, 1.11456927e+00, 9.96705116e-01, -1.04602433e-04,\n", - " -6.90907511e-06, -1.76265835e-05, -9.99999994e-01, 2.91146054e-02,\n", - " -6.28205308e+00, -1.14169723e-03, 1.93171733e-03, -3.13343716e-03,\n", - " -8.99172775e-02, -2.79254658e-03, 8.54010600e-01, -2.92687453e-01,\n", - " -3.64187946e-02, 1.55221971e-04, 5.29531206e-04, 4.20138294e-02,\n", - " 2.23906043e-02, -3.08311765e-03, 8.98972693e-03, -5.75165610e-03,\n", - " -1.37431982e-01]),\n", - " array([-3.68309191e-04, 1.11542335e+00, 9.96405802e-01, -8.72372545e-05,\n", - " -6.98270178e-06, -1.78952550e-05, -9.99999996e-01, 2.91566268e-02,\n", - " -6.28202899e+00, -1.14472515e-03, 1.94070258e-03, -3.13919758e-03,\n", - " -9.00547160e-02, -2.79190611e-03, 8.54020921e-01, -2.99477679e-01,\n", - " -3.47303589e-02, 1.47921708e-04, 5.37087780e-04, 4.20213404e-02,\n", - " 2.40917511e-02, -3.02792110e-03, 8.98525344e-03, -5.76042150e-03,\n", - " -1.37438459e-01]),\n", - " array([-3.71135549e-04, 1.11627742e+00, 9.96099565e-01, -7.06844508e-05,\n", - " -7.05283768e-06, -1.81677306e-05, -9.99999997e-01, 2.91986557e-02,\n", - " -6.28200326e+00, -1.14769966e-03, 1.94968344e-03, -3.14496654e-03,\n", - " -9.01921605e-02, -2.79125916e-03, 8.54031260e-01, -3.06372080e-01,\n", - " -3.31056087e-02, 1.40911750e-04, 5.44707660e-04, 4.20289178e-02,\n", - " 2.57286876e-02, -2.97450584e-03, 8.98085817e-03, -5.76896135e-03,\n", - " -1.37444539e-01]),\n", - " array([-3.73961864e-04, 1.11713151e+00, 9.95786302e-01, -5.49126471e-05,\n", - " -7.11962500e-06, -1.84440331e-05, -9.99999998e-01, 2.92406923e-02,\n", - " -6.28197596e+00, -1.15062252e-03, 1.95865998e-03, -3.15074382e-03,\n", - " -9.03296108e-02, -2.79060573e-03, 8.54041602e-01, -3.13369857e-01,\n", - " -3.15436090e-02, 1.34186757e-04, 5.52373098e-04, 4.20365441e-02,\n", - " 2.73023580e-02, -2.92285972e-03, 8.97654306e-03, -5.77727760e-03,\n", - " -1.37450231e-01]),\n", - " array([-3.76788137e-04, 1.11798559e+00, 9.95465913e-01, -3.98909393e-05,\n", - " -7.18320294e-06, -1.87241743e-05, -9.99999999e-01, 2.92827364e-02,\n", - " -6.28194715e+00, -1.15349549e-03, 1.96763229e-03, -3.15652919e-03,\n", - " -9.04670663e-02, -2.78994583e-03, 8.54051932e-01, -3.20470167e-01,\n", - " -3.00434173e-02, 1.27740754e-04, 5.60061517e-04, 4.20441967e-02,\n", - " 2.88137136e-02, -2.87297064e-03, 8.97231007e-03, -5.78537232e-03,\n", - " -1.37455546e-01]),\n", - " array([-3.79614370e-04, 1.11883967e+00, 9.95138297e-01, -2.55888982e-05,\n", - " -7.24370735e-06, -1.90081520e-05, -9.99999999e-01, 2.93247883e-02,\n", - " -6.28191688e+00, -1.15632031e-03, 1.97660045e-03, -3.16232244e-03,\n", - " -9.06045268e-02, -2.78927951e-03, 8.54062239e-01, -3.27672119e-01,\n", - " -2.86040840e-02, 1.21567065e-04, 5.67744915e-04, 4.20518478e-02,\n", - " 3.02637130e-02, -2.82482655e-03, 8.96816109e-03, -5.79324772e-03,\n", - " -1.37460493e-01]),\n", - " array([-3.82440563e-04, 1.11969376e+00, 9.94803354e-01, -1.19765736e-05,\n", - " -7.30127036e-06, -1.92959467e-05, -1.00000000e+00, 2.93668478e-02,\n", - " -6.28188523e+00, -1.15909873e-03, 1.98556455e-03, -3.16812334e-03,\n", - " -9.07419919e-02, -2.78860679e-03, 8.54072510e-01, -3.34974778e-01,\n", - " -2.72246513e-02, 1.15658234e-04, 5.75389244e-04, 4.20594634e-02,\n", - " 3.16533231e-02, -2.77841556e-03, 8.96409802e-03, -5.80090614e-03,\n", - " -1.37465080e-01]),\n", - " array([-3.85266719e-04, 1.12054784e+00, 9.94460987e-01, 9.75501885e-07,\n", - " -7.35601992e-06, -1.95875188e-05, -1.00000000e+00, 2.94089148e-02,\n", - " -6.28185225e+00, -1.16183246e-03, 1.99452467e-03, -3.17393169e-03,\n", - " -9.08794612e-02, -2.78792776e-03, 8.54082736e-01, -3.42377155e-01,\n", - " -2.59041530e-02, 1.10005948e-04, 5.82953780e-04, 4.20670028e-02,\n", - " 3.29835193e-02, -2.73372594e-03, 8.96012270e-03, -5.80835007e-03,\n", - " -1.37469318e-01]),\n", - " array([-3.88092839e-04, 1.12140193e+00, 9.94111096e-01, 1.32963076e-05,\n", - " -7.40807935e-06, -1.98828046e-05, -1.00000000e+00, 2.94509892e-02,\n", - " -6.28181799e+00, -1.16452320e-03, 2.00348091e-03, -3.17974728e-03,\n", - " -9.10169344e-02, -2.78724252e-03, 8.54092906e-01, -3.49878211e-01,\n", - " -2.46416137e-02, 1.04600963e-04, 5.90390497e-04, 4.20744181e-02,\n", - " 3.42552863e-02, -2.69074617e-03, 8.95623692e-03, -5.81558211e-03,\n", - " -1.37473217e-01]),\n", - " array([-3.90918923e-04, 1.12225602e+00, 9.93753587e-01, 2.50143303e-05,\n", - " -7.45756685e-06, -2.01817125e-05, -9.99999999e-01, 2.94930708e-02,\n", - " -6.28178252e+00, -1.16717267e-03, 2.01243335e-03, -3.18556988e-03,\n", - " -9.11544112e-02, -2.78655119e-03, 8.54103013e-01, -3.57476857e-01,\n", - " -2.34360478e-02, 9.94330249e-05, 5.97643449e-04, 4.20816533e-02,\n", - " 3.54696192e-02, -2.64946501e-03, 8.95244244e-03, -5.82260505e-03,\n", - " -1.37476786e-01]),\n", - " array([-3.93744974e-04, 1.12311011e+00, 9.93388363e-01, 3.61575581e-05,\n", - " -7.50459492e-06, -2.04841185e-05, -9.99999999e-01, 2.95351595e-02,\n", - " -6.28174589e+00, -1.16978254e-03, 2.02138209e-03, -3.19139930e-03,\n", - " -9.12918912e-02, -2.78585398e-03, 8.54113049e-01, -3.65171944e-01,\n", - " -2.22864582e-02, 9.44907922e-05, 6.04648182e-04, 4.20886440e-02,\n", - " 3.66275244e-02, -2.60987147e-03, 8.94874097e-03, -5.82942180e-03,\n", - " -1.37480034e-01]),\n", - " array([-3.96570992e-04, 1.12396420e+00, 9.93015329e-01, 4.67534748e-05,\n", - " -7.54926981e-06, -2.07898620e-05, -9.99999999e-01, 2.95772548e-02,\n", - " -6.28170816e+00, -1.17235449e-03, 2.03032723e-03, -3.19723534e-03,\n", - " -9.14293742e-02, -2.78515110e-03, 8.54123009e-01, -3.72962272e-01,\n", - " -2.11918361e-02, 8.97617696e-05, 6.11331200e-04, 4.20953167e-02,\n", - " 3.77300205e-02, -2.57195489e-03, 8.94513415e-03, -5.83603545e-03,\n", - " -1.37482972e-01]),\n", - " array([-3.99396980e-04, 1.12481830e+00, 9.92634394e-01, 5.68290528e-05,\n", - " -7.59169090e-06, -2.10987408e-05, -9.99999998e-01, 2.96193564e-02,\n", - " -6.28166939e+00, -1.17489020e-03, 2.03926885e-03, -3.20307779e-03,\n", - " -9.15668598e-02, -2.78444286e-03, 8.54132887e-01, -3.80846580e-01,\n", - " -2.01511590e-02, 8.52322437e-05, 6.17609486e-04, 4.21015883e-02,\n", - " 3.87781399e-02, -2.53570492e-03, 8.94162358e-03, -5.84244923e-03,\n", - " -1.37485610e-01]),\n", - " array([-4.02222938e-04, 1.12567239e+00, 9.92245466e-01, 6.64107461e-05,\n", - " -7.63195006e-06, -2.14105063e-05, -9.99999998e-01, 2.96614637e-02,\n", - " -6.28162961e+00, -1.17739131e-03, 2.04820706e-03, -3.20892645e-03,\n", - " -9.17043478e-02, -2.78372962e-03, 8.54142680e-01, -3.88823546e-01,\n", - " -1.91633896e-02, 8.08872309e-05, 6.23390128e-04, 4.21073660e-02,\n", - " 3.97729296e-02, -2.50111156e-03, 8.93821077e-03, -5.84866656e-03,\n", - " -1.37487958e-01]),\n", - " array([-4.05048867e-04, 1.12652649e+00, 9.91848453e-01, 7.55244818e-05,\n", - " -7.67013103e-06, -2.17248583e-05, -9.99999997e-01, 2.97035763e-02,\n", - " -6.28158890e+00, -1.17985948e-03, 2.05714196e-03, -3.21478114e-03,\n", - " -9.18418378e-02, -2.78301182e-03, 8.54152386e-01, -3.96891791e-01,\n", - " -1.82274747e-02, 7.67104385e-05, 6.28570051e-04, 4.21125466e-02,\n", - " 4.07154529e-02, -2.46816509e-03, 8.93489718e-03, -5.85469102e-03,\n", - " -1.37490026e-01]),\n", - " array([-4.07874768e-04, 1.12738058e+00, 9.91443266e-01, 8.41956521e-05,\n", - " -7.70630867e-06, -2.20414400e-05, -9.99999996e-01, 2.97456933e-02,\n", - " -6.28154729e+00, -1.18229633e-03, 2.06607364e-03, -3.22064167e-03,\n", - " -9.19793296e-02, -2.78228999e-03, 8.54162001e-01, -4.05049868e-01,\n", - " -1.73423438e-02, 7.26842437e-05, 6.33035914e-04, 4.21170167e-02,\n", - " 4.16067909e-02, -2.43685607e-03, 8.93168419e-03, -5.86052635e-03,\n", - " -1.37491825e-01]),\n", - " array([-4.10700643e-04, 1.12823468e+00, 9.91029819e-01, 9.24491040e-05,\n", - " -7.74054840e-06, -2.23598328e-05, -9.99999995e-01, 2.97878140e-02,\n", - " -6.28150484e+00, -1.18470351e-03, 2.07500222e-03, -3.22650785e-03,\n", - " -9.21168230e-02, -2.78156477e-03, 8.54171527e-01, -4.13296269e-01,\n", - " -1.65069073e-02, 6.87896932e-05, 6.36664178e-04, 4.21206527e-02,\n", - " 4.24480435e-02, -2.40717528e-03, 8.92857310e-03, -5.86617650e-03,\n", - " -1.37493365e-01]),\n", - " array([-4.13526492e-04, 1.12908878e+00, 9.90608025e-01, 1.00309130e-04,\n", - " -7.77290547e-06, -2.26795514e-05, -9.99999995e-01, 2.98299373e-02,\n", - " -6.28146160e+00, -1.18708262e-03, 2.08392778e-03, -3.23237949e-03,\n", - " -9.22543177e-02, -2.78083690e-03, 8.54180963e-01, -4.21629416e-01,\n", - " -1.57200556e-02, 6.50065296e-05, 6.39321404e-04, 4.21233211e-02,\n", - " 4.32403310e-02, -2.37911362e-03, 8.92556514e-03, -5.87164558e-03,\n", - " -1.37494656e-01]),\n", - " array([-4.16352316e-04, 1.12994288e+00, 9.90177800e-01, 1.07799457e-04,\n", - " -7.80342436e-06, -2.30000389e-05, -9.99999994e-01, 2.98720622e-02,\n", - " -6.28141762e+00, -1.18943528e-03, 2.09285044e-03, -3.23825643e-03,\n", - " -9.23918134e-02, -2.78010722e-03, 8.54190311e-01, -4.30047667e-01,\n", - " -1.49806570e-02, 6.13132486e-05, 6.40864812e-04, 4.21248790e-02,\n", - " 4.39847961e-02, -2.35266201e-03, 8.92266143e-03, -5.87693790e-03,\n", - " -1.37495710e-01]),\n", - " array([-4.19178116e-04, 1.13079698e+00, 9.89739060e-01, 1.14943233e-04,\n", - " -7.83213821e-06, -2.33206631e-05, -9.99999993e-01, 2.99141873e-02,\n", - " -6.28137293e+00, -1.19176309e-03, 2.10177031e-03, -3.24413849e-03,\n", - " -9.25293099e-02, -2.77937672e-03, 8.54199573e-01, -4.38549306e-01,\n", - " -1.42875567e-02, 5.76871927e-05, 6.41143152e-04, 4.21251750e-02,\n", - " 4.46826047e-02, -2.32781124e-03, 8.91986303e-03, -5.88205797e-03,\n", - " -1.37496538e-01]),\n", - " array([-4.22003893e-04, 1.13165109e+00, 9.89291726e-01, 1.21763019e-04,\n", - " -7.85906829e-06, -2.36407124e-05, -9.99999992e-01, 2.99563114e-02,\n", - " -6.28132760e+00, -1.19406765e-03, 2.11068748e-03, -3.25002550e-03,\n", - " -9.26668071e-02, -2.77864653e-03, 8.54208753e-01, -4.47132547e-01,\n", - " -1.36395751e-02, 5.41046877e-05, 6.39997931e-04, 4.21240505e-02,\n", - " 4.53349477e-02, -2.30455174e-03, 8.91717088e-03, -5.88701049e-03,\n", - " -1.37497151e-01]),\n", - " array([-4.24829646e-04, 1.13250519e+00, 9.88835717e-01, 1.28280770e-04,\n", - " -7.88422361e-06, -2.39593931e-05, -9.99999991e-01, 2.99984327e-02,\n", - " -6.28128166e+00, -1.19635052e-03, 2.11960206e-03, -3.25591730e-03,\n", - " -9.28043046e-02, -2.77791791e-03, 8.54217856e-01, -4.55795532e-01,\n", - " -1.30355064e-02, 5.05412273e-05, 6.37265050e-04, 4.21213413e-02,\n", - " 4.59430428e-02, -2.28287336e-03, 8.91458585e-03, -5.89180037e-03,\n", - " -1.37497561e-01]),\n", - " array([-4.27655377e-04, 1.13335929e+00, 9.88370956e-01, 1.34517826e-04,\n", - " -7.90760062e-06, -2.42758277e-05, -9.99999991e-01, 3.00405496e-02,\n", - " -6.28123515e+00, -1.19861328e-03, 2.12851417e-03, -3.26181373e-03,\n", - " -9.29418024e-02, -2.77719226e-03, 8.54226885e-01, -4.64536326e-01,\n", - " -1.24741169e-02, 4.69717133e-05, 6.32776903e-04, 4.21168796e-02,\n", - " 4.65081355e-02, -2.26276507e-03, 8.91210867e-03, -5.89643272e-03,\n", - " -1.37497779e-01]),\n", - " array([-4.30481085e-04, 1.13421340e+00, 9.87897368e-01, 1.40494896e-04,\n", - " -7.92918303e-06, -2.45890545e-05, -9.99999990e-01, 3.00826601e-02,\n", - " -6.28118812e+00, -1.20085750e-03, 2.13742391e-03, -3.26771465e-03,\n", - " -9.30793002e-02, -2.77647117e-03, 8.54235849e-01, -4.73352918e-01,\n", - " -1.19541439e-02, 4.33707579e-05, 6.26365003e-04, 4.21104969e-02,\n", - " 4.70315006e-02, -2.24421458e-03, 8.90974001e-03, -5.90091286e-03,\n", - " -1.37497818e-01]),\n", - " array([-4.33306771e-04, 1.13506751e+00, 9.87414880e-01, 1.46232041e-04,\n", - " -7.94894189e-06, -2.48980288e-05, -9.99999989e-01, 3.01247621e-02,\n", - " -6.28114060e+00, -1.20308471e-03, 2.14633139e-03, -3.27361989e-03,\n", - " -9.32167979e-02, -2.77575635e-03, 8.54244753e-01, -4.82243218e-01,\n", - " -1.14742939e-02, 3.97130542e-05, 6.17863181e-04, 4.21020267e-02,\n", - " 4.75144439e-02, -2.22720793e-03, 8.90748039e-03, -5.90524635e-03,\n", - " -1.37497689e-01]),\n", - " array([-4.36132435e-04, 1.13592161e+00, 9.86923421e-01, 1.51748660e-04,\n", - " -7.96683584e-06, -2.52016257e-05, -9.99999988e-01, 3.01668534e-02,\n", - " -6.28109264e+00, -1.20529644e-03, 2.15523672e-03, -3.27952933e-03,\n", - " -9.33542953e-02, -2.77504970e-03, 8.54253605e-01, -4.91205058e-01,\n", - " -1.10332416e-02, 3.59738241e-05, 6.07111428e-04, 4.20913088e-02,\n", - " 4.79583036e-02, -2.21172897e-03, 8.90533025e-03, -5.90943896e-03,\n", - " -1.37497405e-01]),\n", - " array([-4.38958076e-04, 1.13677572e+00, 9.86422921e-01, 1.57063472e-04,\n", - " -7.98281164e-06, -2.54986459e-05, -9.99999987e-01, 3.02089316e-02,\n", - " -6.28104428e+00, -1.20749419e-03, 2.16414001e-03, -3.28544283e-03,\n", - " -9.34917923e-02, -2.77435324e-03, 8.54262413e-01, -5.00236186e-01,\n", - " -1.06296286e-02, 3.21293480e-05, 5.93960431e-04, 4.20781939e-02,\n", - " 4.83644509e-02, -2.19775876e-03, 8.90328988e-03, -5.91349666e-03,\n", - " -1.37496980e-01]),\n", - " array([-4.41783695e-04, 1.13762983e+00, 9.85913314e-01, 1.62194501e-04,\n", - " -7.99680501e-06, -2.57878230e-05, -9.99999986e-01, 3.02509942e-02,\n", - " -6.28099555e+00, -1.20967947e-03, 2.17304137e-03, -3.29136025e-03,\n", - " -9.36292887e-02, -2.77366917e-03, 8.54271187e-01, -5.09334267e-01,\n", - " -1.02620616e-02, 2.81575859e-05, 5.78276865e-04, 4.20625484e-02,\n", - " 4.87342922e-02, -2.18527492e-03, 8.90135948e-03, -5.91742570e-03,\n", - " -1.37496426e-01]),\n", - " array([-4.44609291e-04, 1.13848394e+00, 9.85394536e-01, 1.67159055e-04,\n", - " -8.00874184e-06, -2.60678355e-05, -9.99999986e-01, 3.02930384e-02,\n", - " -6.28094648e+00, -1.21185372e-03, 2.18194091e-03, -3.29728149e-03,\n", - " -9.37667845e-02, -2.77299979e-03, 8.54279936e-01, -5.18496882e-01,\n", - " -9.92911212e-03, 2.40388938e-05, 5.59949497e-04, 4.20442609e-02,\n", - " 4.90692696e-02, -2.17425084e-03, 8.89953910e-03, -5.92123253e-03,\n", - " -1.37495757e-01]),\n", - " array([-4.47434863e-04, 1.13933805e+00, 9.84866524e-01, 1.71973710e-04,\n", - " -8.01853979e-06, -2.63373205e-05, -9.99999985e-01, 3.03350617e-02,\n", - " -6.28089711e+00, -1.21401837e-03, 2.19083874e-03, -3.30320641e-03,\n", - " -9.39042795e-02, -2.77234754e-03, 8.54288670e-01, -5.27721523e-01,\n", - " -9.62931442e-03, 1.97568434e-05, 5.38896146e-04, 4.20232490e-02,\n", - " 4.93708623e-02, -2.16465482e-03, 8.89782869e-03, -5.92492386e-03,\n", - " -1.37494986e-01]),\n", - " array([-4.50260411e-04, 1.14019216e+00, 9.84329221e-01, 1.76654291e-04,\n", - " -8.02611038e-06, -2.65948925e-05, -9.99999984e-01, 3.03770612e-02,\n", - " -6.28084746e+00, -1.21617482e-03, 2.19973497e-03, -3.30913492e-03,\n", - " -9.40417736e-02, -2.77171494e-03, 8.54297400e-01, -5.37005595e-01,\n", - " -9.36116515e-03, 1.52991490e-05, 5.15071540e-04, 4.19994672e-02,\n", - " 4.96405874e-02, -2.15644907e-03, 8.89622802e-03, -5.92850663e-03,\n", - " -1.37494128e-01]),\n", - " array([-4.53085935e-04, 1.14104627e+00, 9.83782569e-01, 1.81215850e-04,\n", - " -8.03136157e-06, -2.68391662e-05, -9.99999983e-01, 3.04190341e-02,\n", - " -6.28079758e+00, -1.21832441e-03, 2.20862970e-03, -3.31506690e-03,\n", - " -9.41792668e-02, -2.77110455e-03, 8.54306137e-01, -5.46346413e-01,\n", - " -9.12312207e-03, 1.06587063e-05, 4.88476118e-04, 4.19729160e-02,\n", - " 4.98800013e-02, -2.14958864e-03, 8.89473676e-03, -5.93198806e-03,\n", - " -1.37493198e-01]),\n", - " array([-4.55911434e-04, 1.14190038e+00, 9.83226514e-01, 1.85672650e-04,\n", - " -8.03420093e-06, -2.70687844e-05, -9.99999982e-01, 3.04609777e-02,\n", - " -6.28074749e+00, -1.22046843e-03, 2.21752306e-03, -3.32100228e-03,\n", - " -9.43167590e-02, -2.77051899e-03, 8.54314892e-01, -5.55741199e-01,\n", - " -8.91360324e-03, 5.83474517e-06, 4.59165781e-04, 4.19436511e-02,\n", - " 5.00906999e-02, -2.14402021e-03, 8.89335443e-03, -5.93537558e-03,\n", - " -1.37492210e-01]),\n", - " array([-4.58736907e-04, 1.14275449e+00, 9.82661006e-01, 1.90038141e-04,\n", - " -8.03453947e-06, -2.72824507e-05, -9.99999982e-01, 3.05028895e-02,\n", - " -6.28069722e+00, -1.22260811e-03, 2.22641514e-03, -3.32694096e-03,\n", - " -9.44542502e-02, -2.76996080e-03, 8.54323676e-01, -5.65187081e-01,\n", - " -8.73098617e-03, 8.34097702e-07, 4.27262606e-04, 4.19117943e-02,\n", - " 5.02743200e-02, -2.13968079e-03, 8.89208040e-03, -5.93867691e-03,\n", - " -1.37491178e-01]),\n", - " array([-4.61562353e-04, 1.14360860e+00, 9.82085997e-01, 1.94324943e-04,\n", - " -8.03229615e-06, -2.74789688e-05, -9.99999981e-01, 3.05447671e-02,\n", - " -6.28064679e+00, -1.22474461e-03, 2.23530605e-03, -3.33288286e-03,\n", - " -9.45917403e-02, -2.76943246e-03, 8.54332501e-01, -5.74681093e-01,\n", - " -8.57360709e-03, -4.32742007e-06, 3.92966521e-04, 4.18775456e-02,\n", - " 5.04325397e-02, -2.13649628e-03, 8.89091387e-03, -5.94190004e-03,\n", - " -1.37490120e-01]),\n", - " array([-4.64387774e-04, 1.14446271e+00, 9.81501441e-01, 1.98544822e-04,\n", - " -8.02740308e-06, -2.76572875e-05, -9.99999980e-01, 3.05866083e-02,\n", - " -6.28059622e+00, -1.22687899e-03, 2.24419591e-03, -3.33882791e-03,\n", - " -9.47292293e-02, -2.76893629e-03, 8.54341379e-01, -5.84220172e-01,\n", - " -8.43976032e-03, -9.62351629e-06, 3.56567890e-04, 4.18411953e-02,\n", - " 5.05670790e-02, -2.13437994e-03, 8.88985392e-03, -5.94505321e-03,\n", - " -1.37489051e-01]),\n", - " array([-4.67213167e-04, 1.14531683e+00, 9.80907297e-01, 2.02708669e-04,\n", - " -8.01981162e-06, -2.78165529e-05, -9.99999979e-01, 3.06284114e-02,\n", - " -6.28054554e+00, -1.22901222e-03, 2.25308481e-03, -3.34477605e-03,\n", - " -9.48667173e-02, -2.76847433e-03, 8.54350321e-01, -5.93801155e-01,\n", - " -8.32769768e-03, -1.50158285e-05, 3.18460968e-04, 4.18031376e-02,\n", - " 5.06797004e-02, -2.13323077e-03, 8.88889943e-03, -5.94814494e-03,\n", - " -1.37487987e-01]),\n", - " array([-4.70038534e-04, 1.14617094e+00, 9.80303527e-01, 2.06826481e-04,\n", - " -8.00949925e-06, -2.79561671e-05, -9.99999978e-01, 3.06701753e-02,\n", - " -6.28049477e+00, -1.23114515e-03, 2.26197285e-03, -3.35072724e-03,\n", - " -9.50042043e-02, -2.76804833e-03, 8.54359339e-01, -6.03420779e-01,\n", - " -8.23562797e-03, -2.04522360e-05, 2.79158126e-04, 4.17638849e-02,\n", - " 5.07722094e-02, -2.13293176e-03, 8.88804915e-03, -5.95118404e-03,\n", - " -1.37486945e-01]),\n", - " array([-4.72863874e-04, 1.14702505e+00, 9.79690094e-01, 2.10907338e-04,\n", - " -7.99647736e-06, -2.80758548e-05, -9.99999977e-01, 3.07118994e-02,\n", - " -6.28044392e+00, -1.23327850e-03, 2.27086016e-03, -3.35668142e-03,\n", - " -9.51416902e-02, -2.76765955e-03, 8.54368443e-01, -6.13075679e-01,\n", - " -8.16171658e-03, -2.58650944e-05, 2.39304730e-04, 4.17240828e-02,\n", - " 5.08464547e-02, -2.13334813e-03, 8.88730162e-03, -5.95417958e-03,\n", - " -1.37485942e-01]),\n", - " array([-4.75689188e-04, 1.14787916e+00, 9.79066968e-01, 2.14959379e-04,\n", - " -7.98079995e-06, -2.81757378e-05, -9.99999976e-01, 3.07535839e-02,\n", - " -6.28039302e+00, -1.23541283e-03, 2.27974681e-03, -3.36263856e-03,\n", - " -9.52791752e-02, -2.76730870e-03, 8.54377646e-01, -6.22762387e-01,\n", - " -8.10408513e-03, -3.11694113e-05, 1.99694508e-04, 4.16845250e-02,\n", - " 5.09043287e-02, -2.13432544e-03, 8.88665522e-03, -5.95714094e-03,\n", - " -1.37484996e-01]),\n", - " array([-4.78514478e-04, 1.14873327e+00, 9.78434120e-01, 2.18989784e-04,\n", - " -7.96257323e-06, -2.82564164e-05, -9.99999976e-01, 3.07952301e-02,\n", - " -6.28034207e+00, -1.23754851e-03, 2.28863292e-03, -3.36859864e-03,\n", - " -9.54166593e-02, -2.76699576e-03, 8.54386956e-01, -6.32477329e-01,\n", - " -8.06081119e-03, -3.62609869e-05, 1.61285206e-04, 4.16461697e-02,\n", - " 5.09477675e-02, -2.13568772e-03, 8.88610817e-03, -5.96007777e-03,\n", - " -1.37484125e-01]),\n", - " array([-4.81339745e-04, 1.14958739e+00, 9.77791526e-01, 2.23004747e-04,\n", - " -7.94196622e-06, -2.83190600e-05, -9.99999975e-01, 3.08368402e-02,\n", - " -6.28029109e+00, -1.23968575e-03, 2.29751858e-03, -3.37456164e-03,\n", - " -9.55541427e-02, -2.76671986e-03, 8.54396384e-01, -6.42216824e-01,\n", - " -8.02992810e-03, -4.10145520e-05, 1.25214268e-04, 4.16101545e-02,\n", - " 5.09787513e-02, -2.13723557e-03, 8.88565846e-03, -5.96300004e-03,\n", - " -1.37483346e-01]),\n", - " array([-4.84164991e-04, 1.15044150e+00, 9.77139164e-01, 2.27009458e-04,\n", - " -7.91922219e-06, -2.83655040e-05, -9.99999974e-01, 3.08784180e-02,\n", - " -6.28024009e+00, -1.24182449e-03, 2.30640388e-03, -3.38052756e-03,\n", - " -9.56916254e-02, -2.76647908e-03, 8.54405938e-01, -6.51977081e-01,\n", - " -8.00942473e-03, -4.52819381e-05, 9.28142315e-05, 4.15778125e-02,\n", - " 5.09993043e-02, -2.13874431e-03, 8.88530391e-03, -5.96591800e-03,\n", - " -1.37482680e-01]),\n", - " array([-4.86990221e-04, 1.15129561e+00, 9.76477019e-01, 2.31008080e-04,\n", - " -7.89467106e-06, -2.83983549e-05, -9.99999973e-01, 3.09199687e-02,\n", - " -6.28018908e+00, -1.24396446e-03, 2.31528892e-03, -3.38649640e-03,\n", - " -9.58291075e-02, -2.76627027e-03, 8.54415628e-01, -6.61754201e-01,\n", - " -7.99724549e-03, -4.88903261e-05, 6.56274681e-05, 4.15506866e-02,\n", - " 5.10114946e-02, -2.13996221e-03, 8.88504215e-03, -5.96884223e-03,\n", - " -1.37482144e-01]),\n", - " array([-4.89815438e-04, 1.15214972e+00, 9.75805077e-01, 2.35003724e-04,\n", - " -7.86874252e-06, -2.84211024e-05, -9.99999972e-01, 3.09614993e-02,\n", - " -6.28013806e+00, -1.24610506e-03, 2.32417379e-03, -3.39246818e-03,\n", - " -9.59665893e-02, -2.76608887e-03, 8.54425459e-01, -6.71544169e-01,\n", - " -7.99129017e-03, -5.16406248e-05, 4.54198245e-05, 4.15305433e-02,\n", - " 5.10174348e-02, -2.14060885e-03, 8.88487057e-03, -5.97178359e-03,\n", - " -1.37481759e-01]),\n", - " array([-4.92640647e-04, 1.15300384e+00, 9.75123329e-01, 2.38998430e-04,\n", - " -7.84197998e-06, -2.84382364e-05, -9.99999971e-01, 3.10030186e-02,\n", - " -6.28008704e+00, -1.24824544e-03, 2.33305858e-03, -3.39844293e-03,\n", - " -9.61040708e-02, -2.76592867e-03, 8.54435439e-01, -6.81342861e-01,\n", - " -7.98941402e-03, -5.33060403e-05, 3.41926545e-05, 4.15193848e-02,\n", - " 5.10192813e-02, -2.14037366e-03, 8.88478637e-03, -5.97475328e-03,\n", - " -1.37481544e-01])],\n", - " [array([ 1.17519943e+02, 2.11305505e+02, 1.17355139e+02, 2.11140701e+02,\n", - " 5.75374672e-04, 3.23738398e-01, -3.90869476e-03, -3.22259742e-04,\n", - " -3.79812908e-04, -1.53569807e-02]),\n", - " array([ 1.16186384e+02, 2.02830360e+02, 1.16054649e+02, 2.02698625e+02,\n", - " 5.59035589e-04, 3.00324142e-01, -3.73569748e-03, -3.15875905e-04,\n", - " -3.66706021e-04, -1.53578591e-02]),\n", - " array([ 1.14823441e+02, 1.94588752e+02, 1.14721881e+02, 1.94487193e+02,\n", - " 5.39118872e-04, 2.77773891e-01, -3.57024506e-03, -3.09608851e-04,\n", - " -3.53845798e-04, -1.53607888e-02]),\n", - " array([ 1.13433926e+02, 1.86568163e+02, 1.13359568e+02, 1.86493805e+02,\n", - " 5.16203285e-04, 2.56037229e-01, -3.41226236e-03, -3.03449659e-04,\n", - " -3.41209873e-04, -1.53656091e-02]),\n", - " array([ 1.12020986e+02, 1.78756005e+02, 1.11970847e+02, 1.78705866e+02,\n", - " 4.90823870e-04, 2.35062413e-01, -3.26163327e-03, -2.97390593e-04,\n", - " -3.28778915e-04, -1.53721652e-02]),\n", - " array([ 1.10588107e+02, 1.71139753e+02, 1.10559252e+02, 1.71110898e+02,\n", - " 4.63473007e-04, 2.14796806e-01, -3.11820820e-03, -2.91424965e-04,\n", - " -3.16536255e-04, -1.53803075e-02]),\n", - " array([ 1.09139094e+02, 1.63707045e+02, 1.09128683e+02, 1.63696634e+02,\n", - " 4.34601802e-04, 1.95187253e-01, -2.98181056e-03, -2.85547004e-04,\n", - " -3.04467535e-04, -1.53898917e-02]),\n", - " array([ 1.07678053e+02, 1.56445758e+02, 1.07683380e+02, 1.56451084e+02,\n", - " 4.04621666e-04, 1.76180411e-01, -2.85224249e-03, -2.79751738e-04,\n", - " -2.92560400e-04, -1.54007780e-02]),\n", - " array([ 1.06209370e+02, 1.49344076e+02, 1.06227886e+02, 1.49362591e+02,\n", - " 3.73906064e-04, 1.57723029e-01, -2.72928993e-03, -2.74034888e-04,\n", - " -2.80804224e-04, -1.54128309e-02]),\n", - " array([ 1.04737676e+02, 1.42390531e+02, 1.04767012e+02, 1.42419866e+02,\n", - " 3.42792368e-04, 1.39762196e-01, -2.61272689e-03, -2.68392767e-04,\n", - " -2.69189871e-04, -1.54259190e-02]),\n", - " array([ 1.03267815e+02, 1.35574037e+02, 1.03305794e+02, 1.35612016e+02,\n", - " 3.11583765e-04, 1.22245557e-01, -2.50231915e-03, -2.62822197e-04,\n", - " -2.57709477e-04, -1.54399141e-02]),\n", - " array([ 1.01804812e+02, 1.28883911e+02, 1.01849458e+02, 1.28928558e+02,\n", - " 2.80551211e-04, 1.05121491e-01, -2.39782745e-03, -2.57320432e-04,\n", - " -2.46356278e-04, -1.54546915e-02]),\n", - " array([ 1.00353835e+02, 1.22309888e+02, 1.00403374e+02, 1.22359426e+02,\n", - " 2.49935378e-04, 8.83392735e-02, -2.29901012e-03, -2.51885098e-04,\n", - " -2.35124454e-04, -1.54701292e-02]),\n", - " array([ 9.89201589e+01, 1.15842120e+02, 9.89730157e+01, 1.15894977e+02,\n", - " 2.19948606e-04, 7.18492139e-02, -2.20562537e-03, -2.46514135e-04,\n", - " -2.24009005e-04, -1.54861074e-02]),\n", - " array([ 9.75091287e+01, 1.09471182e+02, 9.75639244e+01, 1.09525978e+02,\n", - " 1.90776813e-04, 5.56027715e-02, -2.11743310e-03, -2.41205757e-04,\n", - " -2.13005650e-04, -1.55025088e-02]),\n", - " array([ 9.61261227e+01, 1.03188065e+02, 9.61816660e+01, 1.03243608e+02,\n", - " 1.62581370e-04, 3.95526581e-02, -2.03419647e-03, -2.35958418e-04,\n", - " -2.02110747e-04, -1.55192175e-02]),\n", - " array([ 9.47765164e+01, 9.69841625e+01, 9.48317944e+01, 9.70394404e+01,\n", - " 1.35500929e-04, 2.36529256e-02, -1.95568315e-03, -2.30770792e-04,\n", - " -1.91321242e-04, -1.55361191e-02]),\n", - " array([ 9.34656483e+01, 9.08512647e+01, 9.35198146e+01, 9.09054310e+01,\n", - " 1.09653181e-04, 7.85904215e-03, -1.88166633e-03, -2.25641751e-04,\n", - " -1.80634627e-04, -1.55531003e-02]),\n", - " array([ 9.21987852e+01, 8.47815415e+01, 9.22511482e+01, 8.48339045e+01,\n", - " 8.51365556e-05, -7.87204147e-03, -1.81192552e-03, -2.20570368e-04,\n", - " -1.70048926e-04, -1.55700486e-02]),\n", - " array([ 9.09810895e+01, 7.87675283e+01, 9.10310992e+01, 7.88175380e+01,\n", - " 6.20318444e-05, -2.35818334e-02, -1.74624714e-03, -2.15555913e-04,\n", - " -1.59562692e-04, -1.55868517e-02]),\n", - " array([ 8.98175881e+01, 7.28021111e+01, 8.98648226e+01, 7.28493456e+01,\n", - " 4.04037479e-05, -3.93102481e-02, -1.68442499e-03, -2.10597864e-04,\n", - " -1.49175022e-04, -1.56033977e-02]),\n", - " array([ 8.87131421e+01, 6.68785107e+01, 8.87572943e+01, 6.69226629e+01,\n", - " 2.03023463e-05, -5.50955589e-02, -1.62626056e-03, -2.05695926e-04,\n", - " -1.38885591e-04, -1.56195744e-02]),\n", - " array([ 8.76724184e+01, 6.09902680e+01, 8.77132826e+01, 6.10311322e+01,\n", - " 1.76448933e-06, -7.09743533e-02, -1.57156317e-03, -2.00850050e-04,\n", - " -1.28694690e-04, -1.56352694e-02]),\n", - " array([ 8.66998626e+01, 5.51312300e+01, 8.67373216e+01, 5.51686890e+01,\n", - " -1.51848934e-05, -8.69814899e-02, -1.52015007e-03, -1.96060470e-04,\n", - " -1.18603287e-04, -1.56503693e-02]),\n", - " array([ 8.57996737e+01, 4.92955376e+01, 8.58336859e+01, 4.93295498e+01,\n", - " -3.05315595e-05, -1.03150057e-01, -1.47184639e-03, -1.91327730e-04,\n", - " -1.08613096e-04, -1.56647601e-02]),\n", - " array([ 8.49757799e+01, 4.34776144e+01, 8.50063678e+01, 4.35082022e+01,\n", - " -4.42707976e-05, -1.19511329e-01, -1.42648495e-03, -1.86652730e-04,\n", - " -9.87266554e-05, -1.56783265e-02]),\n", - " array([ 8.42318171e+01, 3.76721585e+01, 8.42590557e+01, 3.76993971e+01,\n", - " -5.64063431e-05, -1.36094721e-01, -1.38390610e-03, -1.82036773e-04,\n", - " -8.89474188e-05, -1.56909518e-02]),\n", - " array([ 8.35711081e+01, 3.18741366e+01, 8.35951143e+01, 3.18981428e+01,\n", - " -6.69493643e-05, -1.52927748e-01, -1.34395732e-03, -1.77481612e-04,\n", - " -7.92798588e-05, -1.57025176e-02]),\n", - " array([ 8.29966440e+01, 2.60787805e+01, 8.30175670e+01, 2.60997035e+01,\n", - " -7.59175124e-05, -1.70035963e-01, -1.30649285e-03, -1.72989507e-04,\n", - " -6.97295748e-05, -1.57129041e-02]),\n", - " array([ 8.25110678e+01, 2.02815877e+01, 8.25290796e+01, 2.02995996e+01,\n", - " -8.33340333e-05, -1.87442915e-01, -1.27137318e-03, -1.68563286e-04,\n", - " -6.03034129e-05, -1.57219891e-02]),\n", - " array([ 8.21166599e+01, 1.44783249e+01, 8.21319473e+01, 1.44936123e+01,\n", - " -8.92269345e-05, -2.05170080e-01, -1.23846445e-03, -1.64206406e-04,\n", - " -5.10095927e-05, -1.57296486e-02]),\n", - " array([ 8.18153255e+01, 8.66503567e+00, 8.18280821e+01, 8.67779234e+00,\n", - " -9.36282063e-05, -2.23236797e-01, -1.20763781e-03, -1.59923019e-04,\n", - " -4.18578417e-05, -1.57357562e-02]),\n", - " array([ 8.16085845e+01, 2.83805289e+00, 8.16190043e+01, 2.84847267e+00,\n", - " -9.65730906e-05, -2.41660200e-01, -1.17876868e-03, -1.55718044e-04,\n", - " -3.28595357e-05, -1.57401829e-02]),\n", - " array([ 8.14975642e+01, -3.00598473e+00, 8.15058348e+01, -2.99771412e+00,\n", - " -9.80993980e-05, -2.60455131e-01, -1.15173592e-03, -1.51597238e-04,\n", - " -2.40278453e-05, -1.57427974e-02]),\n", - " array([ 8.14829946e+01, -8.87011059e+00, 8.14892921e+01, -8.86381312e+00,\n", - " -9.82468713e-05, -2.79634061e-01, -1.12642099e-03, -1.47567267e-04,\n", - " -1.53778859e-05, -1.57434657e-02]),\n", - " array([ 8.15652064e+01, -1.47570027e+01, 8.15696901e+01, -1.47525189e+01,\n", - " -9.70565901e-05, -2.99206985e-01, -1.10270698e-03, -1.43635785e-04,\n", - " -6.92687117e-06, -1.57420510e-02]),\n", - " array([ 8.17441325e+01, -2.06689503e+01, 8.17469410e+01, -2.06661417e+01,\n", - " -9.45704474e-05, -3.19181325e-01, -1.08047764e-03, -1.39811509e-04,\n", - " 1.30573274e-06, -1.57384137e-02]),\n", - " array([ 8.20193131e+01, -2.66078138e+01, 8.20205604e+01, -2.66065665e+01,\n", - " -9.08306398e-05, -3.39561813e-01, -1.05961634e-03, -1.36104290e-04,\n", - " 9.29805423e-06, -1.57324114e-02]),\n", - " array([ 8.23899048e+01, -3.25749785e+01, 8.23896771e+01, -3.25752062e+01,\n", - " -8.58792585e-05, -3.60350363e-01, -1.04000507e-03, -1.32525192e-04,\n", - " 1.70256670e-05, -1.57238987e-02]),\n", - " array([ 8.28546932e+01, -3.85712999e+01, 8.28530464e+01, -3.85729467e+01,\n", - " -7.97579314e-05, -3.81545945e-01, -1.02152332e-03, -1.29086559e-04,\n", - " 2.44614485e-05, -1.57127275e-02]),\n", - " array([ 8.34121104e+01, -4.45970426e+01, 8.34090684e+01, -4.46000845e+01,\n", - " -7.25075517e-05, -4.03144431e-01, -1.00404712e-03, -1.25802077e-04,\n", - " 3.15754491e-05, -1.56987464e-02]),\n", - " array([ 8.40602576e+01, -5.06518094e+01, 8.40558111e+01, -5.06562560e+01,\n", - " -6.41681087e-05, -4.25138443e-01, -9.87447992e-04, -1.22686836e-04,\n", - " 3.83347792e-05, -1.56818015e-02]),\n", - " array([ 8.47969325e+01, -5.67344634e+01, 8.47910381e+01, -5.67403578e+01,\n", - " -5.47786199e-05, -4.47517184e-01, -9.71592073e-04, -1.19757372e-04,\n", - " 4.47035181e-05, -1.56617359e-02]),\n", - " array([ 8.56196614e+01, -6.28430395e+01, 8.56122423e+01, -6.28504587e+01,\n", - " -4.43772070e-05, -4.70266257e-01, -9.56339288e-04, -1.17031700e-04,\n", - " 5.06426537e-05, -1.56383900e-02]),\n", - " array([ 8.65257386e+01, -6.89746471e+01, 8.65166851e+01, -6.89837006e+01,\n", - " -3.30013133e-05, -4.93367469e-01, -9.41542683e-04, -1.14529331e-04,\n", - " 5.61100624e-05, -1.56116014e-02]),\n", - " array([ 8.75122695e+01, -7.51253635e+01, 8.75014415e+01, -7.51361914e+01,\n", - " -2.06880899e-05, -5.16798629e-01, -9.27047938e-04, -1.12271259e-04,\n", - " 6.10605379e-05, -1.55812053e-02]),\n", - " array([ 8.85762215e+01, -8.12901166e+01, 8.85634511e+01, -8.13028870e+01,\n", - " -7.47496416e-06, -5.40533325e-01, -9.12693105e-04, -1.10279922e-04,\n", - " 6.54458840e-05, -1.55470345e-02]),\n", - " array([ 8.97144791e+01, -8.74625586e+01, 8.96995747e+01, -8.74774631e+01,\n", - " 6.59959638e-06, -5.64540696e-01, -8.98308609e-04, -1.08579133e-04,\n", - " 6.92150841e-05, -1.55089196e-02]),\n", - " array([ 9.09239058e+01, -9.36349295e+01, 9.09066571e+01, -9.36521783e+01,\n", - " 2.14951172e-05, -5.88785180e-01, -8.83717567e-04, -1.07193956e-04,\n", - " 7.23145650e-05, -1.54666891e-02]),\n", - " array([ 9.22014100e+01, -9.97979121e+01, 9.21815945e+01, -9.98177276e+01,\n", - " 3.71679474e-05, -6.13226261e-01, -8.68736459e-04, -1.06150538e-04,\n", - " 7.46885744e-05, -1.54201698e-02]),\n", - " array([ 9.35440164e+01, -1.05940478e+02, 9.35214067e+01, -1.05963088e+02,\n", - " 5.35698979e-05, -6.37818195e-01, -8.53176187e-04, -1.05475875e-04,\n", - " 7.62796922e-05, -1.53691872e-02]),\n", - " array([ 9.49489393e+01, -1.12049730e+02, 9.49233123e+01, -1.12075357e+02,\n", - " 7.06467071e-05, -6.62509729e-01, -8.36843571e-04, -1.05197502e-04,\n", - " 7.70294993e-05, -1.53135655e-02]),\n", - " array([ 9.64136598e+01, -1.18110732e+02, 9.63848064e+01, -1.18139585e+02,\n", - " 8.83363715e-05, -6.87243811e-01, -8.19543283e-04, -1.05343101e-04,\n", - " 7.68794305e-05, -1.52531281e-02]),\n", - " array([ 9.79360006e+01, -1.24106348e+02, 9.79037371e+01, -1.24138612e+02,\n", - " 1.06567391e-04, -7.11957286e-01, -8.01080249e-04, -1.05940008e-04,\n", - " 7.57718342e-05, -1.51876981e-02]),\n", - " array([ 9.95142001e+01, -1.30017073e+02, 9.94783804e+01, -1.30052893e+02,\n", - " 1.25256992e-04, -7.36580598e-01, -7.81262502e-04, -1.07014610e-04,\n", - " 7.36512694e-05, -1.51170985e-02]),\n", - " array([ 1.01146980e+02, -1.35820872e+02, 1.01107508e+02, -1.35860343e+02,\n", - " 1.44309418e-04, -7.61037481e-01, -7.59904468e-04, -1.08591613e-04,\n", - " 7.04660622e-05, -1.50411531e-02]),\n", - " array([ 1.02833602e+02, -1.41493030e+02, 1.02790448e+02, -1.41536185e+02,\n", - " 1.63614370e-04, -7.85244656e-01, -7.36830630e-04, -1.10693185e-04,\n", - " 6.61701474e-05, -1.49596864e-02]),\n", - " array([ 1.04573915e+02, -1.47006021e+02, 1.04527125e+02, -1.47052812e+02,\n", - " 1.83045703e-04, -8.09111542e-01, -7.11879501e-04, -1.13337943e-04,\n", - " 6.07252118e-05, -1.48725249e-02]),\n", - " array([ 1.06368376e+02, -1.52329398e+02, 1.06318088e+02, -1.52379686e+02,\n", - " 2.02460481e-04, -8.32539973e-01, -6.84907795e-04, -1.16539796e-04,\n", - " 5.41031516e-05, -1.47794974e-02]),\n", - " array([ 1.08218047e+02, -1.57429717e+02, 1.08164507e+02, -1.57483257e+02,\n", - " 2.21698478e-04, -8.55423949e-01, -6.55794664e-04, -1.20306639e-04,\n", - " 4.62888437e-05, -1.46804354e-02]),\n", - " array([ 1.10124564e+02, -1.62270507e+02, 1.10068133e+02, -1.62326938e+02,\n", - " 2.40582193e-04, -8.77649411e-01, -6.24445821e-04, -1.24638891e-04,\n", - " 3.72832176e-05, -1.45751745e-02]),\n", - " array([ 1.12090052e+02, -1.66812294e+02, 1.12031220e+02, -1.66871126e+02,\n", - " 2.58917413e-04, -8.99094061e-01, -5.90797356e-04, -1.29527917e-04,\n", - " 2.71065946e-05, -1.44635548e-02]),\n", - " array([ 1.14117002e+02, -1.71012689e+02, 1.14056395e+02, -1.71073297e+02,\n", - " 2.76494304e-04, -9.19627233e-01, -5.54819009e-04, -1.34954332e-04,\n", - " 1.58022388e-05, -1.43454219e-02]),\n", - " array([ 1.16208076e+02, -1.74826562e+02, 1.16146461e+02, -1.74888178e+02,\n", - " 2.93088944e-04, -9.39109829e-01, -5.16516649e-04, -1.40886247e-04,\n", - " 3.44003474e-06, -1.42206280e-02]),\n", - " array([ 1.18365848e+02, -1.78206301e+02, 1.18304135e+02, -1.78268014e+02,\n", - " 3.08465137e-04, -9.57394322e-01, -4.75933696e-04, -1.47277502e-04,\n", - " -9.87982628e-06, -1.40890324e-02]),\n", - " array([ 1.20592459e+02, -1.81102186e+02, 1.20531701e+02, -1.81162944e+02,\n", - " 3.22376292e-04, -9.74324845e-01, -4.33151256e-04, -1.54065963e-04,\n", - " -2.40233070e-05, -1.39505035e-02]),\n", - " array([ 1.22889189e+02, -1.83462872e+02, 1.22830567e+02, -1.83521494e+02,\n", - " 3.34567093e-04, -9.89737361e-01, -3.88286770e-04, -1.61171973e-04,\n", - " -3.88193280e-05, -1.38049192e-02]),\n", - " array([ 1.25255913e+02, -1.85236007e+02, 1.25200728e+02, -1.85291192e+02,\n", - " 3.44774696e-04, -1.00345993e+00, -3.41491138e-04, -1.68497069e-04,\n", - " -5.40571540e-05, -1.36521684e-02]),\n", - " array([ 1.27690473e+02, -1.86368975e+02, 1.27640118e+02, -1.86419330e+02,\n", - " 3.52729327e-04, -1.01531305e+00, -2.92944458e-04, -1.75923093e-04,\n", - " -6.94846383e-05, -1.34921526e-02]),\n", - " array([ 1.30187919e+02, -1.86809780e+02, 1.30143849e+02, -1.86853850e+02,\n", - " 3.58154407e-04, -1.02511011e+00, -2.42850939e-04, -1.83311843e-04,\n", - " -8.48076424e-05, -1.33247868e-02]),\n", - " array([ 1.32739656e+02, -1.86508052e+02, 1.32703343e+02, -1.86544366e+02,\n", - " 3.60766907e-04, -1.03265783e+00, -1.91434089e-04, -1.90505429e-04,\n", - " -9.96909672e-05, -1.31500013e-02]),\n", - " array([ 1.35332476e+02, -1.85416180e+02, 1.35305353e+02, -1.85443304e+02,\n", - " 3.60279472e-04, -1.03775687e+00, -1.38934142e-04, -1.97327474e-04,\n", - " -1.13761146e-04, -1.29677430e-02]),\n", - " array([ 1.37947502e+02, -1.83490525e+02, 1.37930891e+02, -1.83507136e+02,\n", - " 3.56407120e-04, -1.04020229e+00, -8.56107365e-05, -2.03585343e-04,\n", - " -1.26611444e-04, -1.27779771e-02]),\n", - " array([ 1.40559057e+02, -1.80692713e+02, 1.40554086e+02, -1.80697685e+02,\n", - " 3.48882723e-04, -1.03978410e+00, -3.17550028e-05, -2.09073512e-04,\n", - " -1.37809364e-04, -1.25806886e-02]),\n", - " array([ 1.43133486e+02, -1.76990936e+02, 1.43140985e+02, -1.76983437e+02,\n", - " 3.37486691e-04, -1.03628765e+00, 2.22841607e-05, -2.13578223e-04,\n", - " -1.46906917e-04, -1.23758838e-02]),\n", - " array([ 1.45627961e+02, -1.72361229e+02, 1.45648358e+02, -1.72340833e+02,\n", - " 3.22095958e-04, -1.02949394e+00, 7.60557805e-05, -2.16883487e-04,\n", - " -1.53453786e-04, -1.21635921e-02]),\n", - " array([ 1.47989333e+02, -1.66788655e+02, 1.48022547e+02, -1.66755441e+02,\n", - " 3.02753923e-04, -1.01917966e+00, 1.28944856e-04, -2.18778486e-04,\n", - " -1.57013426e-04, -1.19438676e-02]),\n", - " array([ 1.50153057e+02, -1.60268319e+02, 1.50198415e+02, -1.60222960e+02,\n", - " 2.79754200e-04, -1.00511708e+00, 1.80102388e-04, -2.19066359e-04,\n", - " -1.57181945e-04, -1.17167905e-02]),\n", - " array([ 1.52042281e+02, -1.52806148e+02, 1.52098477e+02, -1.52749952e+02,\n", - " 2.53716677e-04, -9.87073545e-01, 2.28391160e-04, -2.17574312e-04,\n", - " -1.53609431e-04, -1.14824688e-02]),\n", - " array([ 1.53567165e+02, -1.44419341e+02, 1.53632282e+02, -1.44354224e+02,\n", - " 2.25619010e-04, -9.64810760e-01, 2.72385235e-04, -2.14164880e-04,\n", - " -1.46023205e-04, -1.12410399e-02]),\n", - " array([ 1.54624509e+02, -1.35136415e+02, 1.54696127e+02, -1.35064796e+02,\n", - " 1.96741863e-04, -9.38083691e-01, 3.10463905e-04, -2.08748042e-04,\n", - " -1.34252203e-04, -1.09926721e-02]),\n", - " array([ 1.55097788e+02, -1.24996752e+02, 1.55173165e+02, -1.24921375e+02,\n", - " 1.68506179e-04, -9.06639222e-01, 3.41018855e-04, -2.01293710e-04,\n", - " -1.18251496e-04, -1.07375659e-02]),\n", - " array([ 1.54857691e+02, -1.14049585e+02, 1.54933979e+02, -1.13973297e+02,\n", - " 1.42228242e-04, -8.70214579e-01, 3.62745021e-04, -1.91843875e-04,\n", - " -9.81256827e-05, -1.04759561e-02]),\n", - " array([ 1.53763224e+02, -1.02352383e+02, 1.53837685e+02, -1.02277922e+02,\n", - " 1.18870816e-04, -8.28535639e-01, 3.74933457e-04, -1.80523498e-04,\n", - " -7.41497094e-05, -1.02081130e-02]),\n", - " array([ 1.51663430e+02, -8.99686169e+01, 1.51733603e+02, -8.98984439e+01,\n", - " 9.88872152e-05, -7.81315268e-01, 3.77666592e-04, -1.67549147e-04,\n", - " -4.67854685e-05, -9.93434403e-03]),\n", - " array([ 1.48399740e+02, -7.69649551e+01, 1.48463540e+02, -7.69011557e+01,\n", - " 8.22181129e-05, -7.28251820e-01, 3.71852733e-04, -1.53234417e-04,\n", - " -1.66924482e-05, -9.65499567e-03]),\n", - " array([ 1.43808929e+02, -6.34079635e+01, 1.43864690e+02, -6.33522025e+01,\n", - " 6.84303615e-05, -6.69027999e-01, 3.59106056e-04, -1.37991290e-04,\n", - " 1.52693059e-05, -9.37045516e-03]),\n", - " array([ 1.37726602e+02, -4.93604218e+01, 1.37773108e+02, -4.93139159e+01,\n", - " 5.69306550e-05, -6.03310229e-01, 3.41534549e-04, -1.22326752e-04,\n", - " 4.80455360e-05, -9.08115231e-03]),\n", - " array([ 1.29991141e+02, -3.48773983e+01, 1.30027670e+02, -3.48408696e+01,\n", - " 4.71748726e-05, -5.30748702e-01, 3.21511971e-04, -1.06834169e-04,\n", - " 8.04047947e-05, -8.78756147e-03]),\n", - " array([ 1.20447940e+02, -2.00022504e+01, 1.20474359e+02, -1.99758320e+01,\n", - " 3.88196610e-05, -4.50978168e-01, 3.01486823e-04, -9.21790692e-05,\n", - " 1.10967091e-04, -8.49020360e-03]),\n", - " array([ 1.08953785e+02, -4.76274104e+00, 1.08970703e+02, -4.74582309e+00,\n", - " 3.17995430e-05, -3.63619540e-01, 2.83846448e-04, -7.90792340e-05,\n", - " 1.38244507e-04, -8.18964849e-03]),\n", - " array([ 9.53811254e+01, 1.08325227e+01, 9.53901078e+01, 1.08415051e+01,\n", - " 2.63392981e-05, -2.68282242e-01, 2.70828138e-04, -6.82793516e-05,\n", - " 1.60693329e-04, -7.88651719e-03]),\n", - " array([ 7.96220204e+01, 2.67971172e+01, 7.96258446e+01, 2.68009415e+01,\n", - " 2.29213567e-05, -1.64567202e-01, 2.64457452e-04, -6.05209093e-05,\n", - " 1.76776251e-04, -7.58148456e-03]),\n", - " array([ 6.15914729e+01, 4.31690966e+01, 6.15944131e+01, 4.31720368e+01,\n", - " 2.22255288e-05, -5.20702630e-02, 2.66493426e-04, -5.65085510e-05,\n", - " 1.85032091e-04, -7.27528207e-03]),\n", - " array([ 4.12299156e+01, 6.00123788e+01, 4.12380307e+01, 6.00204939e+01,\n", - " 2.50501376e-05, 6.96142111e-02, 2.78365058e-04, -5.68746790e-05,\n", - " 1.84149311e-04, -6.96870080e-03]),\n", - " array([ 2.13550117e+01, 7.45841160e+01, 2.13649263e+01, 7.45940306e+01,\n", - " 3.10691705e-05, 1.82255804e-01, 3.00628673e-04, -6.15828880e-05,\n", - " 1.74202796e-04, -6.66253051e-03]),\n", - " array([ 1.96579298e+00, 8.70079530e+01, 1.97501399e+00, 8.70171740e+01,\n", - " 4.06329975e-05, 2.86263850e-01, 3.31203394e-04, -6.99851610e-05,\n", - " 1.56539212e-04, -6.35756386e-03]),\n", - " array([-1.69154697e+01, 9.74251594e+01, -1.69085656e+01, 9.74320635e+01,\n", - " 5.37654562e-05, 3.82029221e-01, 3.67939030e-04, -8.13645025e-05,\n", - " 1.32649886e-04, -6.05453501e-03]),\n", - " array([-3.52473615e+01, 1.05990367e+02, -3.52435902e+01, 1.05994138e+02,\n", - " 7.01878941e-05, 4.69923777e-01, 4.08678400e-04, -9.49688188e-05,\n", - " 1.04100135e-04, -5.75412254e-03]),\n", - " array([-5.29738194e+01, 1.12867117e+02, -5.29732853e+01, 1.12867651e+02,\n", - " 8.93524367e-05, 5.50300512e-01, 4.51285550e-04, -1.10043554e-04,\n", - " 7.24612503e-05, -5.45695197e-03]),\n", - " array([-7.00287768e+01, 1.18223468e+02, -7.00309914e+01, 1.18221254e+02,\n", - " 1.10471647e-04, 6.23494384e-01, 4.93651954e-04, -1.25861353e-04,\n", - " 3.92487269e-05, -5.16359816e-03]),\n", - " array([-8.63407256e+01, 1.22227872e+02, -8.63447408e+01, 1.22223856e+02,\n", - " 1.32541905e-04, 6.89823745e-01, 5.33692519e-04, -1.41747452e-04,\n", - " 5.86938355e-06, -4.87458731e-03]),\n", - " array([-1.01836990e+02, 1.25045472e+02, -1.01841545e+02, 1.25040918e+02,\n", - " 1.54367920e-04, 7.49592243e-01, 5.69345559e-04, -1.57099924e-04,\n", - " -2.64208338e-05, -4.59039891e-03]),\n", - " array([-1.16447552e+02, 1.26834953e+02, -1.16451232e+02, 1.26831273e+02,\n", - " 1.74604737e-04, 8.03090995e-01, 5.98594666e-04, -1.71404346e-04,\n", - " -5.65474849e-05, -4.31146741e-03]),\n", - " array([-1.30108301e+02, 1.27745975e+02, -1.30109714e+02, 1.27744562e+02,\n", - " 1.91837892e-04, 8.50600879e-01, 6.19531471e-04, -1.84242800e-04,\n", - " -8.36365930e-05, -4.03818385e-03]),\n", - " array([-1.42763658e+02, 1.27917234e+02, -1.42761606e+02, 1.27919285e+02,\n", - " 2.04716361e-04, 8.92394742e-01, 6.30470816e-04, -1.95297493e-04,\n", - " -1.07022500e-04, -3.77089740e-03]),\n", - " array([-1.54368524e+02, 1.27475114e+02, -1.54362167e+02, 1.27481471e+02,\n", - " 2.12132226e-04, 9.28739403e-01, 6.30109698e-04, -2.04349535e-04,\n", - " -1.26245728e-04, -3.50991685e-03]),\n", - " array([-1.64889591e+02, 1.26532897e+02, -1.64878561e+02, 1.26543926e+02,\n", - " 2.13410184e-04, 9.59897321e-01, 6.17692934e-04, -2.11273617e-04,\n", - " -1.41042353e-04, -3.25551218e-03]),\n", - " array([-1.74306033e+02, 1.25190447e+02, -1.74290483e+02, 1.25205997e+02,\n", - " 2.08446724e-04, 9.86127873e-01, 5.93128229e-04, -2.16029495e-04,\n", - " -1.51326644e-04, -3.00791609e-03]),\n", - " array([-1.82609654e+02, 1.23534337e+02, -1.82590225e+02, 1.23553766e+02,\n", - " 1.97743876e-04, 1.00768822e+00, 5.57000094e-04, -2.18651210e-04,\n", - " -1.57168834e-04, -2.76732564e-03]),\n", - " array([-1.89804548e+02, 1.21638313e+02, -1.89782268e+02, 1.21660593e+02,\n", - " 1.82320362e-04, 1.02483372e+00, 5.10468945e-04, -2.19234953e-04,\n", - " -1.58769857e-04, -2.53390382e-03]),\n", - " array([-1.95906361e+02, 1.19564053e+02, -1.95882501e+02, 1.19587913e+02,\n", - " 1.63532094e-04, 1.03781804e+00, 4.55087683e-04, -2.17926389e-04,\n", - " -1.56434759e-04, -2.30778124e-03]),\n", - " array([-2.00941248e+02, 1.17362128e+02, -2.00917166e+02, 1.17386210e+02,\n", - " 1.42863100e-04, 1.04689284e+00, 3.92594337e-04, -2.14908128e-04,\n", - " -1.50546267e-04, -2.08905783e-03]),\n", - " array([-2.04944610e+02, 1.15073109e+02, -2.04921612e+02, 1.15096106e+02,\n", - " 1.21743853e-04, 1.05230726e+00, 3.24734181e-04, -2.10387870e-04,\n", - " -1.41539731e-04, -1.87780451e-03]),\n", - " array([-2.07959694e+02, 1.12728740e+02, -2.07938936e+02, 1.12749499e+02,\n", - " 1.01427710e-04, 1.05430722e+00, 2.53139122e-04, -2.04587629e-04,\n", - " -1.29880320e-04, -1.67406494e-03]),\n", - " array([-2.10036157e+02, 1.10353135e+02, -2.10018574e+02, 1.10370718e+02,\n", - " 8.29283480e-05, 1.05313461e+00, 1.79265730e-04, -1.97734298e-04,\n", - " -1.16043107e-04, -1.47785735e-03]),\n", - " array([-2.11228625e+02, 1.07963932e+02, -2.11214906e+02, 1.07977652e+02,\n", - " 6.70044687e-05, 1.04902637e+00, 1.04377688e-04, -1.90051713e-04,\n", - " -1.00496362e-04, -1.28917624e-03]),\n", - " array([-2.11595331e+02, 1.05573405e+02, -2.11585913e+02, 1.05582823e+02,\n", - " 5.41737507e-05, 1.04221362e+00, 2.95547269e-05, -1.81754265e-04,\n", - " -8.36881550e-05, -1.10799424e-03]),\n", - " array([-2.11196841e+02, 1.03189473e+02, -2.11191928e+02, 1.03194386e+02,\n", - " 4.47410641e-05, 1.03292087e+00, -4.42866758e-05, -1.73042029e-04,\n", - " -6.60361895e-05, -9.34263837e-04]),\n", - " array([-2.10094906e+02, 1.00816620e+02, -2.10094498e+02, 1.00817028e+02,\n", - " 3.88312452e-05, 1.02136522e+00, -1.16370190e-04, -1.64097308e-04,\n", - " -4.79206305e-05, -7.67919124e-04]),\n", - " array([-2.08351460e+02, 9.84567055e+01, -2.08355386e+02, 9.84527796e+01,\n", - " 3.64212971e-05, 1.00775574e+00, -1.86038846e-04, -1.55082447e-04,\n", - " -2.96796056e-05, -6.08877467e-04]),\n", - " array([-2.06027749e+02, 9.61096683e+01, -2.06035707e+02, 9.61017112e+01,\n", - " 3.73698876e-05, 9.92292958e-01, -2.52738239e-04, -1.46138745e-04,\n", - " -1.16069975e-05, -4.57041136e-04]),\n", - " array([-2.03183617e+02, 9.37741214e+01, -2.03195206e+02, 9.37625327e+01,\n", - " 4.14436114e-05, 9.75168412e-01, -3.16003705e-04, -1.37386269e-04,\n", - " 6.04787175e-06, -3.12298843e-04]),\n", - " array([-1.99876917e+02, 9.14478490e+01, -1.99891673e+02, 9.14330922e+01,\n", - " 4.83401578e-05, 9.56564408e-01, -3.75450782e-04, -1.28924388e-04,\n", - " 2.30790617e-05, -1.74527218e-04]),\n", - " array([-1.96163059e+02, 8.91282087e+01, -1.96180485e+02, 8.91107826e+01,\n", - " 5.77087034e-05, 9.36653826e-01, -4.30768057e-04, -1.20832852e-04,\n", - " 3.93217106e-05, -4.35921974e-05]),\n", - " array([-1.92094675e+02, 8.68124507e+01, -1.92114260e+02, 8.67928648e+01,\n", - " 6.91678156e-05, 9.15600071e-01, -4.81711606e-04, -1.13173252e-04,\n", - " 5.46489406e-05, 8.06496678e-05]),\n", - " array([-1.87721377e+02, 8.44979609e+01, -1.87742621e+02, 8.44767169e+01,\n", - " 8.23210606e-05, 8.93557093e-01, -5.28100381e-04, -1.05990726e-04,\n", - " 6.89682577e-05, 1.98349986e-04]),\n", - " array([-1.83089618e+02, 8.21824404e+01, -1.83112041e+02, 8.21600170e+01,\n", - " 9.67704344e-05, 8.70669504e-01, -5.69812075e-04, -9.93157949e-05,\n", - " 8.22176877e-05, 3.09667382e-04]),\n", - " array([-1.78242619e+02, 7.98640291e+01, -1.78265777e+02, 7.98408715e+01,\n", - " 1.12127688e-04, 8.47072758e-01, -6.06779158e-04, -9.31662402e-05,\n", - " 9.43618376e-05, 4.14766428e-04]),\n", - " array([-1.73220366e+02, 7.75413829e+01, -1.73243853e+02, 7.75178954e+01,\n", - " 1.28023604e-04, 8.22893379e-01, -6.38984872e-04, -8.75489434e-05,\n", - " 1.05388032e-04, 5.13816658e-04]),\n", - " array([-1.68059648e+02, 7.52137137e+01, -1.68083106e+02, 7.51902559e+01,\n", - " 1.44115309e-04, 7.98249243e-01, -6.66459094e-04, -8.24616423e-05,\n", - " 1.15302634e-04, 6.06991645e-04]),\n", - " array([-1.62794150e+02, 7.28807982e+01, -1.62817265e+02, 7.28576832e+01,\n", - " 1.60091703e-04, 7.73249883e-01, -6.89274013e-04, -7.78945655e-05,\n", - " 1.24127621e-04, 6.94468162e-04]),\n", - " array([-1.57454562e+02, 7.05429639e+01, -1.57477067e+02, 7.05204586e+01,\n", - " 1.75677162e-04, 7.47996824e-01, -7.07539643e-04, -7.38319214e-05,\n", - " 1.31897466e-04, 7.76425389e-04]),\n", - " array([-1.52068718e+02, 6.82010576e+01, -1.52090391e+02, 6.81793844e+01,\n", - " 1.90633656e-04, 7.22583929e-01, -7.21399206e-04, -7.02532313e-05,\n", - " 1.38656354e-04, 8.53044202e-04]),\n", - " array([-1.46661750e+02, 6.58564000e+01, -1.46682410e+02, 6.58357394e+01,\n", - " 2.04761488e-04, 6.97097751e-01, -7.31024447e-04, -6.71345029e-05,\n", - " 1.44455722e-04, 9.24506502e-04]),\n", - " array([-1.41256247e+02, 6.35107336e+01, -1.41275753e+02, 6.34912277e+01,\n", - " 2.17898840e-04, 6.71617891e-01, -7.36610957e-04, -6.44492478e-05,\n", - " 1.49352132e-04, 9.90994611e-04]),\n", - " array([-1.35872426e+02, 6.11661639e+01, -1.35890670e+02, 6.11479200e+01,\n", - " 2.29920355e-04, 6.46217354e-01, -7.38373589e-04, -6.21693498e-05,\n", - " 1.53405463e-04, 1.05269072e-03]),\n", - " array([-1.30528289e+02, 5.88250997e+01, -1.30545195e+02, 5.88081940e+01,\n", - " 2.40734946e-04, 6.20962895e-01, -7.36542018e-04, -6.02657953e-05,\n", - " 1.56677380e-04, 1.10977635e-03]),\n", - " array([-1.25239799e+02, 5.64901923e+01, -1.25255317e+02, 5.64746741e+01,\n", - " 2.50283046e-04, 5.95915360e-01, -7.31356553e-04, -5.87092777e-05,\n", - " 1.59230075e-04, 1.16243194e-03]),\n", - " array([-1.20021027e+02, 5.41642774e+01, -1.20035132e+02, 5.41501724e+01,\n", - " 2.58533474e-04, 5.71130015e-01, -7.23064226e-04, -5.74706898e-05,\n", - " 1.61125240e-04, 1.21083637e-03]),\n", - " array([-1.14884314e+02, 5.18503196e+01, -1.14897001e+02, 5.18376331e+01,\n", - " 2.65480081e-04, 5.46656868e-01, -7.11915218e-04, -5.65215165e-05,\n", - " 1.62423253e-04, 1.25516661e-03]),\n", - " array([-1.09840412e+02, 4.95513600e+01, -1.09851691e+02, 4.95400805e+01,\n", - " 2.71138318e-04, 5.22540969e-01, -6.98159658e-04, -5.58341407e-05,\n", - " 1.63182534e-04, 1.29559735e-03]),\n", - " array([-1.04898617e+02, 4.72704696e+01, -1.04908516e+02, 4.72605713e+01,\n", - " 2.75541846e-04, 4.98822708e-01, -6.82044815e-04, -5.53820764e-05,\n", - " 1.63459072e-04, 1.33230071e-03]),\n", - " array([-1.00066905e+02, 4.50107066e+01, -1.00075460e+02, 4.50021518e+01,\n", - " 2.78739264e-04, 4.75538092e-01, -6.63812687e-04, -5.51401371e-05,\n", - " 1.63306070e-04, 1.36544595e-03]),\n", - " array([-9.53520440e+01, 4.27750790e+01, -9.53593029e+01, 4.27678201e+01,\n", - " 2.80791049e-04, 4.52719013e-01, -6.43697979e-04, -5.50845528e-05,\n", - " 1.62773705e-04, 1.39519919e-03]),\n", - " array([-9.07597056e+01, 4.05665117e+01, -9.07657239e+01, 4.05604934e+01,\n", - " 2.81766737e-04, 4.30393500e-01, -6.21926474e-04, -5.51930424e-05,\n", - " 1.61908983e-04, 1.42172324e-03]),\n", - " array([-8.62945686e+01, 3.83878189e+01, -8.62994079e+01, 3.83829796e+01,\n", - " 2.81742376e-04, 4.08585966e-01, -5.98713752e-04, -5.54448505e-05,\n", - " 1.60755663e-04, 1.44517737e-03]),\n", - " array([-8.19604103e+01, 3.62416809e+01, -8.19641371e+01, 3.62379541e+01,\n", - " 2.80798282e-04, 3.87317433e-01, -5.74264248e-04, -5.58207550e-05,\n", - " 1.59354250e-04, 1.46571714e-03]),\n", - " array([-7.77601928e+01, 3.41306252e+01, -7.77628774e+01, 3.41279406e+01,\n", - " 2.79017078e-04, 3.66605751e-01, -5.48770608e-04, -5.63030519e-05,\n", - " 1.57742022e-04, 1.48349428e-03]),\n", - " array([-7.36961413e+01, 3.20570115e+01, -7.36978565e+01, 3.20552962e+01,\n", - " 2.76482030e-04, 3.46465811e-01, -5.22413309e-04, -5.68755220e-05,\n", - " 1.55953112e-04, 1.49865653e-03]),\n", - " array([-6.97698152e+01, 3.00230202e+01, -6.97706359e+01, 3.00221996e+01,\n", - " 2.73275649e-04, 3.26909735e-01, -4.95360510e-04, -5.75233830e-05,\n", - " 1.54018604e-04, 1.51134754e-03]),\n", - " array([-6.59821741e+01, 2.80306449e+01, -6.59821758e+01, 2.80306432e+01,\n", - " 2.69478543e-04, 3.07947070e-01, -4.67768098e-04, -5.82332321e-05,\n", - " 1.51966661e-04, 1.52170682e-03]),\n", - " array([-6.23336364e+01, 2.60816867e+01, -6.23328952e+01, 2.60824280e+01,\n", - " 2.65168506e-04, 2.89584963e-01, -4.39779894e-04, -5.89929811e-05,\n", - " 1.49822660e-04, 1.52986964e-03]),\n", - " array([-5.88241342e+01, 2.41777521e+01, -5.88227257e+01, 2.41791606e+01,\n", - " 2.60419804e-04, 2.71828330e-01, -4.11527993e-04, -5.97917855e-05,\n", - " 1.47609344e-04, 1.53596697e-03]),\n", - " array([-5.54531623e+01, 2.23202523e+01, -5.54511612e+01, 2.23222534e+01,\n", - " 2.55302646e-04, 2.54680021e-01, -3.83133199e-04, -6.06199714e-05,\n", - " 1.45346978e-04, 1.54012549e-03]),\n", - " array([-5.22198234e+01, 2.05104055e+01, -5.22173032e+01, 2.05129258e+01,\n", - " 2.49882803e-04, 2.38140968e-01, -3.54705535e-04, -6.14689606e-05,\n", - " 1.43053505e-04, 1.54246753e-03]),\n", - " array([-4.91228693e+01, 1.87492395e+01, -4.91199013e+01, 1.87522074e+01,\n", - " 2.44221372e-04, 2.22210335e-01, -3.26344812e-04, -6.23311948e-05,\n", - " 1.40744707e-04, 1.54311108e-03]),\n", - " array([-4.61607380e+01, 1.70375967e+01, -4.61573916e+01, 1.70409432e+01,\n", - " 2.38374638e-04, 2.06885652e-01, -2.98141221e-04, -6.32000614e-05,\n", - " 1.38434366e-04, 1.54216978e-03]),\n", - " array([-4.33315887e+01, 1.53761400e+01, -4.33279302e+01, 1.53797985e+01,\n", - " 2.32394036e-04, 1.92162952e-01, -2.70175947e-04, -6.40698200e-05,\n", - " 1.36134412e-04, 1.53975296e-03]),\n", - " array([-4.06333322e+01, 1.37653592e+01, -4.06294251e+01, 1.37692664e+01,\n", - " 2.26326187e-04, 1.78036888e-01, -2.42521783e-04, -6.49355308e-05,\n", - " 1.33855080e-04, 1.53596567e-03]),\n", - " array([-3.80636606e+01, 1.22055788e+01, -3.80595651e+01, 1.22096743e+01,\n", - " 2.20212991e-04, 1.64500860e-01, -2.15243731e-04, -6.57929865e-05,\n", - " 1.31605050e-04, 1.53090868e-03]),\n", - " array([-3.56200728e+01, 1.06969655e+01, -3.56158455e+01, 1.07011928e+01,\n", - " 2.14091772e-04, 1.51547121e-01, -1.88399594e-04, -6.66386455e-05,\n", - " 1.29391589e-04, 1.52467857e-03]),\n", - " array([-3.32998994e+01, 9.23953670e+00, -3.32955931e+01, 9.24384305e+00,\n", - " 2.07995452e-04, 1.39166886e-01, -1.62040537e-04, -6.74695697e-05,\n", - " 1.27220685e-04, 1.51736777e-03]),\n", - " array([-3.11003244e+01, 7.83316935e+00, -3.10959879e+01, 7.83750586e+00,\n", - " 2.01952763e-04, 1.27350434e-01, -1.36211620e-04, -6.82833642e-05,\n", - " 1.25097167e-04, 1.50906461e-03]),\n", - " array([-2.90184059e+01, 6.47760824e+00, -2.90140840e+01, 6.48193012e+00,\n", - " 1.95988467e-04, 1.16087200e-01, -1.10952299e-04, -6.90781211e-05,\n", - " 1.23024833e-04, 1.49985340e-03]),\n", - " array([-2.70510952e+01, 5.17247493e+00, -2.70468285e+01, 5.17674154e+00,\n", - " 1.90123593e-04, 1.05365869e-01, -8.62968984e-05, -6.98523665e-05,\n", - " 1.21006554e-04, 1.48981451e-03]),\n", - " array([-2.51952536e+01, 3.91727639e+00, -2.51910788e+01, 3.92145128e+00,\n", - " 1.84375686e-04, 9.51744618e-02, -6.22750442e-05, -7.06050107e-05,\n", - " 1.19044383e-04, 1.47902444e-03]),\n", - " array([-2.34476694e+01, 2.71141360e+00, -2.34436185e+01, 2.71546447e+00,\n", - " 1.78759051e-04, 8.55004115e-02, -3.89120628e-05, -7.13353017e-05,\n", - " 1.17139651e-04, 1.46755592e-03]),\n", - " array([-2.18050716e+01, 1.55418984e+00, -2.18011728e+01, 1.55808856e+00,\n", - " 1.73285006e-04, 7.63306436e-02, -1.62293500e-05, -7.20427827e-05,\n", - " 1.15293059e-04, 1.45547796e-03]),\n", - " array([-2.02641445e+01, 4.44818978e-01, -2.02604221e+01, 4.48541423e-01,\n", - " 1.67962122e-04, 6.76516458e-02, 5.75529279e-06, -7.27272517e-05,\n", - " 1.13504764e-04, 1.44285601e-03]),\n", - " array([-1.88215402e+01, -6.17566743e-01, -1.88180142e+01, -6.14040759e-01,\n", - " 1.62796473e-04, 5.94495357e-02, 2.70273530e-05, -7.33887253e-05,\n", - " 1.11774452e-04, 1.42975200e-03]),\n", - " array([-1.74738898e+01, -1.63390901e+00, -1.74705767e+01, -1.63059590e+00,\n", - " 1.57791863e-04, 5.17101240e-02, 4.75753278e-05, -7.40274050e-05,\n", - " 1.10101414e-04, 1.41622446e-03]),\n", - " array([-1.62178147e+01, -2.60521616e+00, -1.62147273e+01, -2.60212874e+00,\n", - " 1.52950055e-04, 4.44189737e-02, 6.73904718e-05, -7.46436465e-05,\n", - " 1.08484608e-04, 1.40232861e-03]),\n", - " array([-1.50499364e+01, -3.53255615e+00, -1.50470841e+01, -3.52970384e+00,\n", - " 1.48270994e-04, 3.75614556e-02, 8.64665674e-05, -7.52379320e-05,\n", - " 1.06922720e-04, 1.38811649e-03]),\n", - " array([-1.39668855e+01, -4.41704989e+00, -1.39642745e+01, -4.41443894e+00,\n", - " 1.43753009e-04, 3.11228001e-02, 1.04799717e-04, -7.58108449e-05,\n", - " 1.05414217e-04, 1.37363703e-03]),\n", - " array([-1.29653102e+01, -5.25986492e+00, -1.29629439e+01, -5.25749862e+00,\n", - " 1.39393020e-04, 2.50881452e-02, 1.22388152e-04, -7.63630474e-05,\n", - " 1.03957394e-04, 1.35893618e-03]),\n", - " array([-1.20418842e+01, -6.06220933e+00, -1.20397631e+01, -6.06008827e+00,\n", - " 1.35186718e-04, 1.94425818e-02, 1.39232066e-04, -7.68952602e-05,\n", - " 1.02550419e-04, 1.34405701e-03]),\n", - " array([-1.11933131e+01, -6.82532607e+00, -1.11914355e+01, -6.82344838e+00,\n", - " 1.31128752e-04, 1.41711950e-02, 1.55333450e-04, -7.74082447e-05,\n", - " 1.01191372e-04, 1.32903979e-03]),\n", - " array([-1.04163417e+01, -7.55048757e+00, -1.04147034e+01, -7.54884921e+00,\n", - " 1.27212887e-04, 9.25910291e-03, 1.70695958e-04, -7.79027874e-05,\n", - " 9.98782760e-05, 1.31392216e-03]),\n", - " array([-9.70775905e+00, -8.23899064e+00, -9.70635401e+00, -8.23758560e+00,\n", - " 1.23432169e-04, 4.69149232e-03, 1.85324769e-04, -7.83796856e-05,\n", - " 9.86091306e-05, 1.29873916e-03]),\n", - " array([-9.06440406e+00, -8.89215167e+00, -9.06322464e+00, -8.89097224e+00,\n", - " 1.19779064e-04, 4.53651362e-04, 1.99226468e-04, -7.88397363e-05,\n", - " 9.73819343e-05, 1.28352340e-03]),\n", - " array([-8.48317017e+00, -9.51130208e+00, -8.48220722e+00, -9.51033913e+00,\n", - " 1.16245593e-04, -3.46900017e-03, 2.12408936e-04, -7.92837250e-05,\n", - " 9.61947090e-05, 1.26830511e-03]),\n", - " array([-7.96100950e+00, -1.00977841e+01, -7.96025267e+00, -1.00970273e+01,\n", - " 1.12823459e-04, -7.09088328e-03, 2.24881243e-04, -7.97124182e-05,\n", - " 9.50455179e-05, 1.25311229e-03]),\n", - " array([-7.49493664e+00, -1.06529469e+01, -7.49437457e+00, -1.06523848e+01,\n", - " 1.09504155e-04, -1.04262345e-02, 2.36653554e-04, -8.01265550e-05,\n", - " 9.39324821e-05, 1.23797079e-03]),\n", - " array([-7.08203183e+00, -1.11781425e+01, -7.08165240e+00, -1.11777630e+01,\n", - " 1.06279070e-04, -1.34890831e-02, 2.47737037e-04, -8.05268424e-05,\n", - " 9.28537928e-05, 1.22290441e-03]),\n", - " array([-6.71944387e+00, -1.16747225e+01, -6.71923439e+00, -1.16745130e+01,\n", - " 1.03139578e-04, -1.62932300e-02, 2.58143778e-04, -8.09139495e-05,\n", - " 9.18077226e-05, 1.20793502e-03]),\n", - " array([-6.40439252e+00, -1.21440348e+01, -6.40433988e+00, -1.21439822e+01,\n", - " 1.00077122e-04, -1.88522295e-02, 2.67886702e-04, -8.12885048e-05,\n", - " 9.07926333e-05, 1.19308262e-03]),\n", - " array([-6.13417049e+00, -1.25874205e+01, -6.13426141e+00, -1.25875114e+01,\n", - " 9.70832880e-05, -2.11793721e-02, 2.76979495e-04, -8.16510929e-05,\n", - " 8.98069822e-05, 1.17836549e-03]),\n", - " array([-5.90614520e+00, -1.30062104e+01, -5.90636628e+00, -1.30064315e+01,\n", - " 9.41498661e-05, -2.32876699e-02, 2.85436534e-04, -8.20022529e-05,\n", - " 8.88493263e-05, 1.16380024e-03]),\n", - " array([-5.71776001e+00, -1.34017233e+01, -5.71809795e+00, -1.34020613e+01,\n", - " 9.12689067e-05, -2.51898429e-02, 2.93272815e-04, -8.23424773e-05,\n", - " 8.79183253e-05, 1.14940191e-03]),\n", - " array([-5.56653526e+00, -1.37752625e+01, -5.56697695e+00, -1.37757042e+01,\n", - " 8.84327672e-05, -2.68983074e-02, 3.00503892e-04, -8.26722116e-05,\n", - " 8.70127425e-05, 1.13518408e-03]),\n", - " array([-5.45006896e+00, -1.41281136e+01, -5.45060159e+00, -1.41286462e+01,\n", - " 8.56341512e-05, -2.84251661e-02, 3.07145813e-04, -8.29918545e-05,\n", - " 8.61314448e-05, 1.12115895e-03]),\n", - " array([-5.36603720e+00, -1.44615423e+01, -5.36664835e+00, -1.44621535e+01,\n", - " 8.28661397e-05, -2.97821991e-02, 3.13215057e-04, -8.33017584e-05,\n", - " 8.52734020e-05, 1.10733744e-03]),\n", - " array([-5.31219428e+00, -1.47767924e+01, -5.31287199e+00, -1.47774701e+01,\n", - " 8.01222166e-05, -3.09808560e-02, 3.18728482e-04, -8.36022303e-05,\n", - " 8.44376845e-05, 1.09372921e-03]),\n", - " array([-5.28637260e+00, -1.50750832e+01, -5.28710544e+00, -1.50758161e+01,\n", - " 7.73962870e-05, -3.20322504e-02, 3.23703266e-04, -8.38935336e-05,\n", - " 8.36234605e-05, 1.08034285e-03]),\n", - " array([-5.28648232e+00, -1.53576080e+01, -5.28725945e+00, -1.53583852e+01,\n", - " 7.46826905e-05, -3.29471536e-02, 3.28156856e-04, -8.41758895e-05,\n", - " 8.28299929e-05, 1.06718585e-03]),\n", - " array([-5.31051082e+00, -1.56255321e+01, -5.31132201e+00, -1.56263433e+01,\n", - " 7.19762082e-05, -3.37359915e-02, 3.32106918e-04, -8.44494787e-05,\n", - " 8.20566348e-05, 1.05426476e-03]),\n", - " array([-5.35652195e+00, -1.58799910e+01, -5.35735762e+00, -1.58808267e+01,\n", - " 6.92720661e-05, -3.44088404e-02, 3.35571288e-04, -8.47144441e-05,\n", - " 8.13028256e-05, 1.04158522e-03]),\n", - " array([-5.42265509e+00, -1.61220887e+01, -5.42350632e+00, -1.61229399e+01,\n", - " 6.65659336e-05, -3.49754253e-02, 3.38567925e-04, -8.49708921e-05,\n", - " 8.05680861e-05, 1.02915203e-03]),\n", - " array([-5.50712408e+00, -1.63528961e+01, -5.50798260e+00, -1.63537547e+01,\n", - " 6.38539179e-05, -3.54451178e-02, 3.41114866e-04, -8.52188957e-05,\n", - " 7.98520138e-05, 1.01696925e-03]),\n", - " array([-5.60821597e+00, -1.65734498e+01, -5.60907420e+00, -1.65743080e+01,\n", - " 6.11325557e-05, -3.58269355e-02, 3.43230185e-04, -8.54584964e-05,\n", - " 7.91542773e-05, 1.00504024e-03]),\n", - " array([-5.72428964e+00, -1.67847500e+01, -5.72514066e+00, -1.67856011e+01,\n", - " 5.83988010e-05, -3.61295415e-02, 3.44931954e-04, -8.56897066e-05,\n", - " 7.84746118e-05, 9.93367744e-04]),\n", - " array([-5.85377435e+00, -1.69877598e+01, -5.85461186e+00, -1.69885973e+01,\n", - " 5.56500125e-05, -3.63612452e-02, 3.46238192e-04, -8.59125121e-05,\n", - " 7.78128131e-05, 9.81953928e-04]),\n", - " array([-5.99516811e+00, -1.71834031e+01, -5.99598647e+00, -1.71842215e+01,\n", - " 5.28839350e-05, -3.65300026e-02, 3.47166843e-04, -8.61268744e-05,\n", - " 7.71687333e-05, 9.70800458e-04]),\n", - " array([-6.14703602e+00, -1.73725642e+01, -6.14783016e+00, -1.73733584e+01,\n", - " 5.00986830e-05, -3.66434183e-02, 3.47735731e-04, -8.63327329e-05,\n", - " 7.65422750e-05, 9.59908551e-04]),\n", - " array([-6.30800849e+00, -1.75560859e+01, -6.30877392e+00, -1.75568513e+01,\n", - " 4.72927204e-05, -3.67087467e-02, 3.47962525e-04, -8.65300073e-05,\n", - " 7.59333863e-05, 9.49279031e-04]),\n", - " array([-6.47677943e+00, -1.77347684e+01, -6.47751221e+00, -1.77355011e+01,\n", - " 4.44648402e-05, -3.67328948e-02, 3.47864706e-04, -8.67185996e-05,\n", - " 7.53420564e-05, 9.38912377e-04]),\n", - " array([-6.65210434e+00, -1.79093685e+01, -6.65280105e+00, -1.79100653e+01,\n", - " 4.16141427e-05, -3.67224243e-02, 3.47459537e-04, -8.68983966e-05,\n", - " 7.47683102e-05, 9.28808776e-04]),\n", - " array([-6.83279841e+00, -1.80805985e+01, -6.83345611e+00, -1.80812562e+01,\n", - " 3.87400132e-05, -3.66835545e-02, 3.46764029e-04, -8.70692711e-05,\n", - " 7.42122042e-05, 9.18968167e-04]),\n", - " array([-7.01773457e+00, -1.82491247e+01, -7.01835075e+00, -1.82497408e+01,\n", - " 3.58420998e-05, -3.66221656e-02, 3.45794915e-04, -8.72310849e-05,\n", - " 7.36738217e-05, 9.09390288e-04]),\n", - " array([-7.20584146e+00, -1.84155669e+01, -7.20641402e+00, -1.84161394e+01,\n", - " 3.29202905e-05, -3.65438020e-02, 3.44568616e-04, -8.73836895e-05,\n", - " 7.31532690e-05, 9.00074717e-04]),\n", - " array([-7.39610145e+00, -1.85804973e+01, -7.39662869e+00, -1.85810245e+01,\n", - " 2.99746903e-05, -3.64536757e-02, 3.43101218e-04, -8.75269290e-05,\n", - " 7.26506711e-05, 8.91020908e-04]),\n", - " array([-7.58754868e+00, -1.87444398e+01, -7.58802923e+00, -1.87449203e+01,\n", - " 2.70055989e-05, -3.63566702e-02, 3.41408444e-04, -8.76606405e-05,\n", - " 7.21661678e-05, 8.82228235e-04]),\n", - " array([-7.77926700e+00, -1.89078688e+01, -7.77969980e+00, -1.89083016e+01,\n", - " 2.40134889e-05, -3.62573445e-02, 3.39505626e-04, -8.77846567e-05,\n", - " 7.16999103e-05, 8.73696021e-04]),\n", - " array([-7.97038800e+00, -1.90712088e+01, -7.97077228e+00, -1.90715930e+01,\n", - " 2.09989834e-05, -3.61599367e-02, 3.37407685e-04, -8.78988067e-05,\n", - " 7.12520581e-05, 8.65423573e-04]),\n", - " array([-8.16008905e+00, -1.92348336e+01, -8.16042430e+00, -1.92351688e+01,\n", - " 1.79628353e-05, -3.60683689e-02, 3.35129104e-04, -8.80029175e-05,\n", - " 7.08227751e-05, 8.57410212e-04]),\n", - " array([-8.34759134e+00, -1.93990655e+01, -8.34787726e+00, -1.93993514e+01,\n", - " 1.49059070e-05, -3.59862508e-02, 3.32683904e-04, -8.80968154e-05,\n", - " 7.04122272e-05, 8.49655300e-04]),\n", - " array([-8.53215796e+00, -1.95641749e+01, -8.53239448e+00, -1.95644115e+01,\n", - " 1.18291501e-05, -3.59168845e-02, 3.30085624e-04, -8.81803270e-05,\n", - " 7.00205793e-05, 8.42158269e-04]),\n", - " array([-8.71309203e+00, -1.97303798e+01, -8.71327923e+00, -1.97305670e+01,\n", - " 8.73358727e-06, -3.58632689e-02, 3.27347301e-04, -8.82532802e-05,\n", - " 6.96479929e-05, 8.34918638e-04]),\n", - " array([-8.88973483e+00, -1.98978451e+01, -8.88987298e+00, -1.98979833e+01,\n", - " 5.62029361e-06, -3.58281041e-02, 3.24481446e-04, -8.83155055e-05,\n", - " 6.92946233e-05, 8.27936041e-04]),\n", - " array([-9.06146403e+00, -2.00666825e+01, -9.06155354e+00, -2.00667720e+01,\n", - " 2.49037980e-06, -3.58137965e-02, 3.21500025e-04, -8.83668366e-05,\n", - " 6.89606180e-05, 8.21210244e-04]),\n", - " array([-9.22769196e+00, -2.02369499e+01, -9.22773336e+00, -2.02369913e+01,\n", - " -6.55024107e-07, -3.58224629e-02, 3.18414443e-04, -8.84071114e-05,\n", - " 6.86461140e-05, 8.14741160e-04]),\n", - " array([-9.38786388e+00, -2.04086515e+01, -9.38785783e+00, -2.04086455e+01,\n", - " -3.81478391e-06, -3.58559358e-02, 3.15235522e-04, -8.84361728e-05,\n", - " 6.83512366e-05, 8.08528867e-04]),\n", - " array([-9.54145636e+00, -2.05817376e+01, -9.54140361e+00, -2.05816848e+01,\n", - " -6.98777544e-06, -3.59157685e-02, 3.11973484e-04, -8.84538693e-05,\n", - " 6.80760971e-05, 8.02573620e-04]),\n", - " array([-9.68797571e+00, -2.07561042e+01, -9.68787713e+00, -2.07560056e+01,\n", - " -1.01728978e-05, -3.60032393e-02, 3.08637938e-04, -8.84600558e-05,\n", - " 6.78207916e-05, 7.96875859e-04]),\n", - " array([-9.82695648e+00, -2.09315935e+01, -9.82681302e+00, -2.09314500e+01,\n", - " -1.33690854e-05, -3.61193573e-02, 3.05237858e-04, -8.84545939e-05,\n", - " 6.75853999e-05, 7.91436226e-04]),\n", - " array([-9.95796001e+00, -2.11079937e+01, -9.95777270e+00, -2.11078064e+01,\n", - " -1.65753191e-05, -3.62648676e-02, 3.01781573e-04, -8.84373527e-05,\n", - " 6.73699835e-05, 7.86255563e-04]),\n", - " array([-1.00805730e+01, -2.12850396e+01, -1.00803430e+01, -2.12848096e+01,\n", - " -1.97906365e-05, -3.64402561e-02, 2.98276750e-04, -8.84082092e-05,\n", - " 6.71745853e-05, 7.81334922e-04]),\n", - " array([-1.01944063e+01, -2.14624125e+01, -1.01941348e+01, -2.14621409e+01,\n", - " -2.30141404e-05, -3.66457554e-02, 2.94730381e-04, -8.83670486e-05,\n", - " 6.69992283e-05, 7.76675570e-04]),\n", - " array([-1.02990936e+01, -2.16397409e+01, -1.02987819e+01, -2.16394292e+01,\n", - " -2.62450071e-05, -3.68813502e-02, 2.91148771e-04, -8.83137648e-05,\n", - " 6.68439148e-05, 7.72278986e-04]),\n", - " array([-1.03942902e+01, -2.18166012e+01, -1.03939397e+01, -2.18162507e+01,\n", - " -2.94824931e-05, -3.71467828e-02, 2.87537525e-04, -8.82482606e-05,\n", - " 6.67086258e-05, 7.68146865e-04]),\n", - " array([-1.04796721e+01, -2.19925181e+01, -1.04792842e+01, -2.19921303e+01,\n", - " -3.27259407e-05, -3.74415594e-02, 2.83901539e-04, -8.81704481e-05,\n", - " 6.65933206e-05, 7.64281113e-04]),\n", - " array([-1.05549348e+01, -2.21669656e+01, -1.05545111e+01, -2.21665420e+01,\n", - " -3.59747827e-05, -3.77649557e-02, 2.80244988e-04, -8.80802486e-05,\n", - " 6.64979365e-05, 7.60683845e-04]),\n", - " array([-1.06197922e+01, -2.23393678e+01, -1.06193345e+01, -2.23389101e+01,\n", - " -3.92285456e-05, -3.81160234e-02, 2.76571320e-04, -8.79775931e-05,\n", - " 6.64223882e-05, 7.57357381e-04]),\n", - " array([-1.06739763e+01, -2.25091001e+01, -1.06734863e+01, -2.25086100e+01,\n", - " -4.24868521e-05, -3.84935964e-02, 2.72883246e-04, -8.78624224e-05,\n", - " 6.63665679e-05, 7.54304237e-04]),\n", - " array([-1.07172357e+01, -2.26754903e+01, -1.07167153e+01, -2.26749698e+01,\n", - " -4.57494224e-05, -3.88962975e-02, 2.69182738e-04, -8.77346869e-05,\n", - " 6.63303457e-05, 7.51527116e-04]),\n", - " array([-1.07493351e+01, -2.28378199e+01, -1.07487863e+01, -2.28372711e+01,\n", - " -4.90160729e-05, -3.93225452e-02, 2.65471012e-04, -8.75943468e-05,\n", - " 6.63135691e-05, 7.49028900e-04]),\n", - " array([-1.07700549e+01, -2.29953259e+01, -1.07694797e+01, -2.29947507e+01,\n", - " -5.22867167e-05, -3.97705606e-02, 2.61748541e-04, -8.74413720e-05,\n", - " 6.63160640e-05, 7.46812641e-04]),\n", - " array([-1.07791900e+01, -2.31472018e+01, -1.07785908e+01, -2.31466026e+01,\n", - " -5.55613605e-05, -4.02383750e-02, 2.58015044e-04, -8.72757422e-05,\n", - " 6.63376346e-05, 7.44881543e-04]),\n", - " array([-1.07765498e+01, -2.32925999e+01, -1.07759290e+01, -2.32919790e+01,\n", - " -5.88400960e-05, -4.07238371e-02, 2.54269474e-04, -8.70974465e-05,\n", - " 6.63780642e-05, 7.43238949e-04]),\n", - " array([-1.07619576e+01, -2.34306329e+01, -1.07613176e+01, -2.34299929e+01,\n", - " -6.21231093e-05, -4.12246213e-02, 2.50510051e-04, -8.69064833e-05,\n", - " 6.64371163e-05, 7.41888329e-04]),\n", - " array([-1.07352498e+01, -2.35603762e+01, -1.07345932e+01, -2.35597196e+01,\n", - " -6.54106557e-05, -4.17382350e-02, 2.46734227e-04, -8.67028604e-05,\n", - " 6.65145349e-05, 7.40833262e-04]),\n", - " array([-1.06962759e+01, -2.36808698e+01, -1.06956055e+01, -2.36801994e+01,\n", - " -6.87030695e-05, -4.22620280e-02, 2.42938722e-04, -8.64865942e-05,\n", - " 6.66100456e-05, 7.40077415e-04]),\n", - " array([-1.06448982e+01, -2.37911209e+01, -1.06442169e+01, -2.37904396e+01,\n", - " -7.20007286e-05, -4.27932003e-02, 2.39119474e-04, -8.62577097e-05,\n", - " 6.67233573e-05, 7.39624529e-04]),\n", - " array([-1.05809913e+01, -2.38901062e+01, -1.05803021e+01, -2.38894170e+01,\n", - " -7.53040812e-05, -4.33288117e-02, 2.35271729e-04, -8.60162400e-05,\n", - " 6.68541628e-05, 7.39478393e-04]),\n", - " array([-1.05044422e+01, -2.39767747e+01, -1.05037482e+01, -2.39760807e+01,\n", - " -7.86136075e-05, -4.38657906e-02, 2.31389991e-04, -8.57622263e-05,\n", - " 6.70021405e-05, 7.39642831e-04]),\n", - " array([-1.04151497e+01, -2.40500503e+01, -1.04144542e+01, -2.40493549e+01,\n", - " -8.19298156e-05, -4.44009443e-02, 2.27468051e-04, -8.54957167e-05,\n", - " 6.71669562e-05, 7.40121671e-04]),\n", - " array([-1.03130248e+01, -2.41088351e+01, -1.03123312e+01, -2.41081415e+01,\n", - " -8.52532257e-05, -4.49309683e-02, 2.23498999e-04, -8.52167664e-05,\n", - " 6.73482640e-05, 7.40918729e-04]),\n", - " array([-1.01979905e+01, -2.41520122e+01, -1.01973022e+01, -2.41513238e+01,\n", - " -8.85843558e-05, -4.54524568e-02, 2.19475241e-04, -8.49254366e-05,\n", - " 6.75457092e-05, 7.42037782e-04]),\n", - " array([-1.00699816e+01, -2.41784487e+01, -1.00693020e+01, -2.41777691e+01,\n", - " -9.19237043e-05, -4.59619135e-02, 2.15388516e-04, -8.46217944e-05,\n", - " 6.77589289e-05, 7.43482546e-04]),\n", - " array([-9.92894467e+00, -2.41869997e+01, -9.92827753e+00, -2.41863326e+01,\n", - " -9.52717327e-05, -4.64557624e-02, 2.11229919e-04, -8.43059119e-05,\n", - " 6.79875552e-05, 7.45256647e-04]),\n", - " array([-9.77483863e+00, -2.41765113e+01, -9.77418752e+00, -2.41758602e+01,\n", - " -9.86288469e-05, -4.69303590e-02, 2.06989919e-04, -8.39778656e-05,\n", - " 6.82312164e-05, 7.47363601e-04]),\n", - " array([-9.60763426e+00, -2.41458245e+01, -9.60700285e+00, -2.41451931e+01,\n", - " -1.01995377e-04, -4.73820019e-02, 2.02658391e-04, -8.36377359e-05,\n", - " 6.84895395e-05, 7.49806782e-04]),\n", - " array([-9.42731465e+00, -2.40937788e+01, -9.42670664e+00, -2.40931708e+01,\n", - " -1.05371556e-04, -4.78069447e-02, 1.98224639e-04, -8.32856061e-05,\n", - " 6.87621525e-05, 7.52589400e-04]),\n", - " array([-9.23387529e+00, -2.40192160e+01, -9.23329433e+00, -2.40186350e+01,\n", - " -1.08757500e-04, -4.82014083e-02, 1.93677429e-04, -8.29215621e-05,\n", - " 6.90486865e-05, 7.55714473e-04]),\n", - " array([-9.02732423e+00, -2.39209845e+01, -9.02677397e+00, -2.39204343e+01,\n", - " -1.12153185e-04, -4.85615932e-02, 1.89005024e-04, -8.25456914e-05,\n", - " 6.93487781e-05, 7.59184798e-04]),\n", - " array([-8.80768235e+00, -2.37979433e+01, -8.80716635e+00, -2.37974273e+01,\n", - " -1.15558424e-04, -4.88836920e-02, 1.84195219e-04, -8.21580823e-05,\n", - " 6.96620715e-05, 7.63002927e-04]),\n", - " array([-8.57498354e+00, -2.36489661e+01, -8.57450529e+00, -2.36484878e+01,\n", - " -1.18972845e-04, -4.91639032e-02, 1.79235379e-04, -8.17588236e-05,\n", - " 6.99882212e-05, 7.67171137e-04]),\n", - " array([-8.32927497e+00, -2.34729455e+01, -8.32883784e+00, -2.34725084e+01,\n", - " -1.22395865e-04, -4.93984434e-02, 1.74112486e-04, -8.13480037e-05,\n", - " 7.03268940e-05, 7.71691406e-04]),\n", - " array([-8.07061741e+00, -2.32687977e+01, -8.07022462e+00, -2.32684049e+01,\n", - " -1.25826671e-04, -4.95835615e-02, 1.68813179e-04, -8.09257098e-05,\n", - " 7.06777713e-05, 7.76565381e-04]),\n", - " array([-7.79908542e+00, -2.30354666e+01, -7.79874003e+00, -2.30351212e+01,\n", - " -1.29264196e-04, -4.97155517e-02, 1.63323808e-04, -8.04920275e-05,\n", - " 7.10405513e-05, 7.81794357e-04]),\n", - " array([-7.51476774e+00, -2.27719286e+01, -7.51447260e+00, -2.27716335e+01,\n", - " -1.32707095e-04, -4.97907678e-02, 1.57630479e-04, -8.00470402e-05,\n", - " 7.14149512e-05, 7.87379245e-04]),\n", - " array([-7.21776752e+00, -2.24771969e+01, -7.21752526e+00, -2.24769547e+01,\n", - " -1.36153723e-04, -4.98056367e-02, 1.51719114e-04, -7.95908285e-05,\n", - " 7.18007088e-05, 7.93320551e-04]),\n", - " array([-6.90820270e+00, -2.21503262e+01, -6.90801568e+00, -2.21501392e+01,\n", - " -1.39602121e-04, -4.97566723e-02, 1.45575503e-04, -7.91234697e-05,\n", - " 7.21975848e-05, 7.99618347e-04]),\n", - " array([-6.58620626e+00, -2.17904171e+01, -6.58607657e+00, -2.17902874e+01,\n", - " -1.43049988e-04, -4.96404896e-02, 1.39185371e-04, -7.86450376e-05,\n", - " 7.26053641e-05, 8.06272247e-04]),\n", - " array([-6.25192659e+00, -2.13966209e+01, -6.25185599e+00, -2.13965503e+01,\n", - " -1.46494671e-04, -4.94538188e-02, 1.32534434e-04, -7.81556021e-05,\n", - " 7.30238573e-05, 8.13281382e-04]),\n", - " array([-5.90552774e+00, -2.09681441e+01, -5.90551769e+00, -2.09681341e+01,\n", - " -1.49933145e-04, -4.91935190e-02, 1.25608468e-04, -7.76552290e-05,\n", - " 7.34529022e-05, 8.20644380e-04]),\n", - " array([-5.54718982e+00, -2.05042531e+01, -5.54724139e+00, -2.05043046e+01,\n", - " -1.53362005e-04, -4.88565921e-02, 1.18393377e-04, -7.71439801e-05,\n", - " 7.38923643e-05, 8.28359338e-04]),\n", - " array([-5.17710921e+00, -2.00042781e+01, -5.17722312e+00, -2.00043920e+01,\n", - " -1.56777450e-04, -4.84401964e-02, 1.10875266e-04, -7.66219128e-05,\n", - " 7.43421380e-05, 8.36423807e-04]),\n", - " array([-4.79549890e+00, -1.94676182e+01, -4.79567547e+00, -1.94677948e+01,\n", - " -1.60175281e-04, -4.79416603e-02, 1.03040511e-04, -7.60890809e-05,\n", - " 7.48021467e-05, 8.44834765e-04]),\n", - " array([-4.40258879e+00, -1.88937454e+01, -4.40282792e+00, -1.88939845e+01,\n", - " -1.63550894e-04, -4.73584953e-02, 9.48758349e-05, -7.55455343e-05,\n", - " 7.52723431e-05, 8.53588603e-04]),\n", - " array([-3.99862590e+00, -1.82822087e+01, -3.99892709e+00, -1.82825099e+01,\n", - " -1.66899279e-04, -4.66884090e-02, 8.63683888e-05, -7.49913200e-05,\n", - " 7.57527087e-05, 8.62681105e-04]),\n", - " array([-3.58387466e+00, -1.76326385e+01, -3.58423698e+00, -1.76330008e+01,\n", - " -1.70215029e-04, -4.59293176e-02, 7.75058276e-05, -7.44264822e-05,\n", - " 7.62432536e-05, 8.72107432e-04]),\n", - " array([-3.15861713e+00, -1.69447502e+01, -3.15903921e+00, -1.69451723e+01,\n", - " -1.73492342e-04, -4.50793583e-02, 6.82763930e-05, -7.38510635e-05,\n", - " 7.67440149e-05, 8.81862108e-04]),\n", - " array([-2.72315317e+00, -1.62183483e+01, -2.72363323e+00, -1.62188284e+01,\n", - " -1.76725036e-04, -4.41369006e-02, 5.86689955e-05, -7.32651055e-05,\n", - " 7.72550562e-05, 8.91939004e-04]),\n", - " array([-2.27780066e+00, -1.54533295e+01, -2.27833649e+00, -1.54538654e+01,\n", - " -1.79906566e-04, -4.31005573e-02, 4.86732979e-05, -7.26686500e-05,\n", - " 7.77764650e-05, 9.02331329e-04]),\n", - " array([-1.82289562e+00, -1.46496866e+01, -1.82348460e+00, -1.46502756e+01,\n", - " -1.83030048e-04, -4.19691956e-02, 3.82798000e-05, -7.20617406e-05,\n", - " 7.83083513e-05, 9.13031620e-04]),\n", - " array([-1.35879234e+00, -1.38075111e+01, -1.35943143e+00, -1.38081502e+01,\n", - " -1.86088284e-04, -4.07419462e-02, 2.74799223e-05, -7.14444234e-05,\n", - " 7.88508444e-05, 9.24031732e-04]),\n", - " array([-8.85863421e-01, -1.29269963e+01, -8.86549215e-01, -1.29276821e+01,\n", - " -1.89073796e-04, -3.94182129e-02, 1.62660915e-05, -7.08167495e-05,\n", - " 7.94040904e-05, 9.35322833e-04]),\n", - " array([-4.04499855e-01, -1.20084401e+01, -4.05228566e-01, -1.20091688e+01,\n", - " -1.91978862e-04, -3.79976806e-02, 4.63182399e-06, -7.01787759e-05,\n", - " 7.99682489e-05, 9.46895400e-04]),\n", - " array([ 8.48890052e-02, -1.10522466e+01, 8.41215003e-02, -1.10530141e+01,\n", - " -1.94795566e-04, -3.64803229e-02, -7.42819072e-06, -6.95305681e-05,\n", - " 8.05434890e-05, 9.58739215e-04]),\n", - " array([ 5.81875488e-01, -1.00589288e+01, 5.81073623e-01, -1.00597307e+01,\n", - " -1.97515838e-04, -3.48664086e-02, -1.99180084e-05, -6.88722017e-05,\n", - " 8.11299855e-05, 9.70843369e-04]),\n", - " array([ 1.08601370e+00, -9.02910990e+00, 1.08518219e+00, -9.02994141e+00,\n", - " -2.00131516e-04, -3.31565076e-02, -3.28403506e-05, -6.82037650e-05,\n", - " 8.17279144e-05, 9.83196257e-04]),\n", - " array([ 1.59683968e+00, -7.96352431e+00, 1.59598348e+00, -7.96438050e+00,\n", - " -2.02634399e-04, -3.13514949e-02, -4.61965273e-05, -6.75253608e-05,\n", - " 8.23374482e-05, 9.95785590e-04]),\n", - " array([ 2.11387158e+00, -6.86301895e+00, 2.11299586e+00, -6.86389467e+00,\n", - " -2.05016316e-04, -2.94525550e-02, -5.99863636e-05, -6.68371093e-05,\n", - " 8.29587512e-05, 1.00859839e-03]),\n", - " array([ 2.63660995e+00, -5.72855360e+00, 2.63572005e+00, -5.72944350e+00,\n", - " -2.07269191e-04, -2.74611837e-02, -7.42081296e-05, -6.61391505e-05,\n", - " 8.35919740e-05, 1.02162103e-03]),\n", - " array([ 3.16453804e+00, -4.56120097e+00, 3.16363941e+00, -4.56209960e+00,\n", - " -2.09385119e-04, -2.53791900e-02, -8.88584762e-05, -6.54316464e-05,\n", - " 8.42372480e-05, 1.03483917e-03]),\n", - " array([ 3.69712217e+00, -3.36214646e+00, 3.69622035e+00, -3.36304829e+00,\n", - " -2.11356437e-04, -2.32086962e-02, -1.03932375e-04, -6.47147843e-05,\n", - " 8.48946804e-05, 1.04823788e-03]),\n", - " array([ 4.23381219e+00, -2.13268745e+00, 4.23291274e+00, -2.13358690e+00,\n", - " -2.13175808e-04, -2.09521371e-02, -1.19423066e-04, -6.39887788e-05,\n", - " 8.55643481e-05, 1.06180156e-03]),\n", - " array([ 4.77404194e+00, -8.74232141e-01, 4.77315043e+00, -8.75123654e-01,\n", - " -2.14836296e-04, -1.86122576e-02, -1.35322012e-04, -6.32538747e-05,\n", - " 8.62462922e-05, 1.07551399e-03]),\n", - " array([ 5.31722987e+00, 4.11702000e-01, 5.31635179e+00, 4.10823924e-01,\n", - " -2.16331455e-04, -1.61921101e-02, -1.51618859e-04, -6.25103497e-05,\n", - " 8.69405125e-05, 1.08935838e-03]),\n", - " array([ 5.86277962e+00, 1.72349021e+00, 5.86192038e+00, 1.72263097e+00,\n", - " -2.17655405e-04, -1.36950495e-02, -1.68301411e-04, -6.17585168e-05,\n", - " 8.76469613e-05, 1.10331734e-03]),\n", - " array([ 6.41008076e+00, 3.05940286e+00, 6.40924561e+00, 3.05856771e+00,\n", - " -2.18802917e-04, -1.11247278e-02, -1.85355607e-04, -6.09987265e-05,\n", - " 8.83655390e-05, 1.11737293e-03]),\n", - " array([ 6.95850954e+00, 4.41760828e+00, 6.95770355e+00, 4.41680230e+00,\n", - " -2.19769491e-04, -8.48508743e-03, -2.02765513e-04, -6.02313696e-05,\n", - " 8.90960878e-05, 1.13150669e-03]),\n", - " array([ 7.50742972e+00, 5.79617606e+00, 7.50665773e+00, 5.79540408e+00,\n", - " -2.20551437e-04, -5.78035323e-03, -2.20513326e-04, -5.94568789e-05,\n", - " 8.98383874e-05, 1.14569968e-03]),\n", - " array([ 8.05619347e+00, 7.19308066e+00, 8.05546007e+00, 7.19234726e+00,\n", - " -2.21145944e-04, -3.01502335e-03, -2.38579382e-04, -5.86757314e-05,\n", - " 9.05921501e-05, 1.15993246e-03]),\n", - " array([ 8.60414233e+00, 8.60620552e+00, 8.60345179e+00, 8.60551499e+00,\n", - " -2.21551152e-04, -1.93859117e-04, -2.56942184e-04, -5.78884498e-05,\n", - " 9.13570164e-05, 1.17418518e-03]),\n", - " array([ 9.15060823e+00, 1.00333475e+01, 9.14996453e+00, 1.00327038e+01,\n", - " -2.21766217e-04, 2.67812613e-03, -2.75578434e-04, -5.70956042e-05,\n", - " 9.21325514e-05, 1.18843758e-03]),\n", - " array([ 9.69491461e+00, 1.14722217e+01, 9.69432134e+00, 1.14716285e+01,\n", - " -2.21791360e-04, 5.59567932e-03, -2.94463083e-04, -5.62978129e-05,\n", - " 9.29182413e-05, 1.20266903e-03]),\n", - " array([ 1.02363775e+01, 1.29204668e+01, 1.02358379e+01, 1.29199272e+01,\n", - " -2.21627925e-04, 8.55332083e-03, -3.13569383e-04, -5.54957438e-05,\n", - " 9.37134907e-05, 1.21685859e-03]),\n", - " array([ 1.07743068e+01, 1.43756500e+01, 1.07738237e+01, 1.43751670e+01,\n", - " -2.21278413e-04, 1.15453586e-02, -3.32868956e-04, -5.46901142e-05,\n", - " 9.45176202e-05, 1.23098501e-03]),\n", - " array([ 1.13080073e+01, 1.58352738e+01, 1.13075832e+01, 1.58348497e+01,\n", - " -2.20746517e-04, 1.45659030e-02, -3.52331868e-04, -5.38816917e-05,\n", - " 9.53298648e-05, 1.24502681e-03]),\n", - " array([ 1.18367806e+01, 1.72967813e+01, 1.18364174e+01, 1.72964181e+01,\n", - " -2.20037143e-04, 1.76088827e-02, -3.71926715e-04, -5.30712936e-05,\n", - " 9.61493735e-05, 1.25896231e-03]),\n", - " array([ 1.23599254e+01, 1.87575626e+01, 1.23596249e+01, 1.87572621e+01,\n", - " -2.19156422e-04, 2.06680611e-02, -3.91620711e-04, -5.22597861e-05,\n", - " 9.69752083e-05, 1.27276964e-03]),\n", - " array([ 1.28767400e+01, 2.02149622e+01, 1.28765033e+01, 2.02147255e+01,\n", - " -2.18111716e-04, 2.37370533e-02, -4.11379781e-04, -5.14480838e-05,\n", - " 9.78063452e-05, 1.28642685e-03]),\n", - " array([ 1.33865230e+01, 2.16662848e+01, 1.33863508e+01, 2.16661127e+01,\n", - " -2.16911605e-04, 2.68093438e-02, -4.31168668e-04, -5.06371478e-05,\n", - " 9.86416755e-05, 1.29991189e-03]),\n", - " array([ 1.38885748e+01, 2.31088029e+01, 1.38884676e+01, 2.31086957e+01,\n", - " -2.15565878e-04, 2.98783049e-02, -4.50951028e-04, -4.98279842e-05,\n", - " 9.94800072e-05, 1.31320270e-03]),\n", - " array([ 1.43821994e+01, 2.45397639e+01, 1.43821572e+01, 2.45397216e+01,\n", - " -2.14085497e-04, 3.29372148e-02, -4.70689539e-04, -4.90216418e-05,\n", - " 1.00320069e-04, 1.32627724e-03]),\n", - " array([ 1.48667057e+01, 2.59563970e+01, 1.48667280e+01, 2.59564193e+01,\n", - " -2.12482567e-04, 3.59792771e-02, -4.90346010e-04, -4.82192096e-05,\n", - " 1.01160511e-04, 1.33911356e-03]),\n", - " array([ 1.53414088e+01, 2.73559211e+01, 1.53414948e+01, 2.73560071e+01,\n", - " -2.10770289e-04, 3.89976395e-02, -5.09881479e-04, -4.74218134e-05,\n", - " 1.01999912e-04, 1.35168981e-03]),\n", - " array([ 1.58056318e+01, 2.87355518e+01, 1.58057804e+01, 2.87357004e+01,\n", - " -2.08962905e-04, 4.19854136e-02, -5.29256327e-04, -4.66306130e-05,\n", - " 1.02836784e-04, 1.36398430e-03]),\n", - " array([ 1.62587070e+01, 3.00925091e+01, 1.62589168e+01, 3.00927189e+01,\n", - " -2.07075634e-04, 4.49356942e-02, -5.48430379e-04, -4.58467981e-05,\n", - " 1.03669575e-04, 1.37597560e-03]),\n", - " array([ 1.66999778e+01, 3.14240247e+01, 1.67002469e+01, 3.14242938e+01,\n", - " -2.05124604e-04, 4.78415789e-02, -5.67363010e-04, -4.50715844e-05,\n", - " 1.04496678e-04, 1.38764251e-03]),\n", - " array([ 1.71287997e+01, 3.27273496e+01, 1.71291262e+01, 3.27276761e+01,\n", - " -2.03126770e-04, 5.06961876e-02, -5.86013246e-04, -4.43062092e-05,\n", - " 1.05316437e-04, 1.39896418e-03]),\n", - " array([ 1.75445421e+01, 3.39997615e+01, 1.75449236e+01, 3.40001430e+01,\n", - " -2.01099829e-04, 5.34926824e-02, -6.04339869e-04, -4.35519271e-05,\n", - " 1.06127153e-04, 1.40992010e-03]),\n", - " array([ 1.79465896e+01, 3.52385722e+01, 1.79470235e+01, 3.52390061e+01,\n", - " -1.99062130e-04, 5.62242865e-02, -6.22301516e-04, -4.28100044e-05,\n", - " 1.06927094e-04, 1.42049020e-03]),\n", - " array([ 1.83343435e+01, 3.64411346e+01, 1.83348271e+01, 3.64416182e+01,\n", - " -1.97032569e-04, 5.88843036e-02, -6.39856781e-04, -4.20817148e-05,\n", - " 1.07714503e-04, 1.43065487e-03]),\n", - " array([ 1.87072230e+01, 3.76048505e+01, 1.87077532e+01, 3.76053807e+01,\n", - " -1.95030489e-04, 6.14661370e-02, -6.56964316e-04, -4.13683337e-05,\n", - " 1.08487605e-04, 1.44039502e-03]),\n", - " array([ 1.90646666e+01, 3.87271768e+01, 1.90652405e+01, 3.87277506e+01,\n", - " -1.93075570e-04, 6.39633081e-02, -6.73582929e-04, -4.06711328e-05,\n", - " 1.09244616e-04, 1.44969211e-03]),\n", - " array([ 1.94061337e+01, 3.98056333e+01, 1.94067479e+01, 3.98062475e+01,\n", - " -1.91187707e-04, 6.63694748e-02, -6.89671691e-04, -3.99913747e-05,\n", - " 1.09983757e-04, 1.45852823e-03]),\n", - " array([ 1.97311054e+01, 4.08378088e+01, 1.97317566e+01, 4.08384600e+01,\n", - " -1.89386899e-04, 6.86784498e-02, -7.05190031e-04, -3.93303069e-05,\n", - " 1.10703257e-04, 1.46688610e-03]),\n", - " array([ 2.00390860e+01, 4.18213680e+01, 2.00397707e+01, 4.18220528e+01,\n", - " -1.87693119e-04, 7.08842180e-02, -7.20097843e-04, -3.86891567e-05,\n", - " 1.11401366e-04, 1.47474916e-03]),\n", - " array([ 2.03296040e+01, 4.27540580e+01, 2.03303189e+01, 4.27547729e+01,\n", - " -1.86126192e-04, 7.29809537e-02, -7.34355591e-04, -3.80691249e-05,\n", - " 1.12076366e-04, 1.48210159e-03]),\n", - " array([ 2.06022133e+01, 4.36337145e+01, 2.06029549e+01, 4.36344560e+01,\n", - " -1.84705665e-04, 7.49630377e-02, -7.47924409e-04, -3.74713806e-05,\n", - " 1.12726577e-04, 1.48892834e-03]),\n", - " array([ 2.08564944e+01, 4.44582674e+01, 2.08572591e+01, 4.44590321e+01,\n", - " -1.83450677e-04, 7.68250733e-02, -7.60766214e-04, -3.68970552e-05,\n", - " 1.13350370e-04, 1.49521521e-03]),\n", - " array([ 2.10920549e+01, 4.52257475e+01, 2.10928394e+01, 4.52265319e+01,\n", - " -1.82379831e-04, 7.85619025e-02, -7.72843810e-04, -3.63472371e-05,\n", - " 1.13946175e-04, 1.50094885e-03]),\n", - " array([ 2.13085311e+01, 4.59342913e+01, 2.13093319e+01, 4.59350922e+01,\n", - " -1.81511061e-04, 8.01686211e-02, -7.84120999e-04, -3.58229664e-05,\n", - " 1.14512491e-04, 1.50611682e-03]),\n", - " array([ 2.15055882e+01, 4.65821472e+01, 2.15064021e+01, 4.65829611e+01,\n", - " -1.80861502e-04, 8.16405939e-02, -7.94562690e-04, -3.53252295e-05,\n", - " 1.15047893e-04, 1.51070759e-03]),\n", - " array([ 2.16829217e+01, 4.71676799e+01, 2.16837455e+01, 4.71685037e+01,\n", - " -1.80447369e-04, 8.29734687e-02, -8.04135011e-04, -3.48549540e-05,\n", - " 1.15551046e-04, 1.51471065e-03]),\n", - " array([ 2.18402578e+01, 4.76893760e+01, 2.18410884e+01, 4.76902066e+01,\n", - " -1.80283828e-04, 8.41631904e-02, -8.12805424e-04, -3.44130042e-05,\n", - " 1.16020705e-04, 1.51811644e-03]),\n", - " array([ 2.19773542e+01, 4.81458485e+01, 2.19781888e+01, 4.81466830e+01,\n", - " -1.80384877e-04, 8.52060141e-02, -8.20542833e-04, -3.40001767e-05,\n", - " 1.16455730e-04, 1.52091647e-03]),\n", - " array([ 2.20940008e+01, 4.85358412e+01, 2.20948365e+01, 4.85366769e+01,\n", - " -1.80763235e-04, 8.60985178e-02, -8.27317700e-04, -3.36171956e-05,\n", - " 1.16855089e-04, 1.52310328e-03]),\n", - " array([ 2.21900200e+01, 4.88582332e+01, 2.21908543e+01, 4.88590676e+01,\n", - " -1.81430227e-04, 8.68376143e-02, -8.33102155e-04, -3.32647094e-05,\n", - " 1.17217869e-04, 1.52467052e-03]),\n", - " array([ 2.22652676e+01, 4.91120429e+01, 2.22660982e+01, 4.91128734e+01,\n", - " -1.82395690e-04, 8.74205629e-02, -8.37870114e-04, -3.29432869e-05,\n", - " 1.17543277e-04, 1.52561292e-03]),\n", - " array([ 2.23196331e+01, 4.92964313e+01, 2.23204577e+01, 4.92972559e+01,\n", - " -1.83667874e-04, 8.78449804e-02, -8.41597382e-04, -3.26534143e-05,\n", - " 1.17830647e-04, 1.52592634e-03]),\n", - " array([ 2.23530399e+01, 4.94107063e+01, 2.23538566e+01, 4.94115229e+01,\n", - " -1.85253358e-04, 8.81088505e-02, -8.44261768e-04, -3.23954928e-05,\n", - " 1.18079446e-04, 1.52560780e-03]),\n", - " array([ 2.23654460e+01, 4.94543250e+01, 2.23662529e+01, 4.94551319e+01,\n", - " -1.87156978e-04, 8.82105340e-02, -8.45843190e-04, -3.21698357e-05,\n", - " 1.18289280e-04, 1.52465544e-03]),\n", - " array([ 2.23568437e+01, 4.94268973e+01, 2.23576393e+01, 4.94276930e+01,\n", - " -1.89381762e-04, 8.81487770e-02, -8.46323781e-04, -3.19766671e-05,\n", - " 1.18459888e-04, 1.52306860e-03]),\n", - " array([ 2.23272604e+01, 4.93281883e+01, 2.23280435e+01, 4.93289713e+01,\n", - " -1.91928875e-04, 8.79227190e-02, -8.45687990e-04, -3.18161202e-05,\n", - " 1.18591155e-04, 1.52084777e-03]),\n", - " array([ 2.22767586e+01, 4.91581203e+01, 2.22775279e+01, 4.91588897e+01,\n", - " -1.94797583e-04, 8.75318998e-02, -8.43922678e-04, -3.16882367e-05,\n", - " 1.18683106e-04, 1.51799464e-03]),\n", - " array([ 2.22054356e+01, 4.89167754e+01, 2.22061903e+01, 4.89175301e+01,\n", - " -1.97985223e-04, 8.69762659e-02, -8.41017210e-04, -3.15929665e-05,\n", - " 1.18735910e-04, 1.51451208e-03]),\n", - " array([ 2.21134239e+01, 4.86043965e+01, 2.21141632e+01, 4.86051357e+01,\n", - " -2.01487191e-04, 8.62561756e-02, -8.36963548e-04, -3.15301672e-05,\n", - " 1.18749877e-04, 1.51040414e-03]),\n", - " array([ 2.20008911e+01, 4.82213888e+01, 2.20016144e+01, 4.82221120e+01,\n", - " -2.05296941e-04, 8.53724035e-02, -8.31756323e-04, -3.14996056e-05,\n", - " 1.18725457e-04, 1.50567605e-03]),\n", - " array([ 2.18680396e+01, 4.77683208e+01, 2.18687464e+01, 4.77690276e+01,\n", - " -2.09406004e-04, 8.43261432e-02, -8.25392918e-04, -3.15009582e-05,\n", - " 1.18663241e-04, 1.50033422e-03]),\n", - " array([ 2.17151065e+01, 4.72459245e+01, 2.17157967e+01, 4.72466147e+01,\n", - " -2.13804013e-04, 8.31190103e-02, -8.17873526e-04, -3.15338132e-05,\n", - " 1.18563951e-04, 1.49438623e-03]),\n", - " array([ 2.15423635e+01, 4.66550956e+01, 2.15430369e+01, 4.66557690e+01,\n", - " -2.18478751e-04, 8.17530425e-02, -8.09201215e-04, -3.15976725e-05,\n", - " 1.18428442e-04, 1.48784080e-03]),\n", - " array([ 2.13501163e+01, 4.59968931e+01, 2.13507728e+01, 4.59975497e+01,\n", - " -2.23416210e-04, 8.02307000e-02, -7.99381972e-04, -3.16919543e-05,\n", - " 1.18257694e-04, 1.48070779e-03]),\n", - " array([ 2.11387043e+01, 4.52725384e+01, 2.11393441e+01, 4.52731781e+01,\n", - " -2.28600666e-04, 7.85548637e-02, -7.88424745e-04, -3.18159967e-05,\n", - " 1.18052804e-04, 1.47299821e-03]),\n", - " array([ 2.09085002e+01, 4.44834138e+01, 2.09091233e+01, 4.44840368e+01,\n", - " -2.34014769e-04, 7.67288326e-02, -7.76341469e-04, -3.19690607e-05,\n", - " 1.17814983e-04, 1.46472414e-03]),\n", - " array([ 2.06599094e+01, 4.36310609e+01, 2.06605159e+01, 4.36316674e+01,\n", - " -2.39639643e-04, 7.47563194e-02, -7.63147085e-04, -3.21503345e-05,\n", - " 1.17545546e-04, 1.45589875e-03]),\n", - " array([ 2.03933691e+01, 4.27171781e+01, 2.03939593e+01, 4.27177682e+01,\n", - " -2.45455007e-04, 7.26414448e-02, -7.48859547e-04, -3.23589383e-05,\n", - " 1.17245903e-04, 1.44653624e-03]),\n", - " array([ 2.01093481e+01, 4.17436177e+01, 2.01099220e+01, 4.17441916e+01,\n", - " -2.51439300e-04, 7.03887308e-02, -7.33499814e-04, -3.25939287e-05,\n", - " 1.16917551e-04, 1.43665185e-03]),\n", - " array([ 1.98083454e+01, 4.07123824e+01, 1.98089032e+01, 4.07129402e+01,\n", - " -2.57569828e-04, 6.80030915e-02, -7.17091834e-04, -3.28543042e-05,\n", - " 1.16562064e-04, 1.42626179e-03]),\n", - " array([ 1.94908898e+01, 3.96256216e+01, 1.94914315e+01, 3.96261633e+01,\n", - " -2.63822909e-04, 6.54898236e-02, -6.99662515e-04, -3.31390106e-05,\n", - " 1.16181081e-04, 1.41538324e-03]),\n", - " array([ 1.91575387e+01, 3.84856264e+01, 1.91580643e+01, 3.84861520e+01,\n", - " -2.70174039e-04, 6.28545940e-02, -6.81241681e-04, -3.34469471e-05,\n", - " 1.15776297e-04, 1.40403427e-03]),\n", - " array([ 1.88088770e+01, 3.72948247e+01, 1.88093862e+01, 3.72953340e+01,\n", - " -2.76598062e-04, 6.01034273e-02, -6.61862017e-04, -3.37769722e-05,\n", - " 1.15349450e-04, 1.39223384e-03]),\n", - " array([ 1.84455159e+01, 3.60557756e+01, 1.84460086e+01, 3.60562682e+01,\n", - " -2.83069344e-04, 5.72426902e-02, -6.41559007e-04, -3.41279101e-05,\n", - " 1.14902312e-04, 1.38000171e-03]),\n", - " array([ 1.80680920e+01, 3.47711628e+01, 1.80685676e+01, 3.47716384e+01,\n", - " -2.89561954e-04, 5.42790755e-02, -6.20370849e-04, -3.44985570e-05,\n", - " 1.14436674e-04, 1.36735844e-03]),\n", - " array([ 1.76772655e+01, 3.34437884e+01, 1.76777235e+01, 3.34442464e+01,\n", - " -2.96049852e-04, 5.12195841e-02, -5.98338370e-04, -3.48876875e-05,\n", - " 1.13954336e-04, 1.35432533e-03]),\n", - " array([ 1.72737193e+01, 3.20765648e+01, 1.72741590e+01, 3.20770045e+01,\n", - " -3.02507073e-04, 4.80715055e-02, -5.75504922e-04, -3.52940616e-05,\n", - " 1.13457093e-04, 1.34092435e-03]),\n", - " array([ 1.68581570e+01, 3.06725076e+01, 1.68585775e+01, 3.06729280e+01,\n", - " -3.08907918e-04, 4.48423969e-02, -5.51916272e-04, -3.57164308e-05,\n", - " 1.12946728e-04, 1.32717809e-03]),\n", - " array([ 1.64313020e+01, 2.92347266e+01, 1.64317021e+01, 2.92351267e+01,\n", - " -3.15227132e-04, 4.15400610e-02, -5.27620476e-04, -3.61535447e-05,\n", - " 1.12424993e-04, 1.31310973e-03]),\n", - " array([ 1.59938952e+01, 2.77664173e+01, 1.59942737e+01, 2.77667958e+01,\n", - " -3.21440093e-04, 3.81725223e-02, -5.02667748e-04, -3.66041575e-05,\n", - " 1.11893606e-04, 1.29874297e-03]),\n", - " array([ 1.55466937e+01, 2.62708517e+01, 1.55470492e+01, 2.62712071e+01,\n", - " -3.27522983e-04, 3.47480024e-02, -4.77110318e-04, -3.70670338e-05,\n", - " 1.11354233e-04, 1.28410197e-03]),\n", - " array([ 1.50904691e+01, 2.47513681e+01, 1.50907999e+01, 2.47516989e+01,\n", - " -3.33452961e-04, 3.12748937e-02, -4.51002283e-04, -3.75409546e-05,\n", - " 1.10808483e-04, 1.26921129e-03]),\n", - " array([ 1.46260053e+01, 2.32113617e+01, 1.46263098e+01, 2.32116662e+01,\n", - " -3.39208321e-04, 2.77617329e-02, -4.24399445e-04, -3.80247233e-05,\n", - " 1.10257896e-04, 1.25409583e-03]),\n", - " array([ 1.41540972e+01, 2.16542740e+01, 1.41543735e+01, 2.16545503e+01,\n", - " -3.44768643e-04, 2.42171726e-02, -3.97359147e-04, -3.85171704e-05,\n", - " 1.09703932e-04, 1.23878076e-03]),\n", - " array([ 1.36755483e+01, 2.00835817e+01, 1.36757945e+01, 2.00838279e+01,\n", - " -3.50114934e-04, 2.06499531e-02, -3.69940102e-04, -3.90171586e-05,\n", - " 1.09147970e-04, 1.22329151e-03]),\n", - " array([ 1.31911693e+01, 1.85027866e+01, 1.31913832e+01, 1.85030006e+01,\n", - " -3.55229748e-04, 1.70688728e-02, -3.42202210e-04, -3.95235875e-05,\n", - " 1.08591293e-04, 1.20765361e-03]),\n", - " array([ 1.27017754e+01, 1.69154040e+01, 1.27019551e+01, 1.69155836e+01,\n", - " -3.60097304e-04, 1.34827585e-02, -3.14206378e-04, -4.00353973e-05,\n", - " 1.08035086e-04, 1.19189274e-03]),\n", - " array([ 1.22081853e+01, 1.53249515e+01, 1.22083285e+01, 1.53250948e+01,\n", - " -3.64703576e-04, 9.90043542e-03, -2.86014331e-04, -4.05515725e-05,\n", - " 1.07480433e-04, 1.17603457e-03]),\n", - " array([ 1.17112182e+01, 1.37349383e+01, 1.17113230e+01, 1.37350431e+01,\n", - " -3.69036376e-04, 6.33069671e-03, -2.57688420e-04, -4.10711447e-05,\n", - " 1.06928306e-04, 1.16010476e-03]),\n", - " array([ 1.12116928e+01, 1.21488534e+01, 1.12117570e+01, 1.21489176e+01,\n", - " -3.73085414e-04, 2.78227336e-03, -2.29291427e-04, -4.15931953e-05,\n", - " 1.06379569e-04, 1.14412886e-03]),\n", - " array([ 1.07104245e+01, 1.05701547e+01, 1.07104461e+01, 1.05701763e+01,\n", - " -3.76842344e-04, -7.36196020e-04, -2.00886367e-04, -4.21168577e-05,\n", - " 1.05834974e-04, 1.12813228e-03]),\n", - " array([ 1.02082241e+01, 9.00225783e+00, 1.02082013e+01, 9.00223501e+00,\n", - " -3.80300791e-04, -4.21619502e-03, -1.72536293e-04, -4.26413180e-05,\n", - " 1.05295159e-04, 1.11214019e-03]),\n", - " array([ 9.70589535e+00, 7.44852550e+00, 9.70582640e+00, 7.44845655e+00,\n", - " -3.83456361e-04, -7.64935875e-03, -1.44304094e-04, -4.31658165e-05,\n", - " 1.04760648e-04, 1.09617749e-03]),\n", - " array([ 9.20423351e+00, 5.91225653e+00, 9.20411691e+00, 5.91213993e+00,\n", - " -3.86306628e-04, -1.10275026e-02, -1.16252301e-04, -4.36896480e-05,\n", - " 1.04231856e-04, 1.08026876e-03]),\n", - " array([ 8.70402323e+00, 4.39667563e+00, 8.70385771e+00, 4.39651011e+00,\n", - " -3.88851114e-04, -1.43426500e-02, -8.84428840e-05, -4.42121613e-05,\n", - " 1.03709089e-04, 1.06443815e-03]),\n", - " array([ 8.20603687e+00, 2.90492338e+00, 8.20582142e+00, 2.90470793e+00,\n", - " -3.91091237e-04, -1.75870596e-02, -6.09370597e-05, -4.47327591e-05,\n", - " 1.03192546e-04, 1.04870938e-03]),\n", - " array([ 7.71103274e+00, 1.44004651e+00, 7.71076665e+00, 1.43978042e+00,\n", - " -3.93030257e-04, -2.07532511e-02, -3.37950986e-05, -4.52508964e-05,\n", - " 1.02682330e-04, 1.03310564e-03]),\n", - " array([ 7.21975342e+00, 4.98872608e-03, 7.21943632e+00, 4.67162687e-03,\n", - " -3.94673196e-04, -2.38340300e-02, -7.07613446e-06, -4.57660794e-05,\n", - " 1.02178443e-04, 1.01764957e-03]),\n", - " array([ 6.73292418e+00, -1.39741805e+00, 6.73255607e+00, -1.39778616e+00,\n", - " -3.96026751e-04, -2.68225109e-02, 1.91620208e-05, -4.62778634e-05,\n", - " 1.01680801e-04, 1.00236320e-03]),\n", - " array([ 6.25125146e+00, -2.76446190e+00, 6.25083272e+00, -2.76488064e+00,\n", - " -3.97099183e-04, -2.97121393e-02, 4.48630583e-05, -4.67858507e-05,\n", - " 1.01189238e-04, 9.87267892e-04]),\n", - " array([ 5.77542139e+00, -4.09355859e+00, 5.77495282e+00, -4.09402716e+00,\n", - " -3.97900208e-04, -3.24967122e-02, 6.99723470e-05, -4.72896879e-05,\n", - " 1.00703512e-04, 9.72384292e-04]),\n", - " array([ 5.30609848e+00, -5.38225867e+00, 5.30558130e+00, -5.38277584e+00,\n", - " -3.98440862e-04, -3.51703970e-02, 9.44371032e-05, -4.77890633e-05,\n", - " 1.00223314e-04, 9.57732301e-04]),\n", - " array([ 4.84392431e+00, -6.62825392e+00, 4.84336020e+00, -6.62881804e+00,\n", - " -3.98733370e-04, -3.77277481e-02, 1.18206552e-04, -4.82837038e-05,\n", - " 9.97482754e-05, 9.43331020e-04]),\n", - " array([ 4.38951638e+00, -7.82938328e+00, 4.38890744e+00, -7.82999222e+00,\n", - " -3.98790996e-04, -4.01637225e-02, 1.41232084e-04, -4.87733718e-05,\n", - " 9.92779784e-05, 9.29198718e-04]),\n", - " array([ 3.94346698e+00, -8.98363796e+00, 3.94281578e+00, -8.98428916e+00,\n", - " -3.98627898e-04, -4.24736932e-02, 1.63467398e-04, -4.92578621e-05,\n", - " 9.88119629e-05, 9.15352793e-04]),\n", - " array([ 3.50634223e+00, -1.00891660e+01, 3.50565177e+00, -1.00898565e+01,\n", - " -3.98258966e-04, -4.46534606e-02, 1.84868644e-04, -4.97369981e-05,\n", - " 9.83497359e-05, 9.01809742e-04]),\n", - " array([ 3.07868116e+00, -1.11442763e+01, 3.07795487e+00, -1.11450026e+01,\n", - " -3.97699670e-04, -4.66992624e-02, 2.05394545e-04, -5.02106293e-05,\n", - " 9.78907801e-05, 8.88585129e-04]),\n", - " array([ 2.66099490e+00, -1.21474416e+01, 2.66023663e+00, -1.21481999e+01,\n", - " -3.96965898e-04, -4.86077815e-02, 2.25006525e-04, -5.06786270e-05,\n", - " 9.74345627e-05, 8.75693556e-04]),\n", - " array([ 2.25376595e+00, -1.30973009e+01, 2.25297995e+00, -1.30980869e+01,\n", - " -3.96073797e-04, -5.03761516e-02, 2.43668808e-04, -5.11408821e-05,\n", - " 9.69805434e-05, 8.63148647e-04]),\n", - " array([ 1.85744760e+00, -1.39926618e+01, 1.85663848e+00, -1.39934709e+01,\n", - " -3.95039621e-04, -5.20019610e-02, 2.61348524e-04, -5.15973013e-05,\n", - " 9.65281826e-05, 8.50963018e-04]),\n", - " array([ 1.47246336e+00, -1.48325011e+01, 1.47163604e+00, -1.48333285e+01,\n", - " -3.93879574e-04, -5.34832555e-02, 2.78015790e-04, -5.20478043e-05,\n", - " 9.60769491e-05, 8.39148269e-04]),\n", - " array([ 1.09920652e+00, -1.56159658e+01, 1.09836624e+00, -1.56168061e+01,\n", - " -3.92609666e-04, -5.48185379e-02, 2.93643791e-04, -5.24923213e-05,\n", - " 9.56263271e-05, 8.27714962e-04]),\n", - " array([ 7.38039811e-01, -1.63423725e+01, 7.37192046e-01, -1.63432202e+01,\n", - " -3.91245575e-04, -5.60067665e-02, 3.08208841e-04, -5.29307902e-05,\n", - " 9.51758230e-05, 8.16672619e-04]),\n", - " array([ 3.89295140e-01, -1.70112071e+01, 3.88445566e-01, -1.70120566e+01,\n", - " -3.89802509e-04, -5.70473522e-02, 3.21690434e-04, -5.33631542e-05,\n", - " 9.47249711e-05, 8.06029706e-04]),\n", - " array([ 5.32733884e-02, -1.76221231e+01, 5.24278294e-02, -1.76229687e+01,\n", - " -3.88295090e-04, -5.79401531e-02, 3.34071289e-04, -5.37893601e-05,\n", - " 9.42733394e-05, 7.95793634e-04]),\n", - " array([-2.69755678e-01, -1.81749401e+01, -2.70591303e-01, -1.81757757e+01,\n", - " -3.86737238e-04, -5.86854679e-02, 3.45337376e-04, -5.42093558e-05,\n", - " 9.38205342e-05, 7.85970759e-04]),\n", - " array([-5.79553437e-01, -1.86696407e+01, -5.80373170e-01, -1.86704605e+01,\n", - " -3.85142067e-04, -5.92840276e-02, 3.55477929e-04, -5.46230898e-05,\n", - " 9.33662037e-05, 7.76566380e-04]),\n", - " array([-8.75912353e-01, -1.91063680e+01, -8.76710255e-01, -1.91071659e+01,\n", - " -3.83521801e-04, -5.97369858e-02, 3.64485455e-04, -5.50305088e-05,\n", - " 9.29100420e-05, 7.67584748e-04]),\n", - " array([-1.15865585e+00, -1.94854217e+01, -1.15942606e+00, -1.94861919e+01,\n", - " -3.81887690e-04, -6.00459072e-02, 3.72355725e-04, -5.54315577e-05,\n", - " 9.24517915e-05, 7.59029073e-04]),\n", - " array([-1.42763812e+00, -1.98072541e+01, -1.42837492e+00, -1.98079909e+01,\n", - " -3.80249949e-04, -6.02127555e-02, 3.79087752e-04, -5.58261782e-05,\n", - " 9.19912442e-05, 7.50901535e-04]),\n", - " array([-1.68274384e+00, -2.00724659e+01, -1.68344169e+00, -2.00731637e+01,\n", - " -3.78617706e-04, -6.02398791e-02, 3.84683757e-04, -5.62143087e-05,\n", - " 9.15282438e-05, 7.43203297e-04]),\n", - " array([-1.92388784e+00, -2.02818009e+01, -1.92454147e+00, -2.02824545e+01,\n", - " -3.76998958e-04, -6.01299963e-02, 3.89149135e-04, -5.65958844e-05,\n", - " 9.10626857e-05, 7.35934526e-04]),\n", - " array([-2.15101472e+00, -2.04361409e+01, -2.15161915e+00, -2.04367454e+01,\n", - " -3.75400550e-04, -5.98861791e-02, 3.92492388e-04, -5.69708367e-05,\n", - " 9.05945166e-05, 7.29094407e-04]),\n", - " array([-2.36409836e+00, -2.05365000e+01, -2.36464896e+00, -2.05370506e+01,\n", - " -3.73828161e-04, -5.95118362e-02, 3.94725070e-04, -5.73390942e-05,\n", - " 9.01237344e-05, 7.22681171e-04]),\n", - " array([-2.56314139e+00, -2.05840184e+01, -2.56363395e+00, -2.05845110e+01,\n", - " -3.72286296e-04, -5.90106950e-02, 3.95861705e-04, -5.77005830e-05,\n", - " 8.96503862e-05, 7.16692114e-04]),\n", - " array([-2.74817464e+00, -2.05799563e+01, -2.74860537e+00, -2.05803870e+01,\n", - " -3.70778307e-04, -5.83867824e-02, 3.95919701e-04, -5.80552273e-05,\n", - " 8.91745667e-05, 7.11123625e-04]),\n", - " array([-2.91925647e+00, -2.05256871e+01, -2.91962208e+00, -2.05260527e+01,\n", - " -3.69306406e-04, -5.76444058e-02, 3.94919259e-04, -5.84029507e-05,\n", - " 8.86964158e-05, 7.05971219e-04]),\n", - " array([-3.07647210e+00, -2.04226906e+01, -3.07676979e+00, -2.04229883e+01,\n", - " -3.67871702e-04, -5.67881328e-02, 3.92883262e-04, -5.87436767e-05,\n", - " 8.82161156e-05, 7.01229562e-04]),\n", - " array([-3.21993280e+00, -2.02725462e+01, -3.22016033e+00, -2.02727737e+01,\n", - " -3.66474242e-04, -5.58227700e-02, 3.89837166e-04, -5.90773306e-05,\n", - " 8.77338872e-05, 6.96892507e-04]),\n", - " array([-3.34977517e+00, -2.00769250e+01, -3.34993085e+00, -2.00770807e+01,\n", - " -3.65113063e-04, -5.47533427e-02, 3.85808875e-04, -5.94038401e-05,\n", - " 8.72499873e-05, 6.92953129e-04]),\n", - " array([-3.46616024e+00, -1.98375830e+01, -3.46624295e+00, -1.98376658e+01,\n", - " -3.63786249e-04, -5.35850725e-02, 3.80828618e-04, -5.97231373e-05,\n", - " 8.67647042e-05, 6.89403757e-04]),\n", - " array([-3.56927257e+00, -1.95563535e+01, -3.56928177e+00, -1.95563627e+01,\n", - " -3.62491001e-04, -5.23233564e-02, 3.74928807e-04, -6.00351598e-05,\n", - " 8.62783536e-05, 6.86236018e-04]),\n", - " array([-3.65931934e+00, -1.92351388e+01, -3.65925507e+00, -1.92350746e+01,\n", - " -3.61223706e-04, -5.09737442e-02, 3.68143902e-04, -6.03398521e-05,\n", - " 8.57912748e-05, 6.83440868e-04]),\n", - " array([-3.73652933e+00, -1.88759036e+01, -3.73639222e+00, -1.88757665e+01,\n", - " -3.59980016e-04, -4.95419170e-02, 3.60510261e-04, -6.06371672e-05,\n", - " 8.53038262e-05, 6.81008636e-04]),\n", - " array([-3.80115192e+00, -1.84806661e+01, -3.80094316e+00, -1.84804573e+01,\n", - " -3.58754931e-04, -4.80336651e-02, 3.52065990e-04, -6.09270682e-05,\n", - " 8.48163805e-05, 6.78929067e-04]),\n", - " array([-3.85345600e+00, -1.80514912e+01, -3.85317733e+00, -1.80512125e+01,\n", - " -3.57542878e-04, -4.64548657e-02, 3.42850783e-04, -6.12095295e-05,\n", - " 8.43293213e-05, 6.77191357e-04]),\n", - " array([-3.89372890e+00, -1.75904821e+01, -3.89338259e+00, -1.75901358e+01,\n", - " -3.56337803e-04, -4.48114619e-02, 3.32905782e-04, -6.14845379e-05,\n", - " 8.38430379e-05, 6.75784200e-04]),\n", - " array([-3.92227523e+00, -1.70997730e+01, -3.92186406e+00, -1.70993618e+01,\n", - " -3.55133255e-04, -4.31094406e-02, 3.22273393e-04, -6.17520946e-05,\n", - " 8.33579216e-05, 6.74695829e-04]),\n", - " array([-3.93941575e+00, -1.65815213e+01, -3.93894296e+00, -1.65810486e+01,\n", - " -3.53922471e-04, -4.13548118e-02, 3.10997120e-04, -6.20122156e-05,\n", - " 8.28743615e-05, 6.73914059e-04]),\n", - " array([-3.94548613e+00, -1.60379003e+01, -3.94495541e+00, -1.60373696e+01,\n", - " -3.52698468e-04, -3.95535876e-02, 2.99121476e-04, -6.22649331e-05,\n", - " 8.23927408e-05, 6.73426328e-04]),\n", - " array([-3.94083581e+00, -1.54710913e+01, -3.94025124e+00, -1.54705067e+01,\n", - " -3.51454120e-04, -3.77117621e-02, 2.86691699e-04, -6.25102965e-05,\n", - " 8.19134332e-05, 6.73219743e-04]),\n", - " array([-3.92582669e+00, -1.48832769e+01, -3.92519271e+00, -1.48826429e+01,\n", - " -3.50182242e-04, -3.58352916e-02, 2.73753677e-04, -6.27483731e-05,\n", - " 8.14367992e-05, 6.73281122e-04]),\n", - " array([-3.90083194e+00, -1.42766337e+01, -3.90015331e+00, -1.42759551e+01,\n", - " -3.48875668e-04, -3.39300758e-02, 2.60353757e-04, -6.29792486e-05,\n", - " 8.09631833e-05, 6.73597036e-04]),\n", - " array([-3.86623472e+00, -1.36533254e+01, -3.86551645e+00, -1.36526071e+01,\n", - " -3.47527325e-04, -3.20019390e-02, 2.46538593e-04, -6.32030280e-05,\n", - " 8.04929115e-05, 6.74153851e-04]),\n", - " array([-3.82242689e+00, -1.30154960e+01, -3.82167424e+00, -1.30147434e+01,\n", - " -3.46130300e-04, -3.00566128e-02, 2.32354984e-04, -6.34198354e-05,\n", - " 8.00262882e-05, 6.74937769e-04]),\n", - " array([-3.76980776e+00, -1.23652638e+01, -3.76902614e+00, -1.23644822e+01,\n", - " -3.44677905e-04, -2.80997191e-02, 2.17849721e-04, -6.36298147e-05,\n", - " 7.95635945e-05, 6.75934872e-04]),\n", - " array([-3.70878280e+00, -1.17047148e+01, -3.70797776e+00, -1.17039098e+01,\n", - " -3.43163734e-04, -2.61367543e-02, 2.03069437e-04, -6.38331293e-05,\n", - " 7.91050864e-05, 6.77131158e-04]),\n", - " array([-3.63976235e+00, -1.10358970e+01, -3.63893953e+00, -1.10350742e+01,\n", - " -3.41581717e-04, -2.41730737e-02, 1.88060460e-04, -6.40299618e-05,\n", - " 7.86509933e-05, 6.78512583e-04]),\n", - " array([-3.56316038e+00, -1.03608147e+01, -3.56232546e+00, -1.03599797e+01,\n", - " -3.39926163e-04, -2.22138780e-02, 1.72868673e-04, -6.42205144e-05,\n", - " 7.82015169e-05, 6.80065100e-04]),\n", - " array([-3.47939321e+00, -9.68142325e+00, -3.47855185e+00, -9.68058189e+00,\n", - " -3.38191801e-04, -2.02641996e-02, 1.57539374e-04, -6.44050077e-05,\n", - " 7.77568305e-05, 6.81774694e-04]),\n", - " array([-3.38887824e+00, -8.99962429e+00, -3.38803607e+00, -8.99878211e+00,\n", - " -3.36373814e-04, -1.83288907e-02, 1.42117149e-04, -6.45836805e-05,\n", - " 7.73170785e-05, 6.83627418e-04]),\n", - " array([-3.29203278e+00, -8.31726078e+00, -3.29119532e+00, -8.31642332e+00,\n", - " -3.34467861e-04, -1.64126122e-02, 1.26645746e-04, -6.47567890e-05,\n", - " 7.68823765e-05, 6.85609429e-04]),\n", - " array([-3.18927275e+00, -7.63611289e+00, -3.18844544e+00, -7.63528557e+00,\n", - " -3.32470104e-04, -1.45198235e-02, 1.11167956e-04, -6.49246059e-05,\n", - " 7.64528110e-05, 6.87707021e-04]),\n", - " array([-3.08101159e+00, -6.95789405e+00, -3.08019967e+00, -6.95708214e+00,\n", - " -3.30377213e-04, -1.26547736e-02, 9.57255026e-05, -6.50874196e-05,\n", - " 7.60284406e-05, 6.89906658e-04]),\n", - " array([-2.96765901e+00, -6.28424740e+00, -2.96686757e+00, -6.28345596e+00,\n", - " -3.28186383e-04, -1.08214934e-02, 8.03589368e-05, -6.52455329e-05,\n", - " 7.56092962e-05, 6.92195000e-04]),\n", - " array([-2.84961991e+00, -5.61674254e+00, -2.84885381e+00, -5.61597643e+00,\n", - " -3.25895327e-04, -9.02378864e-03, 6.51075427e-05, -6.53992621e-05,\n", - " 7.51953820e-05, 6.94558938e-04]),\n", - " array([-2.72729329e+00, -4.95687274e+00, -2.72655714e+00, -4.95613658e+00,\n", - " -3.23502278e-04, -7.26523457e-03, 5.00092465e-05, -6.55489354e-05,\n", - " 7.47866771e-05, 6.96985616e-04]),\n", - " array([-2.60107113e+00, -4.30605249e+00, -2.60036928e+00, -4.30535064e+00,\n", - " -3.21005977e-04, -5.54917126e-03, 3.51005370e-05, -6.56948922e-05,\n", - " 7.43831366e-05, 6.99462460e-04]),\n", - " array([-2.47133741e+00, -3.66561541e+00, -2.47067394e+00, -3.66495194e+00,\n", - " -3.18405659e-04, -3.87870021e-03, 2.04163921e-05, -6.58374809e-05,\n", - " 7.39846930e-05, 7.01977199e-04]),\n", - " array([-2.33846711e+00, -3.03681256e+00, -2.33784579e+00, -3.03619123e+00,\n", - " -3.15701038e-04, -2.25668205e-03, 5.99021484e-06, -6.59770584e-05,\n", - " 7.35912583e-05, 7.04517891e-04]),\n", - " array([-2.20282527e+00, -2.42081108e+00, -2.20224953e+00, -2.42023535e+00,\n", - " -3.12892279e-04, -6.85735271e-04, -8.14622275e-06, -6.61139879e-05,\n", - " 7.32027255e-05, 7.07072940e-04]),\n", - " array([-2.06476607e+00, -1.81869326e+00, -2.06423903e+00, -1.81816622e+00,\n", - " -3.09979975e-04, 8.31763958e-04, -2.19628273e-05, -6.62486381e-05,\n", - " 7.28189706e-05, 7.09631114e-04]),\n", - " array([-1.92463199e+00, -1.23145590e+00, -1.92415640e+00, -1.23098031e+00,\n", - " -3.06965121e-04, 2.29368099e-03, -3.54312229e-05, -6.63813814e-05,\n", - " 7.24398547e-05, 7.12181568e-04]),\n", - " array([-1.78275298e+00, -6.60010048e-01, -1.78233124e+00, -6.59588310e-01,\n", - " -3.03849074e-04, 3.69812084e-03, -4.85247823e-05, -6.65125926e-05,\n", - " 7.20652256e-05, 7.14713852e-04]),\n", - " array([-1.63944573e+00, -1.05181116e-01, -1.63907985e+00, -1.04815232e-01,\n", - " -3.00633528e-04, 5.04342544e-03, -6.12186487e-05, -6.66426473e-05,\n", - " 7.16949201e-05, 7.17217927e-04]),\n", - " array([-1.49501291e+00, 4.32290753e-01, -1.49470449e+00, 4.32599173e-01,\n", - " -2.97320473e-04, 6.32816991e-03, -7.34897496e-05, -6.67719211e-05,\n", - " 7.13287660e-05, 7.19684182e-04]),\n", - " array([-1.34974252e+00, 9.51749939e-01, -1.34949277e+00, 9.51999698e-01,\n", - " -2.93912159e-04, 7.55115799e-03, -8.53168033e-05, -6.69007876e-05,\n", - " 7.09665839e-05, 7.22103434e-04]),\n", - " array([-1.20390731e+00, 1.45262431e+00, -1.20371697e+00, 1.45281465e+00,\n", - " -2.90411059e-04, 8.71141664e-03, -9.66803158e-05, -6.70296175e-05,\n", - " 7.06081892e-05, 7.24466947e-04]),\n", - " array([-1.05776413e+00, 1.93442394e+00, -1.05763350e+00, 1.93455456e+00,\n", - " -2.86819832e-04, 9.80818981e-03, -1.07562571e-04, -6.71587774e-05,\n", - " 7.02533938e-05, 7.26766430e-04]),\n", - " array([-9.11553478e-01, 2.39673944e+00, -9.11482393e-01, 2.39681053e+00,\n", - " -2.83141282e-04, 1.08409316e-02, -1.17947614e-04, -6.72886287e-05,\n", - " 6.99020081e-05, 7.28994051e-04]),\n", - " array([-7.65499024e-01, 2.83924023e+00, -7.65486776e-01, 2.83925248e+00,\n", - " -2.79378323e-04, 1.18092985e-02, -1.27821224e-04, -6.74195264e-05,\n", - " 6.95538425e-05, 7.31142433e-04]),\n", - " array([-6.19807165e-01, 3.26167233e+00, -6.19852503e-01, 3.26162699e+00,\n", - " -2.75533942e-04, 1.27131416e-02, -1.37170886e-04, -6.75518180e-05,\n", - " 6.92087088e-05, 7.33204661e-04]),\n", - " array([-4.74666673e-01, 3.66385615e+00, -4.74767758e-01, 3.66375507e+00,\n", - " -2.71611159e-04, 1.35524971e-02, -1.45985748e-04, -6.76858431e-05,\n", - " 6.88664218e-05, 7.35174282e-04]),\n", - " array([-3.30248379e-01, 4.04568393e+00, -3.30402735e-01, 4.04552957e+00,\n", - " -2.67613001e-04, 1.43275777e-02, -1.54256574e-04, -6.78219318e-05,\n", - " 6.85268009e-05, 7.37045303e-04]),\n", - " array([-1.86704904e-01, 4.40711705e+00, -1.86909369e-01, 4.40691259e+00,\n", - " -2.63542459e-04, 1.50387627e-02, -1.61975704e-04, -6.79604049e-05,\n", - " 6.81896705e-05, 7.38812194e-04]),\n", - " array([-4.41704357e-02, 4.74818321e+00, -4.44211065e-02, 4.74793254e+00,\n", - " -2.59402467e-04, 1.56865879e-02, -1.69136985e-04, -6.81015725e-05,\n", - " 6.78548618e-05, 7.40469880e-04]),\n", - " array([ 9.72394303e-02, 5.06897337e+00, 9.69472612e-02, 5.06868120e+00,\n", - " -2.55195867e-04, 1.62717350e-02, -1.75735716e-04, -6.82457338e-05,\n", - " 6.75222133e-05, 7.42013739e-04]),\n", - " array([ 2.37427814e-01, 5.36963866e+00, 2.37099724e-01, 5.36931057e+00,\n", - " -2.50925385e-04, 1.67950212e-02, -1.81768579e-04, -6.83931763e-05,\n", - " 6.71915718e-05, 7.43439598e-04]),\n", - " array([ 3.76316618e-01, 5.65038715e+00, 3.75959123e-01, 5.65002966e+00,\n", - " -2.46593609e-04, 1.72573886e-02, -1.87233569e-04, -6.85441760e-05,\n", - " 6.68627927e-05, 7.44743727e-04]),\n", - " array([ 5.13846544e-01, 5.91148048e+00, 5.13467175e-01, 5.91110111e+00,\n", - " -2.42202965e-04, 1.76598925e-02, -1.92129918e-04, -6.86989964e-05,\n", - " 6.65357411e-05, 7.45922830e-04]),\n", - " array([ 6.49977062e-01, 6.15323050e+00, 6.49584436e-01, 6.15283787e+00,\n", - " -2.37755705e-04, 1.80036911e-02, -1.96458018e-04, -6.88578887e-05,\n", - " 6.62102914e-05, 7.46974042e-04]),\n", - " array([ 7.84686329e-01, 6.37599579e+00, 7.84290225e-01, 6.37559969e+00,\n", - " -2.33253887e-04, 1.82900343e-02, -2.00219339e-04, -6.90210914e-05,\n", - " 6.58863284e-05, 7.47894913e-04]),\n", - " array([ 9.17971052e-01, 6.58017822e+00, 9.17582488e-01, 6.57978966e+00,\n", - " -2.28699369e-04, 1.85202523e-02, -2.03416347e-04, -6.91888302e-05,\n", - " 6.55637468e-05, 7.48683408e-04]),\n", - " array([ 1.04984631e+00, 6.76621939e+00, 1.04947761e+00, 6.76585068e+00,\n", - " -2.24093799e-04, 1.86957452e-02, -2.06052415e-04, -6.93613182e-05,\n", - " 6.52424518e-05, 7.49337890e-04]),\n", - " array([ 1.18034532e+00, 6.93459717e+00, 1.18001015e+00, 6.93426200e+00,\n", - " -2.19438614e-04, 1.88179721e-02, -2.08131739e-04, -6.95387556e-05,\n", - " 6.49223586e-05, 7.49857114e-04]),\n", - " array([ 1.30951914e+00, 7.08582220e+00, 1.30923260e+00, 7.08553565e+00,\n", - " -2.14735039e-04, 1.88884407e-02, -2.09659252e-04, -6.97213299e-05,\n", - " 6.46033925e-05, 7.50240215e-04]),\n", - " array([ 1.43743634e+00, 7.22043439e+00, 1.43721495e+00, 7.22021301e+00,\n", - " -2.09984090e-04, 1.89086969e-02, -2.10640527e-04, -6.99092158e-05,\n", - " 6.42854887e-05, 7.50486698e-04]),\n", - " array([ 1.56418259e+00, 7.33899958e+00, 1.56404434e+00, 7.33886133e+00,\n", - " -2.05186590e-04, 1.88803152e-02, -2.11081697e-04, -7.01025755e-05,\n", - " 6.39685921e-05, 7.50596425e-04]),\n", - " array([ 1.68986024e+00, 7.44210610e+00, 1.68982454e+00, 7.44207040e+00,\n", - " -2.00343175e-04, 1.88048887e-02, -2.10989362e-04, -7.03015591e-05,\n", - " 6.36526567e-05, 7.50569608e-04]),\n", - " array([ 1.81458777e+00, 7.53036154e+00, 1.81467542e+00, 7.53044919e+00,\n", - " -1.95454317e-04, 1.86840205e-02, -2.10370503e-04, -7.05063042e-05,\n", - " 6.33376455e-05, 7.50406790e-04]),\n", - " array([ 1.93849928e+00, 7.60438950e+00, 1.93873236e+00, 7.60462258e+00,\n", - " -1.90520346e-04, 1.85193149e-02, -2.09232390e-04, -7.07169364e-05,\n", - " 6.30235300e-05, 7.50108843e-04]),\n", - " array([ 2.06174380e+00, 7.66482648e+00, 2.06214557e+00, 7.66522825e+00,\n", - " -1.85541478e-04, 1.83123687e-02, -2.07582524e-04, -7.09335696e-05,\n", - " 6.27102895e-05, 7.49676948e-04]),\n", - " array([ 2.18448466e+00, 7.71231888e+00, 2.18507934e+00, 7.71291355e+00,\n", - " -1.80517852e-04, 1.80647646e-02, -2.05428486e-04, -7.11563058e-05,\n", - " 6.23979110e-05, 7.49112588e-04]),\n", - " array([ 2.30689872e+00, 7.74752008e+00, 2.30771121e+00, 7.74833256e+00,\n", - " -1.75449561e-04, 1.77780631e-02, -2.02777989e-04, -7.13852358e-05,\n", - " 6.20863884e-05, 7.48417537e-04]),\n", - " array([ 2.42917552e+00, 7.77108762e+00, 2.43023113e+00, 7.77214324e+00,\n", - " -1.70336711e-04, 1.74537967e-02, -1.99638569e-04, -7.16204388e-05,\n", - " 6.17757222e-05, 7.47593847e-04]),\n", - " array([ 2.55151645e+00, 7.78368062e+00, 2.55284044e+00, 7.78500462e+00,\n", - " -1.65179450e-04, 1.70934639e-02, -1.96017866e-04, -7.18619831e-05,\n", - " 6.14659188e-05, 7.46643838e-04]),\n", - " array([ 2.67413375e+00, 7.78595714e+00, 2.67575085e+00, 7.78757424e+00,\n", - " -1.59978045e-04, 1.66985238e-02, -1.91923192e-04, -7.21099256e-05,\n", - " 6.11569898e-05, 7.45570088e-04]),\n", - " array([ 2.79724951e+00, 7.77857184e+00, 2.79918329e+00, 7.78050562e+00,\n", - " -1.54732930e-04, 1.62703921e-02, -1.87361672e-04, -7.23643121e-05,\n", - " 6.08489521e-05, 7.44375421e-04]),\n", - " array([ 2.92109455e+00, 7.76217370e+00, 2.92336671e+00, 7.76444586e+00,\n", - " -1.49444778e-04, 1.58104368e-02, -1.82340132e-04, -7.26251775e-05,\n", - " 6.05418267e-05, 7.43062899e-04]),\n", - " array([ 3.04590720e+00, 7.73740390e+00, 3.04853675e+00, 7.74003345e+00,\n", - " -1.44114571e-04, 1.53199756e-02, -1.76865047e-04, -7.28925453e-05,\n", - " 6.02356387e-05, 7.41635812e-04]),\n", - " array([ 3.17193211e+00, 7.70489386e+00, 3.17493435e+00, 7.70789610e+00,\n", - " -1.38743676e-04, 1.48002731e-02, -1.70942492e-04, -7.31664276e-05,\n", - " 5.99304165e-05, 7.40097667e-04]),\n", - " array([ 3.29941880e+00, 7.66526335e+00, 3.30280428e+00, 7.66864884e+00,\n", - " -1.33333927e-04, 1.42525396e-02, -1.64578082e-04, -7.34468249e-05,\n", - " 5.96261916e-05, 7.38452184e-04]),\n", - " array([ 3.42862031e+00, 7.61911888e+00, 3.43239352e+00, 7.62289208e+00,\n", - " -1.27887709e-04, 1.36779304e-02, -1.57776972e-04, -7.37337255e-05,\n", - " 5.93229978e-05, 7.36703283e-04]),\n", - " array([ 3.55979160e+00, 7.56705207e+00, 3.56394956e+00, 7.57121003e+00,\n", - " -1.22408038e-04, 1.30775453e-02, -1.50543831e-04, -7.40271053e-05,\n", - " 5.90208711e-05, 7.34855076e-04]),\n", - " array([ 3.69318791e+00, 7.50963828e+00, 3.69771870e+00, 7.51416907e+00,\n", - " -1.16898663e-04, 1.24524297e-02, -1.42882711e-04, -7.43269267e-05,\n", - " 5.87198493e-05, 7.32911867e-04]),\n", - " array([ 3.82906311e+00, 7.44743535e+00, 3.83394408e+00, 7.45231632e+00,\n", - " -1.11364137e-04, 1.18035759e-02, -1.34797165e-04, -7.46331384e-05,\n", - " 5.84199715e-05, 7.30878135e-04]),\n", - " array([ 3.96766777e+00, 7.38098243e+00, 3.97286375e+00, 7.38617841e+00,\n", - " -1.05809915e-04, 1.11319256e-02, -1.26290169e-04, -7.49456738e-05,\n", - " 5.81212775e-05, 7.28758536e-04]),\n", - " array([ 4.10924729e+00, 7.31079896e+00, 4.11470861e+00, 7.31626029e+00,\n", - " -1.00242428e-04, 1.04383728e-02, -1.17364139e-04, -7.52644504e-05,\n", - " 5.78238081e-05, 7.26557892e-04]),\n", - " array([ 4.25403981e+00, 7.23738385e+00, 4.25970021e+00, 7.24304424e+00,\n", - " -9.46691608e-05, 9.72376735e-03, -1.08020940e-04, -7.55893678e-05,\n", - " 5.75276041e-05, 7.24281188e-04]),\n", - " array([ 4.40227411e+00, 7.16121460e+00, 4.40804851e+00, 7.16698900e+00,\n", - " -8.90987156e-05, 8.98892012e-03, -9.82618985e-05, -7.59203069e-05,\n", - " 5.72327064e-05, 7.21933566e-04]),\n", - " array([ 4.55416726e+00, 7.08274674e+00, 4.55994953e+00, 7.08852901e+00,\n", - " -8.35408657e-05, 8.23460770e-03, -8.80878301e-05, -7.62571275e-05,\n", - " 5.69391557e-05, 7.19520321e-04]),\n", - " array([ 4.70992230e+00, 7.00241319e+00, 4.71558296e+00, 7.00807385e+00,\n", - " -7.80065898e-05, 7.46157859e-03, -7.74990793e-05, -7.65996663e-05,\n", - " 5.66469918e-05, 7.17046893e-04]),\n", - " array([ 4.86972571e+00, 6.92062380e+00, 4.87510963e+00, 6.92600772e+00,\n", - " -7.25080873e-05, 6.67055987e-03, -6.64955657e-05, -7.69477349e-05,\n", - " 5.63562538e-05, 7.14518870e-04]),\n", - " array([ 5.03374477e+00, 6.83776498e+00, 5.03866895e+00, 6.84268916e+00,\n", - " -6.70587665e-05, 5.86226447e-03, -5.50768433e-05, -7.73011168e-05,\n", - " 5.60669796e-05, 7.11941975e-04]),\n", - " array([ 5.20212484e+00, 6.75419935e+00, 5.20637630e+00, 6.75845081e+00,\n", - " -6.16732031e-05, 5.03739913e-03, -4.32421694e-05, -7.76595651e-05,\n", - " 5.57792056e-05, 7.09322069e-04]),\n", - " array([ 5.37498645e+00, 6.67026548e+00, 5.37832036e+00, 6.67359939e+00,\n", - " -5.63670617e-05, 4.19667293e-03, -3.09905849e-05, -7.80227986e-05,\n", - " 5.54929665e-05, 7.06665145e-04]),\n", - " array([ 5.55242239e+00, 6.58627768e+00, 5.55456045e+00, 6.58841574e+00,\n", - " -5.11569740e-05, 3.34080637e-03, -1.83210088e-05, -7.83904992e-05,\n", - " 5.52082949e-05, 7.03977320e-04]),\n", - " array([ 5.73449450e+00, 6.50252578e+00, 5.73512376e+00, 6.50315504e+00,\n", - " -4.60603686e-05, 2.47054098e-03, -5.23233961e-06, -7.87623078e-05,\n", - " 5.49252209e-05, 7.01264836e-04]),\n", - " array([ 5.92010491e+00, 6.41895085e+00, 5.91949346e+00, 6.41833940e+00,\n", - " -4.09104269e-05, 1.58927568e-03, 8.24672410e-06, -7.91355569e-05,\n", - " 5.46485251e-05, 6.98535708e-04]),\n", - " array([ 6.10913751e+00, 6.33566735e+00, 6.10752649e+00, 6.33405634e+00,\n", - " -3.57213102e-05, 6.97760569e-04, 2.21178465e-05, -7.95098023e-05,\n", - " 5.43782249e-05, 6.95796124e-04]),\n", - " array([ 6.30144235e+00, 6.25275692e+00, 6.29904662e+00, 6.25036120e+00,\n", - " -3.05069831e-05, -2.03251009e-04, 3.63827133e-05, -7.98845984e-05,\n", - " 5.41143345e-05, 6.93052355e-04]),\n", - " array([ 6.49683444e+00, 6.17026988e+00, 6.49384362e+00, 6.16727906e+00,\n", - " -2.52810741e-05, -1.11299359e-03, 5.10430004e-05, -8.02594961e-05,\n", - " 5.38568637e-05, 6.90310753e-04]),\n", - " array([ 6.69509274e+00, 6.08822693e+00, 6.69167244e+00, 6.08480662e+00,\n", - " -2.00567700e-05, -2.03068073e-03, 6.61003348e-05, -8.06340414e-05,\n", - " 5.36058190e-05, 6.87577737e-04]),\n", - " array([ 6.89595919e+00, 6.00662075e+00, 6.89225244e+00, 6.00291400e+00,\n", - " -1.48467444e-05, -2.95549641e-03, 8.15562426e-05, -8.10077738e-05,\n", - " 5.33612025e-05, 6.84859795e-04]),\n", - " array([ 7.09913784e+00, 5.92541782e+00, 7.09526663e+00, 5.92154661e+00,\n", - " -9.66311090e-06, -3.88658653e-03, 9.74120881e-05, -8.13802247e-05,\n", - " 5.31230123e-05, 6.82163475e-04]),\n", - " array([ 7.30429415e+00, 5.84456009e+00, 7.30036106e+00, 5.84062700e+00,\n", - " -4.51739995e-06, -4.82305084e-03, 1.13669005e-04, -8.17509157e-05,\n", - " 5.28912424e-05, 6.79495377e-04]),\n", - " array([ 7.51105438e+00, 5.76396677e+00, 7.50714417e+00, 5.76005657e+00,\n", - " 5.79445063e-07, -5.76393510e-03, 1.30327822e-04, -8.21193581e-05,\n", - " 5.26658824e-05, 6.76862146e-04]),\n", - " array([ 7.71900506e+00, 5.68353613e+00, 7.71518636e+00, 5.67971743e+00,\n", - " 5.61705620e-06, -6.70822368e-03, 1.47388975e-04, -8.24850509e-05,\n", - " 5.24469179e-05, 6.74270466e-04]),\n", - " array([ 7.92769268e+00, 5.60314720e+00, 7.92401957e+00, 5.59947409e+00,\n", - " 1.05856165e-05, -7.65483261e-03, 1.64852425e-04, -8.28474806e-05,\n", - " 5.22343298e-05, 6.71727051e-04]),\n", - " array([ 8.13662346e+00, 5.52266161e+00, 8.13313701e+00, 5.51917516e+00,\n", - " 1.54758254e-05, -8.60260305e-03, 1.82717562e-04, -8.32061198e-05,\n", - " 5.20280949e-05, 6.69238638e-04]),\n", - " array([ 8.34526327e+00, 5.44192527e+00, 8.34199307e+00, 5.43865507e+00,\n", - " 2.02788573e-05, -9.55029542e-03, 2.00983111e-04, -8.35604269e-05,\n", - " 5.18281858e-05, 6.66811976e-04]),\n", - " array([ 8.55303771e+00, 5.36077010e+00, 8.55000326e+00, 5.35773565e+00,\n", - " 2.49863143e-05, -1.04965840e-02, 2.19647034e-04, -8.39098453e-05,\n", - " 5.16345706e-05, 6.64453819e-04]),\n", - " array([ 8.75933241e+00, 5.27901576e+00, 8.75654444e+00, 5.27622779e+00,\n", - " 2.95901757e-05, -1.14400520e-02, 2.38706435e-04, -8.42538036e-05,\n", - " 5.14472135e-05, 6.62170912e-04]),\n", - " array([ 8.96349337e+00, 5.19647128e+00, 8.96095508e+00, 5.19393299e+00,\n", - " 3.40827466e-05, -1.23791878e-02, 2.58157456e-04, -8.45917147e-05,\n", - " 5.12660744e-05, 6.59969984e-04]),\n", - " array([ 9.16482759e+00, 5.11293672e+00, 9.16253578e+00, 5.11064490e+00,\n", - " 3.84566061e-05, -1.33123813e-02, 2.77995182e-04, -8.49229766e-05,\n", - " 5.10911097e-05, 6.57857737e-04]),\n", - " array([ 9.36260388e+00, 5.02820474e+00, 9.36054995e+00, 5.02615081e+00,\n", - " 4.27045562e-05, -1.42379212e-02, 2.98213543e-04, -8.52469719e-05,\n", - " 5.09222719e-05, 6.55840830e-04]),\n", - " array([ 9.55605373e+00, 4.94206218e+00, 9.55422467e+00, 4.94023311e+00,\n", - " 4.68195748e-05, -1.51539931e-02, 3.18805222e-04, -8.55630685e-05,\n", - " 5.07595105e-05, 6.53925870e-04]),\n", - " array([ 9.74437256e+00, 4.85429156e+00, 9.74275175e+00, 4.85267075e+00,\n", - " 5.07947704e-05, -1.60586782e-02, 3.39761564e-04, -8.58706204e-05,\n", - " 5.06027720e-05, 6.52119397e-04]),\n", - " array([ 9.92672104e+00, 4.76467260e+00, 9.92528901e+00, 4.76324057e+00,\n", - " 5.46233417e-05, -1.69499531e-02, 3.61072464e-04, -8.61689676e-05,\n", - " 5.04520004e-05, 6.50427869e-04]),\n", - " array([ 1.01022266e+01, 4.67298362e+00, 1.01009618e+01, 4.67171873e+00,\n", - " 5.82985418e-05, -1.78256900e-02, 3.82726272e-04, -8.64574378e-05,\n", - " 5.03071377e-05, 6.48857649e-04]),\n", - " array([ 1.02699854e+01, 4.57900293e+00, 1.02688645e+01, 4.57788198e+00,\n", - " 6.18136539e-05, -1.86836579e-02, 4.04709947e-04, -8.67353470e-05,\n", - " 5.01681246e-05, 6.47414991e-04]),\n", - " array([ 1.04290640e+01, 4.48251023e+00, 1.04280627e+01, 4.48150895e+00,\n", - " 6.51619578e-05, -1.95215249e-02, 4.27008558e-04, -8.70020005e-05,\n", - " 5.00349011e-05, 6.46106017e-04]),\n", - " array([ 1.05785019e+01, 4.38328791e+00, 1.05775954e+01, 4.38238138e+00,\n", - " 6.83367198e-05, -2.03368608e-02, 4.49605522e-04, -8.72566946e-05,\n", - " 4.99074071e-05, 6.44936708e-04]),\n", - " array([ 1.07173137e+01, 4.28112231e+00, 1.07164768e+01, 4.28028537e+00,\n", - " 7.13311796e-05, -2.11271411e-02, 4.72482466e-04, -8.74987179e-05,\n", - " 4.97855836e-05, 6.43912881e-04]),\n", - " array([ 1.08444919e+01, 4.17580496e+00, 1.08436995e+01, 4.17501257e+00,\n", - " 7.41385510e-05, -2.18897516e-02, 4.95619237e-04, -8.77273531e-05,\n", - " 4.96693730e-05, 6.43040175e-04]),\n", - " array([ 1.09590098e+01, 4.06713378e+00, 1.09582373e+01, 4.06636123e+00,\n", - " 7.67520112e-05, -2.26219935e-02, 5.18993606e-04, -8.79418784e-05,\n", - " 4.95587206e-05, 6.42324028e-04]),\n", - " array([ 1.10598244e+01, 3.95491423e+00, 1.10590476e+01, 3.95413743e+00,\n", - " 7.91647281e-05, -2.33210904e-02, 5.42581554e-04, -8.81415697e-05,\n", - " 4.94535755e-05, 6.41769659e-04]),\n", - " array([ 1.11458799e+01, 3.83896039e+00, 1.11450755e+01, 3.83815606e+00,\n", - " 8.13698700e-05, -2.39841947e-02, 5.66357083e-04, -8.83257027e-05,\n", - " 4.93538915e-05, 6.41382048e-04]),\n", - " array([ 1.12161109e+01, 3.71909609e+00, 1.12152568e+01, 3.71824195e+00,\n", - " 8.33606308e-05, -2.46083961e-02, 5.90292207e-04, -8.84935548e-05,\n", - " 4.92596285e-05, 6.41165918e-04]),\n", - " array([ 1.12694467e+01, 3.59515590e+00, 1.12685215e+01, 3.59423077e+00,\n", - " 8.51302596e-05, -2.51907304e-02, 6.14356920e-04, -8.86444076e-05,\n", - " 4.91707538e-05, 6.41125711e-04]),\n", - " array([ 1.13048145e+01, 3.46698612e+00, 1.13037985e+01, 3.46597009e+00,\n", - " 8.66721013e-05, -2.57281885e-02, 6.38519217e-04, -8.87775494e-05,\n", - " 4.90872431e-05, 6.41265567e-04]),\n", - " array([ 1.13211441e+01, 3.33444579e+00, 1.13200186e+01, 3.33332028e+00,\n", - " 8.79796399e-05, -2.62177275e-02, 6.62745086e-04, -8.88922775e-05,\n", - " 4.90090819e-05, 6.41589303e-04]),\n", - " array([ 1.13173720e+01, 3.19740752e+00, 1.13161198e+01, 3.19615541e+00,\n", - " 8.90465497e-05, -2.66562814e-02, 6.86998522e-04, -8.89879010e-05,\n", - " 4.89362669e-05, 6.42100392e-04]),\n", - " array([ 1.12924456e+01, 3.05575845e+00, 1.12910513e+01, 3.05436412e+00,\n", - " 8.98667528e-05, -2.70407728e-02, 7.11241551e-04, -8.90637438e-05,\n", - " 4.88688073e-05, 6.42801941e-04]),\n", - " array([ 1.12453284e+01, 2.90940104e+00, 1.12437778e+01, 2.90785046e+00,\n", - " 9.04344806e-05, -2.73681255e-02, 7.35434255e-04, -8.91191469e-05,\n", - " 4.88067263e-05, 6.43696666e-04]),\n", - " array([ 1.11750043e+01, 2.75825387e+00, 1.11732851e+01, 2.75653466e+00,\n", - " 9.07443423e-05, -2.76352776e-02, 7.59534820e-04, -8.91534718e-05,\n", - " 4.87500618e-05, 6.44786874e-04]),\n", - " array([ 1.10804828e+01, 2.60225242e+00, 1.10785842e+01, 2.60035390e+00,\n", - " 9.07913969e-05, -2.78391951e-02, 7.83499578e-04, -8.91661037e-05,\n", - " 4.86988685e-05, 6.46074439e-04]),\n", - " array([ 1.09608038e+01, 2.44134978e+00, 1.09587171e+01, 2.43926302e+00,\n", - " 9.05712298e-05, -2.79768859e-02, 8.07283073e-04, -8.91564541e-05,\n", - " 4.86532184e-05, 6.47560780e-04]),\n", - " array([ 1.08150433e+01, 2.27551732e+00, 1.08127612e+01, 2.27323520e+00,\n", - " 9.00800327e-05, -2.80454147e-02, 8.30838124e-04, -8.91239645e-05,\n", - " 4.86132022e-05, 6.49246843e-04]),\n", - " array([ 1.06423177e+01, 2.10474532e+00, 1.06398350e+01, 2.10226259e+00,\n", - " 8.93146868e-05, -2.80419180e-02, 8.54115904e-04, -8.90681096e-05,\n", - " 4.85789305e-05, 6.51133073e-04]),\n", - " array([ 1.04417900e+01, 1.92904358e+00, 1.04391033e+01, 1.92635687e+00,\n", - " 8.82728483e-05, -2.79636192e-02, 8.77066032e-04, -8.89884006e-05,\n", - " 4.85505343e-05, 6.53219401e-04]),\n", - " array([ 1.02126746e+01, 1.74844195e+00, 1.02097825e+01, 1.74554986e+00,\n", - " 8.69530347e-05, -2.78078447e-02, 8.99636661e-04, -8.88843884e-05,\n", - " 4.85281659e-05, 6.55505220e-04]),\n", - " array([ 9.95424292e+00, 1.56299084e+00, 9.95114603e+00, 1.55989395e+00,\n", - " 8.53547128e-05, -2.75720395e-02, 9.21774589e-04, -8.87556677e-05,\n", - " 4.85119996e-05, 6.57989367e-04]),\n", - " array([ 9.66582854e+00, 1.37276167e+00, 9.66252945e+00, 1.36946259e+00,\n", - " 8.34783861e-05, -2.72537833e-02, 9.43425368e-04, -8.86018798e-05,\n", - " 4.85022320e-05, 6.60670105e-04]),\n", - " array([ 9.34683263e+00, 1.17784726e+00, 9.34333604e+00, 1.17435067e+00,\n", - " 8.13256811e-05, -2.68508067e-02, 9.64533429e-04, -8.84227167e-05,\n", - " 4.84990821e-05, 6.63545105e-04]),\n", - " array([ 8.99672921e+00, 9.78362201e-01, 8.99304190e+00, 9.74674883e-01,\n", - " 7.88994325e-05, -2.63610069e-02, 9.85042208e-04, -8.82179243e-05,\n", - " 4.85027914e-05, 6.66611431e-04]),\n", - " array([ 8.61507029e+00, 7.74443157e-01, 8.61120115e+00, 7.70574017e-01,\n", - " 7.62037642e-05, -2.57824642e-02, 1.00489429e-03, -8.79873060e-05,\n", - " 4.85136237e-05, 6.69865525e-04]),\n", - " array([ 8.20149092e+00, 5.66249089e-01, 8.19745101e+00, 5.62209174e-01,\n", - " 7.32441683e-05, -2.51134573e-02, 1.02403152e-03, -8.77307264e-05,\n", - " 4.85318641e-05, 6.73303189e-04]),\n", - " array([ 7.75571415e+00, 3.53961454e-01, 7.75151666e+00, 3.49763968e-01,\n", - " 7.00275782e-05, -2.43524792e-02, 1.04239522e-03, -8.74481147e-05,\n", - " 4.85578189e-05, 6.76919582e-04]),\n", - " array([ 7.27755574e+00, 1.37784332e-01, 7.27321604e+00, 1.33444631e-01,\n", - " 6.65624360e-05, -2.34982519e-02, 1.05992628e-03, -8.71394682e-05,\n", - " 4.85918139e-05, 6.80709199e-04]),\n", - " array([ 6.76692874e+00, -8.20555086e-02, 6.76246432e+00, -8.65199261e-02,\n", - " 6.28587540e-05, -2.25497415e-02, 1.07656533e-03, -8.68048557e-05,\n", - " 4.86341932e-05, 6.84665870e-04]),\n", - " array([ 6.22384779e+00, -3.05308612e-01, 6.21927828e+00, -3.09878128e-01,\n", - " 5.89281679e-05, -2.15061722e-02, 1.09225293e-03, -8.64444209e-05,\n", - " 4.86853177e-05, 6.88782748e-04]),\n", - " array([ 5.64843323e+00, -5.31702898e-01, 5.64378032e+00, -5.36355811e-01,\n", - " 5.47839811e-05, -2.03670398e-02, 1.10692972e-03, -8.60583855e-05,\n", - " 4.87455631e-05, 6.93052305e-04]),\n", - " array([ 5.04091481e+00, -7.60943792e-01, 5.03620223e+00, -7.65656373e-01,\n", - " 5.04412008e-05, -1.91321246e-02, 1.12053660e-03, -8.56470524e-05,\n", - " 4.88153171e-05, 6.97466328e-04]),\n", - " array([ 4.40163524e+00, -9.92714434e-01, 4.39688868e+00, -9.97460993e-01,\n", - " 4.59165620e-05, -1.78015035e-02, 1.13301489e-03, -8.52108086e-05,\n", - " 4.88949777e-05, 7.02015921e-04]),\n", - " array([ 3.73105325e+00, -1.22667595e+00, 3.72630028e+00, -1.23142892e+00,\n", - " 4.12285414e-05, -1.63755608e-02, 1.14430653e-03, -8.47501284e-05,\n", - " 4.89849496e-05, 7.06691499e-04]),\n", - " array([ 3.02974638e+00, -1.46246780e+00, 3.02501634e+00, -1.46719785e+00,\n", - " 3.63973591e-05, -1.48549989e-02, 1.15435423e-03, -8.42655755e-05,\n", - " 4.90856415e-05, 7.11482796e-04]),\n", - " array([ 2.29841334e+00, -1.69970822e+00, 2.29373720e+00, -1.70438436e+00,\n", - " 3.14449672e-05, -1.32408472e-02, 1.16310165e-03, -8.37578055e-05,\n", - " 4.91974627e-05, 7.16378871e-04]),\n", - " array([ 1.53787595e+00, -1.93799470e+00, 1.53328622e+00, -1.94258443e+00,\n", - " 2.63950258e-05, -1.15344701e-02, 1.17049358e-03, -8.32275687e-05,\n", - " 4.93208194e-05, 7.21368109e-04]),\n", - " array([ 7.49080637e-01, -2.17690460e+00, 7.44611162e-01, -2.18137407e+00,\n", - " 2.12728645e-05, -9.73757382e-03, 1.17647613e-03, -8.26757112e-05,\n", - " 4.94561110e-05, 7.26438240e-04]),\n", - " array([-6.69004925e-02, -2.41599577e+00, -7.12146980e-02, -2.42030997e+00,\n", - " 1.61054303e-05, -7.85221220e-03, 1.18099685e-03, -8.21031771e-05,\n", - " 4.96037262e-05, 7.31576343e-04]),\n", - " array([-9.08869126e-01, -2.65480733e+00, -9.12992072e-01, -2.65893028e+00,\n", - " 1.09212206e-05, -5.88079081e-03, 1.18400495e-03, -8.15110098e-05,\n", - " 4.97640391e-05, 7.36768865e-04]),\n", - " array([-1.77550067e+00, -2.89286049e+00, -1.77939560e+00, -2.89675543e+00,\n", - " 5.75020205e-06, -3.82606995e-03, 1.18545143e-03, -8.09003529e-05,\n", - " 4.99374046e-05, 7.42001639e-04]),\n", - " array([-2.66534467e+00, -3.12965943e+00, -2.66897432e+00, -3.13328908e+00,\n", - " 6.23714389e-07, -1.69116614e-03, 1.18528924e-03, -8.02724508e-05,\n", - " 5.01241547e-05, 7.47259903e-04]),\n", - " array([-3.57682585e+00, -3.36469230e+00, -3.58015266e+00, -3.36801911e+00,\n", - " -4.42564038e-06, 5.20447824e-04, 1.18347343e-03, -7.96286494e-05,\n", - " 5.03245942e-05, 7.52528320e-04]),\n", - " array([-4.50824554e+00, -3.59743230e+00, -4.51123193e+00, -3.60041869e+00,\n", - " -9.36412287e-06, 2.80494427e-03, 1.17996131e-03, -7.89703956e-05,\n", - " 5.05389964e-05, 7.57791007e-04]),\n", - " array([-5.45778377e+00, -3.82733877e+00, -5.46039243e+00, -3.82994742e+00,\n", - " -1.41569953e-05, 5.15814364e-03, 1.17471254e-03, -7.82992369e-05,\n", - " 5.07675994e-05, 7.63031561e-04]),\n", - " array([-6.42350186e+00, -4.05385846e+00, -6.42569601e+00, -4.05605261e+00,\n", - " -1.87686743e-05, 7.57551893e-03, 1.16768931e-03, -7.76168207e-05,\n", - " 5.10106020e-05, 7.68233086e-04]),\n", - " array([-7.40334551e+00, -4.27642678e+00, -7.40508924e+00, -4.27817050e+00,\n", - " -2.31628958e-05, 1.00522018e-02, 1.15885645e-03, -7.69248925e-05,\n", - " 5.12681602e-05, 7.73378231e-04]),\n", - " array([-8.39514854e+00, -4.49446917e+00, -8.39640707e+00, -4.49572769e+00,\n", - " -2.73028935e-05, 1.25829899e-02, 1.14818149e-03, -7.62252945e-05,\n", - " 5.15403840e-05, 7.78449222e-04]),\n", - " array([-9.39663707e+00, -4.70740252e+00, -9.39737707e+00, -4.70814252e+00,\n", - " -3.11515868e-05, 1.51623564e-02, 1.13563485e-03, -7.55199626e-05,\n", - " 5.18273338e-05, 7.83427899e-04]),\n", - " array([-1.04054343e+01, -4.91463667e+00, -1.04056242e+01, -4.91482660e+00,\n", - " -3.46717808e-05, 1.77844604e-02, 1.12118984e-03, -7.48109245e-05,\n", - " 5.21290187e-05, 7.88295758e-04]),\n", - " array([-1.14190656e+01, -5.11557593e+00, -1.14186760e+01, -5.11518631e+00,\n", - " -3.78263744e-05, 2.04431591e-02, 1.10482281e-03, -7.41002952e-05,\n", - " 5.24453933e-05, 7.93033988e-04]),\n", - " array([-1.24349647e+01, -5.30962065e+00, -1.24339684e+01, -5.30862441e+00,\n", - " -4.05785769e-05, 2.31320213e-02, 1.08651319e-03, -7.33902742e-05,\n", - " 5.27763566e-05, 7.97623523e-04]),\n", - " array([-1.34504794e+01, -5.49616895e+00, -1.34488521e+01, -5.49454170e+00,\n", - " -4.28921310e-05, 2.58443431e-02, 1.06624358e-03, -7.26831404e-05,\n", - " 5.31217504e-05, 8.02045081e-04]),\n", - " array([-1.44628787e+01, -5.67461828e+00, -1.44605991e+01, -5.67233864e+00,\n", - " -4.47315417e-05, 2.85731636e-02, 1.04399978e-03, -7.19812473e-05,\n", - " 5.34813589e-05, 8.06279215e-04]),\n", - " array([-1.54693600e+01, -5.84436724e+00, -1.54664099e+01, -5.84141710e+00,\n", - " -4.60623087e-05, 3.13112835e-02, 1.01977087e-03, -7.12870178e-05,\n", - " 5.38549084e-05, 8.10306365e-04]),\n", - " array([-1.64670564e+01, -6.00481728e+00, -1.64634213e+01, -6.00118208e+00,\n", - " -4.68511616e-05, 3.40512839e-02, 9.93549191e-04, -7.06029380e-05,\n", - " 5.42420679e-05, 8.14106905e-04]),\n", - " array([-1.74530451e+01, -6.15537445e+00, -1.74487141e+01, -6.15104345e+00,\n", - " -4.70662954e-05, 3.67855470e-02, 9.65330450e-04, -6.99315506e-05,\n", - " 5.46424503e-05, 8.17661202e-04]),\n", - " array([-1.84243553e+01, -6.29545121e+00, -1.84193218e+01, -6.29041771e+00,\n", - " -4.66776059e-05, 3.95062775e-02, 9.35113686e-04, -6.92754485e-05,\n", - " 5.50556142e-05, 8.20949666e-04]),\n", - " array([-1.93779776e+01, -6.42446822e+00, -1.93722392e+01, -6.41872980e+00,\n", - " -4.56569222e-05, 4.22055254e-02, 9.02901309e-04, -6.86372663e-05,\n", - " 5.54810666e-05, 8.23952808e-04]),\n", - " array([-2.03108725e+01, -6.54185613e+00, -2.03044312e+01, -6.53541482e+00,\n", - " -4.39782355e-05, 4.48752099e-02, 8.68699100e-04, -6.80196733e-05,\n", - " 5.59182654e-05, 8.26651298e-04]),\n", - " array([-2.12199801e+01, -6.64705734e+00, -2.12128425e+01, -6.63991980e+00,\n", - " -4.16179216e-05, 4.75071442e-02, 8.32516212e-04, -6.74253644e-05,\n", - " 5.63666241e-05, 8.29026019e-04]),\n", - " array([-2.21022294e+01, -6.73952782e+00, -2.20944070e+01, -6.73170547e+00,\n", - " -3.85549565e-05, 5.00930610e-02, 7.94365165e-04, -6.68570514e-05,\n", - " 5.68255157e-05, 8.31058133e-04]),\n", - " array([-2.29545485e+01, -6.81873881e+00, -2.29460577e+01, -6.81024798e+00,\n", - " -3.47711221e-05, 5.26246391e-02, 7.54261832e-04, -6.63174540e-05,\n", - " 5.72942779e-05, 8.32729133e-04]),\n", - " array([-2.37738746e+01, -6.88417863e+00, -2.37647365e+01, -6.87504057e+00,\n", - " -3.02512010e-05, 5.50935302e-02, 7.12225417e-04, -6.58092894e-05,\n", - " 5.77722186e-05, 8.34020908e-04]),\n", - " array([-2.45571636e+01, -6.93535429e+00, -2.45474046e+01, -6.92559529e+00,\n", - " -2.49831589e-05, 5.74913874e-02, 6.68278429e-04, -6.53352631e-05,\n", - " 5.82586225e-05, 8.34915801e-04]),\n", - " array([-2.53014014e+01, -6.97179324e+00, -2.52910527e+01, -6.96144457e+00,\n", - " -1.89583119e-05, 5.98098926e-02, 6.22446651e-04, -6.48980578e-05,\n", - " 5.87527574e-05, 8.35396667e-04]),\n", - " array([-2.60036133e+01, -6.99304493e+00, -2.59927113e+01, -6.98214286e+00,\n", - " -1.21714781e-05, 6.20407862e-02, 5.74759096e-04, -6.45003233e-05,\n", - " 5.92538815e-05, 8.35446937e-04]),\n", - " array([-2.66608755e+01, -6.99868244e+00, -2.66494612e+01, -6.98726815e+00,\n", - " -4.62111095e-06, 6.41758955e-02, 5.25247966e-04, -6.41446650e-05,\n", - " 5.97612509e-05, 8.35050675e-04]),\n", - " array([-2.72703246e+01, -6.98830396e+00, -2.72584441e+01, -6.97642344e+00,\n", - " 3.69058686e-06, 6.62071644e-02, 4.73948573e-04, -6.38336337e-05,\n", - " 6.02741272e-05, 8.34192636e-04]),\n", - " array([-2.78291689e+01, -6.96153433e+00, -2.78168728e+01, -6.94923822e+00,\n", - " 1.27575699e-05, 6.81266829e-02, 4.20899338e-04, -6.35697136e-05,\n", - " 6.07917861e-05, 8.32858326e-04]),\n", - " array([-2.83346983e+01, -6.91802637e+00, -2.83220418e+01, -6.90536981e+00,\n", - " 2.25698821e-05, 6.99267167e-02, 3.66141611e-04, -6.33553113e-05,\n", - " 6.13135248e-05, 8.31034056e-04]),\n", - " array([-2.87842951e+01, -6.85746232e+00, -2.87713375e+01, -6.84450467e+00,\n", - " 3.31136021e-05, 7.15997366e-02, 3.09719745e-04, -6.31927446e-05,\n", - " 6.18386706e-05, 8.28707001e-04]),\n", - " array([-2.91754440e+01, -6.77955509e+00, -2.91622486e+01, -6.76635971e+00,\n", - " 4.43708316e-05, 7.31384481e-02, 2.51680846e-04, -6.30842312e-05,\n", - " 6.23665893e-05, 8.25865250e-04]),\n", - " array([-2.95057423e+01, -6.68404951e+00, -2.94923762e+01, -6.67068341e+00,\n", - " 5.63196942e-05, 7.45358205e-02, 1.92074761e-04, -6.30318772e-05,\n", - " 6.28966929e-05, 8.22497864e-04]),\n", - " array([-2.97729100e+01, -6.57072346e+00, -2.97594436e+01, -6.55725697e+00,\n", - " 6.89343666e-05, 7.57851155e-02, 1.30953947e-04, -6.30376665e-05,\n", - " 6.34284474e-05, 8.18594920e-04]),\n", - " array([-2.99747995e+01, -6.43938901e+00, -2.99613058e+01, -6.42589539e+00,\n", - " 8.21851368e-05, 7.68799161e-02, 6.83733488e-05, -6.31034497e-05,\n", - " 6.39613805e-05, 8.14147563e-04]),\n", - " array([-3.01094047e+01, -6.28989340e+00, -3.00959597e+01, -6.27644840e+00,\n", - " 9.60384907e-05, 7.78141537e-02, 4.39026466e-06, -6.32309339e-05,\n", - " 6.44950886e-05, 8.09148052e-04]),\n", - " array([-3.01748712e+01, -6.12212003e+00, -3.01615526e+01, -6.10880144e+00,\n", - " 1.10457225e-04, 7.85821359e-02, -6.09358022e-05, -6.34216723e-05,\n", - " 6.50292428e-05, 8.03589804e-04]),\n", - " array([-3.01695042e+01, -5.93598932e+00, -3.01563913e+01, -5.92287644e+00,\n", - " 1.25400589e-04, 7.91785722e-02, -1.27543300e-04, -6.36770545e-05,\n", - " 6.55635955e-05, 7.97467430e-04]),\n", - " array([-3.00917776e+01, -5.73145949e+00, -3.00789507e+01, -5.71863264e+00,\n", - " 1.40824453e-04, 7.95986000e-02, -1.95368796e-04, -6.39982976e-05,\n", - " 6.60979848e-05, 7.90776779e-04]),\n", - " array([-2.99403422e+01, -5.50852735e+00, -2.99278821e+01, -5.49606727e+00,\n", - " 1.56681502e-04, 7.98378087e-02, -2.64347156e-04, -6.43864375e-05,\n", - " 6.66323393e-05, 7.83514969e-04]),\n", - " array([-2.97140332e+01, -5.26722891e+00, -2.97020205e+01, -5.25521618e+00,\n", - " 1.72921456e-04, 7.98922632e-02, -3.34411729e-04, -6.48423209e-05,\n", - " 6.71666810e-05, 7.75680419e-04]),\n", - " array([-2.94118779e+01, -5.00763997e+00, -2.94003923e+01, -4.99615440e+00,\n", - " 1.89491313e-04, 7.97585255e-02, -4.05494544e-04, -6.53665981e-05,\n", - " 6.77011279e-05, 7.67272878e-04]),\n", - " array([-2.90331019e+01, -4.72987659e+00, -2.90222220e+01, -4.71899661e+00,\n", - " 2.06335615e-04, 7.94336758e-02, -4.77526507e-04, -6.59597166e-05,\n", - " 6.82358950e-05, 7.58293448e-04]),\n", - " array([-2.85771362e+01, -4.43409554e+00, -2.85669382e+01, -4.42389754e+00,\n", - " 2.23396732e-04, 7.89153314e-02, -5.50437605e-04, -6.66219155e-05,\n", - " 6.87712947e-05, 7.48744603e-04]),\n", - " array([-2.80436218e+01, -4.12049462e+00, -2.80341795e+01, -4.11105228e+00,\n", - " 2.40615168e-04, 7.82016645e-02, -6.24157113e-04, -6.73532211e-05,\n", - " 6.93077354e-05, 7.38630211e-04]),\n", - " array([-2.74324159e+01, -3.78931286e+00, -2.74237996e+01, -3.78069655e+00,\n", - " 2.57929874e-04, 7.72914173e-02, -6.98613789e-04, -6.81534427e-05,\n", - " 6.98457195e-05, 7.27955541e-04]),\n", - " array([-2.67435952e+01, -3.44083072e+00, -2.67358713e+01, -3.43310678e+00,\n", - " 2.75278589e-04, 7.61839167e-02, -7.73736076e-04, -6.90221706e-05,\n", - " 7.03858394e-05, 7.16727272e-04]),\n", - " array([-2.59774605e+01, -3.07537011e+00, -2.59706907e+01, -3.06860027e+00,\n", - " 2.92598171e-04, 7.48790857e-02, -8.49452292e-04, -6.99587738e-05,\n", - " 7.09287727e-05, 7.04953502e-04]),\n", - " array([-2.51345390e+01, -2.69329435e+00, -2.51287798e+01, -2.68753509e+00,\n", - " 3.09824954e-04, 7.33774532e-02, -9.25690808e-04, -7.09624001e-05,\n", - " 7.14752763e-05, 6.92643742e-04]),\n", - " array([-2.42155869e+01, -2.29500802e+00, -2.42108888e+01, -2.29030995e+00,\n", - " 3.26895101e-04, 7.16801619e-02, -1.00238021e-03, -7.20319762e-05,\n", - " 7.20261786e-05, 6.79808916e-04]),\n", - " array([-2.32215904e+01, -1.88095672e+00, -2.32179977e+01, -1.87736403e+00,\n", - " 3.43744961e-04, 6.97889735e-02, -1.07944945e-03, -7.31662098e-05,\n", - " 7.25823707e-05, 6.66461346e-04]),\n", - " array([-2.21537664e+01, -1.45162668e+00, -2.21513163e+01, -1.44917659e+00,\n", - " 3.60311422e-04, 6.77062713e-02, -1.15682799e-03, -7.43635926e-05,\n", - " 7.31447970e-05, 6.52614747e-04]),\n", - " array([-2.10135622e+01, -1.00754427e+00, -2.10122845e+01, -1.00626658e+00,\n", - " 3.76532272e-04, 6.54350609e-02, -1.23444586e-03, -7.56224039e-05,\n", - " 7.37144437e-05, 6.38284203e-04]),\n", - " array([-1.98026541e+01, -5.49275448e-01, -1.98025707e+01, -5.49192033e-01,\n", - " 3.92346542e-04, 6.29789681e-02, -1.31223382e-03, -7.69407162e-05,\n", - " 7.42923269e-05, 6.23486145e-04]),\n", - " array([-1.85229453e+01, -7.74249531e-02, -1.85240698e+01, -7.85494490e-02,\n", - " 4.07694853e-04, 6.03422339e-02, -1.39012335e-03, -7.83164016e-05,\n", - " 7.48794798e-05, 6.08238326e-04]),\n", - " array([-1.71765627e+01, 4.07364491e-01, -1.71789001e+01, 4.05027040e-01,\n", - " 4.22519750e-04, 5.75297073e-02, -1.46804672e-03, -7.97471389e-05,\n", - " 7.54769385e-05, 5.92559790e-04]),\n", - " array([-1.57658527e+01, 9.04413192e-01, -1.57693993e+01, 9.00866570e-01,\n", - " 4.36766023e-04, 5.45468351e-02, -1.54593699e-03, -8.12304224e-05,\n", - " 7.60857280e-05, 5.76470833e-04]),\n", - " array([-1.42933766e+01, 1.41300560e+00, -1.42981196e+01, 1.40826260e+00,\n", - " 4.50381025e-04, 5.13996493e-02, -1.62372798e-03, -8.27635714e-05,\n", - " 7.67068467e-05, 5.59992969e-04]),\n", - " array([-1.27619043e+01, 1.93239159e+00, -1.27678218e+01, 1.92647408e+00,\n", - " 4.63314970e-04, 4.80947514e-02, -1.70135427e-03, -8.43437403e-05,\n", - " 7.73412513e-05, 5.43148880e-04]),\n", - " array([-1.11744072e+01, 2.46178782e+00, -1.11814682e+01, 2.45472677e+00,\n", - " 4.75521220e-04, 4.46392945e-02, -1.77875110e-03, -8.59679305e-05,\n", - " 7.79898414e-05, 5.25962369e-04]),\n", - " array([-9.53405071e+00, 3.00037929e+00, -9.54221530e+00, 2.99221471e+00,\n", - " 4.86956558e-04, 4.10409623e-02, -1.85585429e-03, -8.76330018e-05,\n", - " 7.86534434e-05, 5.08458313e-04]),\n", - " array([-7.84418529e+00, 3.54732103e+00, -7.85340457e+00, 3.53810174e+00,\n", - " 4.97581450e-04, 3.73079462e-02, -1.93260019e-03, -8.93356858e-05,\n", - " 7.93327957e-05, 4.90662600e-04]),\n", - " array([-6.10833676e+00, 4.10173984e+00, -6.11855333e+00, 4.09152328e+00,\n", - " 5.07360283e-04, 3.34489195e-02, -2.00892554e-03, -9.10725991e-05,\n", - " 8.00285333e-05, 4.72602076e-04]),\n", - " array([-4.33019588e+00, 4.66273631e+00, -4.34134407e+00, 4.65158812e+00,\n", - " 5.16261591e-04, 2.94730092e-02, -2.08476738e-03, -9.28402568e-05,\n", - " 8.07411732e-05, 4.54304477e-04]),\n", - " array([-2.51360697e+00, 5.22938679e+00, -2.52561336e+00, 5.21738041e+00,\n", - " 5.24258271e-04, 2.53897659e-02, -2.16006293e-03, -9.46350874e-05,\n", - " 8.14711014e-05, 4.35798365e-04]),\n", - " array([-6.62555945e-01, 5.80074564e+00, -6.75339835e-01, 5.78796175e+00,\n", - " 5.31327763e-04, 2.12091313e-02, -2.23474953e-03, -9.64534468e-05,\n", - " 8.22185595e-05, 4.17113063e-04]),\n", - " array([ 1.21884251e+00, 6.37584749e+00, 1.20536843e+00, 6.36237340e+00,\n", - " 5.37452229e-04, 1.69414045e-02, -2.30876451e-03, -9.82916332e-05,\n", - " 8.29836333e-05, 3.98278576e-04]),\n", - " array([ 3.12635824e+00, 6.95370961e+00, 3.11228721e+00, 6.93963858e+00,\n", - " 5.42618702e-04, 1.25972055e-02, -2.38204519e-03, -1.00145902e-04,\n", - " 8.37662427e-05, 3.79325522e-04]),\n", - " array([ 5.05565959e+00, 7.53333447e+00, 5.04109001e+00, 7.51876489e+00,\n", - " 5.46819210e-04, 8.18743799e-03, -2.45452877e-03, -1.02012480e-04,\n", - " 8.45661325e-05, 3.60285054e-04]),\n", - " array([ 7.00232774e+00, 8.11371221e+00, 6.98736231e+00, 8.09874678e+00,\n", - " 5.50050881e-04, 3.72325097e-03, -2.52615237e-03, -1.03887580e-04,\n", - " 8.53828658e-05, 3.41188781e-04]),\n", - " array([ 8.96187156e+00, 8.69382337e+00, 8.94661639e+00, 8.67856819e+00,\n", - " 5.52316018e-04, -7.84001517e-04, -2.59685304e-03, -1.05767415e-04,\n", - " 8.62158179e-05, 3.22068691e-04]),\n", - " array([ 1.09297427e+01, 9.27264151e+00, 1.09143063e+01, 9.25720514e+00,\n", - " 5.53622147e-04, -5.32280071e-03, -2.66656786e-03, -1.07648212e-04,\n", - " 8.70641726e-05, 3.02957064e-04]),\n", - " array([ 1.29013508e+01, 9.84913601e+00, 1.28858433e+01, 9.83362844e+00,\n", - " 5.53982031e-04, -9.88150446e-03, -2.73523395e-03, -1.09526226e-04,\n", - " 8.79269211e-05, 2.83886395e-04]),\n", - " array([ 1.48720793e+01, 1.04222748e+01, 1.48566109e+01, 1.04068064e+01,\n", - " 5.53413654e-04, -1.44483887e-02, -2.80278871e-03, -1.11397750e-04,\n", - " 8.88028614e-05, 2.64889307e-04]),\n", - " array([ 1.68373004e+01, 1.09910271e+01, 1.68219811e+01, 1.09757078e+01,\n", - " 5.51940161e-04, -1.90116894e-02, -2.86916992e-03, -1.13259130e-04,\n", - " 8.96906008e-05, 2.45998468e-04]),\n", - " array([ 1.87923911e+01, 1.15543664e+01, 1.87773290e+01, 1.15393042e+01,\n", - " 5.49589770e-04, -2.35596436e-02, -2.93431600e-03, -1.15106774e-04,\n", - " 9.05885601e-05, 2.27246507e-04]),\n", - " array([ 2.07327483e+01, 1.21112729e+01, 2.07180488e+01, 1.20965733e+01,\n", - " 5.46395637e-04, -2.80805314e-02, -2.99816620e-03, -1.16937165e-04,\n", - " 9.14949793e-05, 2.08665931e-04]),\n", - " array([ 2.26538039e+01, 1.26607364e+01, 2.26395687e+01, 1.26465012e+01,\n", - " 5.42395687e-04, -3.25627157e-02, -3.06066086e-03, -1.18746866e-04,\n", - " 9.24079259e-05, 1.90289039e-04]),\n", - " array([ 2.45510397e+01, 1.32017592e+01, 2.45373658e+01, 1.31880853e+01,\n", - " 5.37632396e-04, -3.69946827e-02, -3.12174171e-03, -1.20532534e-04,\n", - " 9.33253046e-05, 1.72147840e-04]),\n", - " array([ 2.64200017e+01, 1.37333583e+01, 2.64069806e+01, 1.37203372e+01,\n", - " 5.32152538e-04, -4.13650804e-02, -3.18135212e-03, -1.22290924e-04,\n", - " 9.42448684e-05, 1.54273970e-04]),\n", - " array([ 2.82563147e+01, 1.42545684e+01, 2.82440314e+01, 1.42422850e+01,\n", - " 5.26006897e-04, -4.56627561e-02, -3.23943735e-03, -1.24018896e-04,\n", - " 9.51642321e-05, 1.36698614e-04]),\n", - " array([ 3.00556952e+01, 1.47644438e+01, 3.00442273e+01, 1.47529759e+01,\n", - " 5.19249929e-04, -4.98767927e-02, -3.29594487e-03, -1.25713422e-04,\n", - " 9.60808867e-05, 1.19452422e-04]),\n", - " array([ 3.18139646e+01, 1.52620616e+01, 3.18033818e+01, 1.52514788e+01,\n", - " 5.11939402e-04, -5.39965435e-02, -3.35082453e-03, -1.27371590e-04,\n", - " 9.69922151e-05, 1.02565435e-04]),\n", - " array([ 3.35270616e+01, 1.57465232e+01, 3.35174250e+01, 1.57368866e+01,\n", - " 5.04136004e-04, -5.80116649e-02, -3.40402884e-03, -1.28990606e-04,\n", - " 9.78955090e-05, 8.60670067e-05]),\n", - " array([ 3.51910538e+01, 1.62169567e+01, 3.51824156e+01, 1.62083185e+01,\n", - " 4.95902913e-04, -6.19121474e-02, -3.45551311e-03, -1.30567800e-04,\n", - " 9.87879869e-05, 6.99857329e-05]),\n", - " array([ 3.68021487e+01, 1.66725193e+01, 3.67945514e+01, 1.66649220e+01,\n", - " 4.87305361e-04, -6.56883455e-02, -3.50523560e-03, -1.32100625e-04,\n", - " 9.96668124e-05, 5.43493778e-05]),\n", - " array([ 3.83567041e+01, 1.71123985e+01, 3.83501806e+01, 1.71058750e+01,\n", - " 4.78410170e-04, -6.93310043e-02, -3.55315764e-03, -1.33586660e-04,\n", - " 1.00529114e-04, 3.91848065e-05]),\n", - " array([ 3.98512373e+01, 1.75358148e+01, 3.98458105e+01, 1.75303880e+01,\n", - " 4.69285280e-04, -7.28312850e-02, -3.59924370e-03, -1.35023607e-04,\n", - " 1.01372003e-04, 2.45179202e-05]),\n", - " array([ 4.12824341e+01, 1.79420225e+01, 4.12781167e+01, 1.79377052e+01,\n", - " 4.59999274e-04, -7.61807879e-02, -3.64346137e-03, -1.36409294e-04,\n", - " 1.02192597e-04, 1.03735931e-05]),\n", - " array([ 4.26471564e+01, 1.83303118e+01, 4.26439515e+01, 1.83271069e+01,\n", - " 4.50620896e-04, -7.93715735e-02, -3.68578138e-03, -1.37741672e-04,\n", - " 1.02988034e-04, -3.22438688e-06]),\n", - " array([ 4.39424499e+01, 1.87000098e+01, 4.39403506e+01, 1.86979104e+01,\n", - " 4.41218578e-04, -8.23961815e-02, -3.72617755e-03, -1.39018812e-04,\n", - " 1.03755495e-04, -1.62533735e-05]),\n", - " array([ 4.51655501e+01, 1.90504820e+01, 4.51645398e+01, 1.90494718e+01,\n", - " 4.31859975e-04, -8.52476471e-02, -3.76462664e-03, -1.40238905e-04,\n", - " 1.04492226e-04, -2.86919150e-05]),\n", - " array([ 4.63138878e+01, 1.93811336e+01, 4.63139410e+01, 1.93811868e+01,\n", - " 4.22611510e-04, -8.79195164e-02, -3.80110832e-03, -1.41400256e-04,\n", - " 1.05195550e-04, -4.05198030e-05]),\n", - " array([ 4.73850944e+01, 1.96914098e+01, 4.73861766e+01, 1.96924921e+01,\n", - " 4.13537942e-04, -9.04058586e-02, -3.83560496e-03, -1.42501285e-04,\n", - " 1.05862890e-04, -5.17181171e-05]),\n", - " array([ 4.83770059e+01, 1.99807977e+01, 4.83790745e+01, 1.99828663e+01,\n", - " 4.04701948e-04, -9.27012767e-02, -3.86810151e-03, -1.43540521e-04,\n", - " 1.06491782e-04, -6.22692669e-05]),\n", - " array([ 4.92876662e+01, 2.02488261e+01, 4.92906707e+01, 2.02518306e+01,\n", - " 3.96163729e-04, -9.48009165e-02, -3.89858531e-03, -1.44516598e-04,\n", - " 1.07079897e-04, -7.21570291e-05]),\n", - " array([ 5.01153300e+01, 2.04950667e+01, 5.01192129e+01, 2.04989496e+01,\n", - " 3.87980650e-04, -9.67004733e-02, -3.92704597e-03, -1.45428256e-04,\n", - " 1.07625047e-04, -8.13665811e-05]),\n", - " array([ 5.08584649e+01, 2.07191345e+01, 5.08631623e+01, 2.07238319e+01,\n", - " 3.80206889e-04, -9.83961973e-02, -3.95347514e-03, -1.46274332e-04,\n", - " 1.08125209e-04, -8.98845311e-05]),\n", - " array([ 5.15157528e+01, 2.09206882e+01, 5.15211952e+01, 2.09261306e+01,\n", - " 3.72893137e-04, -9.98848969e-02, -3.97786639e-03, -1.47053761e-04,\n", - " 1.08578529e-04, -9.76989431e-05]),\n", - " array([ 5.20860908e+01, 2.10994304e+01, 5.20922038e+01, 2.11055434e+01,\n", - " 3.66086306e-04, -1.01163940e-01, -4.00021502e-03, -1.47765572e-04,\n", - " 1.08983336e-04, -1.04799359e-04]),\n", - " array([ 5.25685920e+01, 2.12551083e+01, 5.25752967e+01, 2.12618130e+01,\n", - " 3.59829287e-04, -1.02231257e-01, -4.02051796e-03, -1.48408886e-04,\n", - " 1.09338153e-04, -1.11176818e-04]),\n", - " array([ 5.29625845e+01, 2.13875132e+01, 5.29697988e+01, 2.13947275e+01,\n", - " 3.54160721e-04, -1.03085334e-01, -4.03877360e-03, -1.48982913e-04,\n", - " 1.09641705e-04, -1.16823866e-04]),\n", - " array([ 5.32676112e+01, 2.14964811e+01, 5.32752503e+01, 2.15041202e+01,\n", - " 3.49114813e-04, -1.03725217e-01, -4.05498171e-03, -1.49486950e-04,\n", - " 1.09892922e-04, -1.21734569e-04]),\n", - " array([ 5.34834288e+01, 2.15818923e+01, 5.34914059e+01, 2.15898694e+01,\n", - " 3.44721175e-04, -1.04150503e-01, -4.06914331e-03, -1.49920379e-04,\n", - " 1.10090949e-04, -1.25904520e-04]),\n", - " array([ 5.36100056e+01, 2.16436715e+01, 5.36182328e+01, 2.16518987e+01,\n", - " 3.41004697e-04, -1.04361338e-01, -4.08126061e-03, -1.50282671e-04,\n", - " 1.10235146e-04, -1.29330837e-04]),\n", - " array([ 5.36475199e+01, 2.16817877e+01, 5.36559088e+01, 2.16901766e+01,\n", - " 3.37985453e-04, -1.04358410e-01, -4.09133695e-03, -1.50573378e-04,\n", - " 1.10325094e-04, -1.32012164e-04]),\n", - " array([ 5.35963574e+01, 2.16962538e+01, 5.36048198e+01, 2.17047162e+01,\n", - " 3.35678633e-04, -1.04142941e-01, -4.09937671e-03, -1.50792138e-04,\n", - " 1.10360588e-04, -1.33948663e-04]),\n", - " array([ 5.34571084e+01, 2.16871262e+01, 5.34655571e+01, 2.16955749e+01,\n", - " 3.34094511e-04, -1.03716679e-01, -4.10538529e-03, -1.50938675e-04,\n", - " 1.10341646e-04, -1.35142009e-04]),\n", - " array([ 5.32305643e+01, 2.16545047e+01, 5.32389136e+01, 2.16628540e+01,\n", - " 3.33238442e-04, -1.03081888e-01, -4.10936907e-03, -1.51012796e-04,\n", - " 1.10268498e-04, -1.35595370e-04]),\n", - " array([ 5.29177144e+01, 2.15985318e+01, 5.29258809e+01, 2.16066983e+01,\n", - " 3.33110886e-04, -1.02241340e-01, -4.11133541e-03, -1.51014396e-04,\n", - " 1.10141587e-04, -1.35313397e-04]),\n", - " array([ 5.25197415e+01, 2.15193923e+01, 5.25276445e+01, 2.15272953e+01,\n", - " 3.33707460e-04, -1.01198302e-01, -4.11129256e-03, -1.50943459e-04,\n", - " 1.09961560e-04, -1.34302200e-04]),\n", - " array([ 5.20380179e+01, 2.14173128e+01, 5.20455800e+01, 2.14248750e+01,\n", - " 3.35019026e-04, -9.99565237e-02, -4.10924970e-03, -1.50800058e-04,\n", - " 1.09729264e-04, -1.32569325e-04]),\n", - " array([ 5.14741006e+01, 2.12925607e+01, 5.14812485e+01, 2.12997086e+01,\n", - " 3.37031798e-04, -9.85202233e-02, -4.10521691e-03, -1.50584357e-04,\n", - " 1.09445738e-04, -1.30123728e-04]),\n", - " array([ 5.08297264e+01, 2.11454440e+01, 5.08363908e+01, 2.11521084e+01,\n", - " 3.39727477e-04, -9.68940761e-02, -4.09920514e-03, -1.50296614e-04,\n", - " 1.09112203e-04, -1.26975743e-04]),\n", - " array([ 5.01068062e+01, 2.09763100e+01, 5.01129228e+01, 2.09824266e+01,\n", - " 3.43083414e-04, -9.50831978e-02, -4.09122619e-03, -1.49937185e-04,\n", - " 1.08730049e-04, -1.23137050e-04]),\n", - " array([ 4.93074197e+01, 2.07855447e+01, 4.93129294e+01, 2.07910544e+01,\n", - " 3.47072793e-04, -9.30931291e-02, -4.08129272e-03, -1.49506523e-04,\n", - " 1.08300828e-04, -1.18620639e-04]),\n", - " array([ 4.84338092e+01, 2.05735721e+01, 4.84386584e+01, 2.05784212e+01,\n", - " 3.51664840e-04, -9.09298186e-02, -4.06941819e-03, -1.49005183e-04,\n", - " 1.07826240e-04, -1.13440767e-04]),\n", - " array([ 4.74883731e+01, 2.03408524e+01, 4.74925139e+01, 2.03449932e+01,\n", - " 3.56825048e-04, -8.85996053e-02, -4.05561685e-03, -1.48433824e-04,\n", - " 1.07308119e-04, -1.07612923e-04]),\n", - " array([ 4.64736590e+01, 2.00878820e+01, 4.64770498e+01, 2.00912729e+01,\n", - " 3.62515424e-04, -8.61092003e-02, -4.03990373e-03, -1.47793210e-04,\n", - " 1.06748419e-04, -1.01153776e-04]),\n", - " array([ 4.53923569e+01, 1.98151914e+01, 4.53949627e+01, 1.98177972e+01,\n", - " 3.68694754e-04, -8.34656669e-02, -4.02229459e-03, -1.47084216e-04,\n", - " 1.06149201e-04, -9.40811301e-05]),\n", - " array([ 4.42472917e+01, 1.95233444e+01, 4.42490837e+01, 1.95251365e+01,\n", - " 3.75318875e-04, -8.06764005e-02, -4.00280592e-03, -1.46307827e-04,\n", - " 1.05512617e-04, -8.64138771e-05]),\n", - " array([ 4.30414151e+01, 1.92129367e+01, 4.30423716e+01, 1.92138932e+01,\n", - " 3.82340974e-04, -7.77491071e-02, -3.98145488e-03, -1.45465140e-04,\n", - " 1.04840893e-04, -7.81719413e-05]),\n", - " array([ 4.17777977e+01, 1.88845947e+01, 4.17779035e+01, 1.88847005e+01,\n", - " 3.89711887e-04, -7.46917816e-02, -3.95825930e-03, -1.44557371e-04,\n", - " 1.04136318e-04, -6.93762267e-05]),\n", - " array([ 4.04596205e+01, 1.85389736e+01, 4.04588675e+01, 1.85382206e+01,\n", - " 3.97380409e-04, -7.15126845e-02, -3.93323766e-03, -1.43585847e-04,\n", - " 1.03401223e-04, -6.00485605e-05]),\n", - " array([ 3.90901658e+01, 1.81767563e+01, 3.90885527e+01, 1.81751432e+01,\n", - " 4.05293616e-04, -6.82203179e-02, -3.90640906e-03, -1.42552018e-04,\n", - " 1.02637969e-04, -5.02116351e-05]),\n", - " array([ 3.76728085e+01, 1.77986513e+01, 3.76703409e+01, 1.77961836e+01,\n", - " 4.13397189e-04, -6.48234018e-02, -3.87779320e-03, -1.41457449e-04,\n", - " 1.01848929e-04, -3.98889483e-05]),\n", - " array([ 3.62110065e+01, 1.74053916e+01, 3.62076966e+01, 1.74020817e+01,\n", - " 4.21635741e-04, -6.13308478e-02, -3.84741039e-03, -1.40303827e-04,\n", - " 1.01036475e-04, -2.91047422e-05]),\n", - " array([ 3.47082906e+01, 1.69977324e+01, 3.47041574e+01, 1.69935991e+01,\n", - " 4.29953145e-04, -5.77517340e-02, -3.81528156e-03, -1.39092955e-04,\n", - " 1.00202960e-04, -1.78839406e-05]),\n", - " array([ 3.31682555e+01, 1.65764496e+01, 3.31633242e+01, 1.65715183e+01,\n", - " 4.38292868e-04, -5.40952779e-02, -3.78142824e-03, -1.37826755e-04,\n", - " 9.93507061e-05, -6.25208469e-06]),\n", - " array([ 3.15945488e+01, 1.61423379e+01, 3.15888508e+01, 1.61366400e+01,\n", - " 4.46598292e-04, -5.03708097e-02, -3.74587257e-03, -1.36507267e-04,\n", - " 9.84819915e-05, 5.76473102e-06]),\n", - " array([ 2.99908608e+01, 1.56962087e+01, 2.99844335e+01, 1.56897813e+01,\n", - " 4.54813041e-04, -4.65877447e-02, -3.70863738e-03, -1.35136644e-04,\n", - " 9.75990346e-05, 1.81399249e-05]),\n", - " array([ 2.83609146e+01, 1.52388881e+01, 2.83538007e+01, 1.52317742e+01,\n", - " 4.62881302e-04, -4.27555553e-02, -3.66974614e-03, -1.33717151e-04,\n", - " 9.67039839e-05, 3.08464943e-05]),\n", - " array([ 2.67084548e+01, 1.47712153e+01, 2.67007023e+01, 1.47634628e+01,\n", - " 4.70748129e-04, -3.88837433e-02, -3.62922308e-03, -1.32251164e-04,\n", - " 9.57989063e-05, 4.38570825e-05]),\n", - " array([ 2.50372372e+01, 1.42940400e+01, 2.50288988e+01, 1.42857015e+01,\n", - " 4.78359751e-04, -3.49818113e-02, -3.58709317e-03, -1.30741163e-04,\n", - " 9.48857770e-05, 5.71440454e-05]),\n", - " array([ 2.33510181e+01, 1.38082207e+01, 2.33421506e+01, 1.37993532e+01,\n", - " 4.85663868e-04, -3.10592347e-02, -3.54338222e-03, -1.29189727e-04,\n", - " 9.39664703e-05, 7.06795192e-05]),\n", - " array([ 2.16535434e+01, 1.33146225e+01, 2.16442074e+01, 1.33052866e+01,\n", - " 4.92609923e-04, -2.71254336e-02, -3.49811690e-03, -1.27599532e-04,\n", - " 9.30427520e-05, 8.44354869e-05]),\n", - " array([ 1.99485382e+01, 1.28141150e+01, 1.99387978e+01, 1.28043746e+01,\n", - " 4.99149382e-04, -2.31897449e-02, -3.45132484e-03, -1.25973342e-04,\n", - " 9.21162723e-05, 9.83838458e-05]),\n", - " array([ 1.82396963e+01, 1.23075703e+01, 1.82296180e+01, 1.22974920e+01,\n", - " 5.05235982e-04, -1.92613947e-02, -3.40303465e-03, -1.24314005e-04,\n", - " 9.11885607e-05, 1.12496473e-04]),\n", - " array([ 1.65306698e+01, 1.17958607e+01, 1.65203224e+01, 1.17855132e+01,\n", - " 5.10825976e-04, -1.53494714e-02, -3.35327606e-03, -1.22624440e-04,\n", - " 9.02610217e-05, 1.26745291e-04]),\n", - " array([ 1.48250591e+01, 1.12798570e+01, 1.48145127e+01, 1.12693106e+01,\n", - " 5.15878352e-04, -1.14628991e-02, -3.30207992e-03, -1.20907639e-04,\n", - " 8.93349319e-05, 1.41102333e-04]),\n", - " array([ 1.31264026e+01, 1.07604261e+01, 1.31157286e+01, 1.07497521e+01,\n", - " 5.20355044e-04, -7.61041218e-03, -3.24947829e-03, -1.19166647e-04,\n", - " 8.84114381e-05, 1.55539808e-04]),\n", - " array([ 1.14381678e+01, 1.02384294e+01, 1.14274378e+01, 1.02276993e+01,\n", - " 5.24221118e-04, -3.80053047e-03, -3.19550455e-03, -1.17404563e-04,\n", - " 8.74915574e-05, 1.70030159e-04]),\n", - " array([ 9.76374150e+00, 9.71472043e+00, 9.75302693e+00, 9.70400585e+00,\n", - " 5.27444941e-04, -4.15352391e-05, -3.14019341e-03, -1.15624523e-04,\n", - " 8.65761773e-05, 1.84546128e-04]),\n", - " array([ 8.10642143e+00, 9.19014348e+00, 8.09579295e+00, 9.17951500e+00,\n", - " 5.29998327e-04, 3.65855336e-03, -3.08358099e-03, -1.13829696e-04,\n", - " 8.56660582e-05, 1.99060815e-04]),\n", - " array([ 6.46940750e+00, 8.66553131e+00, 6.45893447e+00, 8.65505828e+00,\n", - " 5.31856668e-04, 7.29199783e-03, -3.02570493e-03, -1.12023269e-04,\n", - " 8.47618360e-05, 2.13547733e-04]),\n", - " array([ 4.85579408e+00, 8.14170367e+00, 4.84554399e+00, 8.13145358e+00,\n", - " 5.32999039e-04, 1.08513635e-02, -2.96660434e-03, -1.10208441e-04,\n", - " 8.38640265e-05, 2.27980868e-04]),\n", - " array([ 3.26856254e+00, 7.61946555e+00, 3.25860050e+00, 7.60950351e+00,\n", - " 5.33408278e-04, 1.43295374e-02, -2.90631995e-03, -1.08388409e-04,\n", - " 8.29730299e-05, 2.42334729e-04]),\n", - " array([ 1.71057432e+00, 7.09960560e+00, 1.70096260e+00, 7.08999388e+00,\n", - " 5.33071053e-04, 1.77197454e-02, -2.84489410e-03, -1.06566357e-04,\n", - " 8.20891371e-05, 2.56584401e-04]),\n", - " array([ 1.84564637e-01, 6.58289461e+00, 1.75362218e-01, 6.57369219e+00,\n", - " 5.31977894e-04, 2.10155683e-02, -2.78237077e-03, -1.04745448e-04,\n", - " 8.12125360e-05, 2.70705596e-04]),\n", - " array([-1.30686330e+00, 6.07008413e+00, -1.31560113e+00, 6.06134631e+00,\n", - " 5.30123216e-04, 2.42109559e-02, -2.71879561e-03, -1.02928814e-04,\n", - " 8.03433188e-05, 2.84674695e-04]),\n", - " array([-2.76124343e+00, 5.56190510e+00, -2.76946542e+00, 5.55368311e+00,\n", - " 5.27505304e-04, 2.73002392e-02, -2.65421597e-03, -1.01119541e-04,\n", - " 7.94814900e-05, 2.98468799e-04]),\n", - " array([-4.17625139e+00, 5.05906666e+00, -4.18391068e+00, 5.05140737e+00,\n", - " 5.24126290e-04, 3.02781419e-02, -2.58868090e-03, -9.93206608e-05,\n", - " 7.86269742e-05, 3.12065764e-04]),\n", - " array([-5.54970846e+00, 4.56225500e+00, -5.55676281e+00, 4.55520064e+00,\n", - " 5.19992098e-04, 3.31397890e-02, -2.52224112e-03, -9.75351437e-05,\n", - " 7.77796252e-05, 3.25444242e-04]),\n", - " array([-6.87958486e+00, 4.07213234e+00, -6.88599690e+00, 4.06572030e+00,\n", - " 5.15112373e-04, 3.58807146e-02, -2.45494905e-03, -9.57658847e-05,\n", - " 7.69392345e-05, 3.38583721e-04]),\n", - " array([-8.16400246e+00, 3.58933602e+00, -8.16973985e+00, 3.58359863e+00,\n", - " 5.09500384e-04, 3.84968676e-02, -2.38685874e-03, -9.40156968e-05,\n", - " 7.61055402e-05, 3.51464549e-04]),\n", - " array([-9.40123684e+00, 3.11447761e+00, -9.40627239e+00, 3.10944206e+00,\n", - " 5.03172914e-04, 4.09846153e-02, -2.31802588e-03, -9.22873010e-05,\n", - " 7.52782364e-05, 3.64067974e-04]),\n", - " array([-1.05897188e+01, 2.64814224e+00, -1.05940305e+01, 2.64383048e+00,\n", - " 4.96150122e-04, 4.33407466e-02, -2.24850773e-03, -9.05833188e-05,\n", - " 7.44569815e-05, 3.76376162e-04]),\n", - " array([-1.17280350e+01, 2.19088790e+00, -1.17316063e+01, 2.18731664e+00,\n", - " 4.88455398e-04, 4.55624719e-02, -2.17836306e-03, -8.89062640e-05,\n", - " 7.36414072e-05, 3.88372228e-04]),\n", - " array([-1.28149287e+01, 1.74324494e+00, -1.28177480e+01, 1.74042565e+00,\n", - " 4.80115187e-04, 4.76474228e-02, -2.10765213e-03, -8.72585357e-05,\n", - " 7.28311273e-05, 4.00040252e-04]),\n", - " array([-1.38492991e+01, 1.30571559e+00, -1.38513601e+01, 1.30365457e+00,\n", - " 4.71158814e-04, 4.95936493e-02, -2.03643654e-03, -8.56424124e-05,\n", - " 7.20257451e-05, 4.11365299e-04]),\n", - " array([-1.48302005e+01, 8.78773602e-01, -1.48315020e+01, 8.77472071e-01,\n", - " 4.61618278e-04, 5.13996162e-02, -1.96477922e-03, -8.40600453e-05,\n", - " 7.12248619e-05, 4.22333434e-04]),\n", - " array([-1.57568412e+01, 4.62863966e-01, -1.57573870e+01, 4.62318226e-01,\n", - " 4.51528048e-04, 5.30641974e-02, -1.89274430e-03, -8.25134540e-05,\n", - " 7.04280839e-05, 4.32931731e-04]),\n", - " array([-1.66285817e+01, 5.84026990e-02, -1.66283801e+01, 5.86043045e-02,\n", - " 4.40924836e-04, 5.45866695e-02, -1.82039700e-03, -8.10045220e-05,\n", - " 6.96350288e-05, 4.43148285e-04]),\n", - " array([-1.74449318e+01, -3.34223269e-01, -1.74439958e+01, -3.33287298e-01,\n", - " 4.29847370e-04, 5.59667038e-02, -1.74780355e-03, -7.95349926e-05,\n", - " 6.88453323e-05, 4.52972215e-04]),\n", - " array([-1.82055488e+01, -7.14656152e-01, -1.82038957e+01, -7.13003091e-01,\n", - " 4.18336152e-04, 5.72043569e-02, -1.67503105e-03, -7.81064667e-05,\n", - " 6.80586536e-05, 4.62393669e-04]),\n", - " array([-1.89102334e+01, -1.08256729e+00, -1.89078846e+01, -1.08021844e+00,\n", - " 4.06433213e-04, 5.83000609e-02, -1.60214732e-03, -7.67203998e-05,\n", - " 6.72746802e-05, 4.71403819e-04]),\n", - " array([-1.95589270e+01, -1.43765705e+00, -1.95559074e+01, -1.43463747e+00,\n", - " 3.94181864e-04, 5.92546113e-02, -1.52922082e-03, -7.53781010e-05,\n", - " 6.64931325e-05, 4.79994865e-04]),\n", - " array([-2.01517071e+01, -1.77965470e+00, -2.01480453e+01, -1.77599288e+00,\n", - " 3.81626442e-04, 6.00691557e-02, -1.45632048e-03, -7.40807319e-05,\n", - " 6.57137671e-05, 4.88160025e-04]),\n", - " array([-2.06887837e+01, -2.10831821e+00, -2.06845112e+01, -2.10404575e+00,\n", - " 3.68812055e-04, 6.07451801e-02, -1.38351552e-03, -7.28293065e-05,\n", - " 6.49363800e-05, 4.95893525e-04]),\n", - " array([-2.11704943e+01, -2.42343397e+00, -2.11656456e+01, -2.41858528e+00,\n", - " 3.55784332e-04, 6.12844950e-02, -1.31087538e-03, -7.16246915e-05,\n", - " 6.41608090e-05, 5.03190595e-04]),\n", - " array([-2.15972995e+01, -2.72481648e+00, -2.15919114e+01, -2.71942842e+00,\n", - " 3.42589167e-04, 6.16892215e-02, -1.23846949e-03, -7.04676074e-05,\n", - " 6.33869352e-05, 5.10047446e-04]),\n", - " array([-2.19697780e+01, -3.01230802e+00, -2.19638895e+01, -3.00641957e+00,\n", - " 3.29272476e-04, 6.19617754e-02, -1.16636717e-03, -6.93586305e-05,\n", - " 6.26146842e-05, 5.16461264e-04]),\n", - " array([-2.22886213e+01, -3.28577822e+00, -2.22822732e+01, -3.27943015e+00,\n", - " 3.15879951e-04, 6.21048523e-02, -1.09463742e-03, -6.82981942e-05,\n", - " 6.18440267e-05, 5.22430185e-04]),\n", - " array([-2.25546284e+01, -3.54512365e+00, -2.25478629e+01, -3.53835814e+00,\n", - " 3.02456827e-04, 6.21214110e-02, -1.02334882e-03, -6.72865927e-05,\n", - " 6.10749780e-05, 5.27953280e-04]),\n", - " array([-2.27687005e+01, -3.79026729e+00, -2.27615608e+01, -3.78312766e+00,\n", - " 2.89047657e-04, 6.20146577e-02, -9.52569318e-04, -6.63239834e-05,\n", - " 6.03075979e-05, 5.33030529e-04]),\n", - " array([-2.29318350e+01, -4.02115806e+00, -2.29243654e+01, -4.01368839e+00,\n", - " 2.75696087e-04, 6.17880290e-02, -8.82366099e-04, -6.54103911e-05,\n", - " 5.95419892e-05, 5.37662802e-04]),\n", - " array([-2.30451205e+01, -4.23777024e+00, -2.30373654e+01, -4.23001508e+00,\n", - " 2.62444658e-04, 6.14451751e-02, -8.12805432e-04, -6.45457115e-05,\n", - " 5.87782961e-05, 5.41851828e-04]),\n", - " array([-2.31097303e+01, -4.44010287e+00, -2.31017344e+01, -4.43210693e+00,\n", - " 2.49334606e-04, 6.09899432e-02, -7.43952509e-04, -6.37297160e-05,\n", - " 5.80167026e-05, 5.45600174e-04]),\n", - " array([-2.31269170e+01, -4.62817919e+00, -2.31187249e+01, -4.61998705e+00,\n", - " 2.36405680e-04, 6.04263604e-02, -6.75871301e-04, -6.29620564e-05,\n", - " 5.72574299e-05, 5.48911212e-04]),\n", - " array([-2.30980068e+01, -4.80204593e+00, -2.30896626e+01, -4.79370176e+00,\n", - " 2.23695977e-04, 5.97586167e-02, -6.08624410e-04, -6.22422696e-05,\n", - " 5.65007334e-05, 5.51789091e-04]),\n", - " array([-2.30243932e+01, -4.96177271e+00, -2.30159405e+01, -4.95332000e+00,\n", - " 2.11241784e-04, 5.89910480e-02, -5.42272937e-04, -6.15697832e-05,\n", - " 5.57469004e-05, 5.54238707e-04]),\n", - " array([-2.29075319e+01, -5.10745126e+00, -2.28990132e+01, -5.09893260e+00,\n", - " 1.99077441e-04, 5.81281197e-02, -4.76876341e-04, -6.09439209e-05,\n", - " 5.49962464e-05, 5.56265670e-04]),\n", - " array([-2.27489343e+01, -5.23919480e+00, -2.27403911e+01, -5.23065161e+00,\n", - " 1.87235216e-04, 5.71744101e-02, -4.12492320e-04, -6.03639080e-05,\n", - " 5.42491120e-05, 5.57876272e-04]),\n", - " array([-2.25501623e+01, -5.35713722e+00, -2.25416346e+01, -5.34860960e+00,\n", - " 1.75745200e-04, 5.61345938e-02, -3.49176690e-04, -5.98288777e-05,\n", - " 5.35058592e-05, 5.59077450e-04]),\n", - " array([-2.23128222e+01, -5.46143235e+00, -2.23043487e+01, -5.45295884e+00,\n", - " 1.64635214e-04, 5.50134260e-02, -2.86983272e-04, -5.93378766e-05,\n", - " 5.27668681e-05, 5.59876757e-04]),\n", - " array([-2.20385597e+01, -5.55225320e+00, -2.20301772e+01, -5.54387064e+00,\n", - " 1.53930731e-04, 5.38157264e-02, -2.25963788e-04, -5.88898707e-05,\n", - " 5.20325329e-05, 5.60282324e-04]),\n", - " array([-2.17290538e+01, -5.62979113e+00, -2.17207971e+01, -5.62153447e+00,\n", - " 1.43654821e-04, 5.25463642e-02, -1.66167766e-04, -5.84837519e-05,\n", - " 5.13032582e-05, 5.60302827e-04]),\n", - " array([-2.13860117e+01, -5.69425505e+00, -2.13779139e+01, -5.68615727e+00,\n", - " 1.33828103e-04, 5.12102429e-02, -1.07642454e-04, -5.81183436e-05,\n", - " 5.05794558e-05, 5.59947446e-04]),\n", - " array([-2.10111635e+01, -5.74587058e+00, -2.10032555e+01, -5.73796255e+00,\n", - " 1.24468719e-04, 4.98122857e-02, -5.04327373e-05, -5.77924074e-05,\n", - " 4.98615408e-05, 5.59225836e-04]),\n", - " array([-2.06062570e+01, -5.78487925e+00, -2.05985674e+01, -5.77718960e+00,\n", - " 1.15592327e-04, 4.83574215e-02, 5.41893469e-06, -5.75046483e-05,\n", - " 4.91499279e-05, 5.58148089e-04]),\n", - " array([-2.01730527e+01, -5.81153758e+00, -2.01656078e+01, -5.80409271e+00,\n", - " 1.07212082e-04, 4.68505710e-02, 5.98725917e-05, -5.72537215e-05,\n", - " 4.84450284e-05, 5.56724694e-04]),\n", - " array([-1.97133188e+01, -5.82611627e+00, -1.97061427e+01, -5.81894021e+00,\n", - " 9.93386823e-05, 4.52966339e-02, 1.12890827e-04, -5.70382378e-05,\n", - " 4.77472469e-05, 5.54966509e-04]),\n", - " array([-1.92288266e+01, -5.82889931e+00, -1.92219410e+01, -5.82201371e+00,\n", - " 9.19803793e-05, 4.37004759e-02, 1.64438827e-04, -5.68567698e-05,\n", - " 4.70569780e-05, 5.52884718e-04]),\n", - " array([-1.87213460e+01, -5.82018308e+00, -1.87147701e+01, -5.81360721e+00,\n", - " 8.51430215e-05, 4.20669166e-02, 2.14484401e-04, -5.67078571e-05,\n", - " 4.63746036e-05, 5.50490802e-04]),\n", - " array([-1.81926405e+01, -5.80027550e+00, -1.81863912e+01, -5.79402620e+00,\n", - " 7.88301166e-05, 4.04007182e-02, 2.62998028e-04, -5.65900124e-05,\n", - " 4.57004901e-05, 5.47796499e-04]),\n", - " array([-1.76444638e+01, -5.76949513e+00, -1.76385555e+01, -5.76358685e+00,\n", - " 7.30428918e-05, 3.87065742e-02, 3.09952869e-04, -5.65017265e-05,\n", - " 4.50349862e-05, 5.44813774e-04]),\n", - " array([-1.70785551e+01, -5.72817028e+00, -1.70729999e+01, -5.72261507e+00,\n", - " 6.77803714e-05, 3.69890988e-02, 3.55324785e-04, -5.64414736e-05,\n", - " 4.43784206e-05, 5.41554783e-04]),\n", - " array([-1.64966354e+01, -5.67663810e+00, -1.64914430e+01, -5.67144568e+00,\n", - " 6.30394623e-05, 3.52528177e-02, 3.99092343e-04, -5.64077164e-05,\n", - " 4.37310996e-05, 5.38031842e-04]),\n", - " array([-1.59004036e+01, -5.61524373e+00, -1.58955814e+01, -5.61042154e+00,\n", - " 5.88150486e-05, 3.35021579e-02, 4.41236817e-04, -5.63989110e-05,\n", - " 4.30933063e-05, 5.34257391e-04]),\n", - " array([-1.52915333e+01, -5.54433942e+00, -1.52870865e+01, -5.53989263e+00,\n", - " 5.51000926e-05, 3.17414398e-02, 4.81742182e-04, -5.64135115e-05,\n", - " 4.24652981e-05, 5.30243965e-04]),\n", - " array([-1.46716691e+01, -5.46428363e+00, -1.46676008e+01, -5.46021527e+00,\n", - " 5.18857437e-05, 2.99748685e-02, 5.20595104e-04, -5.64499742e-05,\n", - " 4.18473063e-05, 5.26004164e-04]),\n", - " array([-1.40424237e+01, -5.37544016e+00, -1.40387347e+01, -5.37175118e+00,\n", - " 4.91614522e-05, 2.82065268e-02, 5.57784918e-04, -5.65067623e-05,\n", - " 4.12395346e-05, 5.21550621e-04]),\n", - " array([-1.34053748e+01, -5.27817735e+00, -1.34020641e+01, -5.27486671e+00,\n", - " 4.69150876e-05, 2.64403679e-02, 5.93303604e-04, -5.65823495e-05,\n", - " 4.06421589e-05, 5.16895975e-04]),\n", - " array([-1.27620621e+01, -5.17286719e+00, -1.27591269e+01, -5.16993195e+00,\n", - " 4.51330614e-05, 2.46802093e-02, 6.27145762e-04, -5.66752239e-05,\n", - " 4.00553262e-05, 5.12052842e-04]),\n", - " array([-1.21139855e+01, -5.05988450e+00, -1.21114209e+01, -5.05731995e+00,\n", - " 4.38004521e-05, 2.29297272e-02, 6.59308570e-04, -5.67838916e-05,\n", - " 3.94791551e-05, 5.07033785e-04]),\n", - " array([-1.14626017e+01, -4.93960615e+00, -1.14604014e+01, -4.93740589e+00,\n", - " 4.29011322e-05, 2.11924513e-02, 6.89791750e-04, -5.69068800e-05,\n", - " 3.89137352e-05, 5.01851296e-04]),\n", - " array([-1.08093229e+01, -4.81241023e+00, -1.08074790e+01, -4.81056631e+00,\n", - " 4.24178966e-05, 1.94717600e-02, 7.18597519e-04, -5.70427408e-05,\n", - " 3.83591275e-05, 4.96517762e-04]),\n", - " array([-1.01555143e+01, -4.67867530e+00, -1.01540173e+01, -4.67717835e+00,\n", - " 4.23325908e-05, 1.77708772e-02, 7.45730543e-04, -5.71900530e-05,\n", - " 3.78153650e-05, 4.91045448e-04]),\n", - " array([-9.50249246e+00, -4.53877966e+00, -9.50133179e+00, -4.53761899e+00,\n", - " 4.26262386e-05, 1.60928683e-02, 7.71197880e-04, -5.73474256e-05,\n", - " 3.72824531e-05, 4.85446470e-04]),\n", - " array([-8.85152398e+00, -4.39310060e+00, -8.85068770e+00, -4.39226432e+00,\n", - " 4.32791688e-05, 1.44406375e-02, 7.95008926e-04, -5.75134998e-05,\n", - " 3.67603704e-05, 4.79732777e-04]),\n", - " array([-8.20382370e+00, -4.24201368e+00, -8.20329888e+00, -4.24148887e+00,\n", - " 4.42711394e-05, 1.28169262e-02, 8.17175352e-04, -5.76869513e-05,\n", - " 3.62490699e-05, 4.73916127e-04]),\n", - " array([-7.56055379e+00, -4.08589211e+00, -7.56032657e+00, -4.08566489e+00,\n", - " 4.55814592e-05, 1.12243105e-02, 8.37711039e-04, -5.78664925e-05,\n", - " 3.57484795e-05, 4.68008073e-04]),\n", - " array([-6.92282266e+00, -3.92510605e+00, -6.92287838e+00, -3.92516177e+00,\n", - " 4.71891066e-05, 9.66520062e-03, 8.56632009e-04, -5.80508739e-05,\n", - " 3.52585039e-05, 4.62019940e-04]),\n", - " array([-6.29168419e+00, -3.76002204e+00, -6.29200748e+00, -3.76034533e+00,\n", - " 4.90728436e-05, 8.14184006e-03, 8.73956357e-04, -5.82388861e-05,\n", - " 3.47790256e-05, 4.55962808e-04]),\n", - " array([-5.66813704e+00, -3.59100234e+00, -5.66871202e+00, -3.59157732e+00,\n", - " 5.12113261e-05, 6.65630559e-03, 8.89704172e-04, -5.84293610e-05,\n", - " 3.43099062e-05, 4.49847503e-04]),\n", - " array([-5.05312428e+00, -3.41840445e+00, -5.05393461e+00, -3.41921477e+00,\n", - " 5.35832092e-05, 5.21050761e-03, 9.03897465e-04, -5.86211727e-05,\n", - " 3.38509881e-05, 4.43684574e-04]),\n", - " array([-4.44753304e+00, -3.24258051e+00, -4.44856207e+00, -3.24360954e+00,\n", - " 5.61672471e-05, 3.80619098e-03, 9.16560085e-04, -5.88132392e-05,\n", - " 3.34020960e-05, 4.37484287e-04]),\n", - " array([-3.85219447e+00, -3.06387686e+00, -3.85342534e+00, -3.06510772e+00,\n", - " 5.89423878e-05, 2.44493631e-03, 9.27717640e-04, -5.90045225e-05,\n", - " 3.29630385e-05, 4.31256609e-04]),\n", - " array([-3.26788374e+00, -2.88263351e+00, -3.26929950e+00, -2.88404926e+00,\n", - " 6.18878613e-05, 1.12816176e-03, 9.37397415e-04, -5.91940299e-05,\n", - " 3.25336097e-05, 4.25011196e-04]),\n", - " array([-2.69532031e+00, -2.69918375e+00, -2.69690401e+00, -2.70076745e+00,\n", - " 6.49832626e-05, -1.42874871e-04, 9.45628282e-04, -5.93808140e-05,\n", - " 3.21135912e-05, 4.18757388e-04]),\n", - " array([-2.13516824e+00, -2.51385372e+00, -2.13690304e+00, -2.51558853e+00,\n", - " 6.82086272e-05, -1.36707359e-03, 9.52440613e-04, -5.95639733e-05,\n", - " 3.17027529e-05, 4.12504197e-04]),\n", - " array([-1.58803675e+00, -2.32696206e+00, -1.58990601e+00, -2.32883132e+00,\n", - " 7.15445016e-05, -2.54348929e-03, 9.57866198e-04, -5.97426524e-05,\n", - " 3.13008558e-05, 4.06260298e-04]),\n", - " array([-1.05448084e+00, -2.13881951e+00, -1.05646819e+00, -2.14080686e+00,\n", - " 7.49720060e-05, -3.67132848e-03, 9.61938147e-04, -5.99160421e-05,\n", - " 3.09076526e-05, 4.00034028e-04]),\n", - " array([-5.35002069e-01, -1.94972867e+00, -5.37091502e-01, -1.95181810e+00,\n", - " 7.84728916e-05, -4.74994574e-03, 9.64690804e-04, -6.00833790e-05,\n", - " 3.05228900e-05, 3.93833374e-04]),\n", - " array([-3.00494729e-02, -1.75998365e+00, -3.22254116e-02, -1.76215959e+00,\n", - " 8.20295903e-05, -5.77883982e-03, 9.66159652e-04, -6.02439458e-05,\n", - " 3.01463097e-05, 3.87665975e-04]),\n", - " array([ 4.59979442e-01, -1.56986987e+00, 4.57732080e-01, -1.57211723e+00,\n", - " 8.56252590e-05, -6.75764946e-03, 9.66381227e-04, -6.03970707e-05,\n", - " 2.97776503e-05, 3.81539113e-04]),\n", - " array([ 9.34737562e-01, -1.37966381e+00, 9.32433306e-01, -1.38196807e+00,\n", - " 8.92438164e-05, -7.68614901e-03, 9.65393017e-04, -6.05421269e-05,\n", - " 2.94166486e-05, 3.75459715e-04]),\n", - " array([ 1.39392695e+00, -1.18963281e+00, 1.39157972e+00, -1.19198003e+00,\n", - " 9.28699750e-05, -8.56424376e-03, 9.63233378e-04, -6.06785324e-05,\n", - " 2.90630407e-05, 3.69434350e-04]),\n", - " array([ 1.83729753e+00, -1.00003491e+00, 1.83492061e+00, -1.00241183e+00,\n", - " 9.64892653e-05, -9.39196508e-03, 9.59941437e-04, -6.08057490e-05,\n", - " 2.87165639e-05, 3.63469227e-04]),\n", - " array([ 2.26464569e+00, -8.11118725e-01, 2.26225167e+00, -8.13512746e-01,\n", - " 1.00088056e-04, -1.01694654e-02, 9.55557000e-04, -6.09232818e-05,\n", - " 2.83769570e-05, 3.57570199e-04]),\n", - " array([ 2.67581281e+00, -6.23123312e-01, 2.67341356e+00, -6.25522560e-01,\n", - " 1.03653566e-04, -1.08970131e-02, 9.50120463e-04, -6.10306784e-05,\n", - " 2.80439622e-05, 3.51742760e-04]),\n", - " array([ 3.07068372e+00, -4.36278087e-01, 3.06829038e+00, -4.38671429e-01,\n", - " 1.07173876e-04, -1.15749869e-02, 9.43672721e-04, -6.11275282e-05,\n", - " 2.77173258e-05, 3.45992051e-04]),\n", - " array([ 3.44918512e+00, -2.50802766e-01, 3.44680806e+00, -2.53179827e-01,\n", - " 1.10637926e-04, -1.22038707e-02, 9.36255078e-04, -6.12134610e-05,\n", - " 2.73967990e-05, 3.40322859e-04]),\n", - " array([ 3.81128388e+00, -6.69073225e-02, 3.80893271e+00, -6.92584991e-02,\n", - " 1.14035520e-04, -1.27842480e-02, 9.27909158e-04, -6.12881464e-05,\n", - " 2.70821391e-05, 3.34739624e-04]),\n", - " array([ 4.15698541e+00, 1.15208027e-01, 4.15466895e+00, 1.12891564e-01,\n", - " 1.17357316e-04, -1.33167962e-02, 9.18676820e-04, -6.13512928e-05,\n", - " 2.67731097e-05, 3.29246442e-04]),\n", - " array([ 4.48633188e+00, 2.95352821e-01, 4.48405818e+00, 2.93079121e-01,\n", - " 1.20594814e-04, -1.38022809e-02, 9.08600073e-04, -6.14026459e-05,\n", - " 2.64694820e-05, 3.23847069e-04]),\n", - " array([ 4.79940046e+00, 4.73346326e-01, 4.79717680e+00, 4.71122666e-01,\n", - " 1.23740348e-04, -1.42415504e-02, 8.97720993e-04, -6.14419881e-05,\n", - " 2.61710348e-05, 3.18544927e-04]),\n", - " array([ 5.09630158e+00, 6.49017489e-01, 5.09413447e+00, 6.46850383e-01,\n", - " 1.26787060e-04, -1.46355299e-02, 8.86081639e-04, -6.14691369e-05,\n", - " 2.58775553e-05, 3.13343111e-04]),\n", - " array([ 5.37717707e+00, 8.22204880e-01, 5.37507228e+00, 8.20100089e-01,\n", - " 1.29728885e-04, -1.49852156e-02, 8.73723978e-04, -6.14839437e-05,\n", - " 2.55888394e-05, 3.08244395e-04]),\n", - " array([ 5.64219841e+00, 9.92756601e-01, 5.64016096e+00, 9.90719154e-01,\n", - " 1.32560526e-04, -1.52916696e-02, 8.60689807e-04, -6.14862931e-05,\n", - " 2.53046919e-05, 3.03251237e-04]),\n", - " array([ 5.89156487e+00, 1.16053020e+00, 5.88959908e+00, 1.15856441e+00,\n", - " 1.35277426e-04, -1.55560136e-02, 8.47020676e-04, -6.14761008e-05,\n", - " 2.50249270e-05, 2.98365791e-04]),\n", - " array([ 6.12550172e+00, 1.32539254e+00, 6.12361122e+00, 1.32350204e+00,\n", - " 1.37875740e-04, -1.57794241e-02, 8.32757823e-04, -6.14533131e-05,\n", - " 2.47493680e-05, 2.93589912e-04]),\n", - " array([ 6.34425846e+00, 1.48721969e+00, 6.34244621e+00, 1.48540744e+00,\n", - " 1.40352306e-04, -1.59631261e-02, 8.17942099e-04, -6.14179050e-05,\n", - " 2.44778477e-05, 2.88925166e-04]),\n", - " array([ 6.54810698e+00, 1.64589677e+00, 6.54637533e+00, 1.64416511e+00,\n", - " 1.42704609e-04, -1.61083886e-02, 8.02613905e-04, -6.13698794e-05,\n", - " 2.42102085e-05, 2.84372834e-04]),\n", - " array([ 6.73733985e+00, 1.80131780e+00, 6.73569052e+00, 1.79966847e+00,\n", - " 1.44930753e-04, -1.62165185e-02, 7.86813129e-04, -6.13092655e-05,\n", - " 2.39463020e-05, 2.79933929e-04]),\n", - " array([ 6.91226855e+00, 1.95338553e+00, 6.91070271e+00, 1.95181970e+00,\n", - " 1.47029423e-04, -1.62888562e-02, 7.70579087e-04, -6.12361175e-05,\n", - " 2.36859893e-05, 2.75609200e-04]),\n", - " array([ 7.07322174e+00, 2.10201129e+00, 7.07174003e+00, 2.10052958e+00,\n", - " 1.48999852e-04, -1.63267700e-02, 7.53950464e-04, -6.11505135e-05,\n", - " 2.34291402e-05, 2.71399139e-04]),\n", - " array([ 7.22054364e+00, 2.24711474e+00, 7.21914620e+00, 2.24571729e+00,\n", - " 1.50841785e-04, -1.63316514e-02, 7.36965263e-04, -6.10525541e-05,\n", - " 2.31756339e-05, 2.67304000e-04]),\n", - " array([ 7.35459234e+00, 2.38862374e+00, 7.35327884e+00, 2.38731024e+00,\n", - " 1.52555441e-04, -1.63049106e-02, 7.19660753e-04, -6.09423607e-05,\n", - " 2.29253578e-05, 2.63323798e-04]),\n", - " array([ 7.47573820e+00, 2.52647412e+00, 7.47450789e+00, 2.52524382e+00,\n", - " 1.54141483e-04, -1.62479718e-02, 7.02073424e-04, -6.08200751e-05,\n", - " 2.26782081e-05, 2.59458328e-04]),\n", - " array([ 7.58436232e+00, 2.66060946e+00, 7.58321408e+00, 2.65946122e+00,\n", - " 1.55600977e-04, -1.61622683e-02, 6.84238941e-04, -6.06858573e-05,\n", - " 2.24340886e-05, 2.55707168e-04]),\n", - " array([ 7.68085500e+00, 2.79098087e+00, 7.67978735e+00, 2.78991321e+00,\n", - " 1.56935363e-04, -1.60492392e-02, 6.66192106e-04, -6.05398851e-05,\n", - " 2.21929112e-05, 2.52069694e-04]),\n", - " array([ 7.76561431e+00, 2.91754680e+00, 7.76462544e+00, 2.91655793e+00,\n", - " 1.58146413e-04, -1.59103246e-02, 6.47966821e-04, -6.03823520e-05,\n", - " 2.19545949e-05, 2.48545089e-04]),\n", - " array([ 7.83904462e+00, 3.04027276e+00, 7.83813245e+00, 3.03936060e+00,\n", - " 1.59236207e-04, -1.57469620e-02, 6.29596051e-04, -6.02134667e-05,\n", - " 2.17190657e-05, 2.45132351e-04]),\n", - " array([ 7.90155529e+00, 3.15913114e+00, 7.90071752e+00, 3.15829336e+00,\n", - " 1.60207094e-04, -1.55605826e-02, 6.11111798e-04, -6.00334516e-05,\n", - " 2.14862563e-05, 2.41830307e-04]),\n", - " array([ 7.95355936e+00, 3.27410093e+00, 7.95279344e+00, 3.27333501e+00,\n", - " 1.61061663e-04, -1.53526079e-02, 5.92545071e-04, -5.98425417e-05,\n", - " 2.12561053e-05, 2.38637619e-04]),\n", - " array([ 7.99547228e+00, 3.38516751e+00, 7.99477551e+00, 3.38447073e+00,\n", - " 1.61802711e-04, -1.51244460e-02, 5.73925863e-04, -5.96409833e-05,\n", - " 2.10285572e-05, 2.35552799e-04]),\n", - " array([ 8.02771072e+00, 3.49232237e+00, 8.02708024e+00, 3.49169188e+00,\n", - " 1.62433218e-04, -1.48774892e-02, 5.55283133e-04, -5.94290332e-05,\n", - " 2.08035618e-05, 2.32574213e-04]),\n", - " array([ 8.05069145e+00, 3.59556293e+00, 8.05012427e+00, 3.59499576e+00,\n", - " 1.62956317e-04, -1.46131102e-02, 5.36644781e-04, -5.92069574e-05,\n", - " 2.05810739e-05, 2.29700095e-04]),\n", - " array([ 8.06483024e+00, 3.69489224e+00, 8.06432331e+00, 3.69438531e+00,\n", - " 1.63375266e-04, -1.43326602e-02, 5.18037644e-04, -5.89750301e-05,\n", - " 2.03610527e-05, 2.26928557e-04]),\n", - " array([ 8.07054087e+00, 3.79031875e+00, 8.07009105e+00, 3.78986893e+00,\n", - " 1.63693427e-04, -1.40374659e-02, 4.99487474e-04, -5.87335326e-05,\n", - " 2.01434615e-05, 2.24257595e-04]),\n", - " array([ 8.06823413e+00, 3.88185607e+00, 8.06783826e+00, 3.88146020e+00,\n", - " 1.63914241e-04, -1.37288272e-02, 4.81018936e-04, -5.84827524e-05,\n", - " 1.99282675e-05, 2.21685104e-04]),\n", - " array([ 8.05831696e+00, 3.96952274e+00, 8.05797185e+00, 3.96917762e+00,\n", - " 1.64041206e-04, -1.34080152e-02, 4.62655601e-04, -5.82229823e-05,\n", - " 1.97154409e-05, 2.19208880e-04]),\n", - " array([ 8.04119158e+00, 4.05334195e+00, 8.04089405e+00, 4.05304441e+00,\n", - " 1.64077858e-04, -1.30762701e-02, 4.44419942e-04, -5.79545194e-05,\n", - " 1.95049552e-05, 2.16826635e-04]),\n", - " array([ 8.01725472e+00, 4.13334133e+00, 8.01700160e+00, 4.13308821e+00,\n", - " 1.64027750e-04, -1.27347997e-02, 4.26333330e-04, -5.76776641e-05,\n", - " 1.92967864e-05, 2.14536005e-04]),\n", - " array([ 7.98689686e+00, 4.20955271e+00, 7.98668505e+00, 4.20934090e+00,\n", - " 1.63894439e-04, -1.23847772e-02, 4.08416042e-04, -5.73927196e-05,\n", - " 1.90909128e-05, 2.12334553e-04]),\n", - " array([ 7.95050161e+00, 4.28201187e+00, 7.95032804e+00, 4.28183830e+00,\n", - " 1.63681464e-04, -1.20273406e-02, 3.90687266e-04, -5.70999906e-05,\n", - " 1.88873147e-05, 2.10219786e-04]),\n", - " array([ 7.90844504e+00, 4.35075829e+00, 7.90830673e+00, 4.35061998e+00,\n", - " 1.63392339e-04, -1.16635907e-02, 3.73165104e-04, -5.67997830e-05,\n", - " 1.86859739e-05, 2.08189157e-04]),\n", - " array([ 7.86109515e+00, 4.41583497e+00, 7.86098919e+00, 4.41572901e+00,\n", - " 1.63030535e-04, -1.12945904e-02, 3.55866573e-04, -5.64924027e-05,\n", - " 1.84868740e-05, 2.06240073e-04]),\n", - " array([ 7.80881136e+00, 4.47728815e+00, 7.80873494e+00, 4.47721173e+00,\n", - " 1.62599470e-04, -1.09213640e-02, 3.38807632e-04, -5.61781552e-05,\n", - " 1.82899992e-05, 2.04369905e-04]),\n", - " array([ 7.75194402e+00, 4.53516712e+00, 7.75189443e+00, 4.53511753e+00,\n", - " 1.62102502e-04, -1.05448958e-02, 3.22003167e-04, -5.58573449e-05,\n", - " 1.80953350e-05, 2.02575995e-04]),\n", - " array([ 7.69083405e+00, 4.58952398e+00, 7.69080869e+00, 4.58949863e+00,\n", - " 1.61542908e-04, -1.01661300e-02, 3.05467086e-04, -5.55302744e-05,\n", - " 1.79028674e-05, 2.00855662e-04]),\n", - " array([ 7.62581254e+00, 4.64041344e+00, 7.62580894e+00, 4.64040984e+00,\n", - " 1.60923893e-04, -9.78597012e-03, 2.89212214e-04, -5.51972437e-05,\n", - " 1.77125829e-05, 1.99206207e-04]),\n", - " array([ 7.55720047e+00, 4.68789260e+00, 7.55721626e+00, 4.68790838e+00,\n", - " 1.60248574e-04, -9.40527867e-03, 2.73250394e-04, -5.48585502e-05,\n", - " 1.75244682e-05, 1.97624923e-04]),\n", - " array([ 7.48530842e+00, 4.73202073e+00, 7.48534137e+00, 4.73205367e+00,\n", - " 1.59519975e-04, -9.02487685e-03, 2.57592484e-04, -5.45144875e-05,\n", - " 1.73385103e-05, 1.96109099e-04]),\n", - " array([ 7.41043636e+00, 4.77285912e+00, 7.41048436e+00, 4.77290712e+00,\n", - " 1.58741025e-04, -8.64554460e-03, 2.42248382e-04, -5.41653452e-05,\n", - " 1.71546958e-05, 1.94656027e-04]),\n", - " array([ 7.33287348e+00, 4.81047084e+00, 7.33293454e+00, 4.81053191e+00,\n", - " 1.57914550e-04, -8.26802063e-03, 2.27227045e-04, -5.38114087e-05,\n", - " 1.69730116e-05, 1.93263005e-04]),\n", - " array([ 7.25289801e+00, 4.84492054e+00, 7.25297031e+00, 4.84499284e+00,\n", - " 1.57043276e-04, -7.89300258e-03, 2.12536511e-04, -5.34529583e-05,\n", - " 1.67934439e-05, 1.91927345e-04]),\n", - " array([ 7.17077720e+00, 4.87627432e+00, 7.17085900e+00, 4.87635612e+00,\n", - " 1.56129823e-04, -7.52114730e-03, 1.98183928e-04, -5.30902691e-05,\n", - " 1.66159788e-05, 1.90646377e-04]),\n", - " array([ 7.08676715e+00, 4.90459951e+00, 7.08685686e+00, 4.90468922e+00,\n", - " 1.55176704e-04, -7.15307124e-03, 1.84175577e-04, -5.27236105e-05,\n", - " 1.64406019e-05, 1.89417454e-04]),\n", - " array([ 7.00111287e+00, 4.92996449e+00, 7.00120903e+00, 4.93006065e+00,\n", - " 1.54186327e-04, -6.78935090e-03, 1.70516898e-04, -5.23532461e-05,\n", - " 1.62672980e-05, 1.88237954e-04]),\n", - " array([ 6.91404825e+00, 4.95243857e+00, 6.91414951e+00, 4.95253983e+00,\n", - " 1.53160995e-04, -6.43052340e-03, 1.57212519e-04, -5.19794331e-05,\n", - " 1.60960517e-05, 1.87105288e-04]),\n", - " array([ 6.82579608e+00, 4.97209178e+00, 6.82590121e+00, 4.97219691e+00,\n", - " 1.52102901e-04, -6.07708715e-03, 1.44266278e-04, -5.16024222e-05,\n", - " 1.59268466e-05, 1.86016902e-04]),\n", - " array([ 6.73656814e+00, 4.98899475e+00, 6.73667602e+00, 4.98910263e+00,\n", - " 1.51014139e-04, -5.72950253e-03, 1.31681259e-04, -5.12224574e-05,\n", - " 1.57596661e-05, 1.84970280e-04]),\n", - " array([ 6.64656528e+00, 5.00321854e+00, 6.64667492e+00, 5.00332818e+00,\n", - " 1.49896697e-04, -5.38819271e-03, 1.19459817e-04, -5.08397757e-05,\n", - " 1.55944924e-05, 1.83962945e-04]),\n", - " array([ 6.55597752e+00, 5.01483451e+00, 6.55608802e+00, 5.01494501e+00,\n", - " 1.48752463e-04, -5.05354446e-03, 1.07603605e-04, -5.04546070e-05,\n", - " 1.54313074e-05, 1.82992470e-04]),\n", - " array([ 6.46498424e+00, 5.02391419e+00, 6.46509480e+00, 5.02402475e+00,\n", - " 1.47583227e-04, -4.72590911e-03, 9.61136046e-05, -5.00671738e-05,\n", - " 1.52700921e-05, 1.82056470e-04]),\n", - " array([ 6.37375428e+00, 5.03052911e+00, 6.37386421e+00, 5.03063904e+00,\n", - " 1.46390684e-04, -4.40560349e-03, 8.49901563e-05, -4.96776915e-05,\n", - " 1.51108270e-05, 1.81152614e-04]),\n", - " array([ 6.28244618e+00, 5.03475076e+00, 6.28255487e+00, 5.03485944e+00,\n", - " 1.45176436e-04, -4.09291092e-03, 7.42329860e-05, -4.92863676e-05,\n", - " 1.49534917e-05, 1.80278620e-04]),\n", - " array([ 6.19120834e+00, 5.03665037e+00, 6.19131526e+00, 5.03675728e+00,\n", - " 1.43941994e-04, -3.78808227e-03, 6.38412392e-05, -4.88934023e-05,\n", - " 1.47980653e-05, 1.79432263e-04]),\n", - " array([ 6.10017926e+00, 5.03629888e+00, 6.10028396e+00, 5.03640358e+00,\n", - " 1.42688786e-04, -3.49133704e-03, 5.38135025e-05, -4.84989882e-05,\n", - " 1.46445264e-05, 1.78611373e-04]),\n", - " array([ 6.00948776e+00, 5.03376679e+00, 6.00958988e+00, 5.03386890e+00,\n", - " 1.41418154e-04, -3.20286448e-03, 4.41478477e-05, -4.81033100e-05,\n", - " 1.44928528e-05, 1.77813835e-04]),\n", - " array([ 5.91925323e+00, 5.02912408e+00, 5.91935246e+00, 5.02922331e+00,\n", - " 1.40131362e-04, -2.92282470e-03, 3.48418393e-05, -4.77065449e-05,\n", - " 1.43430218e-05, 1.77037597e-04]),\n", - " array([ 5.82958591e+00, 5.02244011e+00, 5.82968201e+00, 5.02253621e+00,\n", - " 1.38829598e-04, -2.65134986e-03, 2.58925800e-05, -4.73088627e-05,\n", - " 1.41950103e-05, 1.76280664e-04]),\n", - " array([ 5.74058713e+00, 5.01378354e+00, 5.74067992e+00, 5.01387633e+00,\n", - " 1.37513978e-04, -2.38854532e-03, 1.72967306e-05, -4.69104252e-05,\n", - " 1.40487946e-05, 1.75541103e-04]),\n", - " array([ 5.65234958e+00, 5.00322223e+00, 5.65243894e+00, 5.00331158e+00,\n", - " 1.36185549e-04, -2.13449081e-03, 9.05054111e-06, -4.65113869e-05,\n", - " 1.39043506e-05, 1.74817043e-04]),\n", - " array([ 5.56495766e+00, 4.99082317e+00, 5.56504350e+00, 4.99090901e+00,\n", - " 1.34845294e-04, -1.88924166e-03, 1.14987786e-06, -4.61118949e-05,\n", - " 1.37616538e-05, 1.74106675e-04]),\n", - " array([ 5.47848770e+00, 4.97665244e+00, 5.47856997e+00, 4.97673472e+00,\n", - " 1.33494135e-04, -1.65282995e-03, -6.40975122e-06, -4.57120887e-05,\n", - " 1.36206796e-05, 1.73408252e-04]),\n", - " array([ 5.39300828e+00, 4.96077510e+00, 5.39308700e+00, 4.96085382e+00,\n", - " 1.32132933e-04, -1.42526573e-03, -1.36331692e-05, -4.53121008e-05,\n", - " 1.34814029e-05, 1.72720089e-04]),\n", - " array([ 5.30858055e+00, 4.94325513e+00, 5.30865575e+00, 4.94333033e+00,\n", - " 1.30762498e-04, -1.20653818e-03, -2.05255050e-05, -4.49120563e-05,\n", - " 1.33437982e-05, 1.72040568e-04]),\n", - " array([ 5.22525853e+00, 4.92415544e+00, 5.22533027e+00, 4.92422718e+00,\n", - " 1.29383587e-04, -9.96616815e-04, -2.70921674e-05, -4.45120734e-05,\n", - " 1.32078402e-05, 1.71368129e-04]),\n", - " array([ 5.14308939e+00, 4.90353772e+00, 5.14315777e+00, 4.90360610e+00,\n", - " 1.27996911e-04, -7.95452644e-04, -3.33388227e-05, -4.41122634e-05,\n", - " 1.30735032e-05, 1.70701278e-04]),\n", - " array([ 5.06211380e+00, 4.88146250e+00, 5.06217893e+00, 4.88152762e+00,\n", - " 1.26603133e-04, -6.02979324e-04, -3.92713696e-05, -4.37127309e-05,\n", - " 1.29407615e-05, 1.70038582e-04]),\n", - " array([ 4.98236619e+00, 4.85798900e+00, 4.98242820e+00, 4.85805100e+00,\n", - " 1.25202878e-04, -4.19114296e-04, -4.48959158e-05, -4.33135740e-05,\n", - " 1.28095892e-05, 1.69378668e-04]),\n", - " array([ 4.90387509e+00, 4.83317519e+00, 4.90393413e+00, 4.83323422e+00,\n", - " 1.23796731e-04, -2.43759912e-04, -5.02187582e-05, -4.29148842e-05,\n", - " 1.26799606e-05, 1.68720228e-04]),\n", - " array([ 4.82666342e+00, 4.80707771e+00, 4.82671964e+00, 4.80713393e+00,\n", - " 1.22385240e-04, -7.68045286e-05, -5.52463581e-05, -4.25167470e-05,\n", - " 1.25518499e-05, 1.68062013e-04]),\n", - " array([ 4.75074879e+00, 4.77975184e+00, 4.75080238e+00, 4.77980543e+00,\n", - " 1.20968922e-04, 8.18764140e-05, -5.99853244e-05, -4.21192418e-05,\n", - " 1.24252313e-05, 1.67402832e-04]),\n", - " array([ 4.67614381e+00, 4.75125150e+00, 4.67619493e+00, 4.75130263e+00,\n", - " 1.19548262e-04, 2.32419343e-04, -6.44423908e-05, -4.17224421e-05,\n", - " 1.23000793e-05, 1.66741554e-04]),\n", - " array([ 4.60285636e+00, 4.72162921e+00, 4.60290521e+00, 4.72167806e+00,\n", - " 1.18123718e-04, 3.74971526e-04, -6.86243980e-05, -4.13264159e-05,\n", - " 1.21763684e-05, 1.66077107e-04]),\n", - " array([ 4.53088990e+00, 4.69093608e+00, 4.53093666e+00, 4.69098285e+00,\n", - " 1.16695721e-04, 5.09690080e-04, -7.25382756e-05, -4.09312257e-05,\n", - " 1.20540733e-05, 1.65408475e-04]),\n", - " array([ 4.46024375e+00, 4.65922181e+00, 4.46028861e+00, 4.65926668e+00,\n", - " 1.15264679e-04, 6.36740998e-04, -7.61910248e-05, -4.05369287e-05,\n", - " 1.19331689e-05, 1.64734698e-04]),\n", - " array([ 4.39091334e+00, 4.62653466e+00, 4.39095650e+00, 4.62657782e+00,\n", - " 1.13830981e-04, 7.56298218e-04, -7.95897021e-05, -4.01435771e-05,\n", - " 1.18136304e-05, 1.64054869e-04]),\n", - " array([ 4.32289055e+00, 4.59292146e+00, 4.32293218e+00, 4.59296310e+00,\n", - " 1.12394993e-04, 8.68542717e-04, -8.27414023e-05, -3.97512185e-05,\n", - " 1.16954330e-05, 1.63368136e-04]),\n", - " array([ 4.25616387e+00, 4.55842761e+00, 4.25620417e+00, 4.55846791e+00,\n", - " 1.10957065e-04, 9.73661641e-04, -8.56532449e-05, -3.93598956e-05,\n", - " 1.15785526e-05, 1.62673699e-04]),\n", - " array([ 4.19071875e+00, 4.52309706e+00, 4.19075790e+00, 4.52313621e+00,\n", - " 1.09517532e-04, 1.07184746e-03, -8.83323595e-05, -3.89696468e-05,\n", - " 1.14629649e-05, 1.61970807e-04]),\n", - " array([ 4.12653782e+00, 4.48697235e+00, 4.12657599e+00, 4.48701052e+00,\n", - " 1.08076715e-04, 1.16329718e-03, -9.07858724e-05, -3.85805064e-05,\n", - " 1.13486463e-05, 1.61258761e-04]),\n", - " array([ 4.06360110e+00, 4.45009457e+00, 4.06363847e+00, 4.45013193e+00,\n", - " 1.06634920e-04, 1.24821155e-03, -9.30208947e-05, -3.81925047e-05,\n", - " 1.12355734e-05, 1.60536908e-04]),\n", - " array([ 4.00188629e+00, 4.41250342e+00, 4.00192301e+00, 4.41254015e+00,\n", - " 1.05192445e-04, 1.32679434e-03, -9.50445109e-05, -3.78056680e-05,\n", - " 1.11237230e-05, 1.59804642e-04]),\n", - " array([ 3.94136893e+00, 4.37423719e+00, 3.94140518e+00, 4.37427343e+00,\n", - " 1.03749575e-04, 1.39925164e-03, -9.68637664e-05, -3.74200194e-05,\n", - " 1.10130724e-05, 1.59061401e-04]),\n", - " array([ 3.88202270e+00, 4.33533276e+00, 3.88205861e+00, 4.33536867e+00,\n", - " 1.02306590e-04, 1.46579119e-03, -9.84856573e-05, -3.70355783e-05,\n", - " 1.09035993e-05, 1.58306669e-04]),\n", - " array([ 3.82381955e+00, 4.29582566e+00, 3.82385527e+00, 4.29586138e+00,\n", - " 1.00863760e-04, 1.52662174e-03, -9.99171233e-05, -3.66523610e-05,\n", - " 1.07952816e-05, 1.57539969e-04]),\n", - " array([ 3.76672995e+00, 4.25575006e+00, 3.76676562e+00, 4.25578574e+00,\n", - " 9.94213500e-05, 1.58195246e-03, -1.01165036e-04, -3.62703811e-05,\n", - " 1.06880976e-05, 1.56760868e-04]),\n", - " array([ 3.71072306e+00, 4.21513880e+00, 3.71075881e+00, 4.21517455e+00,\n", - " 9.79796183e-05, 1.63199240e-03, -1.02236194e-04, -3.58896489e-05,\n", - " 1.05820260e-05, 1.55968968e-04]),\n", - " array([ 3.65576693e+00, 4.17402339e+00, 3.65580288e+00, 4.17405934e+00,\n", - " 9.65388201e-05, 1.67694991e-03, -1.03137312e-04, -3.55101724e-05,\n", - " 1.04770458e-05, 1.55163914e-04]),\n", - " array([ 3.60182866e+00, 4.13243407e+00, 3.60186492e+00, 4.13247032e+00,\n", - " 9.50992064e-05, 1.71703219e-03, -1.03875014e-04, -3.51319573e-05,\n", - " 1.03731364e-05, 1.54345381e-04]),\n", - " array([ 3.54887460e+00, 4.09039980e+00, 3.54891127e+00, 4.09043647e+00,\n", - " 9.36610255e-05, 1.75244480e-03, -1.04455833e-04, -3.47550067e-05,\n", - " 1.02702775e-05, 1.53513084e-04]),\n", - " array([ 3.49687043e+00, 4.04794832e+00, 3.49690762e+00, 4.04798550e+00,\n", - " 9.22245235e-05, 1.78339122e-03, -1.04886196e-04, -3.43793217e-05,\n", - " 1.01684492e-05, 1.52666769e-04]),\n", - " array([ 3.44578142e+00, 4.00510615e+00, 3.44581921e+00, 4.00514393e+00,\n", - " 9.07899451e-05, 1.81007250e-03, -1.05172429e-04, -3.40049017e-05,\n", - " 1.00676319e-05, 1.51806213e-04]),\n", - " array([ 3.39557249e+00, 3.96189864e+00, 3.39561095e+00, 3.96193711e+00,\n", - " 8.93575341e-05, 1.83268685e-03, -1.05320744e-04, -3.36317441e-05,\n", - " 9.96780626e-06, 1.50931224e-04]),\n", - " array([ 3.34620836e+00, 3.91834998e+00, 3.34624758e+00, 3.91838921e+00,\n", - " 8.79275337e-05, 1.85142928e-03, -1.05337240e-04, -3.32598447e-05,\n", - " 9.86895324e-06, 1.50041639e-04]),\n", - " array([ 3.29765371e+00, 3.87448326e+00, 3.29769376e+00, 3.87452331e+00,\n", - " 8.65001874e-05, 1.86649137e-03, -1.05227897e-04, -3.28891979e-05,\n", - " 9.77105414e-06, 1.49137324e-04]),\n", - " array([ 3.24987326e+00, 3.83032047e+00, 3.24991419e+00, 3.83036140e+00,\n", - " 8.50757391e-05, 1.87806089e-03, -1.04998576e-04, -3.25197967e-05,\n", - " 9.67409050e-06, 1.48218168e-04]),\n", - " array([ 3.20283191e+00, 3.78588255e+00, 3.20287378e+00, 3.78592442e+00,\n", - " 8.36544334e-05, 1.88632165e-03, -1.04655014e-04, -3.21516330e-05,\n", - " 9.57804408e-06, 1.47284087e-04]),\n", - " array([ 3.15649480e+00, 3.74118942e+00, 3.15653765e+00, 3.74123228e+00,\n", - " 8.22365164e-05, 1.89145317e-03, -1.04202820e-04, -3.17846974e-05,\n", - " 9.48289691e-06, 1.46335022e-04]),\n", - " array([ 3.11082746e+00, 3.69626004e+00, 3.11087134e+00, 3.69630393e+00,\n", - " 8.08222354e-05, 1.89363058e-03, -1.03647480e-04, -3.14189799e-05,\n", - " 9.38863119e-06, 1.45370932e-04]),\n", - " array([ 3.06579587e+00, 3.65111241e+00, 3.06584082e+00, 3.65115735e+00,\n", - " 7.94118395e-05, 1.89302435e-03, -1.02994346e-04, -3.10544692e-05,\n", - " 9.29522932e-06, 1.44391801e-04]),\n", - " array([ 3.02136655e+00, 3.60576359e+00, 3.02141260e+00, 3.60580964e+00,\n", - " 7.80055795e-05, 1.88980022e-03, -1.02248645e-04, -3.06911536e-05,\n", - " 9.20267387e-06, 1.43397631e-04]),\n", - " array([ 2.97750663e+00, 3.56022982e+00, 2.97755379e+00, 3.56027699e+00,\n", - " 7.66037084e-05, 1.88411903e-03, -1.01415469e-04, -3.03290208e-05,\n", - " 9.11094752e-06, 1.42388443e-04]),\n", - " array([ 2.93418390e+00, 3.51452646e+00, 2.93423221e+00, 3.51457477e+00,\n", - " 7.52064815e-05, 1.87613659e-03, -1.00499783e-04, -2.99680576e-05,\n", - " 9.02003309e-06, 1.41364274e-04]),\n", - " array([ 2.89136694e+00, 3.46866807e+00, 2.89141641e+00, 3.46871754e+00,\n", - " 7.38141561e-05, 1.86600366e-03, -9.95064186e-05, -2.96082508e-05,\n", - " 8.92991347e-06, 1.40325181e-04]),\n", - " array([ 2.84902510e+00, 3.42266848e+00, 2.84907574e+00, 3.42271913e+00,\n", - " 7.24269921e-05, 1.85386583e-03, -9.84400779e-05, -2.92495864e-05,\n", - " 8.84057162e-06, 1.39271233e-04]),\n", - " array([ 2.80712860e+00, 3.37654076e+00, 2.80718042e+00, 3.37659258e+00,\n", - " 7.10452515e-05, 1.83986348e-03, -9.73053300e-05, -2.88920506e-05,\n", - " 8.75199051e-06, 1.38202513e-04]),\n", - " array([ 2.76564855e+00, 3.33029730e+00, 2.76570156e+00, 3.33035031e+00,\n", - " 6.96691989e-05, 1.82413177e-03, -9.61066150e-05, -2.85356289e-05,\n", - " 8.66415314e-06, 1.37119121e-04]),\n", - " array([ 2.72455701e+00, 3.28394984e+00, 2.72461121e+00, 3.28400404e+00,\n", - " 6.82991011e-05, 1.80680063e-03, -9.48482421e-05, -2.81803070e-05,\n", - " 8.57704248e-06, 1.36021166e-04]),\n", - " array([ 2.68382704e+00, 3.23750950e+00, 2.68388242e+00, 3.23756489e+00,\n", - " 6.69352273e-05, 1.78799473e-03, -9.35343954e-05, -2.78260705e-05,\n", - " 8.49064144e-06, 1.34908769e-04]),\n", - " array([ 2.64343267e+00, 3.19098684e+00, 2.64348925e+00, 3.19104341e+00,\n", - " 6.55778489e-05, 1.76783352e-03, -9.21691293e-05, -2.74729047e-05,\n", - " 8.40493286e-06, 1.33782061e-04]),\n", - " array([ 2.60334902e+00, 3.14439186e+00, 2.60340677e+00, 3.14444961e+00,\n", - " 6.42272395e-05, 1.74643128e-03, -9.07563714e-05, -2.71207953e-05,\n", - " 8.31989948e-06, 1.32641185e-04]),\n", - " array([ 2.56355223e+00, 3.09773406e+00, 2.56361115e+00, 3.09779298e+00,\n", - " 6.28836748e-05, 1.72389714e-03, -8.92999245e-05, -2.67697279e-05,\n", - " 8.23552387e-06, 1.31486291e-04]),\n", - " array([ 2.52401955e+00, 3.05102249e+00, 2.52407964e+00, 3.05108258e+00,\n", - " 6.15474323e-05, 1.70033514e-03, -8.78034691e-05, -2.64196883e-05,\n", - " 8.15178845e-06, 1.30317538e-04]),\n", - " array([ 2.48472933e+00, 3.00426577e+00, 2.48479056e+00, 3.00432700e+00,\n", - " 6.02187912e-05, 1.67584430e-03, -8.62705642e-05, -2.60706623e-05,\n", - " 8.06867545e-06, 1.29135090e-04]),\n", - " array([ 2.44566100e+00, 2.95747210e+00, 2.44572338e+00, 2.95753447e+00,\n", - " 5.88980326e-05, 1.65051872e-03, -8.47046470e-05, -2.57226362e-05,\n", - " 7.98616686e-06, 1.27939120e-04]),\n", - " array([ 2.40679516e+00, 2.91064936e+00, 2.40685866e+00, 2.91071286e+00,\n", - " 5.75854388e-05, 1.62444765e-03, -8.31090378e-05, -2.53755964e-05,\n", - " 7.90424441e-06, 1.26729806e-04]),\n", - " array([ 2.36811350e+00, 2.86380509e+00, 2.36817812e+00, 2.86386970e+00,\n", - " 5.62812936e-05, 1.59771559e-03, -8.14869396e-05, -2.50295296e-05,\n", - " 7.82288956e-06, 1.25507333e-04]),\n", - " array([ 2.32959886e+00, 2.81694655e+00, 2.32966457e+00, 2.81701227e+00,\n", - " 5.49858816e-05, 1.57040238e-03, -7.98414413e-05, -2.46844229e-05,\n", - " 7.74208344e-06, 1.24271888e-04]),\n", - " array([ 2.29123520e+00, 2.77008076e+00, 2.29130200e+00, 2.77014756e+00,\n", - " 5.36994885e-05, 1.54258337e-03, -7.81755192e-05, -2.43402635e-05,\n", - " 7.66180683e-06, 1.23023664e-04]),\n", - " array([ 2.25300761e+00, 2.72321451e+00, 2.25307549e+00, 2.72328240e+00,\n", - " 5.24224004e-05, 1.51432946e-03, -7.64920383e-05, -2.39970393e-05,\n", - " 7.58204014e-06, 1.21762857e-04]),\n", - " array([ 2.21490232e+00, 2.67635443e+00, 2.21497127e+00, 2.67642338e+00,\n", - " 5.11549038e-05, 1.48570730e-03, -7.47937555e-05, -2.36547383e-05,\n", - " 7.50276338e-06, 1.20489666e-04]),\n", - " array([ 2.17690667e+00, 2.62950698e+00, 2.17697669e+00, 2.62957700e+00,\n", - " 4.98972854e-05, 1.45677935e-03, -7.30833210e-05, -2.33133492e-05,\n", - " 7.42395612e-06, 1.19204293e-04]),\n", - " array([ 2.13900912e+00, 2.58267853e+00, 2.13908019e+00, 2.58274961e+00,\n", - " 4.86498321e-05, 1.42760409e-03, -7.13632812e-05, -2.29728609e-05,\n", - " 7.34559747e-06, 1.17906942e-04]),\n", - " array([ 2.10119923e+00, 2.53587537e+00, 2.10127135e+00, 2.53594750e+00,\n", - " 4.74128302e-05, 1.39823609e-03, -6.96360803e-05, -2.26332628e-05,\n", - " 7.26766604e-06, 1.16597819e-04]),\n", - " array([ 2.06346764e+00, 2.48910372e+00, 2.06354083e+00, 2.48917691e+00,\n", - " 4.61865656e-05, 1.36872620e-03, -6.79040625e-05, -2.22945448e-05,\n", - " 7.19013994e-06, 1.15277132e-04]),\n", - " array([ 2.02580611e+00, 2.44236981e+00, 2.02588036e+00, 2.44244406e+00,\n", - " 4.49713232e-05, 1.33912167e-03, -6.61694742e-05, -2.19566972e-05,\n", - " 7.11299671e-06, 1.13945087e-04]),\n", - " array([ 1.98820742e+00, 2.39567989e+00, 1.98828275e+00, 2.39575521e+00,\n", - " 4.37673870e-05, 1.30946630e-03, -6.44344662e-05, -2.16197108e-05,\n", - " 7.03621334e-06, 1.12601895e-04]),\n", - " array([ 1.95066545e+00, 2.34904022e+00, 1.95074186e+00, 2.34911663e+00,\n", - " 4.25750394e-05, 1.27980059e-03, -6.27010963e-05, -2.12835771e-05,\n", - " 6.95976619e-06, 1.11247765e-04]),\n", - " array([ 1.91317508e+00, 2.30245718e+00, 1.91325260e+00, 2.30253471e+00,\n", - " 4.13945614e-05, 1.25016189e-03, -6.09713309e-05, -2.09482878e-05,\n", - " 6.88363101e-06, 1.09882905e-04]),\n", - " array([ 1.87573223e+00, 2.25593725e+00, 1.87581089e+00, 2.25601590e+00,\n", - " 4.02262318e-05, 1.22058455e-03, -5.92470478e-05, -2.06138353e-05,\n", - " 6.80778290e-06, 1.08507526e-04]),\n", - " array([ 1.83833385e+00, 2.20948702e+00, 1.83841367e+00, 2.20956684e+00,\n", - " 3.90703276e-05, 1.19110007e-03, -5.75300382e-05, -2.02802125e-05,\n", - " 6.73219625e-06, 1.07121836e-04]),\n", - " array([ 1.80097783e+00, 2.16311327e+00, 1.80105886e+00, 2.16319430e+00,\n", - " 3.79271231e-05, 1.16173723e-03, -5.58220092e-05, -1.99474127e-05,\n", - " 6.65684477e-06, 1.05726043e-04]),\n", - " array([ 1.76366308e+00, 2.11682297e+00, 1.76374536e+00, 2.11690525e+00,\n", - " 3.67968898e-05, 1.13252229e-03, -5.41245854e-05, -1.96154299e-05,\n", - " 6.58170143e-06, 1.04320356e-04]),\n", - " array([ 1.72638944e+00, 2.07062329e+00, 1.72647302e+00, 2.07070688e+00,\n", - " 3.56798963e-05, 1.10347906e-03, -5.24393122e-05, -1.92842586e-05,\n", - " 6.50673843e-06, 1.02904979e-04]),\n", - " array([ 1.68915769e+00, 2.02452169e+00, 1.68924264e+00, 2.02460663e+00,\n", - " 3.45764077e-05, 1.07462912e-03, -5.07676569e-05, -1.89538939e-05,\n", - " 6.43192719e-06, 1.01480118e-04]),\n", - " array([ 1.65196954e+00, 1.97852585e+00, 1.65205591e+00, 1.97861222e+00,\n", - " 3.34866858e-05, 1.04599191e-03, -4.91110120e-05, -1.86243312e-05,\n", - " 6.35723834e-06, 1.00045978e-04]),\n", - " array([ 1.61482758e+00, 1.93264378e+00, 1.61491545e+00, 1.93273165e+00,\n", - " 3.24109879e-05, 1.01758491e-03, -4.74706965e-05, -1.82955668e-05,\n", - " 6.28264164e-06, 9.86027597e-05]),\n", - " array([ 1.57773531e+00, 1.88688380e+00, 1.57782475e+00, 1.88697325e+00,\n", - " 3.13495676e-05, 9.89423750e-04, -4.58479589e-05, -1.79675973e-05,\n", - " 6.20810603e-06, 9.71506646e-05]),\n", - " array([ 1.54069707e+00, 1.84125460e+00, 1.54078818e+00, 1.84134570e+00,\n", - " 3.03026736e-05, 9.61522367e-04, -4.42439787e-05, -1.76404201e-05,\n", - " 6.13359956e-06, 9.56898915e-05]),\n", - " array([ 1.50371808e+00, 1.79576520e+00, 1.50381093e+00, 1.79585805e+00,\n", - " 2.92705496e-05, 9.33893126e-04, -4.26598693e-05, -1.73140330e-05,\n", - " 6.05908935e-06, 9.42206376e-05]),\n", - " array([ 1.46680436e+00, 1.75042504e+00, 1.46689903e+00, 1.75051972e+00,\n", - " 2.82534344e-05, 9.06546959e-04, -4.10966797e-05, -1.69884345e-05,\n", - " 5.98454163e-06, 9.27430981e-05]),\n", - " array([ 1.42996276e+00, 1.70524397e+00, 1.43005935e+00, 1.70534056e+00,\n", - " 2.72515608e-05, 8.79493485e-04, -3.95553966e-05, -1.66636236e-05,\n", - " 5.90992167e-06, 9.12574662e-05]),\n", - " array([ 1.39320092e+00, 1.66023227e+00, 1.39329951e+00, 1.66033086e+00,\n", - " 2.62651559e-05, 8.52741142e-04, -3.80369469e-05, -1.63396000e-05,\n", - " 5.83519374e-06, 8.97639332e-05]),\n", - " array([ 1.35652727e+00, 1.61540068e+00, 1.35662794e+00, 1.61550135e+00,\n", - " 2.52944403e-05, 8.26297301e-04, -3.65421998e-05, -1.60163637e-05,\n", - " 5.76032116e-06, 8.82626882e-05]),\n", - " array([ 1.31995101e+00, 1.57076040e+00, 1.32005383e+00, 1.57086323e+00,\n", - " 2.43396281e-05, 8.00168382e-04, -3.50719685e-05, -1.56939158e-05,\n", - " 5.68526619e-06, 8.67539180e-05]),\n", - " array([ 1.28348207e+00, 1.52632316e+00, 1.28358710e+00, 1.52642820e+00,\n", - " 2.34009260e-05, 7.74359972e-04, -3.36270125e-05, -1.53722576e-05,\n", - " 5.60999010e-06, 8.52378074e-05]),\n", - " array([ 1.24713113e+00, 1.48210117e+00, 1.24723842e+00, 1.48220846e+00,\n", - " 2.24785335e-05, 7.48876928e-04, -3.22080398e-05, -1.50513912e-05,\n", - " 5.53445304e-06, 8.37145389e-05]),\n", - " array([ 1.21090960e+00, 1.43810718e+00, 1.21101917e+00, 1.43821675e+00,\n", - " 2.15726419e-05, 7.23723484e-04, -3.08157088e-05, -1.47313193e-05,\n", - " 5.45861414e-06, 8.21842925e-05]),\n", - " array([ 1.17482959e+00, 1.39435449e+00, 1.17494143e+00, 1.39446633e+00,\n", - " 2.06834346e-05, 6.98903347e-04, -2.94506299e-05, -1.44120452e-05,\n", - " 5.38243139e-06, 8.06472463e-05]),\n", - " array([ 1.13890389e+00, 1.35085698e+00, 1.13901797e+00, 1.35097105e+00,\n", - " 1.98110858e-05, 6.74419799e-04, -2.81133682e-05, -1.40935727e-05,\n", - " 5.30586166e-06, 7.91035756e-05]),\n", - " array([ 1.10314601e+00, 1.30762907e+00, 1.10326224e+00, 1.30774530e+00,\n", - " 1.89557610e-05, 6.50275781e-04, -2.68044448e-05, -1.37759066e-05,\n", - " 5.22886069e-06, 7.75534536e-05]),\n", - " array([ 1.06757010e+00, 1.26468582e+00, 1.06768836e+00, 1.26480408e+00,\n", - " 1.81176160e-05, 6.26473985e-04, -2.55243386e-05, -1.34590519e-05,\n", - " 5.15138305e-06, 7.59970512e-05]),\n", - " array([ 1.03219099e+00, 1.22204286e+00, 1.03231110e+00, 1.22216298e+00,\n", - " 1.72967968e-05, 6.03016933e-04, -2.42734888e-05, -1.31430146e-05,\n", - " 5.07338212e-06, 7.44345366e-05]),\n", - " array([ 9.97024141e-01, 1.17971647e+00, 9.97145864e-01, 1.17983819e+00,\n", - " 1.64934391e-05, 5.79907058e-04, -2.30522959e-05, -1.28278012e-05,\n", - " 4.99481008e-06, 7.28660758e-05]),\n", - " array([ 9.62085681e-01, 1.13772355e+00, 9.62208692e-01, 1.13784656e+00,\n", - " 1.57076681e-05, 5.57146771e-04, -2.18611239e-05, -1.25134189e-05,\n", - " 4.91561790e-06, 7.12918324e-05]),\n", - " array([ 9.27392353e-01, 1.09608166e+00, 9.27516248e-01, 1.09620555e+00,\n", - " 1.49395981e-05, 5.34738538e-04, -2.07003018e-05, -1.21998754e-05,\n", - " 4.83575528e-06, 6.97119673e-05]),\n", - " array([ 8.92961527e-01, 1.05480899e+00, 8.93085809e-01, 1.05493328e+00,\n", - " 1.41893324e-05, 5.12684936e-04, -1.95701252e-05, -1.18871794e-05,\n", - " 4.75517067e-06, 6.81266392e-05]),\n", - " array([ 8.58811189e-01, 1.01392444e+00, 8.58935255e-01, 1.01404850e+00,\n", - " 1.34569630e-05, 4.90988719e-04, -1.84708580e-05, -1.15753399e-05,\n", - " 4.67381124e-06, 6.65360041e-05]),\n", - " array([ 8.24959936e-01, 9.73447544e-01, 8.25083065e-01, 9.73570674e-01,\n", - " 1.27425706e-05, 4.69652871e-04, -1.74027338e-05, -1.12643669e-05,\n", - " 4.59162285e-06, 6.49402157e-05]),\n", - " array([ 7.91426962e-01, 9.33398550e-01, 7.91548310e-01, 9.33519898e-01,\n", - " 1.20462245e-05, 4.48680653e-04, -1.63659573e-05, -1.09542708e-05,\n", - " 4.50855006e-06, 6.33394249e-05]),\n", - " array([ 7.58232060e-01, 8.93798393e-01, 7.58350641e-01, 8.93916974e-01,\n", - " 1.13679830e-05, 4.28075655e-04, -1.53607057e-05, -1.06450629e-05,\n", - " 4.42453606e-06, 6.17337804e-05]),\n", - " array([ 7.25395612e-01, 8.54668707e-01, 7.25510295e-01, 8.54783390e-01,\n", - " 1.07078934e-05, 4.07841837e-04, -1.43871302e-05, -1.03367552e-05,\n", - " 4.33952271e-06, 6.01234280e-05]),\n", - " array([ 6.92938585e-01, 8.16031835e-01, 6.93048079e-01, 8.16141329e-01,\n", - " 1.00659926e-05, 3.87983562e-04, -1.34453567e-05, -1.00293601e-05,\n", - " 4.25345046e-06, 5.85085110e-05]),\n", - " array([ 6.60882524e-01, 7.77910833e-01, 6.60985374e-01, 7.78013683e-01,\n", - " 9.44230750e-06, 3.68505634e-04, -1.25354878e-05, -9.72289095e-06,\n", - " 4.16625841e-06, 5.68891702e-05]),\n", - " array([ 6.29249552e-01, 7.40329474e-01, 6.29344130e-01, 7.40424052e-01,\n", - " 8.83685622e-06, 3.49413326e-04, -1.16576030e-05, -9.41736178e-06,\n", - " 4.07788422e-06, 5.52655434e-05]),\n", - " array([ 5.98062361e-01, 7.03312252e-01, 5.98146862e-01, 7.03396754e-01,\n", - " 8.24964880e-06, 3.30712403e-04, -1.08117600e-05, -9.11278724e-06,\n", - " 3.98826411e-06, 5.36377661e-05]),\n", - " array([ 5.67344211e-01, 6.66884385e-01, 5.67416653e-01, 6.66956826e-01,\n", - " 7.68068875e-06, 3.12409144e-04, -9.99799601e-06, -8.80918271e-06,\n", - " 3.89733288e-06, 5.20059707e-05]),\n", - " array([ 5.37118928e-01, 6.31071813e-01, 5.37177149e-01, 6.31130034e-01,\n", - " 7.12997465e-06, 2.94510359e-04, -9.21632782e-06, -8.50656428e-06,\n", - " 3.80502385e-06, 5.03702869e-05]),\n", - " array([ 5.07410899e-01, 5.95901206e-01, 5.07452565e-01, 5.95942873e-01,\n", - " 6.59750211e-06, 2.77023401e-04, -8.46675302e-06, -8.20494873e-06,\n", - " 3.71126886e-06, 4.87308415e-05]),\n", - " array([ 4.78245066e-01, 5.61399956e-01, 4.78267683e-01, 5.61422573e-01,\n", - " 6.08326618e-06, 2.59956171e-04, -7.74925036e-06, -7.90435357e-06,\n", - " 3.61599824e-06, 4.70877584e-05]),\n", - " array([ 4.49646930e-01, 5.27596179e-01, 4.49647855e-01, 5.27597104e-01,\n", - " 5.58726401e-06, 2.43317129e-04, -7.06378030e-06, -7.60479702e-06,\n", - " 3.51914083e-06, 4.54411586e-05]),\n", - " array([ 4.21642544e-01, 4.94518715e-01, 4.21619007e-01, 4.94495177e-01,\n", - " 5.10949808e-06, 2.27115287e-04, -6.41028535e-06, -7.30629802e-06,\n", - " 3.42062390e-06, 4.37911600e-05]),\n", - " array([ 3.94258511e-01, 4.62197117e-01, 3.94207644e-01, 4.62146250e-01,\n", - " 4.64997978e-06, 2.11360212e-04, -5.78869038e-06, -7.00887624e-06,\n", - " 3.32037322e-06, 4.21378772e-05]),\n", - " array([ 3.67521981e-01, 4.30661656e-01, 3.67440857e-01, 4.30580531e-01,\n", - " 4.20873350e-06, 1.96062016e-04, -5.19890266e-06, -6.71255212e-06,\n", - " 3.21831295e-06, 4.04814218e-05]),\n", - " array([ 3.41460649e-01, 3.99943305e-01, 3.41346324e-01, 3.99828981e-01,\n", - " 3.78580126e-06, 1.81231347e-04, -4.64081200e-06, -6.41734683e-06,\n", - " 3.11436569e-06, 3.88219021e-05]),\n", - " array([ 3.16102754e-01, 3.70073743e-01, 3.15952326e-01, 3.69923315e-01,\n", - " 3.38124772e-06, 1.66879373e-04, -4.11429055e-06, -6.12328234e-06,\n", - " 3.00845245e-06, 3.71594230e-05]),\n", - " array([ 2.91477073e-01, 3.41085337e-01, 2.91287745e-01, 3.40896009e-01,\n", - " 2.99516586e-06, 1.53017771e-04, -3.61919264e-06, -5.83038139e-06,\n", - " 2.90049263e-06, 3.54940860e-05]),\n", - " array([ 2.67612921e-01, 3.13011142e-01, 2.67382083e-01, 3.12780304e-01,\n", - " 2.62768310e-06, 1.39658706e-04, -3.15535442e-06, -5.53866758e-06,\n", - " 2.79040400e-06, 3.38259889e-05]),\n", - " array([ 2.44540144e-01, 2.85884885e-01, 2.44265465e-01, 2.85610205e-01,\n", - " 2.27896787e-06, 1.26814807e-04, -2.72259345e-06, -5.24816536e-06,\n", - " 2.67810267e-06, 3.21552261e-05]),\n", - " array([ 2.22289122e-01, 2.59740957e-01, 2.21968653e-01, 2.59420488e-01,\n", - " 1.94923674e-06, 1.14499151e-04, -2.32070809e-06, -4.95890006e-06,\n", - " 2.56350314e-06, 3.04818883e-05]),\n", - " array([ 2.00890757e-01, 2.34614405e-01, 2.00523056e-01, 2.34246704e-01,\n", - " 1.63876198e-06, 1.02725230e-04, -1.94947692e-06, -4.67089798e-06,\n", - " 2.44651820e-06, 2.88060621e-05]),\n", - " array([ 1.80376477e-01, 2.10540914e-01, 1.79960745e-01, 2.10125182e-01,\n", - " 1.34787941e-06, 9.15069316e-05, -1.60865792e-06, -4.38418643e-06,\n", - " 2.32705900e-06, 2.71278306e-05]),\n", - " array([ 1.60778227e-01, 1.87556799e-01, 1.60314458e-01, 1.87093031e-01,\n", - " 1.07699665e-06, 8.08585100e-05, -1.29798767e-06, -4.09879376e-06,\n", - " 2.20503496e-06, 2.54472726e-05]),\n", - " array([ 1.42128467e-01, 1.65698993e-01, 1.41617622e-01, 1.65188148e-01,\n", - " 8.26601515e-07, 7.07945558e-05, -1.01718042e-06, -3.81474949e-06,\n", - " 2.08035383e-06, 2.37644629e-05]),\n", - " array([ 1.24460169e-01, 1.45005030e-01, 1.23904359e-01, 1.44449219e-01,\n", - " 5.97270506e-07, 6.13299697e-05, -7.65927162e-07, -3.53208437e-06,\n", - " 1.95292161e-06, 2.20794723e-05]),\n", - " array([ 1.07806809e-01, 1.25513035e-01, 1.07209500e-01, 1.24915726e-01,\n", - " 3.89677191e-07, 5.24799322e-05, -5.43894544e-07, -3.25083048e-06,\n", - " 1.82264259e-06, 2.03923669e-05]),\n", - " array([ 9.22023691e-02, 1.07261714e-01, 9.15685994e-02, 1.06627944e-01,\n", - " 2.04600352e-07, 4.42598752e-05, -3.50723886e-07, -2.97102136e-06,\n", - " 1.68941932e-06, 1.87032087e-05]),\n", - " array([ 7.76813288e-02, 9.02903347e-02, 7.70179458e-02, 8.96269517e-02,\n", - " 4.29316384e-08, 3.66854524e-05, -1.86030110e-07, -2.69269214e-06,\n", - " 1.55315259e-06, 1.70120553e-05]),\n", - " array([ 6.42786663e-02, 7.46387232e-02, 6.35945716e-02, 7.39546285e-02,\n", - " -9.43175206e-08, 2.97725115e-05, -4.94007327e-08, -2.41587965e-06,\n", - " 1.41374145e-06, 1.53189593e-05]),\n", - " array([ 5.20298551e-02, 6.03472486e-02, 5.13362644e-02, 5.96536579e-02,\n", - " -2.06010032e-07, 2.35370658e-05, 5.96051053e-08, -2.14062266e-06,\n", - " 1.27108314e-06, 1.36239690e-05]),\n", - " array([ 4.09708644e-02, 4.74568166e-02, 4.02815746e-02, 4.67675268e-02,\n", - " -2.90878627e-07, 1.79952679e-05, 1.41457507e-07, -1.86696197e-06,\n", - " 1.12507317e-06, 1.19271277e-05]),\n", - " array([ 3.11381600e-02, 3.60088627e-02, 3.04698216e-02, 3.53405244e-02,\n", - " -3.47523096e-07, 1.31633842e-05, 1.96656558e-07, -1.59494069e-06,\n", - " 9.75605217e-07, 1.02284738e-05]),\n", - " array([ 2.25687076e-02, 2.60453481e-02, 2.19410976e-02, 2.54177381e-02,\n", - " -3.74409712e-07, 9.05777104e-06, 2.25732895e-07, -1.32460442e-06,\n", - " 8.22571196e-07, 8.52804084e-06]),\n", - " array([ 1.52999785e-02, 1.76087584e-02, 1.47362682e-02, 1.70450482e-02,\n", - " -3.69873318e-07, 5.69485303e-06, 2.29248030e-07, -1.05600146e-06,\n", - " 6.65861203e-07, 6.82585718e-06]),\n", - " array([ 9.36995823e-03, 1.07421068e-02, 8.89696989e-03, 1.02691184e-02,\n", - " -3.32122597e-07, 3.09110359e-06, 2.07794405e-07, -7.89183158e-07,\n", - " 5.05363526e-07, 5.12194601e-06]),\n", - " array([ 4.81715860e-03, 5.48894048e-03, 4.46560242e-03, 5.13738430e-03,\n", - " -2.59249109e-07, 1.26302804e-06, 1.61995090e-07, -5.24204078e-07,\n", - " 3.40964637e-07, 3.41632527e-06]),\n", - " array([ 1.68063355e-03, 1.89335267e-03, 1.48531729e-03, 1.69803642e-03,\n", - " -1.49240707e-07, 2.27149838e-07, 9.25030605e-08, -2.61122360e-07,\n", - " 1.72549187e-07, 1.70900755e-06])],\n", - " False)" + " array([-8.31866622e-07, -3.25978404e-04, 7.24283918e-02, 4.63047162e-03,\n", + " -1.18178567e-05, 5.23085205e-08, 9.99989279e-01, -1.27197423e-06,\n", + " 5.68737200e-04, 4.60060741e-05, 2.97355493e-05, 1.39762510e-05,\n", + " 2.71695010e-04, 2.40795347e-06, 9.40273736e-04, 7.24293836e+00,\n", + " 9.26097633e-01, -2.36357979e-03, 1.04617415e-05, -1.27197423e-04,\n", + " 5.68737200e-02, 4.60060741e-03, 2.97355493e-03, 1.39762510e-03,\n", + " 2.71695010e-02]),\n", + " array([-2.17056282e-06, -1.84710123e-03, 1.69575435e-01, 1.81171485e-02,\n", + " -1.95111637e-05, 1.27774207e-06, 9.99835871e-01, -3.59344339e-06,\n", + " 1.00033350e-02, 9.57875415e-05, 6.85058127e-05, 3.88288910e-05,\n", + " 2.51552967e-03, 1.70445776e-04, 6.89062970e-02, 9.71594535e+00,\n", + " 2.69753033e+00, -1.53806035e-03, 2.20340373e-04, -2.32146916e-04,\n", + " 9.43459785e-01, 4.97814674e-03, 3.87702635e-03, 2.48526400e-03,\n", + " 2.24383466e-01]),\n", + " array([-3.28713098e-06, -3.89111420e-03, 2.70942109e-01, 3.43933137e-02,\n", + " -2.25735850e-05, 2.81880821e-06, 9.99408375e-01, -6.50413410e-06,\n", + " 1.99619344e-02, 1.37998102e-04, 1.03847345e-04, 6.35346217e-05,\n", + " 4.97181203e-03, 3.15256012e-04, 3.28010240e-01, 1.01338690e+01,\n", + " 3.25639163e+00, -6.12654409e-04, 2.55866275e-04, -2.91069071e-04,\n", + " 9.95859934e-01, 4.22105606e-03, 3.53415324e-03, 2.47057307e-03,\n", + " 2.45628237e-01]),\n", + " array([-3.88522924e-06, -5.55100420e-03, 3.67471544e-01, 5.02709364e-02,\n", + " -2.20949592e-05, 4.27432057e-06, 9.98735617e-01, -9.57795582e-06,\n", + " 2.78217813e-02, 1.70219289e-04, 1.31865410e-04, 8.39111246e-05,\n", + " 6.94154758e-03, 3.73007932e-04, 6.51185705e-01, 9.63279156e+00,\n", + " 3.17840730e+00, 9.36959495e-05, 2.16343351e-04, -3.07382172e-04,\n", + " 7.85984686e-01, 3.22211871e-03, 2.80180651e-03, 2.03765029e-03,\n", + " 1.96973555e-01]),\n", + " array([-3.95213360e-06, -6.10803764e-03, 4.55257242e-01, 6.41005580e-02,\n", + " -1.92972714e-05, 5.45324628e-06, 9.97943444e-01, -1.24197413e-05,\n", + " 3.31486196e-02, 1.93076377e-04, 1.52275929e-04, 9.91360942e-05,\n", + " 8.28838000e-03, 3.60541761e-04, 9.47090385e-01, 8.72779131e+00,\n", + " 2.77048038e+00, 5.55377932e-04, 1.46927459e-04, -2.84178553e-04,\n", + " 5.32683832e-01, 2.28570875e-03, 2.04105193e-03, 1.52249695e-03,\n", + " 1.34683242e-01]),\n", + " array([-3.60252851e-06, -5.11226723e-03, 5.32831412e-01, 7.50862824e-02,\n", + " -1.52232186e-05, 6.27804665e-06, 9.97177040e-01, -1.47536662e-05,\n", + " 3.62505855e-02, 2.08135461e-04, 1.66066471e-04, 1.09655390e-04,\n", + " 9.07874290e-03, 3.09351019e-04, 1.17576495e+00, 7.66860108e+00,\n", + " 2.20249624e+00, 8.08785763e-04, 7.08294205e-05, -2.33392488e-04,\n", + " 3.10196593e-01, 1.50590848e-03, 1.37905418e-03, 1.05192959e-03,\n", + " 7.90362902e-02]),\n", + " array([-2.98351106e-06, -2.35446710e-03, 5.99930985e-01, 8.29315744e-02,\n", + " -1.06668488e-05, 6.74142812e-06, 9.96555244e-01, -1.64458992e-05,\n", + " 3.76190323e-02, 2.17085128e-04, 1.74534513e-04, 1.16292258e-04,\n", + " 9.43226034e-03, 2.44990858e-04, 1.32933725e+00, 6.58280907e+00,\n", + " 1.57398295e+00, 9.03925767e-04, 8.85121702e-07, -1.69223299e-04,\n", + " 1.36844683e-01, 8.94966641e-04, 8.46804195e-04, 6.63686793e-04,\n", + " 3.53517440e-02]),\n", + " array([-2.22830333e-06, 2.18931296e-03, 6.56907620e-01, 8.76402967e-02,\n", + " -6.18563364e-06, 6.87836578e-06, 9.96152186e-01, -1.74783410e-05,\n", + " 3.77248738e-02, 2.21437640e-04, 1.78918071e-04, 1.19895515e-04,\n", + " 9.46626580e-03, 1.83318489e-04, 1.41609608e+00, 5.53757567e+00,\n", + " 9.45189149e-01, 8.88221709e-04, -5.65358780e-05, -1.03244180e-04,\n", + " 1.05841456e-02, 4.35251248e-04, 4.38355776e-04, 3.60325693e-04,\n", + " 3.40054562e-03]),\n", + " array([-1.43864319e-06, 8.41323548e-03, 7.04432389e-01, 8.93978346e-02,\n", + " -2.13945434e-06, 6.74511299e-06, 9.95995998e-01, -1.79075020e-05,\n", + " 3.69570717e-02, 2.22445897e-04, 1.80274723e-04, 1.21214880e-04,\n", + " 9.27855592e-03, 1.32092866e-04, 1.45070648e+00, 4.56824733e+00,\n", + " 3.52892919e-01, 8.01175801e-04, -9.94291664e-05, -4.29160997e-05,\n", + " -7.67802050e-02, 1.00825624e-04, 1.35665220e-04, 1.31936485e-04,\n", + " -1.87709877e-02]),\n", + " array([-6.82029646e-07, 1.61292511e-02, 7.43341128e-01, 8.84971614e-02,\n", + " 1.26591087e-06, 6.40425984e-06, 9.96076429e-01, -1.78276791e-05,\n", + " 3.56157994e-02, 2.21106174e-04, 1.79461677e-04, 1.20869872e-04,\n", + " 8.94494866e-03, 9.36437983e-05, 1.44881600e+00, 3.69258784e+00,\n", + " -1.80851495e-01, 6.73501252e-04, -1.28507260e-04, 7.98228577e-06,\n", + " -1.34127239e-01, -1.33972219e-04, -8.13046335e-05, -3.45007853e-05,\n", + " -3.33607255e-02]),\n", + " array([ 4.12148280e-09, 2.51053151e-02, 7.74549692e-01, 8.52917213e-02,\n", + " 3.93938809e-06, 5.91535429e-06, 9.96356022e-01, -1.73448326e-05,\n", + " 3.39244341e-02, 2.18190930e-04, 1.77153764e-04, 1.19355214e-04,\n", + " 8.52201776e-03, 6.71956771e-05, 1.42437314e+00, 2.91832818e+00,\n", + " -6.43522398e-01, 5.27979995e-04, -1.45886417e-04, 4.82846496e-05,\n", + " -1.69136528e-01, -2.91524482e-04, -2.30791302e-04, -1.51465792e-04,\n", + " -4.22930907e-02]),\n", + " array([ 6.05710071e-07, 3.50947329e-02, 7.99005634e-01, 8.01649736e-02,\n", + " 5.87168861e-06, 5.33000569e-06, 9.96781609e-01, -1.65610325e-05,\n", + " 3.20461709e-02, 2.14288765e-04, 1.73872975e-04, 1.17058620e-04,\n", + " 8.05117042e-03, 5.05288641e-05, 1.38852854e+00, 2.24741309e+00,\n", + " -1.02887754e+00, 3.80798449e-04, -1.54148399e-04, 7.83800111e-05,\n", + " -1.87826319e-01, -3.90216454e-04, -3.28078847e-04, -2.29659406e-04,\n", + " -4.70847340e-02]),\n", + " array([ 1.12483724e-06, 4.58576618e-02, 8.17659828e-01, 7.35104424e-02,\n", + " 7.10871661e-06, 4.69013449e-06, 9.97294447e-01, -1.55669861e-05,\n", + " 3.01000071e-02, 2.09842968e-04, 1.70019079e-04, 1.14281115e-04,\n", + " 7.56263656e-03, 4.10331577e-05, 1.34941700e+00, 1.67849294e+00,\n", + " -1.33485510e+00, 2.42843597e-04, -1.55758142e-04, 9.94046441e-05,\n", + " -1.94616379e-01, -4.44579740e-04, -3.85389596e-04, -2.77750486e-04,\n", + " -4.88533854e-02]),\n", + " array([ 1.57346908e-06, 5.71759720e-02, 8.31449167e-01, 6.57182129e-02,\n", + " 7.73036746e-06, 4.02814930e-06, 9.97838222e-01, -1.44398270e-05,\n", + " 2.81743028e-02, 2.05185673e-04, 1.65897421e-04, 1.11256033e-04,\n", + " 7.07887118e-03, 3.63002704e-05, 1.31239695e+00, 1.20837873e+00,\n", + " -1.56223995e+00, 1.20798664e-04, -1.52768575e-04, 1.12715913e-04,\n", + " -1.92570430e-01, -4.65729479e-04, -4.12165864e-04, -3.02508174e-04,\n", + " -4.83765387e-02]),\n", + " array([ 1.96833868e-06, 6.88626969e-02, 8.41284688e-01, 5.71649963e-02,\n", + " 7.83378562e-06, 3.36811957e-06, 9.98364745e-01, -1.32437935e-05,\n", + " 2.63372666e-02, 2.00566552e-04, 1.61742394e-04, 1.08165176e-04,\n", + " 6.61718978e-03, 3.43990204e-05, 1.28049916e+00, 8.32796038e-01,\n", + " -1.71388669e+00, 1.80406295e-05, -1.46729749e-04, 1.19603349e-04,\n", + " -1.83703620e-01, -4.61912114e-04, -4.15502651e-04, -3.09085730e-04,\n", + " -4.61681392e-02]),\n", + " array([ 2.32716222e-06, 8.07671524e-02, 8.48040976e-01, 4.82057272e-02,\n", + " 7.52044995e-06, 2.72731436e-06, 9.98837428e-01, -1.20320744e-05,\n", + " 2.46440636e-02, 1.96175342e-04, 1.57735843e-04, 1.05151468e-04,\n", + " 6.19155820e-03, 3.39479967e-05, 1.25494683e+00, 5.46620136e-01,\n", + " -1.79435194e+00, -6.45972527e-05, -1.38726370e-04, 1.21171909e-04,\n", + " -1.69320296e-01, -4.39120982e-04, -4.00655174e-04, -3.01370800e-04,\n", + " -4.25631583e-02]),\n", + " array([ 2.66604918e-06, 9.27765341e-02, 8.52543825e-01, 3.91654548e-02,\n", + " 6.88677106e-06, 2.11772370e-06, 9.99232739e-01, -1.08487367e-05,\n", + " 2.31404907e-02, 1.92157760e-04, 1.54019987e-04, 1.02327837e-04,\n", + " 5.81352491e-03, 3.40702145e-05, 1.23567589e+00, 3.43742614e-01,\n", + " -1.80978844e+00, -1.28130789e-04, -1.29481781e-04, 1.18333767e-04,\n", + " -1.50357291e-01, -4.01758188e-04, -3.71585527e-04, -2.82363083e-04,\n", + " -3.78033289e-02]),\n", + " array([ 2.99791761e-06, 1.04814523e-01, 8.55554578e-01, 3.03311462e-02,\n", + " 6.01806754e-06, 1.54735523e-06, 9.99539905e-01, -9.73019823e-06,\n", + " 2.18635600e-02, 1.88624815e-04, 1.50704961e-04, 9.97824066e-05,\n", + " 5.49238392e-03, 3.42896214e-05, 1.22181898e+00, 2.16740745e-01,\n", + " -1.76793517e+00, -1.74758776e-04, -1.19481162e-04, 1.11853848e-04,\n", + " -1.27693069e-01, -3.53294480e-04, -3.31502628e-04, -2.54543056e-04,\n", + " -3.21140995e-02]),\n", + " array([ 3.33172891e-06, 1.16837315e-01, 8.57751293e-01, 2.19438468e-02,\n", + " 4.98577097e-06, 1.02121988e-06, 9.99759205e-01, -8.70613089e-06,\n", + " 2.08398413e-02, 1.85656320e-04, 1.47871646e-04, 9.75805268e-05,\n", + " 5.23478046e-03, 3.44104896e-05, 1.21213017e+00, 1.56545025e-01,\n", + " -1.67803810e+00, -2.07226738e-04, -1.09080722e-04, 1.02406734e-04,\n", + " -1.02371873e-01, -2.96849550e-04, -2.83331510e-04, -2.20187981e-04,\n", + " -2.57603458e-02]),\n", + " array([ 3.67238477e-06, 1.28827584e-01, 8.59708701e-01, 1.41922518e-02,\n", + " 3.84750892e-06, 5.42004878e-07, 9.99899285e-01, -7.79995688e-06,\n", + " 2.00828341e-02, 1.83300222e-04, 1.45571191e-04, 9.57646121e-05,\n", + " 5.04407479e-03, 3.44059015e-05, 1.20532833e+00, 1.52293071e-01,\n", + " -1.55057602e+00, -2.28259507e-04, -9.85834853e-05, 9.06174019e-05,\n", + " -7.57007206e-02, -2.35609751e-04, -2.30045500e-04, -1.81591469e-04,\n", + " -1.90705667e-02]),\n", + " array([ 4.02115213e-06, 1.40787143e-01, 8.61880206e-01, 7.20894860e-03,\n", + " 2.64940009e-06, 1.10491440e-07, 9.99974015e-01, -7.02921659e-06,\n", + " 1.95907695e-02, 1.81569984e-04, 1.43823052e-04, 9.43530556e-05,\n", + " 4.91980998e-03, 3.43292025e-05, 1.20033884e+00, 1.91508808e-01,\n", + " -1.39674344e+00, -2.40124922e-04, -8.82757059e-05, 7.70740286e-05,\n", + " -4.92064632e-02, -1.73023805e-04, -1.74813843e-04, -1.41155658e-04,\n", + " -1.24264814e-02]),\n", + " array([ 4.37648247e-06, 1.52729289e-01, 8.64585820e-01, 1.07034559e-03,\n", + " 1.42957892e-06, -2.74189953e-07, 9.99999427e-01, -6.40607217e-06,\n", + " 1.93459970e-02, 1.80442419e-04, 1.42613555e-04, 9.33395835e-05,\n", + " 4.85756991e-03, 3.42523153e-05, 1.19642117e+00, 2.60666500e-01,\n", + " -1.22773305e+00, -2.44391872e-04, -7.84293310e-05, 6.23144423e-05,\n", + " -2.44772490e-02, -1.12756526e-04, -1.20949774e-04, -1.01347203e-04,\n", + " -6.22400644e-03]),\n", + " array([ 4.73506966e-06, 1.64671878e-01, 8.68009544e-01, -4.19929572e-03,\n", + " 2.21772715e-07, -6.14359152e-07, 9.99991183e-01, -5.93810824e-06,\n", + " 1.93165965e-02, 1.79858215e-04, 1.41896764e-04, 9.26942437e-05,\n", + " 4.84938604e-03, 3.42281980e-05, 1.19318733e+00, 3.46109172e-01,\n", + " -1.05393077e+00, -2.41921661e-04, -6.92826932e-05, 4.67963930e-05,\n", + " -2.94004592e-03, -5.84203852e-05, -7.16791216e-05, -6.45339822e-05,\n", + " -8.18387667e-04]),\n", + " array([ 5.09295541e-06, 1.76632007e-01, 8.72208538e-01, -8.62005087e-03,\n", + " -9.42196007e-07, -9.13541174e-07, 9.99962847e-01, -5.62945308e-06,\n", + " 1.94602245e-02, 1.79726753e-04, 1.41598906e-04, 9.23667877e-05,\n", + " 4.88469427e-03, 3.42722345e-05, 1.19053583e+00, 4.35198133e-01,\n", + " -8.84169912e-01, -2.33083110e-04, -6.10132077e-05, 3.08655151e-05,\n", + " 1.43627998e-02, -1.31461849e-05, -2.97857934e-05, -3.27455984e-05,\n", + " 3.53082360e-03]),\n", + " array([ 5.44647375e-06, 1.88622770e-01, 8.77134190e-01, -1.22458043e-02,\n", + " -2.03173495e-06, -1.17611178e-06, 9.99925017e-01, -5.48210297e-06,\n", + " 1.97295594e-02, 1.79935683e-04, 1.41626605e-04, 9.22925450e-05,\n", + " 4.95168382e-03, 3.43581654e-05, 1.18854053e+00, 5.17477469e-01,\n", + " -7.25190547e-01, -2.18117079e-04, -5.37143415e-05, 1.47350115e-05,\n", + " 2.69334921e-02, 2.08930046e-05, 2.76991394e-06, -7.42426731e-06,\n", + " 6.69895475e-03]),\n", + " array([ 5.79286042e-06, 2.00652082e-01, 8.82662465e-01, -1.51526233e-02,\n", + " -3.01873276e-06, -1.40683436e-06, 9.99885192e-01, -5.49722833e-06,\n", + " 2.00781462e-02, 1.80364130e-04, 1.41877963e-04, 9.24001007e-05,\n", + " 5.03874207e-03, 3.44257804e-05, 1.18733625e+00, 5.85576214e-01,\n", + " -5.81418577e-01, -1.97519893e-04, -4.73866300e-05, -1.51253580e-06,\n", + " 3.48586810e-02, 4.28446434e-05, 2.51358410e-05, 1.07555681e-05,\n", + " 8.70582436e-03]),\n", + " array([ 6.13045347e-06, 2.12723151e-01, 8.88628414e-01, -1.74278429e-02,\n", + " -3.88011908e-06, -1.61036150e-06, 9.99848124e-01, -5.67622182e-06,\n", + " 2.04651929e-02, 1.80896919e-04, 1.42254423e-04, 9.26194439e-05,\n", + " 5.13564259e-03, 3.43975293e-05, 1.18703246e+00, 6.35601761e-01,\n", + " -4.55104404e-01, -1.72303392e-04, -4.19480174e-05, -1.78993495e-05,\n", + " 3.87046696e-02, 5.32788811e-05, 3.76460060e-05, 2.19343223e-05,\n", + " 9.69005209e-03]),\n", + " array([ 6.45854317e-06, 2.24835862e-01, 8.94858690e-01, -1.91612999e-02,\n", + " -4.60065065e-06, -1.79081041e-06, 9.99816405e-01, -6.02133971e-06,\n", + " 2.08582169e-02, 1.81436684e-04, 1.42670959e-04, 9.28890357e-05,\n", + " 5.23420859e-03, 3.41992028e-05, 1.18766865e+00, 6.66922870e-01,\n", + " -3.46749478e-01, -1.44038445e-04, -3.72607934e-05, -3.45117886e-05,\n", + " 3.93024010e-02, 5.39765227e-05, 4.16536175e-05, 2.69591705e-05,\n", + " 9.85660061e-03]),\n", + " array([ 6.77702748e-06, 2.36988407e-01, 9.01196863e-01, -2.04393079e-02,\n", + " -5.17480421e-06, -1.95149191e-06, 9.99791096e-01, -6.53594929e-06,\n", + " 2.12333367e-02, 1.81911438e-04, 1.43062695e-04, 9.31605706e-05,\n", + " 5.32840110e-03, 3.37781267e-05, 1.18920735e+00, 6.81435812e-01,\n", + " -2.55651738e-01, -1.14674910e-04, -3.31638451e-05, -5.14609578e-05,\n", + " 3.75119760e-02, 4.74753940e-05, 3.91736080e-05, 2.71534911e-05,\n", + " 9.41925041e-03]),\n", + " array([ 7.08604916e-06, 2.49178627e-01, 9.07518710e-01, -2.13410257e-02,\n", + " -5.60702800e-06, -2.09479759e-06, 9.99772254e-01, -7.22453428e-06,\n", + " 2.15739843e-02, 1.82276742e-04, 1.43387215e-04, 9.34009216e-05,\n", + " 5.41401752e-03, 3.31132623e-05, 1.19155103e+00, 6.82553113e-01,\n", + " -1.80382913e-01, -8.62123364e-05, -2.94961345e-05, -6.88584990e-05,\n", + " 3.40647588e-02, 3.65304716e-05, 3.24520012e-05, 2.40351065e-05,\n", + " 8.56164205e-03]),\n", + " array([ 7.38573623e-06, 2.61404827e-01, 9.13737476e-01, -2.19363349e-02,\n", + " -5.91020919e-06, -2.22218502e-06, 9.99759370e-01, -8.09264714e-06,\n", + " 2.18692863e-02, 1.82513212e-04, 1.43623059e-04, 9.35915171e-05,\n", + " 5.48830094e-03, 3.22152826e-05, 1.19456821e+00, 6.74193629e-01,\n", + " -1.19089724e-01, -6.03425770e-05, -2.61035416e-05, -8.68112864e-05,\n", + " 2.95302032e-02, 2.36469203e-05, 2.35843243e-05, 1.90595494e-05,\n", + " 7.42834200e-03]),\n", + " array([ 7.67608410e-06, 2.73666078e-01, 9.19801252e-01, -2.22844281e-02,\n", + " -6.10281984e-06, -2.33419020e-06, 9.99751671e-01, -9.14692241e-06,\n", + " 2.21130654e-02, 1.82621071e-04, 1.43765683e-04, 9.37259182e-05,\n", + " 5.54969138e-03, 3.11188630e-05, 1.19811841e+00, 6.59991714e-01,\n", + " -6.96356740e-02, -3.81852680e-05, -2.28326393e-05, -1.05427527e-04,\n", + " 2.43779095e-02, 1.07859063e-05, 1.42624227e-05, 1.34401086e-05,\n", + " 6.13904415e-03]),\n", + " array([ 7.95695219e-06, 2.85962148e-01, 9.25685703e-01, -2.24328254e-02,\n", + " -6.20558090e-06, -2.43043742e-06, 9.99748352e-01, -1.03951413e-05,\n", + " 2.23036315e-02, 1.82613692e-04, 1.43822376e-04, 9.38065278e-05,\n", + " 5.59776367e-03, 2.98717311e-05, 1.20207051e+00, 6.42827618e-01,\n", + " -2.96868790e-02, -2.01914753e-05, -1.95230793e-05, -1.24821887e-04,\n", + " 1.90566122e-02, -7.37831223e-07, 5.66930880e-06, 8.06095920e-06,\n", + " 4.80722950e-03]),\n", + " array([ 8.22812117e-06, 2.98293239e-01, 9.31385199e-01, -2.24170486e-02,\n", + " -6.23851120e-06, -2.50966789e-06, 9.99748706e-01, -1.18462509e-05,\n", + " 2.24438402e-02, 1.82511595e-04, 1.43807324e-04, 9.38412363e-05,\n", + " 5.63322954e-03, 2.85247115e-05, 1.20631324e+00, 6.24667257e-01,\n", + " 3.15614918e-03, -6.22082036e-06, -1.60092603e-05, -1.45110966e-04,\n", + " 1.40208671e-02, -1.02096991e-05, -1.50524284e-06, 3.47084703e-06,\n", + " 3.54658639e-03]),\n", + " array([ 8.48936313e-06, 3.10659704e-01, 9.36904606e-01, -2.22613333e-02,\n", + " -6.21894722e-06, -2.56982583e-06, 9.99752186e-01, -1.35102365e-05,\n", + " 2.25407164e-02, 1.82337731e-04, 1.43737566e-04, 9.38405408e-05,\n", + " 5.65783641e-03, 2.71250637e-05, 1.21075850e+00, 6.06627403e-01,\n", + " 3.11508335e-02, 4.26402498e-06, -1.21333909e-05, -1.66398557e-04,\n", + " 9.68761501e-03, -1.73864235e-05, -6.97572934e-06, -6.95422374e-08,\n", + " 2.46068769e-03]),\n", + " array([ 8.74049724e-06, 3.23061796e-01, 9.42252891e-01, -2.19805064e-02,\n", + " -6.16071027e-06, -2.60822063e-06, 9.99758399e-01, -1.53978095e-05,\n", + " 2.26042804e-02, 1.82114293e-04, 1.43630124e-04, 9.38153891e-05,\n", + " 5.67407490e-03, 2.57133845e-05, 1.21533948e+00, 5.89160785e-01,\n", + " 5.61791256e-02, 1.19675106e-05, -7.76386719e-06, -1.88757295e-04,\n", + " 6.35639997e-03, -2.23438117e-05, -1.07442715e-05, -2.51517553e-06,\n", + " 1.62384888e-03]),\n", + " array([ 8.98142241e-06, 3.35499517e-01, 9.47438812e-01, -2.15827357e-02,\n", + " -6.07421584e-06, -2.62174239e-06, 9.99767066e-01, -1.75199513e-05,\n", + " 2.26457435e-02, 1.81860905e-04, 1.43500242e-04, 9.37757767e-05,\n", + " 5.68473386e-03, 2.43231401e-05, 1.22000575e+00, 5.72269948e-01,\n", + " 7.95730236e-02, 1.75723238e-05, -2.80904952e-06, -2.12214188e-04,\n", + " 4.14631827e-03, -2.53387857e-05, -1.29881809e-05, -3.96123685e-06,\n", + " 1.06589568e-03]),\n", + " array([ 9.21212992e-06, 3.47972527e-01, 9.52468374e-01, -2.10725486e-02,\n", + " -5.96713035e-06, -2.60708667e-06, 9.99777949e-01, -1.98874098e-05,\n", + " 2.26756038e-02, 1.81593837e-04, 1.43360531e-04, 9.37299855e-05,\n", + " 5.69243079e-03, 2.29816037e-05, 1.22471751e+00, 5.55690572e-01,\n", + " 1.02060636e-01, 2.16295848e-05, 2.77861057e-06, -2.36745847e-04,\n", + " 2.98602275e-03, -2.67068218e-05, -1.39710640e-05, -4.57911781e-06,\n", + " 7.69692555e-04]),\n", + " array([ 9.43270317e-06, 3.60480115e-01, 9.57343508e-01, -2.04534839e-02,\n", + " -5.84516306e-06, -2.56094461e-06, 9.99790806e-01, -2.25102356e-05,\n", + " 2.27021975e-02, 1.81325864e-04, 1.43220708e-04, 9.36842934e-05,\n", + " 5.69925281e-03, 2.17112214e-05, 1.22944028e+00, 5.39020915e-01,\n", + " 1.23839632e-01, 2.45317121e-05, 9.00829150e-06, -2.62282579e-04,\n", + " 2.65937334e-03, -2.67973032e-05, -1.39822780e-05, -4.56921377e-06,\n", + " 6.82202737e-04]),\n", + " array([ 9.64331052e-06, 3.73021197e-01, 9.62061504e-01, -1.97299505e-02,\n", + " -5.71272495e-06, -2.48014144e-06, 9.99805346e-01, -2.53974065e-05,\n", + " 2.27310199e-02, 1.81066469e-04, 1.43087695e-04, 9.36429889e-05,\n", + " 5.70658531e-03, 2.05308366e-05, 1.23414115e+00, 5.21802957e-01,\n", + " 1.44735913e-01, 2.65391256e-05, 1.58606315e-05, -2.88717088e-04,\n", + " 2.88223666e-03, -2.59394557e-05, -1.33013199e-05, -4.13045291e-06,\n", + " 7.33249597e-04]),\n", + " array([ 9.84419456e-06, 3.85594350e-01, 9.66614931e-01, -1.89081756e-02,\n", + " -5.57336270e-06, -2.36173798e-06, 9.99821224e-01, -2.85565194e-05,\n", + " 2.27648011e-02, 1.80822211e-04, 1.42965909e-04, 9.36085618e-05,\n", + " 5.71512677e-03, 1.94565522e-05, 1.23878661e+00, 5.03574152e-01,\n", + " 1.64385659e-01, 2.78255729e-05, 2.32949686e-05, -3.15911294e-04,\n", + " 3.37812241e-03, -2.44257908e-05, -1.21786456e-05, -3.44270556e-06,\n", + " 8.54146468e-04]),\n", + " array([ 1.00356595e-05, 3.98197853e-01, 9.70991926e-01, -1.79963852e-02,\n", + " -5.43000388e-06, -2.20313560e-06, 9.99838052e-01, -3.19934781e-05,\n", + " 2.28040974e-02, 1.80597181e-04, 1.42857654e-04, 9.35819847e-05,\n", + " 5.72503197e-03, 1.85022089e-05, 1.24334181e+00, 4.83906249e-01,\n", + " 1.82389134e-01, 2.85163050e-05, 3.12485417e-05, -3.43695870e-04,\n", + " 3.92962719e-03, -2.25030904e-05, -1.08255135e-05, -2.65771337e-06,\n", + " 9.90519601e-04]),\n", + " array([ 1.02180577e-05, 4.10829750e-01, 9.75176801e-01, -1.70044858e-02,\n", + " -5.28509473e-06, -2.00224047e-06, 9.99855413e-01, -3.57120706e-05,\n", + " 2.28480841e-02, 1.80393506e-04, 1.42763560e-04, 9.35630289e-05,\n", + " 5.73610704e-03, 1.76795195e-05, 1.24777099e+00, 4.62437187e-01,\n", + " 1.98410276e-01, 2.87099770e-05, 3.96245399e-05, -3.71859244e-04,\n", + " 4.39867094e-03, -2.03674606e-05, -9.40932834e-06, -1.89557741e-06,\n", + " 1.10750735e-03]),\n", + " array([ 1.03917773e-05, 4.23487922e-01, 9.79150889e-01, -1.59435244e-02,\n", + " -5.14069399e-06, -1.75775086e-06, 9.99872894e-01, -3.97133167e-05,\n", + " 2.28952987e-02, 1.80211859e-04, 1.42683018e-04, 9.35505724e-05,\n", + " 5.74799401e-03, 1.69978618e-05, 1.25203834e+00, 4.38893633e-01,\n", + " 2.12221085e-01, 2.84878308e-05, 4.82674965e-05, -4.00124616e-04,\n", + " 4.72146306e-03, -1.81646456e-05, -8.05427221e-06, -1.24564736e-06,\n", + " 1.18869665e-03]),\n", + " array([ 1.05572335e-05, 4.36170155e-01, 9.82893486e-01, -1.48251340e-02,\n", + " -4.99854622e-06, -1.46963862e-06, 9.99890102e-01, -4.39944545e-05,\n", + " 2.29441941e-02, 1.80051885e-04, 1.42614536e-04, 9.35428530e-05,\n", + " 5.76030930e-03, 1.64636620e-05, 1.25610915e+00, 4.13099550e-01,\n", + " 2.23704568e-01, 2.79181031e-05, 5.69245916e-05, -4.28113780e-04,\n", + " 4.88954344e-03, -1.59974579e-05, -6.84816017e-06, -7.71948153e-07,\n", + " 1.23152863e-03]),\n", + " array([ 1.07148655e-05, 4.48874201e-01, 9.86382727e-01, -1.36610845e-02,\n", + " -4.86012598e-06, -1.13991072e-06, 9.99906683e-01, -4.85474077e-05,\n", + " 2.29934622e-02, 1.79912478e-04, 1.42555968e-04, 9.35376052e-05,\n", + " 5.77272521e-03, 1.60792290e-05, 1.25995091e+00, 3.84968023e-01,\n", + " 2.32833533e-01, 2.70620842e-05, 6.51899311e-05, -4.55295316e-04,\n", + " 4.92680222e-03, -1.39406863e-05, -5.85677088e-06, -5.24774427e-07,\n", + " 1.24159105e-03]),\n", + " array([ 1.08651436e-05, 4.61597824e-01, 9.89596182e-01, -1.24629958e-02,\n", + " -4.72662122e-06, -7.73764768e-07, 9.99922334e-01, -5.33565297e-05,\n", + " 2.30421318e-02, 1.79791835e-04, 1.42504463e-04, 9.35319532e-05,\n", + " 5.78499398e-03, 1.58408273e-05, 1.26353421e+00, 3.54472358e-01,\n", + " 2.39638193e-01, 2.59864310e-05, 7.24261332e-05, -4.80912201e-04,\n", + " 4.86695992e-03, -1.20643008e-05, -5.15049870e-06, -5.65198767e-07,\n", + " 1.22687706e-03]),\n", + " array([ 1.10085910e-05, 4.74338819e-01, 9.92510752e-01, -1.12422459e-02,\n", + " -4.59877252e-06, -3.81299924e-07, 9.99936804e-01, -5.83953344e-05,\n", + " 2.30894136e-02, 1.79687088e-04, 1.42455821e-04, 9.35216805e-05,\n", + " 5.79690487e-03, 1.57356964e-05, 1.26683331e+00, 3.21575975e-01,\n", + " 2.44167164e-01, 2.47920958e-05, 7.76538022e-05, -5.03880468e-04,\n", + " 4.72818844e-03, -1.04747272e-05, -4.86419160e-06, -1.02726844e-06,\n", + " 1.19108953e-03]),\n", + " array([ 1.11458341e-05, 4.87094998e-01, 9.95100611e-01, -1.00101436e-02,\n", + " -4.47623775e-06, 1.99818664e-08, 9.99949897e-01, -6.36217958e-05,\n", + " 2.31341054e-02, 1.79592839e-04, 1.42402211e-04, 9.34987839e-05,\n", + " 5.80812433e-03, 1.57375586e-05, 1.26982639e+00, 2.86035894e-01,\n", + " 2.46434375e-01, 2.37091530e-05, 7.93945865e-05, -5.22646141e-04,\n", + " 4.46917971e-03, -9.42486150e-06, -5.36106401e-06, -2.28966700e-06,\n", + " 1.12194546e-03]),\n", + " array([ 1.12777230e-05, 4.99864062e-01, 9.97328794e-01, -8.77856820e-03,\n", + " -4.35459983e-06, 4.01545053e-07, 9.99961468e-01, -6.89715934e-05,\n", + " 2.31729731e-02, 1.79494909e-04, 1.42325721e-04, 9.34461671e-05,\n", + " 5.81778570e-03, 1.57997003e-05, 1.27249506e+00, 2.46769363e-01,\n", + " 2.46325972e-01, 2.35679062e-05, 7.54497444e-05, -5.34979760e-04,\n", + " 3.88676914e-03, -9.79302905e-06, -7.64893821e-06, -5.26167462e-06,\n", + " 9.66137120e-04]),\n", + " array([ 1.14045915e-05, 5.12643208e-01, 9.99117120e-01, -7.56161746e-03,\n", + " -4.20946169e-06, 8.01323095e-07, 9.99971411e-01, -7.41828783e-05,\n", + " 2.31964309e-02, 1.79315792e-04, 1.42192852e-04, 9.33640396e-05,\n", + " 5.82380883e-03, 1.58430451e-05, 1.27482224e+00, 1.99689421e-01,\n", + " 2.43398288e-01, 2.82355494e-05, 7.91467028e-05, -5.21128496e-04,\n", + " 2.34578224e-03, -1.79116725e-05, -1.32869084e-05, -8.21275604e-06,\n", + " 6.02312748e-04]),\n", + " array([ 1.15267645e-05, 5.25431380e-01, 1.00048554e+00, -6.36266332e-03,\n", + " -4.04870377e-06, 1.19169412e-06, 9.99979758e-01, -7.91924964e-05,\n", + " 2.32100117e-02, 1.79075670e-04, 1.42007464e-04, 9.32449176e-05,\n", + " 5.82736102e-03, 1.59675601e-05, 1.27678817e+00, 1.54635354e-01,\n", + " 2.39796654e-01, 3.13751831e-05, 7.73043822e-05, -5.00961807e-04,\n", + " 1.35807474e-03, -2.40122446e-05, -1.85388099e-05, -1.19122011e-05,\n", + " 3.55219807e-04]),\n", + " array([ 1.16442711e-05, 5.38227736e-01, 1.00147914e+00, -5.18306844e-03,\n", + " -3.88182595e-06, 1.55612104e-06, 9.99986568e-01, -8.39596402e-05,\n", + " 2.32195702e-02, 1.78799637e-04, 1.41786439e-04, 9.30972591e-05,\n", + " 5.82986045e-03, 1.61117268e-05, 1.27840337e+00, 1.14127585e-01,\n", + " 2.35922920e-01, 3.26355220e-05, 7.21394919e-05, -4.76714378e-04,\n", + " 9.55845782e-04, -2.76032558e-05, -2.21024969e-05, -1.47658506e-05,\n", + " 2.49942297e-04]),\n", + " array([ 1.17570670e-05, 5.51031273e-01, 1.00214655e+00, -4.02461597e-03,\n", + " -3.71546949e-06, 1.88535911e-06, 9.99991901e-01, -8.84588976e-05,\n", + " 2.32287010e-02, 1.78507296e-04, 1.41545922e-04, 9.29320768e-05,\n", + " 5.83221576e-03, 1.62365779e-05, 1.27968523e+00, 7.85268107e-02,\n", + " 2.31692962e-01, 3.25731607e-05, 6.51181499e-05, -4.49925747e-04,\n", + " 9.13081585e-04, -2.92341569e-05, -2.40516802e-05, -1.65182253e-05,\n", + " 2.35531665e-04]),\n", + " array([ 1.18650980e-05, 5.63840777e-01, 1.00253421e+00, -2.88997091e-03,\n", + " -3.55353569e-06, 2.17495951e-06, 9.99995824e-01, -9.26755678e-05,\n", + " 2.32391006e-02, 1.78212337e-04, 1.41298167e-04, 9.27584966e-05,\n", + " 5.83486659e-03, 1.63175283e-05, 1.28065196e+00, 4.76219741e-02,\n", + " 2.26930381e-01, 3.17284713e-05, 5.72053404e-05, -4.21667012e-04,\n", + " 1.03996235e-03, -2.94958244e-05, -2.47755062e-05, -1.73580190e-05,\n", + " 2.65082870e-04]),\n", + " array([ 1.19683178e-05, 5.76654834e-01, 1.00268525e+00, -1.78261997e-03,\n", + " -3.39796466e-06, 2.42358193e-06, 9.99998411e-01, -9.66024180e-05,\n", + " 2.32512613e-02, 1.77923864e-04, 1.41051748e-04, 9.25831929e-05,\n", + " 5.83794674e-03, 1.63401773e-05, 1.28132149e+00, 2.10916951e-02,\n", + " 2.21470805e-01, 3.04905306e-05, 4.90260777e-05, -3.92685025e-04,\n", + " 1.21607399e-03, -2.88473048e-05, -2.46419625e-05, -1.75303712e-05,\n", + " 3.08015073e-04]),\n", + " array([ 1.20666938e-05, 5.89471874e-01, 1.00263957e+00, -7.06684701e-04,\n", + " -3.24944277e-06, 2.63184803e-06, 9.99999750e-01, -1.00237423e-04,\n", + " 2.32649929e-02, 1.77647731e-04, 1.40812454e-04, 9.24108347e-05,\n", + " 5.84141458e-03, 1.62973894e-05, 1.28171157e+00, -1.37732283e-03,\n", + " 2.15187231e-01, 2.91094703e-05, 4.09742662e-05, -3.63500500e-04,\n", + " 1.37315968e-03, -2.76132875e-05, -2.39293993e-05, -1.72358195e-05,\n", + " 3.46784184e-04]),\n", + " array([ 1.21602088e-05, 6.02290195e-01, 1.00243407e+00, 3.33286153e-04,\n", + " -3.10792140e-06, 2.80156543e-06, 9.99999944e-01, -1.03582184e-04,\n", + " 2.32797508e-02, 1.77387582e-04, 1.40584123e-04, 9.22446408e-05,\n", + " 5.84513670e-03, 1.61870970e-05, 1.28183995e+00, -2.00712726e-02,\n", + " 2.07994184e-01, 2.77330019e-05, 3.32875133e-05, -3.34476125e-04,\n", + " 1.47578458e-03, -2.60149211e-05, -2.28330385e-05, -1.66193859e-05,\n", + " 3.72211390e-04]),\n", + " array([ 1.22488632e-05, 6.15108008e-01, 1.00210287e+00, 1.33251731e-03,\n", + " -2.97296603e-06, 2.93520723e-06, 9.99999112e-01, -1.06640826e-04,\n", + " 2.32948301e-02, 1.77145576e-04, 1.40369262e-04, 9.20868245e-05,\n", + " 5.84893777e-03, 1.60106446e-05, 1.28172454e+00, -3.52558788e-02,\n", + " 1.99846310e-01, 2.64395857e-05, 2.60987266e-05, -3.05864154e-04,\n", + " 1.50793403e-03, -2.42006060e-05, -2.14861041e-05, -1.57816350e-05,\n", + " 3.80107119e-04]),\n", + " array([ 1.23326755e-05, 6.27923463e-01, 1.00167737e+00, 2.28619341e-03,\n", + " -2.84397797e-06, 3.03556763e-06, 9.99997387e-01, -1.09419223e-04,\n", + " 2.33094790e-02, 1.76922876e-04, 1.40169469e-04, 9.19389052e-05,\n", + " 5.85262971e-03, 1.57715617e-05, 1.28138339e+00, -4.71871412e-02,\n", + " 1.90735540e-01, 2.52634661e-05, 1.94716531e-05, -2.77839715e-04,\n", + " 1.46489059e-03, -2.22699626e-05, -1.99793628e-05, -1.47919269e-05,\n", + " 3.69193731e-04]),\n", + " array([ 1.24116835e-05, 6.40734689e-01, 1.00118631e+00, 3.18962945e-03,\n", + " -2.72032653e-06, 3.10553862e-06, 9.99994913e-01, -1.11924464e-04,\n", + " 2.33229650e-02, 1.76719967e-04, 1.39985709e-04, 9.18019139e-05,\n", + " 5.85602883e-03, 1.54746739e-05, 1.28083463e+00, -5.61203358e-02,\n", + " 1.80687890e-01, 2.42123251e-05, 1.34252572e-05, -2.50524152e-04,\n", + " 1.34860237e-03, -2.02909902e-05, -1.83759270e-05, -1.36991330e-05,\n", + " 3.39912307e-04]),\n", + " array([ 1.24859441e-05, 6.53539821e-01, 1.00065569e+00, 4.03842414e-03,\n", + " -2.60142049e-06, 3.14796936e-06, 9.99991846e-01, -1.14164478e-04,\n", + " 2.33346163e-02, 1.76536848e-04, 1.39818493e-04, 9.16765208e-05,\n", + " 5.85896643e-03, 1.51254750e-05, 1.28009633e+00, -6.23160238e-02,\n", + " 1.69760052e-01, 2.32792940e-05, 7.95035707e-06, -2.24001352e-04,\n", + " 1.16512114e-03, -1.83118223e-05, -1.67216168e-05, -1.25393138e-05,\n", + " 2.93759549e-04]),\n", + " array([ 1.25555332e-05, 6.66337035e-01, 1.00010871e+00, 4.82859487e-03,\n", + " -2.48673982e-06, 3.16558156e-06, 9.99988342e-01, -1.16147770e-04,\n", + " 2.33438480e-02, 1.76373163e-04, 1.39667975e-04, 9.15631121e-05,\n", + " 5.86129560e-03, 1.47296964e-05, 1.27918630e+00, -6.60431007e-02,\n", + " 1.58035704e-01, 2.24508665e-05, 3.02087900e-06, -1.98329164e-04,\n", + " 9.23176280e-04, -1.63684881e-05, -1.50518495e-05, -1.13408689e-05,\n", + " 2.32917667e-04]),\n", + " array([ 1.26205454e-05, 6.79124583e-01, 9.99565689e-01, 5.55669236e-03,\n", + " -2.37584231e-06, 3.16092252e-06, 9.99984561e-01, -1.17883243e-04,\n", + " 2.33501812e-02, 1.76228266e-04, 1.39534015e-04, 9.14618343e-05,\n", + " 5.86289592e-03, 1.42930240e-05, 1.27812197e+00, -6.75792568e-02,\n", + " 1.45621465e-01, 2.17118938e-05, -1.39861755e-06, -1.73547363e-04,\n", + " 6.33315596e-04, -1.44897847e-05, -1.33959638e-05, -1.01277779e-05,\n", + " 1.60031687e-04]),\n", + " array([ 1.26810923e-05, 6.91900813e-01, 9.99044018e-01, 6.21989309e-03,\n", + " -2.26835594e-06, 3.13634276e-06, 9.99980656e-01, -1.19380075e-04,\n", + " 2.33532540e-02, 1.76101265e-04, 1.39416218e-04, 9.13726197e-05,\n", + " 5.86367642e-03, 1.38209208e-05, 1.27692017e+00, -6.72092940e-02,\n", + " 1.32642448e-01, 2.10485081e-05, -5.34799346e-06, -1.49683185e-04,\n", + " 3.07286857e-04, -1.27000920e-05, -1.17796987e-05, -8.92145688e-06,\n", + " 7.80503711e-05]),\n", + " array([ 1.27373012e-05, 7.04664201e-01, 9.98558139e-01, 6.81606771e-03,\n", + " -2.16396392e-06, 3.09398960e-06, 9.99976770e-01, -1.20647627e-04,\n", + " 2.33528289e-02, 1.75991057e-04, 1.39313954e-04, 9.12952033e-05,\n", + " 5.86357729e-03, 1.33185264e-05, 1.27559709e+00, -6.52217736e-02,\n", + " 1.19237458e-01, 2.04495893e-05, -8.86836026e-06, -1.26755154e-04,\n", + " -4.25098856e-05, -1.10207445e-05, -1.02263733e-05, -7.74163677e-06,\n", + " -9.91311552e-06]),\n", + " array([ 1.27893135e-05, 7.17413370e-01, 9.98119572e-01, 7.34382423e-03,\n", + " -2.06238793e-06, 3.03581046e-06, 9.99973034e-01, -1.21695384e-04,\n", + " 2.33487933e-02, 1.75896353e-04, 1.39226382e-04, 9.12291375e-05,\n", + " 5.86257010e-03, 1.27906067e-05, 1.27416815e+00, -6.19044798e-02,\n", + " 1.05553950e-01, 1.99072239e-05, -1.20001257e-05, -1.04775707e-04,\n", + " -4.03569335e-04, -9.47043190e-06, -8.75719129e-06, -6.60658083e-06,\n", + " -1.00719195e-04]),\n", + " array([ 1.28372825e-05, 7.30147105e-01, 9.97737000e-01, 7.80252582e-03,\n", + " -1.96337252e-06, 2.96356183e-06, 9.99969560e-01, -1.22532914e-04,\n", + " 2.33411549e-02, 1.75815703e-04, 1.39152472e-04, 9.11738087e-05,\n", + " 5.86065669e-03, 1.22415388e-05, 1.27264796e+00, -5.75391921e-02,\n", + " 9.17429503e-02, 1.94164942e-05, -1.47818612e-05, -8.37529878e-05,\n", + " -7.63835803e-04, -8.06499767e-06, -7.39099969e-06, -5.53288860e-06,\n", + " -1.91341167e-04]),\n", + " array([ 1.28813714e-05, 7.42864362e-01, 9.97416401e-01, 8.19228412e-03,\n", + " -1.86667285e-06, 2.87882119e-06, 9.99966443e-01, -1.23169834e-04,\n", + " 2.33300325e-02, 1.75747534e-04, 1.39091035e-04, 9.11284578e-05,\n", + " 5.85786669e-03, 1.16753160e-05, 1.27105036e+00, -5.23962495e-02,\n", + " 7.79541544e-02, 1.89748689e-05, -1.72497141e-05, -6.36920598e-05,\n", + " -1.11223928e-03, -6.81692933e-06, -6.14376491e-06, -4.53508228e-06,\n", + " -2.78999479e-04]),\n", + " array([ 1.29217515e-05, 7.55564281e-01, 9.97161232e-01, 8.51393011e-03,\n", + " -1.77204669e-06, 2.78299999e-06, 9.99963756e-01, -1.23615791e-04,\n", + " 2.33156408e-02, 1.75690186e-04, 1.39040755e-04, 9.10922066e-05,\n", + " 5.85425389e-03, 1.10955651e-05, 1.26938841e+00, -4.67293493e-02,\n", + " 6.43314425e-02, 1.85814030e-05, -1.94371718e-05, -4.45957302e-05,\n", + " -1.43917099e-03, -5.73476831e-06, -5.02797063e-06, -3.62512782e-06,\n", + " -3.61280731e-04]),\n", + " array([ 1.29586000e-05, 7.68246179e-01, 9.96972666e-01, 8.76896574e-03,\n", + " -1.67925061e-06, 2.67735682e-06, 9.99961552e-01, -1.23880443e-04,\n", + " 2.32982722e-02, 1.75641960e-04, 1.39000234e-04, 9.10640865e-05,\n", + " 5.84989158e-03, 1.05055687e-05, 1.26767445e+00, -4.07709607e-02,\n", + " 5.10090306e-02, 1.82359229e-05, -2.13750416e-05, -2.64651131e-05,\n", + " -1.73685632e-03, -4.82260180e-06, -4.05208516e-06, -2.81200196e-06,\n", + " -4.36231028e-04]),\n", + " array([ 1.29920986e-05, 7.80909547e-01, 9.96849853e-01, 8.95950037e-03,\n", + " -1.58804014e-06, 2.56300991e-06, 9.99959863e-01, -1.23973443e-04,\n", + " 2.32782763e-02, 1.75601162e-04, 1.38968032e-04, 9.10430726e-05,\n", + " 5.84486742e-03, 9.90829020e-06, 1.26592015e+00, -3.47286433e-02,\n", + " 3.81084224e-02, 1.79382589e-05, -2.30915534e-05, -9.30002559e-06,\n", + " -1.99959333e-03, -4.07977283e-06, -3.22021619e-06, -2.10139097e-06,\n", + " -5.02415751e-04]),\n", + " array([ 1.30224315e-05, 7.93554048e-01, 9.96790213e-01, 9.08817646e-03,\n", + " -1.49817298e-06, 2.44094893e-06, 9.99958702e-01, -1.23904436e-04,\n", + " 2.32560379e-02, 1.75566154e-04, 1.38942712e-04, 9.10281171e-05,\n", + " 5.83927800e-03, 9.30639774e-06, 1.26413657e+00, -2.87824528e-02,\n", + " 2.57362655e-02, 1.76876597e-05, -2.46125233e-05, 6.90071915e-06,\n", + " -2.22384085e-03, -3.50082517e-06, -2.53198032e-06, -1.49554806e-06,\n", + " -5.58941804e-04]),\n", + " array([ 1.30497845e-05, 8.06179501e-01, 9.96789736e-01, 9.15808924e-03,\n", + " -1.40941500e-06, 2.31204575e-06, 9.99958064e-01, -1.23683045e-04,\n", + " 2.32319563e-02, 1.75535396e-04, 1.38922886e-04, 9.10181839e-05,\n", + " 5.83322357e-03, 8.70228702e-06, 1.26233420e+00, -2.30835107e-02,\n", + " 1.39831397e-02, 1.74822432e-05, -2.59615367e-05, 2.21390827e-05,\n", + " -2.40815863e-03, -3.07580389e-06, -1.98264543e-06, -9.93326803e-07,\n", + " -6.05442869e-04]),\n", + " array([ 1.30743436e-05, 8.18785867e-01, 9.96843283e-01, 9.17270483e-03,\n", + " -1.32154083e-06, 2.17706433e-06, 9.99957930e-01, -1.23318869e-04,\n", + " 2.32064261e-02, 1.75507497e-04, 1.38907256e-04, 9.10122828e-05,\n", + " 5.82680325e-03, 8.09810037e-06, 1.26052300e+00, -1.77537067e-02,\n", + " 2.92323950e-03, 1.73200653e-05, -2.71601624e-05, 3.64175964e-05,\n", + " -2.55301782e-03, -2.78993847e-06, -1.56295637e-06, -5.90105640e-07,\n", + " -6.42032232e-04]),\n", + " array([ 1.30962944e-05, 8.31373241e-01, 9.96944882e-01, 9.13578061e-03,\n", + " -1.23435050e-06, 2.03666983e-06, 9.99958268e-01, -1.22821477e-04,\n", + " 2.31798210e-02, 1.75481239e-04, 1.38894650e-04, 9.10094961e-05,\n", + " 5.82011094e-03, 7.49574915e-06, 1.25871240e+00, -1.28864223e-02,\n", + " -7.38515314e-03, 1.71959392e-05, -2.82280596e-05, 4.97392118e-05,\n", + " -2.66051203e-03, -2.62577662e-06, -1.26063643e-06, -2.78673904e-07,\n", + " -6.69230687e-04]),\n", + " array([ 1.31158211e-05, 8.43941830e-01, 9.97088001e-01, 9.05129138e-03,\n", + " -1.14767034e-06, 1.89143693e-06, 9.99959036e-01, -1.22200406e-04,\n", + " 2.31524809e-02, 1.75455618e-04, 1.38884053e-04, 9.10090071e-05,\n", + " 5.81323216e-03, 6.89692589e-06, 1.25691133e+00, -8.54810115e-03,\n", + " -1.68985445e-02, 1.71045518e-05, -2.91832027e-05, 6.21071185e-05,\n", + " -2.73400552e-03, -2.56210053e-06, -1.05972116e-06, -4.88956351e-08,\n", + " -6.87878583e-04]),\n", + " array([ 1.31331065e-05, 8.56491943e-01, 9.97265800e-01, 8.92336344e-03,\n", + " -1.06136020e-06, 1.74185739e-06, 9.99960186e-01, -1.21465159e-04,\n", + " 2.31247034e-02, 1.75429867e-04, 1.38874639e-04, 9.10101250e-05,\n", + " 5.80624174e-03, 6.30311983e-06, 1.25512816e+00, -4.78045844e-03,\n", + " -2.55866208e-02, 1.70392009e-05, -3.00419959e-05, 7.35246094e-05,\n", + " -2.77775493e-03, -2.57504729e-06, -9.41381948e-07, 1.11783467e-07,\n", + " -6.99041162e-04]),\n", + " array([ 1.31483311e-05, 8.69023975e-01, 9.97471353e-01, 8.75621835e-03,\n", + " -9.75324963e-07, 1.58834723e-06, 9.99961664e-01, -1.20625210e-04,\n", + " 2.30967380e-02, 1.75403480e-04, 1.38865795e-04, 9.10123050e-05,\n", + " 5.79920259e-03, 5.71562983e-06, 1.25337073e+00, -1.60311220e-03,\n", + " -3.34303250e-02, 1.69909386e-05, -3.08193901e-05, 8.39949519e-05,\n", + " -2.79653684e-03, -2.63870063e-06, -8.84416098e-07, 2.18000711e-07,\n", + " -7.03915178e-04]),\n", + " array([ 1.31616734e-05, 8.81538392e-01, 9.97697844e-01, 8.55412703e-03,\n", + " -8.89524432e-07, 1.43125308e-06, 9.99963413e-01, -1.19689997e-04,\n", + " 2.30687850e-02, 1.75376233e-04, 1.38857145e-04, 9.10151712e-05,\n", + " 5.79216516e-03, 5.13557297e-06, 1.25164626e+00, 9.83566409e-04,\n", + " -4.04197775e-02, 1.69488777e-05, -3.15290172e-05, 9.35212674e-05,\n", + " -2.79530489e-03, -2.72469077e-06, -8.64989313e-07, 2.86619466e-07,\n", + " -7.03742789e-04]),\n", + " array([ 1.31733095e-05, 8.94035720e-01, 9.97938725e-01, 8.32137443e-03,\n", + " -8.03988372e-07, 1.27085817e-06, 9.99965377e-01, -1.18668933e-04,\n", + " 2.30409961e-02, 1.75348214e-04, 1.38848581e-04, 9.10185404e-05,\n", + " 5.78516780e-03, 4.56389152e-06, 1.24996138e+00, 2.99556042e-03,\n", + " -4.65521787e-02, 1.68991534e-05, -3.21833011e-05, 1.02106433e-04,\n", + " -2.77889037e-03, -2.80190430e-06, -8.56383810e-07, 3.36919146e-07,\n", + " -6.99736210e-04]),\n", + " array([ 1.31834130e-05, 9.06516534e-01, 9.98187856e-01, 8.06223409e-03,\n", + " -7.18838733e-07, 1.10738757e-06, 9.99967500e-01, -1.17571403e-04,\n", + " 2.30134786e-02, 1.75319858e-04, 1.38840298e-04, 9.10224515e-05,\n", + " 5.77823766e-03, 4.00135609e-06, 1.24832203e+00, 4.46241091e-03,\n", + " -5.18298059e-02, 1.68234859e-05, -3.27935710e-05, 1.09753001e-04,\n", + " -2.75174975e-03, -2.83559585e-06, -8.28262326e-07, 3.91118058e-07,\n", + " -6.93013975e-04]),\n", + " array([ 1.31921552e-05, 9.18981444e-01, 9.98439612e-01, 7.78095199e-03,\n", + " -6.34321535e-07, 9.41012913e-07, 9.99969728e-01, -1.16406771e-04,\n", + " 2.29863011e-02, 1.75292001e-04, 1.38832845e-04, 9.10272050e-05,\n", + " 5.77139219e-03, 3.44856377e-06, 1.24673346e+00, 5.42461654e-03,\n", + " -5.62581863e-02, 1.66972381e-05, -3.33701841e-05, 1.16463148e-04,\n", + " -2.71775216e-03, -2.78575717e-06, -7.45300904e-07, 4.75348727e-07,\n", + " -6.84547106e-04]),\n", + " array([ 1.31997042e-05, 9.31431090e-01, 9.98688963e-01, 7.48173817e-03,\n", + " -5.50853299e-07, 7.71856294e-07, 9.99972011e-01, -1.15184385e-04,\n", + " 2.29595012e-02, 1.75265954e-04, 1.38827194e-04, 9.10334165e-05,\n", + " 5.76464108e-03, 2.90592934e-06, 1.24520019e+00, 5.93128930e-03,\n", + " -5.98445062e-02, 1.64865048e-05, -3.39226628e-05, 1.22238643e-04,\n", + " -2.67999058e-03, -2.60470088e-06, -5.65128877e-07, 6.21145805e-07,\n", + " -6.75111068e-04]),\n", + " array([ 1.32062254e-05, 9.43866130e-01, 9.98931545e-01, 7.16876508e-03,\n", + " -4.69087674e-07, 5.99993292e-07, 9.99974304e-01, -1.13913576e-04,\n", + " 2.29330952e-02, 1.75243618e-04, 1.38824841e-04, 9.10420926e-05,\n", + " 5.75798871e-03, 2.37366685e-06, 1.24372597e+00, 6.03809243e-03,\n", + " -6.25962973e-02, 1.61440674e-05, -3.44598622e-05, 1.27080868e-04,\n", + " -2.64059108e-03, -2.23356899e-06, -2.35335871e-07, 8.67616131e-07,\n", + " -6.65237028e-04]),\n", + " array([ 1.32118797e-05, 9.56287234e-01, 9.99163699e-01, 6.84617085e-03,\n", + " -3.90010101e-07, 4.25454781e-07, 9.99976565e-01, -1.12603667e-04,\n", + " 2.29070904e-02, 1.75227643e-04, 1.38827948e-04, 9.10547375e-05,\n", + " 5.75143718e-03, 1.85175727e-06, 1.24231376e+00, 5.80545771e-03,\n", + " -6.45204304e-02, 1.56037864e-05, -3.49901898e-05, 1.30990901e-04,\n", + " -2.60048413e-03, -1.59748350e-06, 3.10708755e-07, 1.26448300e-06,\n", + " -6.55153331e-04]),\n", + " array([ 1.32168230e-05, 9.68695075e-01, 9.99382507e-01, 6.51806594e-03,\n", + " -3.15070829e-07, 2.48227065e-07, 9.99978757e-01, -1.11263971e-04,\n", + " 2.28814995e-02, 1.75221654e-04, 1.38839544e-04, 9.10735003e-05,\n", + " 5.74499013e-03, 1.33989660e-06, 1.24096571e+00, 5.29705573e-03,\n", + " -6.56224478e-02, 1.47729268e-05, -3.55219162e-05, 1.33969685e-04,\n", + " -2.55908939e-03, -5.98908196e-07, 1.15959858e-06, 1.87627948e-06,\n", + " -6.44704824e-04]),\n", + " array([ 1.32212041e-05, 9.81090323e-01, 9.99585806e-01, 6.18854121e-03,\n", + " -2.46370241e-07, 6.82495581e-08, 9.99980851e-01, -1.09903787e-04,\n", + " 2.28563610e-02, 1.75230568e-04, 1.38863801e-04, 9.11013809e-05,\n", + " 5.73865780e-03, 8.37416201e-07, 1.23968312e+00, 4.57847299e-03,\n", + " -6.59062760e-02, 1.35216963e-05, -3.60636357e-05, 1.36018362e-04,\n", + " -2.51384721e-03, 8.91357824e-07, 2.42569948e-06, 2.78806120e-06,\n", + " -6.33233056e-04]),\n", + " array([ 1.32251612e-05, 9.93473641e-01, 9.99772199e-01, 5.86167520e-03,\n", + " -1.86915258e-07, -1.14591243e-07, 9.99982820e-01, -1.08532399e-04,\n", + " 2.28317660e-02, 1.75261031e-04, 1.38906418e-04, 9.11425123e-05,\n", + " 5.73246386e-03, 3.43164152e-07, 1.23846648e+00, 3.71602508e-03,\n", + " -6.53743894e-02, 1.16690242e-05, -3.66249695e-05, 1.37138834e-04,\n", + " -2.45950307e-03, 3.04634917e-06, 4.26171147e-06, 4.11313742e-06,\n", + " -6.19393426e-04]),\n", + " array([ 1.32288177e-05, 1.00584567e+00, 9.99941044e-01, 5.54153771e-03,\n", + " -1.40972177e-07, -3.00473451e-07, 9.99984646e-01, -1.07159052e-04,\n", + " 2.28078959e-02, 1.75322025e-04, 1.38975147e-04, 9.12025470e-05,\n", + " 5.72645512e-03, -1.44668195e-07, 1.23731537e+00, 2.77558843e-03,\n", + " -6.40285382e-02, 8.96327355e-06, -3.72176545e-05, 1.37334696e-04,\n", + " -2.38700888e-03, 6.09934349e-06, 6.87289609e-06, 6.00347160e-06,\n", + " -6.00874531e-04]),\n", + " array([ 1.32322757e-05, 1.01820705e+00, 1.00009244e+00, 5.23218611e-03,\n", + " -1.14549940e-07, -4.89660221e-07, 9.99986312e-01, -1.05792924e-04,\n", + " 2.27850775e-02, 1.75425684e-04, 1.39080508e-04, 9.12891822e-05,\n", + " 5.72071544e-03, -6.28796148e-07, 1.23622855e+00, 1.82119420e-03,\n", + " -6.18712194e-02, 5.05614584e-06, -3.78572356e-05, 1.36612742e-04,\n", + " -2.28183791e-03, 1.03659272e-05, 1.05361141e-05, 8.66352355e-06,\n", + " -5.73967659e-04]),\n", + " array([ 1.32356059e-05, 1.03055835e+00, 1.00022718e+00, 4.93764909e-03,\n", + " -1.16058653e-07, -6.82533641e-07, 9.99987810e-01, -1.04443071e-04,\n", + " 2.27638635e-02, 1.75588419e-04, 1.39236757e-04, 9.14128642e-05,\n", + " 5.71538638e-03, -1.11319845e-06, 1.23520390e+00, 9.12675570e-04,\n", + " -5.89081657e-02, -5.32378706e-07, -3.85656832e-05, 1.34985334e-04,\n", + " -2.12139920e-03, 1.62734905e-05, 1.56249044e-05, 1.23681964e-05,\n", + " -5.32905779e-04]),\n", + " array([ 1.32388341e-05, 1.04290016e+00, 1.00034667e+00, 4.66189102e-03,\n", + " -1.57199564e-07, -8.79649114e-07, 9.99989133e-01, -1.03118330e-04,\n", + " 2.27451531e-02, 1.75832419e-04, 1.39463168e-04, 9.15877085e-05,\n", + " 5.71069796e-03, -1.60362318e-06, 1.23423842e+00, 1.00117156e-04,\n", + " -5.51522484e-02, -8.46035164e-06, -3.93754052e-05, 1.32474077e-04,\n", + " -1.87104741e-03, 2.43999857e-05, 2.26411147e-05, 1.74844305e-05,\n", + " -4.68842133e-04]),\n", + " array([ 1.32419217e-05, 1.05523299e+00, 1.00045261e+00, 4.40874695e-03,\n", + " -2.54146692e-07, -1.08182049e-06, 9.99990281e-01, -1.01827177e-04,\n", + " 2.27303746e-02, 1.76187643e-04, 1.39785666e-04, 9.18326198e-05,\n", + " 5.70701546e-03, -2.10830315e-06, 1.23332830e+00, -5.92446701e-04,\n", + " -5.06293352e-02, -1.96222146e-05, -4.03352842e-05, 1.29115354e-04,\n", + " -1.47784342e-03, 3.55224732e-05, 3.22497852e-05, 2.44911346e-05,\n", + " -3.68250557e-04]),\n", + " array([ 1.32447391e-05, 1.06755733e+00, 1.00054629e+00, 4.18181504e-03,\n", + " -4.29045330e-07, -1.29024963e-06, 9.99991256e-01, -1.00577493e-04,\n", + " 2.27217686e-02, 1.76694337e-04, 1.40238656e-04, 9.21723608e-05,\n", + " 5.70491172e-03, -2.63897144e-06, 1.23246894e+00, -1.21993974e-03,\n", + " -4.53868003e-02, -3.52122207e-05, -4.15194608e-05, 1.24968386e-04,\n", + " -8.60604073e-04, 5.06693818e-05, 4.52990227e-05, 3.39740935e-05,\n", + " -2.10373769e-04]),\n", + " array([ 1.32470313e-05, 1.07987364e+00, 1.00062592e+00, 3.98428846e-03,\n", + " -7.11664969e-07, -1.50671512e-06, 9.99992063e-01, -9.93762328e-05,\n", + " 2.27228310e-02, 1.77405780e-04, 1.40866183e-04, 9.26374502e-05,\n", + " 5.70528057e-03, -3.21233567e-06, 1.23165499e+00, -2.09487484e-03,\n", + " -3.95056467e-02, -5.67553801e-05, -4.30391890e-05, 1.20125991e-04,\n", + " 1.06242674e-04, 7.11442639e-05, 6.27526486e-05, 4.65089440e-05,\n", + " 3.68845477e-05]),\n", + " array([ 1.32483875e-05, 1.09218241e+00, 1.00067797e+00, 3.81869764e-03,\n", + " -1.14026727e-06, -1.73382271e-06, 9.99992709e-01, -9.82289726e-05,\n", + " 2.27390162e-02, 1.78389690e-04, 1.41718968e-04, 9.32587841e-05,\n", + " 5.70951217e-03, -3.85238508e-06, 1.23088060e+00, -4.39960862e-03,\n", + " -3.31184150e-02, -8.59505597e-05, -4.50558584e-05, 1.14726014e-04,\n", + " 1.61851578e-03, 9.83909682e-05, 8.52785252e-05, 6.21333942e-05,\n", + " 4.23160386e-04]),\n", + " array([ 1.32482904e-05, 1.10448438e+00, 1.00064732e+00, 3.68648617e-03,\n", + " -1.75750319e-06, -1.97525847e-06, 9.99993205e-01, -9.71394410e-05,\n", + " 2.27788025e-02, 1.79721365e-04, 1.42835493e-04, 9.40438651e-05,\n", + " 5.71970806e-03, -4.59481225e-06, 1.23013961e+00, -1.22968223e-02,\n", + " -2.64424813e-02, -1.23676411e-04, -4.77850695e-05, 1.08953164e-04,\n", + " 3.97863580e-03, 1.33167542e-04, 1.11652521e-04, 7.85080994e-05,\n", + " 1.01958875e-03]),\n", + " array([ 1.32466234e-05, 1.11678125e+00, 1.00033456e+00, 3.58692493e-03,\n", + " -2.57996836e-06, -2.23577307e-06, 9.99993567e-01, -9.61093619e-05,\n", + " 2.28546968e-02, 1.81434350e-04, 1.44174808e-04, 9.49098300e-05,\n", + " 5.73819911e-03, -5.49951066e-06, 1.22942620e+00, -4.02198038e-02,\n", + " -1.99123781e-02, -1.64723199e-04, -5.14610268e-05, 1.03007909e-04,\n", + " 7.58943106e-03, 1.71298540e-04, 1.33931449e-04, 8.65964833e-05,\n", + " 1.84910561e-03])],\n", + " [array([ 2.64384428e+02, 2.89350425e+02, 2.89367532e+02, 2.64366573e+02,\n", + " 4.83533174e-04, -4.41156021e+00, -4.19269086e-02, -1.18985927e-02,\n", + " 5.90701266e-03, -9.34680397e-01]),\n", + " array([ 7.98280190e+01, 1.14110646e+02, 1.14055984e+02, 7.98819088e+01,\n", + " 9.26741194e-04, -4.30262850e+00, -2.57209930e-02, -1.23123856e-02,\n", + " -3.04843177e-03, -7.63272289e-01]),\n", + " array([ 1.21236991e+01, 2.69303001e+01, 2.68790947e+01, 1.21738072e+01,\n", + " 1.03939795e-03, -2.56442623e+00, -1.39105060e-02, -9.58008857e-03,\n", + " -5.57199220e-03, -5.38590207e-01]),\n", + " array([-1.55764650e+01, -1.40395013e+01, -1.40760398e+01, -1.55410139e+01,\n", + " 9.75124349e-04, -7.27969860e-01, -5.87178669e-03, -6.08991303e-03,\n", + " -5.09818526e-03, -2.00405587e-01]),\n", + " array([-2.61857516e+01, -3.31622065e+01, -3.31836821e+01, -2.61651815e+01,\n", + " 7.96443981e-04, 7.20992751e-01, -4.34233940e-04, -2.94851521e-03,\n", + " -3.72573713e-03, 1.02492742e-01]),\n", + " array([-2.92766233e+01, -4.13055690e+01, -4.13145149e+01, -2.92683136e+01,\n", + " 5.55954831e-04, 1.70371546e+00, 3.15545747e-03, -4.85705998e-04,\n", + " -2.29598519e-03, 3.21733494e-01]),\n", + " array([-2.90143234e+01, -4.36209119e+01, -4.36204673e+01, -2.90151121e+01,\n", + " 3.04838036e-04, 2.27737878e+00, 5.40126250e-03, 1.28233978e-03,\n", + " -1.09604574e-03, 4.56739308e-01]),\n", + " array([-2.72575802e+01, -4.27100701e+01, -4.27031503e+01, -2.72645778e+01,\n", + " 8.23043411e-05, 2.53247326e+00, 6.66277924e-03, 2.44819681e-03,\n", + " -1.90223982e-04, 5.22346107e-01]),\n", + " array([-2.48519595e+01, -3.99695993e+01, -3.99586336e+01, -2.48627928e+01,\n", + " -8.92620400e-05, 2.55558592e+00, 7.20565998e-03, 3.12981096e-03,\n", + " 4.40834700e-04, 5.35863975e-01]),\n", + " array([-2.21897555e+01, -3.61939063e+01, -3.61808039e+01, -2.22025830e+01,\n", + " -2.02625324e-04, 2.41819092e+00, 7.22943088e-03, 3.43879882e-03,\n", + " 8.42716597e-04, 5.12606463e-01]),\n", + " array([-1.94574519e+01, -3.18590185e+01, -3.18452195e+01, -1.94708998e+01,\n", + " -2.61172768e-04, 2.17543145e+00, 6.88516741e-03, 3.47039296e-03,\n", + " 1.06438408e-03, 4.64789441e-01]),\n", + " array([-1.67454402e+01, -2.72615686e+01, -2.72481185e+01, -1.67585197e+01,\n", + " -2.74239584e-04, 1.86833744e+00, 6.28768431e-03, 3.30213847e-03,\n", + " 1.15001257e-03, 4.01679790e-01]),\n", + " array([-1.40968805e+01, -2.25907880e+01, -2.25784105e+01, -1.41089107e+01,\n", + " -2.53467057e-04, 1.52688188e+00, 5.52441440e-03, 2.99579706e-03,\n", + " 1.13689224e-03, 3.30134896e-01]),\n", + " array([-1.15310387e+01, -1.79701804e+01, -1.79593413e+01, -1.15415831e+01,\n", + " -2.10426687e-04, 1.17291850e+00, 4.66223857e-03, 2.60012744e-03,\n", + " 1.05558713e-03, 2.55197479e-01]),\n", + " array([-9.05710125e+00, -1.34858428e+01, -1.34768028e+01, -9.06591563e+00,\n", + " -1.55315644e-04, 8.22674131e-01, 3.75298381e-03, 2.15360705e-03,\n", + " 9.30715333e-04, 1.80621349e-01]),\n", + " array([-6.68469468e+00, -9.20796741e+00, -9.20082604e+00, -6.69168565e+00,\n", + " -9.64056655e-05, 4.88677105e-01, 2.83787633e-03, 1.68674450e-03,\n", + " 7.81726091e-04, 1.09283435e-01]),\n", + " array([-4.43229276e+00, -5.20651604e+00, -5.20124878e+00, -4.43748288e+00,\n", + " -3.99475683e-05, 1.81065027e-01, 1.95093617e-03, 1.22386496e-03,\n", + " 6.23521094e-04, 4.34668581e-02]),\n", + " array([-2.33241068e+00, -1.55972305e+00, -1.55621396e+00, -2.33590825e+00,\n", + " 9.69220623e-06, -9.17401405e-02, 1.12117264e-03, 7.84348974e-04,\n", + " 4.66967358e-04, -1.49847970e-02]),\n", + " array([-4.32091757e-01, 1.64586289e+00, 1.64779212e+00, -4.34063804e-01,\n", + " 4.98026628e-05, -3.22928613e-01, 3.73496975e-04, 3.83365603e-04,\n", + " 3.19401232e-04, -6.46265524e-02]),\n", + " array([ 1.21197603e+00, 4.32349419e+00, 4.32405835e+00, 1.21132792e+00,\n", + " 7.90749855e-05, -5.07614068e-01, -2.71539111e-04, 3.21950526e-05,\n", + " 1.85196777e-04, -1.04452271e-01]),\n", + " array([ 2.54304391e+00, 6.40016390e+00, 6.39959205e+00, 2.54350431e+00,\n", + " 9.73446819e-05, -6.43321624e-01, -7.98840397e-04, -2.61713922e-04,\n", + " 6.64188381e-05, -1.33970594e-01]),\n", + " array([ 3.51676030e+00, 7.83265360e+00, 7.83117147e+00, 3.51811646e+00,\n", + " 1.05327023e-04, -7.30389631e-01, -1.20020186e-03, -4.94774748e-04,\n", + " -3.64611954e-05, -1.53267353e-01]),\n", + " array([ 4.11392574e+00, 8.62161030e+00, 8.61942823e+00, 4.11597883e+00,\n", + " 1.04344267e-04, -7.72071835e-01, -1.47553369e-03, -6.67205571e-04,\n", + " -1.23836717e-04, -1.63013993e-01]),\n", + " array([ 4.35034099e+00, 8.81971163e+00, 8.81701823e+00, 4.35291196e+00,\n", + " 9.60559854e-05, -7.74230431e-01, -1.63336412e-03, -7.82747917e-04,\n", + " -1.96313943e-04, -1.64400765e-01]),\n", + " array([ 4.28007976e+00, 8.53028600e+00, 8.52724675e+00, 4.28301054e+00,\n", + " 8.22157138e-05, -7.44629477e-01, -1.69019073e-03, -8.48098731e-04,\n", + " -2.54280191e-04, -1.58996998e-01]),\n", + " array([ 3.98934834e+00, 7.89430048e+00, 7.89105918e+00, 3.99250048e+00,\n", + " 6.44785575e-05, -6.91947438e-01, -1.66847008e-03, -8.72075934e-04,\n", + " -2.97831182e-04, -1.48562299e-01]),\n", + " array([ 3.58122251e+00, 7.06754099e+00, 7.06422143e+00, 3.58447569e+00,\n", + " 4.42754286e-05, -6.24718201e-01, -1.59346753e-03, -8.64607011e-04,\n", + " -3.27062431e-04, -1.34847191e-01]),\n", + " array([ 3.15564700e+00, 6.19446387e+00, 6.19117016e+00, 3.15889907e+00,\n", + " 2.27570307e-05, -5.50452925e-01, -1.48967622e-03, -8.35675851e-04,\n", + " -3.42535656e-04, -1.19425617e-01]),\n", + " array([ 2.79122843e+00, 5.38700992e+00, 5.38382496e+00, 2.79439725e+00,\n", + " 7.99421301e-07, -4.75142762e-01, -1.37772991e-03, -7.94381467e-04,\n", + " -3.45641405e-04, -1.03591323e-01]),\n", + " array([ 2.53424085e+00, 4.71415856e+00, 4.71114186e+00, 2.53726681e+00,\n", + " -2.09472764e-05, -4.03189942e-01, -1.27252569e-03, -7.48243936e-04,\n", + " -3.38661370e-04, -8.83267555e-02]),\n", + " array([ 2.39708329e+00, 4.20313620e+00, 4.20032252e+00, 2.39993086e+00,\n", + " -4.19943605e-05, -3.37636970e-01, -1.18279395e-03, -7.02834928e-04,\n", + " -3.24505293e-04, -7.43267637e-02]),\n", + " array([ 2.36501417e+00, 3.84895037e+00, 3.84635068e+00, 2.36767114e+00,\n", + " -6.19641555e-05, -2.80468953e-01, -1.11187577e-03, -6.61732664e-04,\n", + " -3.06244381e-04, -6.20441670e-02]),\n", + " array([ 2.40758080e+00, 3.62708950e+00, 3.62469483e+00, 2.41005458e+00,\n", + " -8.05738189e-05, -2.32808058e-01, -1.05918717e-03, -6.26736003e-04,\n", + " -2.86626014e-04, -5.17281233e-02]),\n", + " array([ 2.49045080e+00, 3.50498082e+00, 3.50276849e+00, 2.49276234e+00,\n", + " -9.76521922e-05, -1.94959536e-01, -1.02182414e-03, -5.98238865e-04,\n", + " -2.67726330e-04, -4.34447599e-02]),\n", + " array([ 2.58431649e+00, 3.44999644e+00, 3.44793714e+00, 2.58649336e+00,\n", + " -1.13167194e-04, -1.66400877e-01, -9.95924306e-04, -5.75664584e-04,\n", + " -2.50811997e-04, -3.70893658e-02]),\n", + " array([ 2.66937347e+00, 3.43384994e+00, 3.43191422e+00, 2.67144350e+00,\n", + " -1.27233564e-04, -1.45845800e-01, -9.77614848e-04, -5.57880544e-04,\n", + " -2.36396772e-04, -3.24079538e-02]),\n", + " array([ 2.73562062e+00, 3.43426031e+00, 3.43242315e+00, 2.73760750e+00,\n", + " -1.40082583e-04, -1.31455521e-01, -9.63543936e-04, -5.43542837e-04,\n", + " -2.24427533e-04, -2.90397563e-02]),\n", + " array([ 2.78039965e+00, 3.43494742e+00, 3.43319038e+00, 2.78232083e+00,\n", + " -1.51995559e-04, -1.21169471e-01, -9.51084015e-04, -5.31348735e-04,\n", + " -2.14521298e-04, -2.65779754e-02]),\n", + " array([ 2.80503388e+00, 3.42487245e+00, 3.42318371e+00, 2.80690046e+00,\n", + " -1.63220325e-04, -1.13056849e-01, -9.38335830e-04, -5.20194974e-04,\n", + " -2.06180737e-04, -2.46343929e-02]),\n", + " array([ 2.81211087e+00, 3.39736788e+00, 3.39574085e+00, 2.81392885e+00,\n", + " -1.73891188e-04, -1.05584399e-01, -9.24049228e-04, -5.09254282e-04,\n", + " -1.98941703e-04, -2.28908442e-02]),\n", + " array([ 2.80410471e+00, 3.34943733e+00, 3.34786890e+00, 2.80587661e+00,\n", + " -1.83963811e-04, -9.77419516e-02, -9.07534408e-04, -4.97990570e-04,\n", + " -1.92441198e-04, -2.11266040e-02]),\n", + " array([ 2.78315344e+00, 3.28116505e+00, 3.27965385e+00, 2.78487965e+00,\n", + " -1.93162901e-04, -8.90281352e-02, -8.88583380e-04, -4.86135685e-04,\n", + " -1.86426693e-04, -1.92203272e-02]),\n", + " array([ 2.75135574e+00, 3.19503907e+00, 3.19358420e+00, 2.75303549e+00,\n", + " -2.00930163e-04, -7.93413400e-02, -8.67389347e-04, -4.73647269e-04,\n", + " -1.80740465e-04, -1.71329885e-02]),\n", + " array([ 2.71101803e+00, 3.09509178e+00, 3.09369185e+00, 2.71264991e+00,\n", + " -2.06354592e-04, -6.88336483e-02, -8.44450616e-04, -4.60661190e-04,\n", + " -1.75304893e-04, -1.48815939e-02]),\n", + " array([ 2.66460959e+00, 2.98593632e+00, 2.98458858e+00, 2.66619179e+00,\n", + " -2.08065170e-04, -5.77742029e-02, -8.20461361e-04, -4.47446767e-04,\n", + " -1.70119000e-04, -1.25125696e-02]),\n", + " array([ 2.61443809e+00, 2.87183414e+00, 2.87053364e+00, 2.61596846e+00,\n", + " -2.04064434e-04, -4.64475185e-02, -7.96202577e-04, -4.34371412e-04,\n", + " -1.65268284e-04, -1.00806398e-02]),\n", + " array([ 2.56202064e+00, 2.75574422e+00, 2.75448267e+00, 2.56349664e+00,\n", + " -1.91477502e-04, -3.50940396e-02, -7.72438362e-04, -4.21886249e-04,\n", + " -1.60960930e-04, -7.63594401e-03]),\n", + " array([ 2.50658233e+00, 2.63768767e+00, 2.63645162e+00, 2.50800129e+00,\n", + " -1.66183024e-04, -2.38920223e-02, -7.49782559e-04, -4.10565202e-04,\n", + " -1.57653750e-04, -5.22093081e-03]),\n", + " array([ 2.44030386e+00, 2.50993023e+00, 2.50869689e+00, 2.44166481e+00,\n", + " -1.22278876e-04, -1.29858973e-02, -7.28393221e-04, -4.01300199e-04,\n", + " -1.56484158e-04, -2.88086304e-03]),\n", + " array([ 2.33186427e+00, 2.34043828e+00, 2.33916078e+00, 2.33317939e+00,\n", + " -5.13154415e-05, -2.59531886e-03, -7.07160727e-04, -3.95941231e-04,\n", + " -1.60558591e-04, -6.99099466e-04]),\n", + " array([ 2.06873291e+00, 2.01497992e+00, 2.01354723e+00, 2.07012061e+00,\n", + " 5.88096667e-05, 6.68195771e-03, -6.83581654e-04, -3.98558836e-04,\n", + " -1.76183052e-04, 1.13539256e-03]),\n", + " array([ 2.15845186e+00, 2.07603045e+00, 2.07457995e+00, 2.15976706e+00,\n", + " 1.30048469e-04, 1.30826557e-02, -6.93503398e-04, -4.01580454e-04,\n", + " -1.75202503e-04, 2.62719465e-03]),\n", + " array([ 2.33749528e+00, 2.23708284e+00, 2.23562073e+00, 2.33876619e+00,\n", + " 1.74471347e-04, 1.76222818e-02, -7.20375466e-04, -4.09858768e-04,\n", + " -1.72250115e-04, 3.73652589e-03]),\n", + " array([ 2.52912759e+00, 2.41236092e+00, 2.41086927e+00, 2.53039572e+00,\n", + " 2.00464728e-04, 2.13802950e-02, -7.55261904e-04, -4.23309804e-04,\n", + " -1.72002689e-04, 4.63180507e-03]),\n", + " array([ 2.71336023e+00, 2.57865551e+00, 2.57711800e+00, 2.71465787e+00,\n", + " 2.13868271e-04, 2.50176595e-02, -7.93846438e-04, -4.40450129e-04,\n", + " -1.74772338e-04, 5.46012131e-03]),\n", + " array([ 2.88639825e+00, 2.73127925e+00, 2.72968527e+00, 2.88774678e+00,\n", + " 2.18746167e-04, 2.88456962e-02, -8.33812388e-04, -4.59798289e-04,\n", + " -1.79792199e-04, 6.30328412e-03]),\n", + " array([ 3.04841062e+00, 2.87052340e+00, 2.86886739e+00, 3.04982272e+00,\n", + " 2.17923143e-04, 3.29544628e-02, -8.73762955e-04, -4.80192703e-04,\n", + " -1.86233227e-04, 7.19218343e-03]),\n", + " array([ 3.20007176e+00, 2.99764456e+00, 2.99592477e+00, 3.20155377e+00,\n", + " 2.13358933e-04, 3.73087337e-02, -9.12776522e-04, -5.00785741e-04,\n", + " -1.93437219e-04, 8.12643599e-03]),\n", + " array([ 3.34172689e+00, 3.11376873e+00, 3.11198605e+00, 3.34328079e+00,\n", + " 2.06410102e-04, 4.18082865e-02, -9.50202900e-04, -5.20970701e-04,\n", + " -2.00927646e-04, 9.08860639e-03]),\n", + " array([ 3.47330327e+00, 3.21966914e+00, 3.21782628e+00, 3.47492802e+00,\n", + " 1.98012955e-04, 4.63235441e-02, -9.85559387e-04, -5.40312581e-04,\n", + " -2.08371524e-04, 1.00530778e-02]),\n", + " array([ 3.59441078e+00, 3.31579435e+00, 3.31389522e+00, 3.59610332e+00,\n", + " 1.88811125e-04, 5.07163030e-02, -1.01847456e-03, -5.58496768e-04,\n", + " -2.15539868e-04, 1.09913229e-02]),\n", + " array([ 3.70447452e+00, 3.40235814e+00, 3.40040744e+00, 3.70623047e+00,\n", + " 1.79244402e-04, 5.48519621e-02, -1.04865811e-03, -5.75294531e-04,\n", + " -2.22277005e-04, 1.18750205e-02]),\n", + " array([ 3.80285863e+00, 3.47943531e+00, 3.47743825e+00, 3.80467273e+00,\n", + " 1.69610460e-04, 5.86070534e-02, -1.07588592e-03, -5.90541151e-04,\n", + " -2.28478869e-04, 1.26779463e-02]),\n", + " array([ 3.88897212e+00, 3.54704725e+00, 3.54500933e+00, 3.89083859e+00,\n", + " 1.60107636e-04, 6.18741568e-02, -1.09999413e-03, -6.04122690e-04,\n", + " -2.34078247e-04, 1.33771685e-02]),\n", + " array([ 3.96235530e+00, 3.60523278e+00, 3.60315961e+00, 3.96426807e+00,\n", + " 1.50864553e-04, 6.45652396e-02, -1.12087801e-03, -6.15968297e-04,\n", + " -2.39034931e-04, 1.39538283e-02]),\n", + " array([ 4.02274610e+00, 3.65410311e+00, 3.65200032e+00, 4.02469903e+00,\n", + " 1.41960610e-04, 6.66138610e-02, -1.13849291e-03, -6.26045722e-04,\n", + " -2.43329180e-04, 1.43936363e-02]),\n", + " array([ 4.07012550e+00, 3.69388069e+00, 3.69175381e+00, 4.07211248e+00,\n", + " 1.33440205e-04, 6.79763708e-02, -1.15285509e-03, -6.34358436e-04,\n", + " -2.46957340e-04, 1.46871334e-02]),\n", + " array([ 4.10474155e+00, 3.72492208e+00, 3.72277645e+00, 4.10675666e+00,\n", + " 1.25322674e-04, 6.86321031e-02, -1.16404127e-03, -6.40943224e-04,\n", + " -2.49928842e-04, 1.48297328e-02]),\n", + " array([ 4.12711237e+00, 3.74772562e+00, 3.74556633e+00, 4.12914994e+00,\n", + " 1.17609346e-04, 6.85825504e-02, -1.17218599e-03, -6.45867567e-04,\n", + " -2.52264037e-04, 1.48215437e-02]),\n", + " array([ 4.13800943e+00, 3.76292548e+00, 3.76075729e+00, 4.14006414e+00,\n", + " 1.10288658e-04, 6.78495525e-02, -1.17747659e-03, -6.49226423e-04,\n", + " -2.53992495e-04, 1.46669921e-02]),\n", + " array([ 4.13842425e+00, 3.77127426e+00, 3.76910156e+00, 4.14049119e+00,\n", + " 1.03339971e-04, 6.64726106e-02, -1.18014581e-03, -6.51138267e-04,\n", + " -2.55151547e-04, 1.43742594e-02]),\n", + " array([ 4.12952231e+00, 3.77361713e+00, 3.77144391e+00, 4.13159702e+00,\n", + " 9.67365116e-05, 6.45055165e-02, -1.18046251e-03, -6.51740434e-04,\n", + " -2.55784895e-04, 1.39545792e-02]),\n", + " array([ 4.11258927e+00, 3.77086073e+00, 3.76869051e+00, 4.11466777e+00,\n", + " 9.04477011e-05, 6.20125434e-02, -1.17872105e-03, -6.51183923e-04,\n", + " -2.55941191e-04, 1.34214423e-02]),\n", + " array([ 4.08897434e+00, 3.76394015e+00, 3.76177603e+00, 4.09105315e+00,\n", + " 8.44410256e-05, 5.90644744e-02, -1.17523010e-03, -6.49627921e-04,\n", + " -2.55672530e-04, 1.27897670e-02]),\n", + " array([ 4.06003565e+00, 3.75378715e+00, 3.75163172e+00, 4.06211182e+00,\n", + " 7.86835449e-05, 5.57347411e-02, -1.17030198e-03, -6.47234069e-04,\n", + " -2.55032516e-04, 1.20750873e-02]),\n", + " array([ 4.02709148e+00, 3.74130178e+00, 3.73915722e+00, 4.02916252e+00,\n", + " 7.31430925e-05, 5.20959108e-02, -1.16424041e-03, -6.44161285e-04,\n", + " -2.54075198e-04, 1.12928124e-02]),\n", + " array([ 3.99138006e+00, 3.72732947e+00, 3.72519751e+00, 3.99344399e+00,\n", + " 6.77891771e-05, 4.82167047e-02, -1.15733394e-03, -6.40560446e-04,\n", + " -2.52852114e-04, 1.04575925e-02]),\n", + " array([ 3.95402961e+00, 3.71264407e+00, 3.71052605e+00, 3.95608487e+00,\n", + " 6.25936375e-05, 4.41596623e-02, -1.14984610e-03, -6.36569871e-04,\n", + " -2.51410891e-04, 9.58281710e-03]),\n", + " array([ 3.91603883e+00, 3.69793735e+00, 3.69583429e+00, 3.91808420e+00,\n", + " 5.75310551e-05, 3.99795017e-02, -1.14200871e-03, -6.32310877e-04,\n", + " -2.49792814e-04, 8.68025791e-03]),\n", + " array([ 3.87826718e+00, 3.68381421e+00, 3.68172685e+00, 3.88030176e+00,\n", + " 5.25789513e-05, 3.57221641e-02, -1.13401701e-03, -6.27883681e-04,\n", + " -2.48030058e-04, 7.75985493e-03]),\n", + " array([ 3.84143381e+00, 3.67079274e+00, 3.66872167e+00, 3.84345687e+00,\n", + " 4.77178145e-05, 3.14244880e-02, -1.12602430e-03, -6.23363368e-04,\n", + " -2.46142943e-04, 6.82963632e-03]),\n", + " array([ 3.80612314e+00, 3.65930809e+00, 3.65725385e+00, 3.80813403e+00,\n", + " 4.29309937e-05, 2.71144344e-02, -1.11813711e-03, -6.18795397e-04,\n", + " -2.44136436e-04, 5.89575722e-03]),\n", + " array([ 3.77279543e+00, 3.64971868e+00, 3.64768193e+00, 3.77479341e+00,\n", + " 3.82045091e-05, 2.28117750e-02, -1.11040974e-03, -6.14190274e-04,\n", + " -2.41995834e-04, 4.96264066e-03]),\n", + " array([ 3.74180053e+00, 3.64231369e+00, 3.64029538e+00, 3.74378456e+00,\n", + " 3.35268443e-05, 1.85291715e-02, -1.10283714e-03, -6.09516715e-04,\n", + " -2.39681287e-04, 4.03320695e-03]),\n", + " array([ 3.71339317e+00, 3.63732053e+00, 3.63532216e+00, 3.71536168e+00,\n", + " 2.88887994e-05, 1.42736011e-02, -1.09534507e-03, -6.04692458e-04,\n", + " -2.37120556e-04, 3.10918395e-03]),\n", + " array([ 3.68774895e+00, 3.63491135e+00, 3.63293530e+00, 3.68969949e+00,\n", + " 2.42835109e-05, 1.00481324e-02, -1.08777612e-03, -5.99571634e-04,\n", + " -2.34199338e-04, 2.19150136e-03]),\n", + " array([ 3.66497986e+00, 3.63520750e+00, 3.63325746e+00, 3.66690870e+00,\n", + " 1.97067896e-05, 5.85412142e-03, -1.07986968e-03, -5.93927297e-04,\n", + " -2.30748161e-04, 1.28078692e-03]),\n", + " array([ 3.64514924e+00, 3.63828090e+00, 3.63636239e+00, 3.64705079e+00,\n", + " 1.51579955e-05, 1.69398546e-03, -1.07123388e-03, -5.87427270e-04,\n", + " -2.26524586e-04, 3.78003045e-04]),\n", + " array([ 3.62828565e+00, 3.64415066e+00, 3.64227183e+00, 3.63015170e+00,\n", + " 1.06417762e-05, -2.42516251e-03, -1.06130603e-03, -5.79600857e-04,\n", + " -2.21189014e-04, -5.14709000e-04]),\n", + " array([ 3.61439495e+00, 3.65277231e+00, 3.65094491e+00, 3.61621367e+00,\n", + " 6.17115790e-06, -6.48656633e-03, -1.04929788e-03, -5.69793192e-04,\n", + " -2.14271878e-04, -1.39286939e-03]),\n", + " array([ 3.60346679e+00, 3.66401267e+00, 3.66225340e+00, 3.60522136e+00,\n", + " 1.77272959e-06, -1.04568625e-02, -1.03411973e-03, -5.57103013e-04,\n", + " -2.05129536e-04, -2.24801676e-03]),\n", + " array([ 3.59546071e+00, 3.67759093e+00, 3.67592323e+00, 3.59712748e+00,\n", + " -2.50497553e-06, -1.42760232e-02, -1.01427525e-03, -5.40298605e-04,\n", + " -1.92886184e-04, -3.06532334e-03]),\n", + " array([ 3.59021700e+00, 3.69292430e+00, 3.69138077e+00, 3.59176307e+00,\n", + " -6.57826075e-06, -1.78425538e-02, -9.87713408e-04, -5.17706365e-04,\n", + " -1.76361520e-04, -3.82006639e-03]),\n", + " array([ 3.58709708e+00, 3.70867301e+00, 3.70729848e+00, 3.58847710e+00,\n", + " -1.03078273e-05, -2.09913680e-02, -9.51611398e-04, -4.87069750e-04,\n", + " -1.53995366e-04, -4.47231978e-03]),\n", + " array([ 3.58367064e+00, 3.72128649e+00, 3.72014175e+00, 3.58482302e+00,\n", + " -1.34678176e-05, -2.34602133e-02, -9.02026028e-04, -4.45393945e-04,\n", + " -1.23824369e-04, -4.95883366e-03]),\n", + " array([ 3.57107534e+00, 3.72015252e+00, 3.71931764e+00, 3.57191872e+00,\n", + " -1.57002893e-05, -2.48378328e-02, -8.33235570e-04, -3.88860236e-04,\n", + " -8.37231873e-05, -5.18042207e-03]),\n", + " array([ 3.51782116e+00, 3.67107341e+00, 3.67064616e+00, 3.51825577e+00,\n", + " -1.64520078e-05, -2.44824373e-02, -7.36215199e-04, -3.13139791e-04,\n", + " -3.26658630e-05, -4.98243519e-03]),\n", + " array([ 3.31356513e+00, 3.45946346e+00, 3.45953460e+00, 3.31349722e+00,\n", + " -1.48985113e-05, -2.13919115e-02, -5.94487640e-04, -2.15263700e-04,\n", + " 2.44565878e-05, -4.12851385e-03]),\n", + " array([ 2.57458619e+00, 2.69413091e+00, 2.69464954e+00, 2.57406254e+00,\n", + " -9.89238399e-06, -1.39969790e-02, -3.72692469e-04, -1.00585553e-04,\n", + " 6.12364647e-05, -2.31966354e-03])],\n", + " True)" ] }, - "execution_count": 115, + "execution_count": 5, "metadata": {}, "output_type": "execute_result" } @@ -10280,7 +1197,7 @@ }, { "cell_type": "code", - "execution_count": 116, + "execution_count": 6, "metadata": {}, "outputs": [], "source": [ @@ -10289,7 +1206,7 @@ }, { "cell_type": "code", - "execution_count": 109, + "execution_count": 7, "metadata": {}, "outputs": [], "source": [ @@ -10325,24 +1242,24 @@ }, { "cell_type": "code", - "execution_count": 112, + "execution_count": 9, "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "<matplotlib.text.Text at 0x7feda970e3d0>" + "Text(0.5,0,'[s]')" ] }, - "execution_count": 112, + "execution_count": 9, "metadata": {}, "output_type": "execute_result" }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "<matplotlib.figure.Figure at 0x7fedb118a8d0>" + "<Figure size 1080x720 with 4 Axes>" ] }, "metadata": { @@ -10352,9 +1269,9 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "<matplotlib.figure.Figure at 0x7fedc0323710>" + "<Figure size 432x288 with 1 Axes>" ] }, "metadata": { @@ -10364,9 +1281,9 @@ }, { "data": { - "image/png": "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\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAYIAAAEWCAYAAABrDZDcAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDIuMi4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvIxREBQAAIABJREFUeJzt3Xl4HOWV6OHf6UWSZa2WJe+yZLzgBWMTA3FYgiEhhAkwcBkuSRhCAkMImXuZkExCJgyZLJfJQjIhQxLiLCyBxMnADAHCYBgMISzeWGwwNni3ZVu2LFurLauXc/+obrkta2lLVV1S93mfp5/urq6u75SWOnW+rxZRVYwxxuSugN8BGGOM8ZclAmOMyXGWCIwxJsdZIjDGmBxnicAYY3KcJQJjjMlxlgiM8YGInCcidYNcRrWItIlI0K24TG6yRGCGDBE5W0ReEZFmETkgIi+LyOmJz64TkZdOYFk1IqIiEvIo1qUi8s0epl8mIvVetZtKVXeoapGqxhJtvyAiN3jdrsk+lgjMkCAiJcCTwL8Do4AJwDeAI37G1Yf7gb8VEek2/W+Bh1U1mvmQjBkYSwRmqJgOoKq/U9WYqh5W1WdUda2IzATuBRYmukKaAETkr0TkDRFpEZGdIvIvKct7MfHclPjOwsR3PiMi60XkYGKvfvIA430MJ2Gdk5wgIuXAx4AHE+/zReQuEdkhIntF5F4RGdHTwkRkZmKPvklE1onIpSmfjRCRH4jI9kS19FJiWlfVIyL/LxHLPYn1vUdEfiIiP+jWzhMi8g8DXGeTrVTVHvbw/QGUAI3AA8BHgfJun18HvNRt2nnAKTg7NHOBvcBfJz6rARQIpcz/18AmYCYQAm4HXhlEzL8Afpny/rPAmynvfwQ8jpMwioEngH9Nib0u8TqciOufgDzgfKAVmJH4/CfACzhVUhD4AJDffR0T89yQ0v4ZwG4gkHg/GjgEjPH7922PofWwisAMCaraApyNs2H7BdAgIo+LyJg+vvOCqr6lqnFVXQv8DvhgH818FmdDvF6drps7gXmDqAoeAP4mZS//2sQ0El1Gfwd8QVUPqGpror2re1jO+4Ei4Duq2qmqy3C6yT4uIgHgM8AtqrpLnWrpFVXtt8tMVVcCzcAFiUlXAy+o6t4Brq/JUpYIzJCR2EBfp6oTgTnAeJy96h6JyJki8ryINIhIM3ATzl5vbyYDdye6X5qAA4Dg7Gl3X/a9iS6WNhH5p17ifQloAC4TkSnA6cBvEx9XAoXAayntPZ2Y3t14YKeqxlOmbU/ENRooADb3sV59eQC4JvH6GuA3A1yOyWKWCMyQpKobcAZk5yQn9TDbb3G6XiapainOOIL0Mf9O4LOqWpbyGKGqr/TQ/k3qHJFTpKp39hHqgziVwN8Cz6Tsbe8HDgOzU9oqVdWiHpaxG5iU2PtPqgZ2JZbTAZzURwxdYfcw7SGcRHUqTpfYY2ksx+QYSwRmSBCRk0XkiyIyMfF+EvBxYHlilr3ARBHJS/laMXBAVTtE5AzgEymfNQBxYErKtHuBr4rI7EQbpSLyN4MM/UHgQzjdQA8kJyb27n8B/JuIVCXamyAiH+lhGSuAduDLIhIWkfOAS4AlieX8GvihiIwXkaCILBSR/B6Ws7fb+qKqdcAqnErgUVU9PLjVNdnIEoEZKlqBM4EVItKOkwDeBr6Y+HwZsA6oF5H9iWk3A98UkVbgDuAPyYWp6iHg/wEvJ7pm3q+q/wV8F1giIi2J5X90MEGr6jbgFWAkTnWS6is4g8DLE+39DzCjh2V0ApcmYtkP/BS4NlEVAXwJeAtng34gsQ49/e/eDVyZOCLqxynTH8AZVLduIdMjUbUb0xiTzUTkXJwuoppu4xDGAFYRGJPVRCQM3IJzmKslAdMjSwTGZKnEiXhNwDj6OPrKGOsaMsaYHGcVgTHG5DjPr5DohtGjR2tNTY3fYRhjzLDy2muv7VfVnk5iPMawSAQ1NTWsXr3a7zCMMWZYEZHt6cxnXUPGGJPjLBEYY0yOs0RgjDE5bliMERhjjF8ikQh1dXV0dHT4HUqvCgoKmDhxIuFweEDft0RgjDF9qKuro7i4mJqaGo6/M6n/VJXGxkbq6uqora0d0DKsa8gYY/rQ0dFBRUXFkEwCACJCRUXFoCoWSwTGGNOPoZoEkgYbX84ngm3N23h+x/N+h2GMMb7xLBGIyK9FZJ+IvJ0ybZSIPCsiGxPP5V61n647V9zJrS/cSktni9+hGGOML7ysCO4HLuo27TbgOVWdBjyXeO+b+vZ6lu9ZTlSj/KXuL36GYowxvvEsEajqizh3U0p1GUdv5/cA8NdetZ+OJzY/gaIUh4t5bsdzfoZijDE9WrVqFXPnzqWjo4P29nZmz57N22+/3f8XT0CmDx8do6p7AFR1T/Jerj0RkRuBGwGqq6tdD0RV+ePmP7JgzAJqS2t5csuTHIkdIT/Y061gjTEGvvHEOt7Z7W438qzxJXz9ktm9fn766adz6aWXcvvtt3P48GGuueYa5syZ42oMQ3awWFUXq+oCVV1QWdnvxfNO2JqGNWxv2c5lUy/j/OrzORw9zIo9K1xvxxhjBuuOO+7g2WefZfXq1Xz5y192ffmZrgj2isi4RDUwDtiX4fa7PLbpMUaERnDh5AsJB8IUhYtYtmMZ504816+QjDFDXF977l46cOAAbW1tRCIROjo6GDlypKvLz3RF8DjwqcTrTwF/zHD7AByOHubpbU9z4eQLKQwXEg6GOWfCOTy/83li8ZgfIRljTK9uvPFGvvWtb/HJT36Sr3zlK64v38vDR38HvArMEJE6Ebke+A7wYRHZCHw48T7jntvxHO2Rdi6belnXtPOrz+dAxwHWNKzxIyRjjOnRgw8+SCgU4hOf+AS33XYbq1atYtmyZa624VnXkKp+vJePLvCqzXS9uvtVKgoqeN+Y93VNO3vC2YQDYZbtWMZpY07zMTpjjDnq2muv5dprrwUgGAyyYoX7Y5lDdrDYSy1HWqgqrCIgR1e/KK+IM8edybKd7mZaY4wZ6nIzEXS2UJxXfNz0M8eeyc7WnTR1NPkQlTHG+MMSQYpp5dMA2Ni0MdMhGWOMb3IyEbR2tvaZCDY1bcp0SMYY45ucTQQleSXHTa8cUUlJXgkbD1pFYIzJHTmXCCLxCIeih3qsCESEqWVTrSIwxuSUnEsEbZ1tAD0mAnC6hzYd3ISqZjIsY4zxTc4lgtbOVoAeu4YAppVNozXSyt5DezMZljHG+MYSQTddRw7ZOIExZgj453/+Z+6+++6u91/72tf48Y9/7Gobmb7onO+aO5uB3ruGTio7CXAOIT1n4jkZi8sYMwz8921Q/5a7yxx7Cny096vtXH/99VxxxRXccsstxONxlixZwsqVK10NIecSQbIi6C0RlOaXUlVYxaaDNmBsjPFfTU0NFRUVvPHGG+zdu5f58+dTUVHhahuWCHowrXyanVRmjDleH3vuXrrhhhu4//77qa+v5zOf+Yzry8+5MYLkTep7GyMAZ8B4S9MWovFopsIyxpheXX755Tz99NOsWrWKj3zkI64vPycrgpCEGBEa0es8U8um0hnvZGfrTmpLazMYnTHGHC8vL49FixZRVlZGMBh0ffk5VxEkLy8hIr3OY0cOGWOGkng8zvLly7n++us9WX7OJYLeLjiXakrpFAISsDOMjTG+e+edd5g6dSoXXHAB06ZN86SNnOsaauls6XN8AKAgVEB1cbVVBMYY382aNYstW7Z42kbOVQS9XXm0O7vmkDEmV1gi6MXU8qnsaN3BkdiRDERljDH+yclEUJLfd9cQQE1JDXGNU9dal4GojDHGPzmXCFqO9D9YDE4iANjWss3bgIwxxmc5lQiOxI7QGe/sd7AYoLqkGoDtLdu9DssYY3yVU4mg6/IS4f4rguK8YioKKiwRGGOyXk4lgpYjictLpDFGADC5ZDLbmrd5GJExxvTt3nvvZd68ecybN4/a2loWLVrkehs5dR5B8jpD6YwRANSU1vDnnX/2MiRjzDDy3ZXfZcOBDa4u8+RRJ/OVM77S6+c33XQTN910E5FIhPPPP59bb73V1fYhxyqCdK48mmpyyWQaOxq7vmeMMX655ZZbOP/887nkkktcX3ZOVQQDSQQAO1p2MHv0bM/iMsYMD33tuXvp/vvvZ/v27dxzzz2eLD+nKoJ0LkGdyg4hNcb47bXXXuOuu+7ioYceIhDwZpOdU4ngRCuCScWTEMSOHDLG+Oaee+7hwIEDLFq0iHnz5nHDDTe43oYvXUMi8gXgBkCBt4BPq2qH1+22draSH8wnP5if1vx5wTzGF423isAY45v77rvP8zYyXhGIyATg/wILVHUOEASuzkTb6VyCuruakhqrCIwxWc2vrqEQMEJEQkAhsDsTjaZzCeruJpdMZnvLdlTVo6iMMcZfGU8EqroLuAvYAewBmlX1mUy0ne6VR1NNLplMe6Sdxo5Gj6Iyxgx1Q31HcLDx+dE1VA5cBtQC44GRInJND/PdKCKrRWR1Q0ODK20PJBF0HTlkZxgbk5MKCgpobGwcsslAVWlsbKSgoGDAy/BjsPhDwFZVbQAQkf8EPgA8lDqTqi4GFgMsWLDAld9Aa2dr18Xk0jW51DmXYHvLdhaMXeBGGMaYYWTixInU1dXh1g6pFwoKCpg4ceKAv+9HItgBvF9ECoHDwAXA6kw0PJAxgrGFY8kL5NmAsTE5KhwOU1tb63cYnvJjjGAF8AjwOs6howESe/4et+vclOYEE0EwEKS6pNoOITXGZC1fziNQ1a8DX89km4ejh4lp7ITHCMAZMN7avNWDqIwxxn85c2bxiV55NNXkksnsaN1BNB51OyxjjPFdziWCE+0aAicRRONR9rTvcTssY4zxXc4kghO9zlCq6mLnSKMdLTtcjckYY4aCnEsEA60IwO5fbIzJTjmTCAYzRjB6xGgKQ4XsaLWKwBiTfXImEQymIhARqkuqrSIwxmSlnEkEyYqgKK9oQN+vLq62MQJjTFbKmUTQ2tlKYaiQUGBgp05MLpnMrrZdROIRlyMzxhh/5UwiaDly4vciSFVdUk1MY+xuy8gVs40xJmNyJhEcih5iZHjkgL9vRw4ZY7JVziSCSCxCXjBvwN+3cwmMMdkqdxKBRggHwgP+/qiCURSFi6wiMMZknZxJBNFYdMADxXD0EFI7l8AYk21yJhFE4oOrCAAmF0+2isAYk3VyJhFE44OrCMA5cmhP+x4iMTuE1BiTPXImEbhSEZRMJq5xdrbtdCkqY4zxX04lAjcqAoDtzdY9ZIzJHjmTCKLxqCtjBIANGBtjskqvu8gi8uM0vt+iqre7GI9n3KgIygrKKMkrsQFjY0xW6WvLeBlwRz/fvw0YNolgsBUBQE1JjZ1UZozJKn0lgn9T1Qf6+rKIlLscj2fcOGoInHGC1XtXuxCRMcYMDb2OEajqj/r7cjrzDBVuVQTVJdXUt9fTEe1wISpjjPFfv4PFIvI9ESkRkbCIPCci+0XkmkwE5yY3Bovh6IDxzlY7hNQYkx3SOWroQlVtAT4G1AHTgX/0NCoPuDFYDFBTWgPAtpZtg16WMcYMBekkguRu9MXA71T1gIfxeEJVnYog6EJFYJejNsZkmXR2kZ8QkQ3AYeBmEakEhlUHeVSjAIRk8BXByPBIqkZUsbV566CXZYwxQ0GvFYGIjANQ1duAhcACVY0Ah3AOLR02ktcGcqMiAJhcahefM8Zkj766hn4tIstF5DvAqYAAqGq7qtZnJDqXuFkRgHMugY0RGGOyRV+Hj34UOA94AbgcWC4i/ykiN4pIdWbCc4frFUHJZJqPNNPU0eTK8owxxk99DharaoeqPq2qt6jqAuCLOOMK94jIyoxE6IJoPFERuHDUEEBtaS1gRw4ZY7JD2hedE5ESoBlYAlwHnD3QRkWkTEQeEZENIrJeRBYOdFnpiMQTFYEL5xHA0SOHLBEYY7JBv7vIIvJZ4Js4Rw1pYrKq6pRBtHs38LSqXikieUDhIJbVr2RF4FYimFA0gZCEbMDYGJMV0ukr+RIwW1X3u9FgorI4F6eqQFU7gU43lt2bZEXgVtdQKBBiYvFEtjVvc2V5xhjjp3S6hjbjHDLqlilAA3CfiLwhIr8UkZHdZ0oMSq8WkdUNDQ2DatDtigCcM4yta8gYkw3SSQRfBV4RkZ+LyI+Tj0G0GQJOA36mqvOBdpzLWR9DVRer6gJVXVBZWTmI5tyvCODo5ahj8ZhryzTGGD+ks2X8ObAMeAuIu9BmHVCnqisS7x+hh0TgJk8qgpIaOuOd1B+qZ0LRBNeWa4wxmZZOIoiq6q1uNaiq9SKyU0RmqOq7wAXAO24tvydeVARdRw41b7NEYIwZ1tLpGno+0V8/TkRGJR+DbPf/AA+LyFpgHnDnIJfXJ7cPHwW7CqkxJnuks4v8icTzV1OmKc6g74Co6pvAgoF+/0R50TVUUVBBUbjIjhwyxgx7/SYCVa3NRCBe8qJrSESoKamxcwmMMcNeX1cfPa2/L6czz1DgRUUAzlVIrWvIGDPc9TVGcJ+IlKeOC3R/AL/KVKCD4cUYAThHDu1p32P3LzbGDGt99ZWUAq+RuPx0LwZ3pleGdFUELl19NCk5YLy9ZTszRs1wddnGGJMpvSYCVa3JYByeSl6G2s0xAoAppc54+ZbmLZYIjDHDVtpXHx3Okjem8aJrKCABNjdtdnW5xhiTSTmRCLyqCPKCeUwqnsSW5i2uLtcYYzIpNxKBR4PF4NykZkuTJQJjzPB1wokgcYZxvhfBeMXtO5SlOqn0JLa3bu9KNsYYM9wMpCL4DbBBRO5yOxivROIRghIkIO4XQFPKphCNR9nZutP1ZRtjTCac8C6yqn5IRASY5UE8nojGo55UA+BUBABbm7Z2HUVkjDHDSb+7yCJyl4jMTp2mjnXeheWuSDziyfgAHL2R/eZmO3LIGDM8pdNXsgFYLCIrROQmESn1Oii3eZkICsOFjBs5zo4cMsYMW/0mAlX9paqeBVwL1ABrReS3IrLI6+Dc4mXXEDgnltmRQ8aY4Sqt0VMRCQInJx77gTXArSKyxMPYXONlRQBO99DW5q3E1Y0buBljTGalM0bwQ5zuoYuBO1X1far6XVW9BJjvdYBuiMQjnlYEJ5WdREesg91tuz1rwxhjvJLO1vFt4HZVPdTDZ2e4HI8novGopxVB6jWHJhZP9KwdY4zxQjpdQ5/sngRE5DkAVW32JCqXeV0RdCUCGycwxgxDvW4dRaQAKARGi0g5Ry9HXQKMz0BsrvF6jKCsoIxRBaPsyCFjzLDU127yZ4F/wNnov54yvQX4iZdBuc3ro4bAGSewcwmMMcNRr11Dqnp34n7FX1LV2pTHqap6TwZjHLRILOL6TWm6m1I6ha1NW1FVT9sxxhi39dU1dL6qLgN2icgV3T9X1f/0NDIXRTVKvsfXyZtSOoXWSCsNhxuoKqzytC1jjHFTX/0lHwSWAZf08JkCwyYRRGIRwvneVgRTy6YCsKlpkyUCY8yw0tetKr+eeP505sLxRlS9PXwUYFr5NAA2HtzIB8Z/wNO2jDHGTemcUHaniJSlvC8XkW97G5a7IjFvDx8FKC8op3JEJe8dfM/Tdowxxm3pnEfwUVVtSr5R1YM4ZxkPG16fUJY0vXy6JQJjzLCTTiIIpt6RTERGAMPqDmVen1CWNL18OpubNtvdyowxw0o6ieAh4DkRuV5EPgM8CzzgbVju8vqEsqRp5dOIxCNsb97ueVvGGOOWfneTVfV7IrIW+FBi0rdUdam3YbkrEyeUgVMRALx38D2mlk/1vD1jjHFDujfxfQP4M/BC4vWwkqmKYErpFEISsnECY8ywks5RQ1cBK4ErgauAFSJy5WAbFpGgiLwhIk8Odln9yVRFEA6GqS2rZWPTRs/bMsYYt6SzdfwacLqq7gMQkUrgf4BHBtn2LcB6nIvYeUZVM1YRgNM99Nre1zLSljHGuCGdrqFAMgkkNKb5vV6JyETgr4BfDmY56YhpDCCjiaC+vZ7mI8PiCt3GGJPWBv1pEVkqIteJyHXAn4CnBtnuj4AvA73e21FEbhSR1SKyuqGhYcANJQ/lzETXEBwdMN540LqHjDHDQzo3r/9HYDEwFzgVWKyqXxlogyLyMWCfqvbZf6Kqi1V1gaouqKysHGhzRONRILMVAWADxsaYYSOt3WRVfRR41KU2zwIuFZGLgQKgREQeUtVrXFr+MTJdEVSOqKQsv8wSgTFm2OjrMtStOFcZPe4jQFV1QIO8qvpV4KuJNs7Dud+BJ0kAUioCj+9HkCQiTC+fbl1Dxphho68b0xSrakkPj+KBJgE/dFUEkpmKAJzuoY1NG4lrr0MgxhgzZKR19I+InC0in068Hi0itW40rqovqOrH3FhWbyIxJxFkqiIAJxEcjh6mrrUuY20aY8xApXNC2deBr5DozgHycK4/NCwku4YyNUYAMH2UM2C8/sD6jLVpjDEDlU5FcDlwKdAOoKq7gWIvg3JTsmsoU0cNAUwrm0Y4EGZd47qMtWmMMQOVTiLoVOeO7AogIiO9DcldmT58FCAvmMf08um8s/+djLVpjDEDlU4i+IOI/BwoE5G/w7m8xC+8Dcs9mT58NGl2xWzeaXzHBoyNMUNeOieU3YVzXaFHgRnAHar6714H5hY/KgKA2aNn0xppZWfrzoy2a4wxJ6qv8wjuAX6rqq+o6rM4N6QZdvwYIwCnIgBYt38dk0smZ7RtY4w5EX1VBBuBH4jINhH5rojMy1RQbvKrIphSNoX8YL4NGBtjhry+Tii7W1UXAh8EDgD3ich6EblDRKZnLMJB8muMIBwIM2PUDEsExpghL50xgu2q+l1VnQ98Audw0mFzgLxfFQE43UPrG9cTi8cy3rYxxqQrnRPKwiJyiYg8DPw38B7wvzyPzCV+VQTgJIJD0UNsb7Gb2Rtjhq6+Bos/DHwc5wYyK4ElwI2q2p6h2Fzh12AxwKyKWQCsa1zHlLIpGW/fGGPS0VdF8E/Aq8BMVb1EVR8ebkkA/LnERFJtaS0jQiNsnMAYM6T1unVU1UWZDMQrflYEoUCIk0edzLr9lgiMMUPXoO49PBxk+n4E3c2umM2GAxu64jDGmKEm6xOBn4PF4IwTdMQ62Ny02Zf2jTGmP7mTCDJ4Y5pUp4w+BYC1+9f60r4xxvQn+xNBLEJAAgQDQV/an1wymVEFo3hz35u+tG+MMf3J+kQQ1agvA8VJIsL8qvm8vvd132Iwxpi+ZH0iiMQivo0PJM2vmk9dWx37Du3zNQ5jjOlJ9ieCeMTXigDgtKrTAHhj3xu+xmGMMT3J+kQQjUd9rwhOrjiZgmCBJQJjzJCU9YlgKFQE4UCYuZVzbZzAGDMkZX0iGAoVATjjBO8efJf2yLC7SocxJstlfSIYChUBOOMEcY2zpmGN36EYY8wxsj4RROP+Hj6aNLdyLgEJ2PkExpghJ+sTQSTu/+GjAEV5Rcwon8Hr+2ycwBgztGR9IhgqFQE44wRrG9Z2XfbCGGOGgqxPBEOlIgCYP2Y+h6OHeffAu36HYowxXbI+EQylimDBmAUArNizwudIjDHmqKxPBEOpIhg9YjTTy6fzyu5X/A7FGGO6ZDwRiMgkEXleRNaLyDoRucXL9obK4aNJZ40/i9f3vc6hyCG/QzHGGMCfiiAKfFFVZwLvBz4vIrM8a2yInFCWtHD8QqLxKKv3rvY7FGOMAXxIBKq6R1VfT7xuBdYDE7xqLxKL+Habyp6cNuY0CoIFvLzrZb9DMcYYwOcxAhGpAeYDx42eisiNIrJaRFY3NDQMuA2/70fQXX4wnwVjF9g4gTFmyPAtEYhIEfAo8A+q2tL9c1VdrKoLVHVBZWXlgNsZCvcj6O6s8WexrWUbu9p2+R2KMcb4kwhEJIyTBB5W1f/0sq2hVhEAfGD8BwCsKjDGDAl+HDUkwK+A9ar6Q6/bG4oVQW1pLWNHjuWVXZYIjDH+86MiOAv4W+B8EXkz8bjYq8aG0gllSSLCWePPYsWeFUTjUb/DMcbkOD+OGnpJVUVV56rqvMTjKY/aGlInlKVaOH4hrZFW3t7/tt+hGGNyXFafWRzTGIoOuYoAnEQQCoRYtmOZ36EYY3JcVieCZLfLUKwISvJKWDhuIUu3LUVV/Q7HGJPDsjoRJC/3PBQrAoALay5kd/tu1jWu8zsUY0wOG3q7yi7KaEVw6AA0bABVCAQhmAflNVA4qtevLJq0iFAgxNJtS5kzeo73MRpjTA+yOhF4XhHseh1W/gLqVkLjpp7nKRwNlTNgwmkw6f0w6Uwock6QK80vZeG4hTyz7Rlufd+tOEfWGmNMZmV1IkhWBK4ngoPb4blvwtuPQEEpTD4b5n0Sxs2FQBg0BpHDcGAL7N8I+96BFT+HV/7d+f7o6TD5LKg5m4+MOZPbd/2Ft/e/zSmVp7gbpzHGpCGrE0GyInC1a+iNh+HJfwAJwjlfgrNugYKS/r8XPQJ71sCOV2Hby/DWI/DafSwKCKHqSTzz7Jc4ZeqVMH4+jJkD4QL3YjbGmD5kdSLoqgjcuvro6vucJDDlPLjsp1B6AhdNDeXDpDOcx1m3QCwK9Wsp2bGcD2x6iGc66rj1qS8hAIEQjDoJKqdD5clQXgtlk6CsGorGWpJIUoVYBGJHnEQb7Ug8H0lM63SmxTqPnRY74nwvOa3rdWdieZ0Qjxx9HUu8Tk6LxyAedd7HoxCPJ56jTjUYjyeeY86zxp1HPPGMJqZpt9c479MiINLLc8B5fcz73h7ijGl1vQ/28FliWvJ1INDDtJ7ep8zbfb6evtvr/N2nd3/dbXldr7t/1n0du697Dz+b5Otjfq49TZOUab3Mc9zvZujI6kTQNUYgLiSCFYvhv/8Rpn0Ernpw8BvjYMgZN5hwGhdWTuDFl2/nrU89ytyOw7D7TWfged8G2PCUszFJlV8CIythRLnTNVVQCnkjnUe40HmE8iFU4DwH8yCU5zwHwk7bgTAEw07SSf5Tpf4jpf7xdtGjG6/kRi71OR5N2WAmNpSpG9fokZQNd2fKBvxIt9eJDXjXhryHDX3yfdobzn4Ews7PJxhKPOc5P5vk6+4/s1C+8xwIHfuzS77vcYOZspGB4zceyZ91fxuJrgTS03PHSLO3AAAR6UlEQVTic01NOppISMnpMefH1vU6mahSXie/0zUt5XW08+j3un7/3ZJfvPvn3eZL/awr1lzUPZFz/OubXnJ2Cj2U1YnAtYrgzd85SeDkj8GV9zkbVRctql5E/vJ8Hqt/hbkL74CZlxz9MNoJLXXQtAOadkJbPbTvh7Z90NHkPJq2Q2f70Uf3xDFUBUIQzE8kqfxE8spPeV3gdLt1JbSU6aG8btMLjn6/a1peymd5x7fVtZHPczbaxj/JJNXTDkb3pNH1WnuZHk9JOCkJrWsHJn789OT3k4mzt+nHJdh479NJma6kvO8lkSd/Dse8xtnh81hWJ4KuMQIZxGoe3AZPfckZEP6b+509QpeV5JVwce3FPLnlSb7wvi9QnFd89MNQHoya4jzSFYs4e8uRRLfIMY+Ubo5kd0Ys2aWR8g92THcFOH+cKXsqqaV7alURDDt7zoFQShUSOrpxDoaPboQDQTd+fCYbiBz9GzIZl92JIJboGhroxjseh8duBgQu/5knSSDp6pOv5r82/RePb36cT8785OAWFkx0YeQX9z+vMSbnZXU9POgTypb/FLa/DB/9rjNQ66FZFbOYWzmXJRuWEM/Z/lJjjB+yOhEM6oSyfRuccwVm/BXM+4TLkfXs6hlXs61lG8v3LM9Ie8YYA1meCAZ1QtnSr0JeIVxyd8YO9bqw5kLK88tZsmFJRtozxhjI8kQw4BPKtr4Im5c5J4wVDfx+yScqP5jPFdOu4M91f2ZP256MtWuMyW05kQhOqCJQhf/5BpRMgNNv8Ciy3l014yoE4b5192W8bWNMbsrqRDCgweINf4Jdq+G823w5g3d80Xgun3Y5//Huf7CjZUfG2zfG5J7sPnz0RCuCeAyWfQsqpsGpmRkg7snn532eP235Ez96/Uf88Lwf+hZHT1SVxo5G9h/eT+PhRpqPNBNLOYGtMFxIUbiIonARowpGUTGigryguyfgGWPclROJIO2KYO3vnUs7XPWgc0kBn4weMZrrZl/Hz9b8jDUNazi18lTfYonEI6yqX8XyPct5p/Ed1jeup6Wz5YSWUZJXQlVhFWNGjmFs4VjGjnQe40aOY+zIsYwpHENByK6fZIxfsjoRnNBRQ7EovPh9GDsXZl7qcWT9u272dfzh3T/wg9U/4IGLHsjovQpUlVf3vMqTm5/khboXaO1sJRQIMa1sGh+e/GGml0+nqrCKihEVlOaXEpQgAQLEidMeaac90k5LZwsHOg7QeNipHvYd2sfeQ3vZ0LiBxo7G49oszy93kkIiWYwZOYYxhc6jqrCKqsIqCsOFGfsZGJNLsjoRnFBFsO6/nPsH/O+HhsSVAQvDhdw872a+tfxbPLP9GT5S8xHP2zwcPcwTm5/gt+t/y+bmzZTklbBo0iIuqL6AheMXMiI0wpV2OmOd7G3fy572PdQfqmdPm/Nc317PrrZdvLb3NVo7W4/7XlG46JjEkEwWyapiXNE4isPFdoMfY05QTiSCfiuCeBz+chdUzXJOIBsirph2BY+89wjfePUbzKqYxaTiSZ60E4lFeHTjo/x87c/Zf3g/M0fN5NtnfZuLai8iP5jvent5wTwmlUxiUknv63Mocqirikh9Tj4279nM/sP7jzsLe2R4JONGjmNC0QTGF41nQtEEJhVP6npYF5Qxx8vqRBCNRxGEYH8XstrwhDM28L9+NaSuQhkKhPjheT/kqiev4tYXbuU3H/2NqxuyuMZ5autT3PPGPexq28VpVafxvXO/x4IxC3zfqy4MF1JTWkNNaU2v80TjUfYf3k99ez17D+2lvr2ePe172N22m91tu3lt72u0RdqO+c64keOoKamhtrSWk8pOYkrpFKaWTaWsoMzjNTJm6MrqRBCJR/qvBlSdsYGKqTD78swEdgImFk/kO+d8h88/93nuXHEn3zzrm64s9819b/K9Vd/jrf1vMXPUTG7/0O2cNf4s3xPAiQgFQl0Dz71pPtLMjpYd7GzdyfbW7Wxv2c625m08tukxDkUPdc1XNaKKaaOmMaN8BjMrZjJr1CwmFk8kIENnx8AYr2R1IojGo/1fefS9pVD/Fvz1z4bsJXDPnXguN869kcVrF1NdUs31c64f8AZ7Z8tO7n7jbpZuW0rViCq+fda3ueSkS7J2g1eaX8oplaccdz9oVWXvob1satrE5qbNvHfwPd47+B4P7nmw6yCDonARs0fP5pTRpzBn9BxOrTyV0SNG+7EaxngqqxNBJBbpe6A42gnP3gHlNXDK32QsroG4+dSb2da8jbtfv5stTVu4Y+EdJ9RN1Hi4kcVrF/OHd/9AOBjmplNv4tOzP52zR+KISFc1cfaEs7umR2IRNjVtYv2B9bzT+A5v7X+L+9++n6g6yWFS8STmV81nwZgFnD72dCYUTRhWVZQxPcnqRBDVaN9dQ8t/AvvfhY//3tN7DbghGAjy/Q9+n6lrp/LTN3/KluYt/Os5/0ptaW2f39t4cCMPr3+YJ7c8STQe5YppV/C5Uz9HZWHmrqE0nISDYWZWzGRmxUyumHYFAEdiR1jfuJ43973JmoY1vLTrJR7f/DgAE4omcM6Eczhv0nmcPvZ0O3nODEtZnQj6rAiadsKfv+ccJTTjoswGNkABCfC5Uz/HjPIZfPUvX+XSxy7lfWPex+VTL2fO6DnkBfIIB8Nsbd7KqvpVrKxfyZqGNeQH87nkpEu4dta1/SYOc7z8YD7zquYxr2oe4HQrbWnewqr6Vbyy+xX+uPmPLHl3CSNCIzhz3JmcM+Eczp5wNuOLxvscuTHpET3mdoQZalTkIuBuIAj8UlW/09f8CxYs0NWrV59wO7f95TbWNqzlqSueOv7D318DG/8H/n6l5zed8ULDoQb+uPmPPLbpMba3bD/u86AEmV0xm0XVi7hy2pV2VIyHOqIdrKxfyYt1L/LSrpfY1bYLcLqRzhh7BmeMPYPTxpzW56C2MV4QkddUdUF/82W8IhCRIPAT4MNAHbBKRB5X1XfcbqvHikAV1iyB9U/A+f88LJMAQGVhJTeccgPXz7metfvXsqdtD53xTjpjnYwdOZb5VfMZGR7pd5g5oSBUwLkTz+Xcieeiqmxt3srLu19mZf1Klm5byqMbHwWgqrCKUytPZXbFbKf7adRMygu8vzG5Mf3xo2voDGCTqm4BEJElwGWA64mg7VAzRGLUbVwDqhTseoWStb8i7+AmjlTMZNf0T0NDW/8LOgF+DByWyFRKiqceM21fM0B7xmMxIIzh7KorOLvqCmJzomxt3cSGg2+x4eBbrNn3Fs9uf7Zr3vL8CqqLaqkunsL4kdWMHzmJcSMnMrpgzMBvsTpMxTVONB4hGo8S1SjReISYRolpjLjGiMVjiddxYhpDiRNX56Eo2vUMigK99XYIgvN/KkLitRAQ6fpMJIDgdMcmXx/9TJzpKe+PfnbsfCAEEq+FACLiXJJFgoQCIQqCI/o9Ym9C2QjyQt4e1efHX9oEYGfK+zrgTC8aOrTzDUZIKxMfPrdr2pr4FO6L3sxTu86k80d2S0iTKZXA+c4jcIhgwW4CBbvZl7+X/U31vJm/Fgl0ds2tKmi0GI2UEY+WOK+jJWisEI2NTDwXoPECNFYAmgcaBNzYEVEgDhJFAhGQKAQiiERSnqOIdHabnngfiIB0f452fQ+JIBJNLCPqLF9iiOTmvbo1lpf4PRah0cQjVkQ8WoRGi3n0U9dz6oRxnsbgRyLo6S/1uNQtIjcCNwJUVw+s++aSKdfS1lLPqnG1gNA+ciJNZadwngjn4f4lhXwYbjFZQlVpjR6g8cguDnTupqmzgebIXpo6G2iNHqAtspWOeN8VXoAA4UABQQkTlFDXnqezJ+rswSb3lFWVOHHiyb1tjRLXKFGNENNIYr4TF5QQIckjHMgnHMg/+loKCAVKCUmYcCCfoIQJBcKEJI9QMt5AOPF95znQtQ4hAgQJSICABAkQdPbKU9Yrubd9zN4+cvw/uWrKuiVfOT+Prp9N4n3ydfIyJt0/T3yaWCZdn3Utt2seTWkjUcUQIxaPcCTeQWf8EB2xdtqiTbRHD9IWraM9epCoOpfICeZdPaDfxYnwIxHUAakXmZkI7O4+k6ouBhaDM1g8kIau+vAtA/maMT6ZCMzt9dOOaAdNR5poPtLMwSMHaetso7WzlbZIGx3RDg5HD9MR6yASixCJR+iMdTpdKKrH3DMiuRENBAIEE10U4UCYUCBEXiDPeQ7mkR/MP/oI5VMQLCA/mE9BqIARoRHO+1D+Ma8HdH9wcxxVpS3SRuPhRiYUT/C8PT8SwSpgmojUAruAqwH/7gJjzDBRECpgbKjvS2qY7CAiFOcVU5xXnJH2Mp4IVDUqIn8PLMU5fPTXqrou03EYY4xx+HJYgqo+BfRwcL8xxphMy84rjRljjEmbJQJjjMlxlgiMMSbHWSIwxpgcZ4nAGGNynCUCY4zJcb5chvpEiUgDcPy1ltMzGtjvYjjDga1zbrB1zn6DXd/JqtrvXaiGRSIYDBFZnc71uLOJrXNusHXOfplaX+saMsaYHGeJwBhjclwuJILFfgfgA1vn3GDrnP0ysr5ZP0ZgjDGmb7lQERhjjOmDJQJjjMlxWZMIROQiEXlXRDaJyG09fJ4vIr9PfL5CRGoyH6W70ljnW0XkHRFZKyLPichkP+J0U3/rnDLflSKiIjKsDzVMZ31F5KrE73mdiPw20zG6LY2/62oReV5E3kj8bV/sR5xuEpFfi8g+EXm7l89FRH6c+JmsFZHTXA1AVYf9A+cGN5uBKUAesAaY1W2em4F7E6+vBn7vd9wZWOdFQGHi9edyYZ0T8xUDLwLLgQV+x+3x73ga8AZQnnhf5XfcGVjnxcDnEq9nAdv8jtuF9T4XOA14u5fPLwb+G+ee7+8HVrjZfrZUBGcAm1R1i6p2AkuAy7rNcxnwQOL1I8AFIm7fvj6j+l1nVX1eVQ8l3i7HuSnucJbO7xngW8D3gI5MBueBdNb374CfqOpBAFXdl+EY3ZbOOitQknhdSg/3PB9uVPVF4EAfs1wGPKiO5UCZiIxzq/1sSQQTgJ0p7+sS03qcR1WjQDNQkZHovJHOOqe6HmePYjjrd51FZD4wSVWfzGRgHknndzwdmC4iL4vIchG5KGPReSOddf4X4BoRqcO50+H/yUxovjrR//cT4sutKj3Q05599+Ni05lnOEl7fUTkGmAB8EFPI/Jen+ssIgHg34DrMhWQx9L5HYdwuofOw6n4/iIic1S1yePYvJLOOn8cuF9VfyAiC4HfJNY57n14vvF0+5UtFUEdMCnl/USOLxe75hGREE5J2VcpNtSls86IyIeArwGXquqRDMXmlf7WuRiYA7wgIttw+lIfH8YDxun+Xf9RVSOquhV4FycxDFfprPP1wB8AVPVVoADn4mzZLK3/94HKlkSwCpgmIrUikoczGPx4t3keBz6VeH0lsEwTozDDVL/rnOgm+TlOEhjufcfQzzqrarOqjlbVGlWtwRkXuVRVV/sT7qCl83f9GM5BAYjIaJyuoi0ZjdJd6azzDuACABGZiZMIGjIaZeY9DlybOHro/UCzqu5xa+FZ0TWkqlER+XtgKc5RB79W1XUi8k1gtao+DvwKp4TchFMJXO1fxIOX5jp/HygC/iMxLr5DVS/1LehBSnOds0aa67sUuFBE3gFiwD+qaqN/UQ9Omuv8ReAXIvIFnO6R64b5Th0i8juc7r3RibGPrwNhAFW9F2cs5GJgE3AI+LSr7Q/zn58xxphBypauIWOMMQNkicAYY3KcJQJjjMlxlgiMMSbHWSIwxpgcZ4nAGGNynCUCY9IkIjUiclhE3uxjnodF5ICIXJnJ2IwZDEsExpyYzao6r7cPVfWTHH8mrDFDmiUCYwZAREaKyJ9EZI2IvC0i/9vvmIwZqKy4xIQxPrgI2K2qfwUgIqU+x2PMgFlFYMzAvAV8SES+KyLnqGqz3wEZM1CWCIwZAFV9D3gfTkL4VxG5w+eQjBkw6xoyZgBEZDxwQFUfEpE2sudmOCYHWSIwZmBOAb4vInEgAnzO53iMGTBLBMYMgKouxblmvjHDno0RGJO+GFDa3wllOPeG7shYVMYMkt2YxhhjcpxVBMYYk+MsERhjTI6zRGCMMTnOEoExxuS4/w+ZrlX6oQ5mEQAAAABJRU5ErkJggg==\n", "text/plain": [ - "<matplotlib.figure.Figure at 0x7feda9a1a210>" + "<Figure size 432x288 with 1 Axes>" ] }, "metadata": { @@ -10430,7 +1347,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython2", - "version": "2.7.12" + "version": "2.7.16" } }, "nbformat": 4, diff --git a/kinton_description/meshes/arm/base.dae b/kinton_description/meshes/arm/base.dae new file mode 100644 index 0000000000000000000000000000000000000000..448793b8ca9d74daaa0a30489f9af189ac7d9990 --- /dev/null +++ b/kinton_description/meshes/arm/base.dae @@ -0,0 +1,107 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor/> + <created>2019-07-22T14:43:13.264623</created> + <modified>2019-07-22T14:43:13.264636</modified> + <unit name="meter" meter="1.0"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_effects> + <effect name="effect_Mesh" id="effect_Mesh"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color>0.0 0.0 0.0 1.0</color> + </emission> + <ambient> + <color>0.0 0.0 0.0 1.0</color> + </ambient> + <diffuse> + <color>0.0298847109079 0.0291743408889 0.0299277901649 1.0</color> + </diffuse> + <specular> + <color>1 1 1 1.0</color> + </specular> + <shininess> + <float>0.0</float> + </shininess> + <reflective> + <color>0.0 0.0 0.0 1.0</color> + </reflective> + <reflectivity> + <float>0.0</float> + </reflectivity> + <transparent> + <color>0.0 0.0 0.0 1.0</color> + </transparent> + <transparency> + <float>1.0</float> + </transparency> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>0</double_sided> + </technique> + </extra> + </profile_COMMON> + </effect> + </library_effects> + <library_geometries> + <geometry id="geometry0" name="Mesh"> + <mesh> + <source id="cubenormals-array0"> + <float_array count="9924" id="cubenormals-array0-array">0 0 -1 0 0 -1 -1.235028e-07 -4.309375e-06 -1 1.476825e-11 2.379623e-05 -1 -2.975653e-06 -1.236559e-05 -1 -2.491544e-07 2.147589e-05 -1 -2.29198e-06 5.096582e-09 -1 9.732698e-06 6.233865e-05 -1 -2.92974e-06 -3.861118e-05 -1 -2.385068e-06 1.155276e-05 -1 -6.036795e-06 7.302383e-06 -1 0 0 -1 0 0 -1 0 0 -1 -1.493661e-07 -5.211822e-06 -1 4.686544e-07 1.204792e-06 -1 -1.487106e-05 4.976026e-05 -1 -1.979541e-05 -1.392951e-05 -1 -0.008209096 0.005069415 -0.9999534 -0.002069905 0.003636481 -0.9999912 0.06367473 0.00028195 -0.9979706 -8.306118e-07 -1 -0 -8.306118e-07 -1 -0 8.306117e-07 1 -0 8.306117e-07 1 -0 0.006684914 0.007615675 -0.9999487 0.01041509 0.006397921 -0.9999253 0.01088734 2.069786e-06 -0.9999408 0.009237493 -0.001046328 -0.9999568 -2.454837e-08 -0.02983577 -0.9995548 -0.03018006 0.003666843 -0.9995378 -0.01182313 1.026409e-08 -0.9999301 -0.01235328 -0.004295451 -0.9999145 -0.0290721 2.566096e-08 -0.9995773 0.007953665 0.04103575 -0.999126 8.939639e-09 0.01080132 -0.9999416 0.01870109 -9.199493e-06 -0.9998251 0.01993385 -0.01179709 -0.9997317 0.02232694 -0.01105344 -0.9996896 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 -0 -0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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.351761e-05 2.10857e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.049929e-05 -1.657565e-06 -1 1 -7.629397e-07 0 1 -7.629397e-07 0 0.001185104 -0.9998835 -0.01521996 -6.781683e-07 -1 -0 0.003246153 -0.9998279 0.01826343 -7.19612e-07 -0.9998024 -0.0198791 0.0005538545 -0.9999746 -0.007115536 0.0005535898 -0.9994966 -0.0317227 -0.004437402 -0.9999287 0.0110916 -7.629395e-07 -1 0 -7.629395e-07 -1 0 7.629395e-07 1 -0 0.01169909 0.9985883 -0.05181238 7.485376e-07 0.9999909 -0.004271103 0.0006756218 0.9999926 0.003796558 6.781684e-07 1 -0 7.629395e-07 1 0 -0.003745378 0.9999491 0.009365351 0.001484329 0.9993623 -0.03567681 0.001485141 0.9999087 0.01343064 -0.006561026 0.9993222 -0.03622199 1 -7.629395e-07 0 1 -7.629395e-07 0 -6.103518e-07 -1 0 -1 4.487879e-07 0 4.009359e-07 -9.305014e-07 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 -0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 -6.421989e-07 4.397823e-06 1 0 0 1 0 0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 -0 1 0 -0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.9998806 0.008626634 0.01281656 0.9993639 -7.390408e-07 -0.03566223 0.9997583 0.00107807 -0.02196019 0.9999933 -7.362843e-07 -0.003675354 0.9998025 -0.004358661 0.01939075 -0.999962 -0.004921251 0.007203321 -0.9998577 -0.000547657 -0.01685976 -0.9999932 7.883654e-07 -0.003674124 -0.9993042 0.007593966 0.03651721 0.9991878 -0.03849732 -0.01190693 1 -1.271566e-06 0 1 -1.271566e-06 0 0.9996816 0.02351587 -0.009152384 1 -6.357829e-07 2.474469e-07 1 -6.357829e-07 0 1 -6.357829e-07 0 1 -7.629397e-07 0 1 -8.247994e-07 3.092982e-07 1 -7.529284e-07 2.823467e-07 1 -7.629395e-07 0 0.9999992 0.0002536182 0.001271906 0.9999987 -7.399738e-07 -0.001615339 0.9999978 -0.0001435676 0.002101594 1 -7.657533e-07 3.683777e-07 1 -1.271566e-06 1.321054e-05 1 -7.26609e-07 4.644485e-07 6.781683e-07 1 0 7.366312e-07 1 3.28854e-07 6.781684e-07 1 -0 7.629395e-07 1 -0 7.629395e-07 1 -4.768372e-07 7.629395e-07 1 5.820766e-13 7.629394e-07 1 -0 -1 7.629396e-07 0 -1 6.185995e-07 7.217001e-07 -0.9999999 -0.0002996001 0.0001133034 -0.9999983 -8.83893e-06 -0.001839421 -0.9999979 7.910058e-07 -0.002090086 -0.9999986 0.0003301906 0.001647139 -1 7.629392e-07 0 -6.781684e-07 -1 -0 -6.840147e-07 -1 3.288512e-08 -6.781684e-07 -1 0 -7.629394e-07 -1 0 -6.866455e-07 -1 -4.768342e-08 -6.866455e-07 -1 9.536743e-07 -6.103515e-07 -1 0 -0 0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.514653e-06 -5.50576e-07 1 -2.153249e-06 1.481151e-07 1 -2.6871e-06 -1.675829e-07 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 0 0 1 -3.271834e-06 2.259929e-06 1 1.022948e-05 1.512089e-05 1 0 0 1 0 -0 1 0 0 1 0 0 1 -5.522272e-05 -5.473452e-05 1 0 0 1 -0 0 1 5.274406e-05 2.839853e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 1.249712e-05 -1.903942e-05 1 -6.643549e-05 6.481839e-05 1 5.601045e-05 -2.488529e-05 1 -0 0 1 -0 0 1 -2.509661e-06 2.086994e-08 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 -0 0 1 0 0 1 -0 0 1 0 0 1 0 -0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 0 0 1 -0 0 1 -0.1429608 0.9897277 0.001133882 -0.2022941 0.9785737 -0.03834837 -0.8503693 0.5247868 0.03835121 -0.8946128 0.4463684 -0.02056905 -0.9171733 -0.3984822 0.002277328 -0.9320759 -0.3613391 -0.02585693 -0.5285127 -0.8480883 0.03768981 -0.283702 -0.956714 -0.06489518 0.08068397 -0.9956627 0.0463239 0.5512036 -0.8333363 -0.04153479 0.6165791 -0.787292 -0.00124592 0.9641182 -0.2649486 0.01668154 0.9921921 -0.1133453 -0.0520358 0.949556 0.3097794 0.04878698 0.7026072 0.7083906 -0.06727456 0.5526643 0.8328094 0.03147253 0.1220948 0.9917986 0.03779352 -0.05976395 0.9958458 -0.06869823 -0.6410802 0.7633342 0.07960566 -0.8630642 0.4987815 -0.0796065 -0.9971638 -0.05193226 0.05447461 -0.9547893 -0.2922497 -0.05447525 -0.7103914 -0.7013758 0.05844622 -0.3689609 -0.9284437 -0.04312951 -0.2067227 -0.9781973 0.01989229 0.2648908 -0.9638146 -0.02990479 0.4447407 -0.8947003 0.04143797 0.7867256 -0.6162211 -0.03652675 0.9274707 -0.3706009 0.049528 0.9957877 -0.08069092 -0.04353973 0.8791695 0.4737755 0.05096774 0.7978702 0.601644 -0.03778267 -1 6.634256e-07 0 -1 6.634256e-07 0 -1 6.634256e-07 0 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 -2.677591e-07 -2.915204e-06 -1 0 0 -1 -0 0 -1 9.730694e-07 1.308992e-05 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.34039e-07 1.176691e-05 -1 0 0 -1 3.235795e-07 -1.564055e-06 -1 0 0 -1 -4.185547e-07 3.125615e-06 -1 2.780089e-08 -2.821198e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 -0 0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 -0 0 1 0 0 1 0.0934631 0.9951734 0.02991017 -0.3997471 0.9163406 -0.02285198 -0.4704964 0.8823273 0.01147207 -0.8823476 0.4704584 -0.01147886 -0.9386701 0.3411563 0.05010797 -0.9902878 -0.1226372 -0.06549795 -0.7999482 -0.59336 0.08948196 -0.5683855 -0.8188698 -0.07993919 0.05186559 -0.9959815 0.07301269 0.3410093 -0.938087 -0.06087159 0.7237432 -0.688498 0.04654389 0.9186745 -0.3896293 -0.06500919 0.9969168 -0.03101757 0.07207465 0.8643712 0.4985263 -0.06583152 0.709631 0.7030362 0.04651722 0.2826215 0.9583358 -0.04144422 0.06224909 0.9980585 -0.002090816 -0.5682257 0.8227037 0.01667934 -0.6657754 0.7451372 -0.03890537 -0.9269789 0.3732125 0.03771633 -0.9926289 0.1118907 -0.04656397 -0.9581212 -0.2825525 0.04656093 -0.8480877 -0.5285114 -0.03772093 -0.5262713 -0.8494269 0.0388904 -0.3895991 -0.920501 -0.02984283 0.284139 -0.958124 0.03554532 0.3709987 -0.9284557 -0.0181689 0.8954794 -0.445098 0.002111654 0.9042345 -0.4268179 0.01365271 0.9783354 0.2067076 -0.01147702 0.9675172 0.2526395 0.009157697 0.7025104 0.7116148 -0.009137794 0.6681842 0.7439074 0.01147211 0.08248837 0.9964986 -0.01364914 -1 6.634252e-07 0 -1 6.634252e-07 0 -1 6.634251e-07 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 2.610497e-08 3.017776e-06 -1 1.085291e-07 -1.032441e-07 -1 7.813792e-08 -1.818666e-06 -1 0 0 -1 0 0 -1 0.09778099 -0.9945003 0.03752185 -0.3050413 -0.9505128 -0.05895236 -0.5506886 -0.8298013 0.09039763 -0.6989622 -0.7141199 -0.03853226 -0.9373334 -0.3483667 -0.006840277 -0.9419779 -0.335605 0.006851034 -0.9912397 0.125751 0.04038005 -0.954983 0.2816222 -0.09325472 -0.759698 0.6462995 0.07180429 -0.5776373 0.8138698 -0.06285726 -0.4125791 0.9101487 0.03752097 -0.06510327 0.9968662 -0.04493692 0.0651003 0.9968668 0.04492727 0.4698845 0.8811945 -0.05200769 0.5550829 0.831183 0.03190183 0.9089667 0.4168059 -0.007254731 0.9162108 0.3996937 -0.02833282 0.9716979 -0.2345219 0.02833151 0.9587773 -0.2827425 -0.028332 0.6163964 -0.7870097 0.02590749 0.5786698 -0.8153003 -0.02065467 0.08076794 -0.9965193 0.02063283 -0.2691609 -0.9630532 -0.008997552 -0.3098442 -0.9497282 -0.04486576 -0.7099826 -0.7009856 0.0674087 -0.8295843 -0.5505388 -0.09325697 -0.9893771 -0.1115169 0.09325656 -0.9893779 0.1115141 -0.09325277 -0.8295825 0.5505406 0.09326206 -0.7099817 0.7009876 -0.06739823 -0.3354036 0.9412848 0.038566 -0.2064505 0.9769228 -0.05477254 0.09764806 0.9933416 0.06113377 0.4438342 0.8928751 -0.07606053 0.5778901 0.8141936 0.05596226 0.9021726 0.4277283 -0.05597346 0.9415935 0.3354817 0.02921616 0.9919835 -0.1258459 -0.01147079 0.9897669 -0.14032 -0.02591979 0.7242536 -0.6889523 0.02831215 0.7115987 -0.7025488 0.007242565 0.2373482 -0.9708999 -0.03192699 0.1668739 -0.9855452 0.02921999 -0.03847994 -0.9988921 0.02708786 -0.1355485 -0.9904003 -0.02709143 -0.4319745 -0.9009532 0.04100586 -0.590481 -0.8049327 -0.05844297 -0.8208256 -0.5669699 0.06921263 -0.9010509 -0.431997 -0.0385462 -0.9999534 -0.006800003 -0.006856559 -0.9988552 0.03368692 0.03396142 -0.8154529 0.5787779 -0.00724852 -0.8042358 0.5936333 -0.02836297 -0.2827454 0.9587762 0.02834122 -0.2959046 0.9541984 0.04411281 0.1353636 0.9890412 -0.05894196 0.3477804 0.935612 0.06065417 0.6154809 0.7858435 -0.06027801 0.714308 0.6991988 0.02974971 0.9521619 0.3055768 -0.003235566 0.955064 0.2961739 -0.0115665 0.9951519 -0.09783398 0.01005656 0.9906296 -0.1355795 -0.01646918 0.8314683 -0.5552641 0.01850083 0.7864746 -0.615989 -0.04489304 0.4416598 -0.8951141 0.06088903 0.2958862 -0.9540631 -0.04706569 -0.1088967 -0.9921848 -0.06091706 -0.5283808 -0.8478206 0.04487553 -0.5647531 -0.8252109 0.008994685 -0.8458472 -0.5327645 -0.02653928 -0.907096 -0.4159655 0.06441675 -0.9951885 -0.06499023 -0.07332239 -0.9756319 0.2061545 0.0751176 -0.8952395 0.4417343 -0.05845586 -0.7213076 0.6901443 0.05844862 -0.5544301 0.830173 -0.05848077 -0.3052149 0.951058 0.04829619 -0.09779114 0.9945827 -0.03524502 0.1257188 0.9910307 0.04531047 0.3051242 0.9507362 -0.05477046 0.6883143 0.7235811 0.05151584 0.6989653 0.7141697 0.03753667 0.9352908 0.3476332 -0.06619967 0.986523 0.139848 0.08494116 0.9739304 -0.2207486 -0.05224545 0.9018034 -0.4275514 0.06285277 0.7890437 -0.611893 -0.05474588 0.4937612 -0.8687418 0.03856961 0.4023082 -0.9149124 -0.03291625 0.04827277 -0.9977252 0.04705549 -0.3400196 0.9389235 0.0530016 -0.5661815 0.8202164 -0.08175299 -0.8202037 0.5661951 0.08178618 -0.9391004 0.339487 -0.05328197 0.5122741 0.8567032 0.06029076 0.7251526 0.6818235 -0.09628297 0.8353561 0.5490347 0.02722226 0.5680693 -0.8229607 -0.005747402 0.5676181 -0.823268 -0.006286624 0.9069474 -0.4204262 0.02623317 0.9400128 -0.3398202 -0.02996879 -0.5344542 -0.8450377 0.01643242 -0.5409636 -0.8409885 0.009831825 -0.8587595 -0.5117894 -0.02456647 -0.8915269 -0.4523542 0.02356801 0 0 -1 1.326851e-06 1 0 -0.02210042 0.9961594 -0.08472322 0.01543533 0.9998809 0 0.9999961 -0.002801669 0 0.9997082 -0.008429309 -0.02263349 0.0007196337 0.01718548 0.9998521 4.662764e-05 0.0006117444 0.9999998 -8.554902e-05 -0.0009274376 0.9999996 0.0005772811 -0.003088834 0.999995 -0.0006402949 0.0005873271 0.9999996 0.001381363 -0.0005624912 0.9999989 0.0002031359 -1.502213e-10 1 0.001006717 0.0001544196 0.9999996 -0.0003394293 -0.0002444771 0.9999999 5.935271e-11 8.486704e-05 1 -0.0004534299 0.001919392 0.999998 0.0004881493 0.0009453591 0.9999994 -1.481109e-09 -0.001939996 0.9999982 -5.41019e-05 -0.00057182 0.9999998 0.002753237 -0.0002834786 0.9999962 5.301454e-05 -3.903404e-11 1 0.001227077 0.0005202291 0.999999 -3.362096e-05 -0.0004426169 0.9999999 -0 0 1 0 0 1 0 0 1 -1.184183e-05 1.30467e-05 1 0 -0 1 -1.031369e-05 1.595161e-05 1 -0 0 1 0 0 1 -1.851763e-05 4.857522e-06 1 0 0 1 0 0 1 -0 0 1 0 0 1 0 0 1 0 0 1 4.906257e-06 1.477223e-05 1 -3.613168e-06 1.294373e-05 1 0 0 1 0 0 1 -8.154656e-06 1.269274e-05 1 0 0 1 8.746078e-06 -3.524368e-05 1 -1.161461e-05 -2.502833e-05 1 -1.495248e-05 -2.395905e-05 1 -3.482583e-06 -2.714267e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 -0.0001838899 0.0006009661 0.9999998 -0.0001918219 0.0006362356 0.9999998 -1.533337e-05 7.625602e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 -0 0 1 0 0 1 -3.590932e-05 1.301855e-06 1 0 0 1 2.596444e-05 -2.395649e-05 1 -1.56617e-05 1.445051e-05 1 -0.0004030734 0.0001785407 0.9999999 -0.0006555323 0.0002564116 0.9999997 0.0001501565 -0.0003021659 0.9999999 -7.165562e-05 -0.0001477267 1 -0.0187956 -0.9998233 0 -6.632176e-07 -0.9996086 -0.02797432 0.01250207 -0.9999219 0 -0.01578821 0.9997858 -0.01338068 -0.01160081 0.9999327 0 -0.0157898 -0.9997857 0.013381 -0.01160232 -0.9999326 0 0 0 -1 -0.0003479316 -0.0003790508 -0.9999999 0 -0 -1 0 0 -1 0 0 -1 0 0 -1 0.001585753 -0.001580311 -0.9999975 1.464827e-05 -2.002778e-05 -1 0 0 -1 0.0002951001 0.0006665309 -0.9999998 7.078733e-07 1 -0 7.078733e-07 1 -0 -7.963577e-07 -1 -0 -7.963577e-07 -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 -1 0 -0 -1 8.719308e-07 0 -1 7.892476e-07 -9.646353e-07 -1 8.719307e-07 0 -1 0 0 -1 -0 0 -1 0 1.017251e-05 -1 8.477104e-07 -1.412849e-06 -1 0 2.79744e-05 -1 0 0 0.009672865 0.9999533 -0 0.02811775 0.9975028 -0.06478839 -0.01283494 -0.9999177 -0 0.00203569 -0.9991581 -0.040974 -7.132328e-07 -0.9999615 -0.00877461 0.005517546 -0.9999848 0 -0.004485231 -0.9998921 -0.01399144 -0.003177149 -0.9999949 -0.000411985 -0.0008882927 -0.9999996 -0.0001448215 -0.0008241197 -0.9999891 0.004595122 0.006220163 -0.9999804 0.000677966 0.007005529 -0.9999686 -0.00370234 -6.993229e-07 -0.9999453 -0.01045924 -0.0008882906 -0.9999967 -0.002440016 -0.004304873 -0.9997023 0.0240192 0.009671781 -0.9999533 0 0.02811804 -0.9975025 0.06479323 -0.0156076 0.9998782 0 -0.008265529 0.9994346 -0.03258986 7.629394e-07 1 1.929558e-07 -0.008704514 0.9992217 -0.03847345 0.01224745 0.999867 0.01077604 0.01224817 0.999925 0.000212762 -0.004533302 0.9999884 -0.001597274 0.0004130852 0.9990436 -0.04372134 0.008150008 0.9998395 0.01595224 0.004548358 0.9999861 0.002646157 0.006320618 0.99998 0 7.8455e-07 0.9999524 -0.009758875 -0.0009110503 0.9999866 0.005088496 0 0 -1 0 -0 -1 0 0 -1 0 0 -1 0 0 -1 -1.960984e-06 2.770228e-06 -1 8.712336e-07 -3.238366e-06 -1 -1.612735e-06 -2.325614e-06 -1 0 0 -1 -0.0001149075 -2.634999e-06 -1 -8.220204e-05 -4.395e-05 -1 0 0 -1 -0.0001162602 2.642894e-06 -1 -8.573329e-05 4.120599e-05 -1 -0.2292033 -0.9732827 -0.01365695 -0.2106169 -0.9774616 0.01447023 0.2402441 -0.9684721 -0.06591333 0.3596431 -0.929934 0.07667989 0.4639319 -0.8857206 -0.01631117 0.6097932 -0.7923225 0.01942324 0.6568546 -0.7529353 -0.04037843 0.7271835 -0.6863194 0.0130326 0.8473899 -0.5307087 -0.01669528 0.8607261 -0.5086349 0.02100205 0.965952 -0.2579752 -0.01963362 0.9729456 -0.2302586 0.01891759 0.9958492 0.02475942 -0.08758592 0.9999943 0.003357023 0 0.9624659 0.250379 0.1047367 0.8766388 0.4735847 -0.08498147 0.8523714 0.5229367 -0.0003178274 0.7308503 0.682322 0.01715773 0.6594778 0.7504401 -0.04391629 0.6097964 0.7923208 0.01939261 0.4593585 0.8880807 -0.01739096 0.3610557 0.9299102 0.07004125 0.2471768 0.9669145 -0.06308701 -0.2241222 0.9734958 0.04555448 -0.2783044 0.9602297 -0.02248587 -0.9986795 0.03104748 0.04093073 -0.9977911 -0.06222794 -0.02324833 -0.7245427 -0.6892242 0.002792401 -0.6875371 -0.7249449 0.04180441 -0.1118743 -0.9923854 -0.05152947 0.1440041 -0.9847282 0.09784274 0.5274094 -0.8462518 -0.07547988 0.9191663 -0.3890549 0.06139707 0.8908513 -0.4542658 -0.005153982 0.9495893 0.3125567 0.02425731 0.9283355 0.3709523 -0.02423877 0.4183707 0.9082676 0.003981447 0.4547365 0.8901045 -0.03047213 -0.1401678 0.9888521 0.05024479 -0.3437085 0.9373407 -0.05706969 -0.723809 0.6885315 0.04500021 -0.8223518 0.5680168 -0.03308252 -0.9388921 -0.3412871 -0.04477362 -0.8940154 -0.446083 0.04179291 -0.3897489 -0.9189848 -0.05968935 -0.2630805 -0.9638041 0.04324625 0.5003697 -0.8658117 -0.0004217161 0.5500548 -0.8331355 -0.05766153 0.9912476 -0.1220361 0.05035395 0.9989948 -0.0004248983 -0.04482228 0.8040187 0.5934498 0.03703182 0.7240558 0.6887469 -0.03702551 0.2648438 0.9637236 0.03308456 0.05186396 0.9958481 -0.07481044 -0.3384836 0.9369668 0.08672988 -0.7985746 0.5923445 -0.1068019 -0.9151137 0.3976001 0.06694155 0.9999016 -0.003023179 0.01369696 0.9986103 0.004109364 -0.05253955 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 -0 0 1 0 0 1 -0 0 1 0 -0 1 0 -0 1 -4.854485e-06 -3.057651e-06 1 1.285544e-06 -2.717385e-06 1 0 0 1 0 -0 1 -1.811074e-07 1.547814e-06 1 -3.610747e-06 -9.452147e-07 1 -1.396677e-06 -3.657278e-06 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 -0 0 1 0 0 1 -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.557814e-06 2.015798e-07 1 -1.22271e-06 2.590414e-06 1 -4.238646e-07 2.387536e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.322363e-06 1.232991e-06 1 -1.46922e-06 3.575231e-06 1 -3.217132e-06 9.615777e-07 1 0 0 1 -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.609548e-06 8.298146e-07 1 -4.019564e-06 -5.668083e-06 1 -6.76167e-07 -5.243468e-06 1 -1.43414e-06 -1.966534e-06 1 -0 0 1 -0 0 1 0 0 1 -0 0 1 0 -0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 -0.3135326 -0.932017 -0.1817731 0.0807316 -0.9851795 0.1513402 0.4004297 -0.9072154 -0.1289034 0.6967393 -0.7094365 0.1060863 0.8902764 -0.4421241 -0.1092431 0.9766555 -0.1746345 0.1250878 0.9503286 0.2603671 -0.1705414 0.8078358 0.5631711 0.1738952 0.4655537 0.8743309 -0.1371318 0.2661705 0.9604011 0.08235844 -0.2059316 0.977058 -0.05431192 -0.3127651 0.9481087 0.05716502 -0.6857927 0.723959 -0.07464343 -0.8270946 0.551051 0.110713 -0.9619727 0.2511874 -0.1073002 -0.9856886 -0.1111072 0.1267798 -0.89336 -0.4228485 -0.1520103 -0.6581951 -0.7339449 0.1676423 -0.6690491 -0.7405154 0.0633266 -0.5679384 -0.82024 -0.068208 -0.09330636 -0.9933184 0.06791504 0.06198872 -0.9938061 -0.09223264 0.4679343 -0.8777499 0.1029204 0.668303 -0.7362961 -0.1060144 0.8997753 -0.4295037 0.07701246 0.9642771 -0.2529494 -0.07865321 0.9848589 0.1395 0.1029206 0.9204665 0.3761683 -0.1060127 0.7113486 0.6986069 0.07701698 0.5415177 0.834359 -0.1029737 0.1739778 0.9729494 0.1519907 -0.2009994 0.9637244 -0.1755973 -0.5397442 0.8322622 0.1265531 -0.7647099 0.6408527 -0.06727993 -0.9238723 0.3750934 0.07592636 -0.9728788 0.2233501 -0.06017964 -0.9651585 -0.2526555 0.06807615 -0.9236112 -0.3774528 -0.06687187 -0.3146957 -0.9475163 -0.05638674 -0.2403157 -0.9704285 0.022736 0.2687786 -0.9628662 -0.02542885 0.2808775 -0.959686 -0.01051677 0.7198322 -0.6932931 0.03444135 0.7977691 -0.5954895 -0.09463947 0.973192 -0.2056554 0.1029717 0.9941194 0.03352812 -0.1029682 0.875376 0.4714974 0.1068031 0.8317272 0.5551329 -0.007561912 0.4199502 0.9049495 -0.06861596 0.2643396 0.9558794 0.1281375 -0.2392296 0.9640127 -0.1159681 -0.3799052 0.9244694 0.03206911 -0.7574808 0.6528024 0.008476064 -0.7830697 0.6205362 -0.04167431 -0.9966925 0.08078557 0.008809817 -0.9965368 0.03098875 0.077163 -0.8265027 -0.5527684 -0.1064914 -0.7275585 -0.680508 0.08699097 -0.5428599 -0.8381891 0.05236606 -0.5805411 -0.8141813 -0.008996141 -0.03367715 -0.9985822 0.04122455 0.06207591 -0.9951739 -0.07599679 0.5675242 -0.8205373 0.06808013 0.670584 -0.7388138 -0.06686763 0.924688 -0.3754225 0.06332426 0.9650214 -0.2531432 -0.06820803 0.965158 0.2526573 0.06807594 0.923611 0.3774532 -0.06687088 0.6690493 0.7405152 0.06332695 0.5679394 0.8202394 -0.06820683 0.06207407 0.9951744 0.07599148 -0.06207339 0.9951744 -0.07599261 -0.5944359 0.8004731 0.07673805 -0.6714584 0.7397721 -0.04336844 -0.9743508 0.2246686 0.01283283 -0.9622049 0.2666703 -0.05521516 -0.9445404 -0.3115842 0.1037244 -0.8780684 -0.4719731 -0.07897624 0.03101252 0.9985942 0.04298662 0.08152706 0.9966479 0.006811362 0.6142077 0.7889068 -0.01936426 0.6635547 0.7478095 0.02182057 0.974591 0.2239124 -0.005968492 0.9638589 0.2648739 0.02859659 0.9389225 -0.3391789 -0.05815553 0.8475674 -0.5251332 0.07657936 0.4261183 -0.902763 -0.05867084 0.3100798 -0.9504657 0.02157127 -0.264992 -0.9642397 -0.004605446 -0.2209559 -0.9748808 0.02803346 -0.6370093 -0.7697066 -0.04208199 -0.8192128 -0.5679256 0.07969208 -0.9538156 -0.2957879 -0.05239558 -0.9800159 0.1978406 0.02068735 -0.9843828 0.1760297 0.002026112 -0.6756635 0.736256 0.0374941 -0.5761241 0.8155067 -0.05504408 0.649912 -0.7571027 -0.06640778 0.164407 -0.9847918 0.05617443 0.06224683 -0.9978986 -0.0179916 -0.5288337 -0.8485659 0.01645353 -0.541257 -0.8408257 0.007279756 -0.8624641 -0.505778 -0.0185547 -0.9196995 -0.3892412 0.05142017 -0.9868225 0.1425387 -0.07657744 -0.9129837 0.3966583 0.09551401 -0.5752891 0.8134678 -0.08551342 -0.3391178 0.9387408 0.06135779 0.1118669 0.992545 -0.04837551 0.2648176 0.9636422 0.03557229 0.7025711 0.7107196 -0.03565658 0.7899786 0.6121333 0.03502474 0.977254 0.2094638 -0.0331574 0.9947758 0.09848984 0.02685155 0.9256194 -0.3780666 -0.01716311 0.8523058 -0.5199251 0.05703166 -0.2093039 0.9765096 -0.05119567 0.1240273 0.9897303 0.07107093 0.428673 0.900903 -0.06792033 0.7814549 0.6190674 0.07799855 0.9115746 0.4065306 -0.06135599 0.9980618 -0.03367023 0.05233292 0.9474789 -0.3118607 -0.07089781 0.8138828 -0.5776724 0.0623659 0.4261166 -0.902764 -0.05866653 0.310087 -0.9504635 0.02157131 -0.2649873 -0.9642409 -0.004604879 -0.2828152 -0.9590057 -0.01799143 -0.7871699 -0.6165167 0.01645602 -0.8327714 -0.5526484 -0.0327378 -0.9958163 -0.08070642 0.04285201 -0.9919557 0.1118032 -0.05936351 -0.8475034 0.5282038 0.05233375 -0.7104746 0.7023289 -0.04427252 -0.4537219 0.8905427 0.03271129 0.7683197 -0.6381518 -0.04946715 0.5404559 -0.8395819 0.05486032 0.09165221 -0.9940613 -0.05866918 -0.06220433 -0.9972689 0.03981787 -0.6180714 -0.7848895 -0.04400221 -0.6682389 -0.7439367 0.003874598 -0.9594147 -0.2798884 0.03443947 -0.9934998 -0.09160413 -0.06757799 -0.9703398 0.2372051 0.04662998 -0.8036334 0.5931551 -0.04837896 -0.7021285 0.7111615 0.03556708 -0.2344371 0.9713157 -0.039815 -0.08236019 0.9948741 0.05867304 0.4160069 0.9072203 -0.06236676 0.6430089 0.7636625 0.05795781 0.8480602 0.5278468 -0.04660109 0.9715881 0.2266076 0.06830584 0.9944078 -0.08134471 -0.06735091 0.8757515 -0.4814824 0.03512872 0 0 -1 -0 0 -1 0 0 -1 0 0 -1 -2.388564e-07 2.07227e-06 -1 0 0 -1 0 0 -1 3.985515e-06 -1.77446e-06 -1 0 0 -1 -0 0 -1 1.177782e-06 -6.667566e-07 -1 0 0 -1 0 0 -1 0 0 -1 -2.217732e-06 -2.141526e-06 -1 -0 0 -1 0 -0 -1 0 0 -1 0 -0 -1 -1.215599e-07 6.876088e-07 -1 -2.395762e-07 9.730636e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 0 0 -1 0 0 -1 -2.531448e-07 1.433084e-07 -1 3.32976e-07 -1.352417e-06 -1 0 -0 -1 -0 0 -1 -0 0 -1 0 0 -1 2.242848e-06 -5.366189e-06 -1 -6.834526e-07 1.846137e-06 -1 0 0 -1 1.185818e-06 -1.330289e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0 -0 -1 0 0 -1 0 -0 -1 -3.638041e-09 5.918349e-07 -1 -5.172859e-07 -1.049905e-06 -1 2.521094e-07 2.109964e-07 -1 -2.111027e-07 -1.962437e-06 -1 -2.661278e-07 5.13069e-07 -1 -1.416349e-06 -7.158947e-07 -1 0 -0 -1 0 0 -1 0 0 -1 0 0 -1 7.556283e-07 1.362959e-06 -1 -1.722465e-06 -1.050029e-05 -1 3.263253e-05 7.152151e-05 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.574592e-07 8.251385e-07 -1 -4.097213e-07 -8.168229e-09 -1 -3.22415e-06 -5.333181e-06 -1 0 0 -1 0 0 -1 6.105411e-07 -5.103296e-07 -1 -0 0 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 3.43842e-05 -1.2622e-05 -1 5.836074e-06 9.261525e-05 -1 -6.914124e-06 -1.204884e-05 -1 -0 0 -1 -0 0 -1 0 0 -1 -2.350985e-07 4.62988e-10 -1 2.990117e-07 -2.29906e-07 -1 2.911137e-07 -4.724534e-06 -1 0.0005936516 -7.224346e-05 -0.9999998 -0 0 -1 0 0 -1 3.234739e-07 -5.552681e-06 -1 8.766207e-06 3.581865e-07 -1 -2.739433e-06 2.106312e-06 -1 -0.999841 -0.007831019 -0.01601945 -0.9994115 -0.002748912 0.03419014 -0.5515916 -0.8341119 -0.002038822 -0.5443342 -0.8386956 -0.01702679 -0.2787374 -0.9602086 -0.01746567 -0.2675042 -0.9635336 0.006669747 -0.9246118 -0.3657386 -0.106434 -0.9175528 -0.3966911 -0.02707602 -0.5879787 -0.8088754 -0.00123695 -0.7357726 -0.6772282 -0.0009097906 -0.7534643 -0.6574866 0.001725629 -0.8233374 -0.567551 -0.001185235 -0.8271416 0.5567723 -0.07642918 -0.9232432 0.3739946 0.08803524 -0.9572141 0.2761404 -0.08653171 -0.278551 0.9602697 0.01707061 -0.2675028 0.9635341 -0.006663641 -0.7978752 0.6028203 -0.00169828 -0.7464504 0.6654215 0.005110118 -0.6546682 0.7559164 -3.485415e-05 -0.582735 0.8098068 -0.06806456 -0.5429368 0.8395869 0.01770164 0.2583103 0.9601188 0.1069939 0.4201982 0.8997227 -0.1180363 0.5580752 0.8239921 0.09792355 0.7145668 0.6926793 -0.09792686 0.8062459 0.5834211 0.09791525 0.9138418 0.3895541 -0.1146338 0.9560521 0.2789986 0.09013494 0.9644654 -0.2641224 0.006760107 0.9587494 -0.2825567 -0.03100743 0.8406384 -0.540869 0.02807088 0.8086013 -0.5851333 -0.06150539 0.6900176 -0.7210995 0.06237879 0.558076 -0.8239914 -0.09792531 0.4201941 -0.8997238 0.1180433 0.258306 -0.9601209 -0.1069858 0.9285521 -0.3690024 -0.04035167 0.7638981 -0.6441354 0.0393619 0.2525573 -0.9672242 -0.02631066 0.292672 -0.9561664 -0.009421772 -0.4542595 -0.8908195 0.009421866 -0.4450795 -0.8953881 0.01358697 -0.9161817 -0.3996839 -0.02939109 -0.9918795 -0.114175 0.05602911 -0.94886 0.3123235 -0.04602886 -0.642553 0.7650874 0.0420337 -0.3690181 0.9282349 -0.04696544 0.0621982 0.9971853 0.04186858 0.544044 0.8383361 -0.03476603 0.6891224 0.7244282 0.01772015 0.9641308 0.2649554 -0.01582842 0.9961837 0.08246183 0.02860285 -1 7.26609e-07 0 -1 7.26609e-07 0 1 -7.26609e-07 0 1 -7.26609e-07 0 -1 9.398135e-07 6.971109e-07 -0.9999802 -0.004506349 -0.004414854 -0.9999992 0.0008570711 -0.0009121 -0.9999866 -0.003165741 -0.004093039 -0.9999526 -0.00970753 -0.0008036156 -0.9999703 -0.00156991 -0.007545934 -0.9999773 -0.002435144 -0.006275312 -0.9999989 0.0006740566 -0.001356031 -0.9999987 0.001496532 -0.0005439355 -1 9.536741e-07 6.479482e-07 -1 1.672129e-07 -3.210265e-06 -1 9.070367e-07 -8.104437e-07 1.271461e-06 0.9999629 -0.00862269 -0.03019325 0.9995399 0.002872389 1 -8.675289e-06 -9.169387e-06 1 -5.685368e-06 1.33659e-05 1 1.492575e-05 -1.356271e-05 0.9999988 -0.001163862 0.001005207 0.9999989 -0.0006723189 0.001297128 0.9999998 0.0003666894 0.0003835494 0.9999999 0.0004248662 0.0003518744 1 -1.038706e-05 -1.115581e-05 0.9999977 -0.0001296845 0.002130453 1 4.025477e-06 2.317353e-05 1 -7.152557e-07 1.073418e-06 1 -2.881993e-07 -8.833531e-07 0.9999988 -0.001226622 0.0009658976 -0.0153551 -0.9998806 -0.001743868 -6.356941e-07 -0.999965 -0.00836808 -0 0 -1 0 -0 -1 -1 -2.888641e-05 -3.167292e-05 -0.9999995 -0.0006778425 -0.0007064764 -0.9999991 -0.001211061 -0.0003887386 -0.9999993 -0.000496882 -0.001074782 -1 8.902271e-07 8.29604e-07 -0.9999871 0.001775816 -0.004758169 -0.999987 0.001752842 -0.004792817 -0.9999832 0.005633101 -0.001350358 -0.9999925 0.002416059 -0.003004593 -1 1.993456e-07 3.196841e-06 -1 9.536734e-07 -4.648564e-07 -1 1.41716e-05 5.081246e-05 -0.03134349 0.9993731 -0.01645776 6.359774e-07 0.9999984 -0.001789721 0.9999982 0.001279763 0.001381868 0.9999959 0.002794949 0.0006009509 1 -6.794658e-06 -6.485762e-06 0.9999978 0.001480448 0.001499348 1 -1.647956e-05 1.330704e-05 0.9999994 0.0008487736 -0.0007200138 1 3.375733e-06 1.653915e-05 1 -7.152549e-07 -8.872609e-07 1 -1.571707e-06 3.221971e-06 1 6.337e-06 -2.243238e-05 0.999998 0.00196618 0.0003058095 0.9999961 0.0002280111 0.002773707 0.9999994 0.0007732545 -0.0007578718 -1.271566e-06 -0.9999992 0.001307914 -0.0295455 -0.9994917 -0.01197676 -0 0 -1 0 -0 -1 -0.9779798 0.007919626 -0.2085493 -0.9434234 -0.005808294 -0.3315393 -0.8786219 0.006514518 -0.4774735 -0.8195015 -0.004418953 -0.5730601 -0.6871455 0.008028435 -0.7264754 -0.6074096 -0.002999794 -0.7943832 -0.3754637 0.002062175 -0.9268348 -0.3612272 0.0002883497 -0.9324778 0.02129001 0.9891961 -0.145044 -0.009723848 0.9195094 -0.3929477 -0.001303329 0.9098319 -0.4149748 -0.01159053 0.7291514 -0.6842542 0.0007515823 0.7752566 -0.631646 -0.0009264263 0.6324314 -0.7746159 0.01952184 -0.9790981 -0.2024494 -0.01336824 -0.9416571 -0.3363083 0.01253839 -0.8782788 -0.4779845 -0.0124141 -0.8254204 -0.564382 0.01953993 -0.6969584 -0.7168453 -0.01249126 -0.5604277 -0.8281092 0.009662911 -0.3730743 -0.9277511 -0.005256892 -0.2764214 -0.9610222 0.748467 -0.001869085 -0.6631694 0.7401365 0.0009611246 -0.672456 0.833513 -0.00407699 -0.5524848 0.8492476 -0.001150499 -0.5279934 0.9624651 0.0005399768 -0.271405 0.9700453 -0.003918629 -0.2428925 0.9993271 0.003686365 -0.03649436 -0.9791279 -0.005629784 -0.203167 -0.9525515 0.006314524 -0.3043121 -0.8908839 -0.005500014 -0.4541979 -0.7078786 -0.006195361 -0.7063069 -0.8311294 0.00489793 -0.5560575 -0.6496362 0.003316887 -0.7602381 -0.3831457 -0.001149695 -0.9236872 -0.3679743 0.0009230294 -0.9298355 0.01700237 0.9797967 -0.199272 -0.01421865 0.9108523 -0.4124875 0.002848262 0.8917787 -0.4524629 -0.003731959 0.7281231 -0.6854363 0.007518819 0.7057049 -0.7084661 -0.008004041 0.4062194 -0.9137406 0.001414407 0.378182 -0.9257302 0.01709832 -0.9921283 -0.1240531 -0.00234203 -0.9190811 -0.3940614 -0.01303299 -0.9062678 -0.4225031 0.01250701 -0.8130617 -0.5820433 0.002423734 -0.6364534 -0.7713113 -0.00981445 -0.6408015 -0.7676439 0.789447 0.003902819 -0.6138063 0.7858226 0.000324615 -0.6184518 0.7905192 -0.0008937092 -0.6124365 0.9225805 -0.004494302 -0.3857785 0.9613436 0.009182775 -0.2751983 0.9947481 -0.007629492 -0.1020683 0.007653608 -0.9276043 0.3734859 -0.01523909 -0.8953525 0.4450972 0.01994467 -0.5682428 0.8226192 -0.0199418 -0.4283242 0.9034051 0.01523208 0.06222899 0.9979457 -0.007654261 0.1403444 0.9900732 0.009849187 0.7315421 0.6817251 0.02750055 0.7023203 0.7113296 -0.04447072 0.9884766 0.1446941 0.07122105 0.9701691 -0.2317316 -0.06369279 0.7085613 -0.7027689 0.04951924 0.3420158 -0.9383885 -0.03714805 -0.0824346 -0.9959038 0.03715355 -0.4265617 -0.9036951 -0.03090745 -0.7022721 -0.7112374 0.02429518 -0.9495842 -0.3125695 -0.007653735 -0.9783602 -0.2067676 0.0133008 -0.9955279 -0.09352693 -0.02707957 -0.8669225 0.4977069 0.03569633 -0.7452216 0.6658608 -0.02393244 -0.2932873 0.9557247 0.03748466 -0.05197988 0.9979444 -0.03722286 0.3099509 0.9500236 0.03636932 0.8026362 0.595359 0.02750794 0.8151613 0.5785805 -0.03782023 0.9987161 0.03370245 0.04293674 0.9389787 -0.341285 -0.03527354 0.7851683 -0.618277 0.03715444 0.4448136 -0.8948522 -0.04331509 0.06070233 -0.9972156 0.02514316 -0.2066812 -0.9780852 -0.01330329 -0.7115549 -0.7025046 -0.009097845 -0.7037585 -0.710381 0.009097476 -0.9965498 -0.08249712 -0.9882348 0.1474544 0.0406098 -0.9973536 -0.06220872 -0.03763052 -0.933745 -0.348968 0.07963493 -0.7228157 -0.687594 -0.06893523 -0.3924376 -0.9148645 0.09495021 -0.1121672 -0.9925598 -0.04736778 0.3384884 -0.9374444 0.081384 0.5282695 -0.8484572 -0.03243085 0.9081193 -0.4161549 0.04620083 0.863192 -0.5038195 -0.03264301 0.9973685 0.02823029 0.0667771 0.9626344 0.2632221 -0.06363275 0.6914943 0.7144209 0.1069508 0.4719428 0.8793547 -0.06328808 -0.07734377 0.9936528 0.08168262 -0.2350359 0.9717353 -0.02210466 -0.7379295 0.6733261 0.04573807 -0.804395 0.5937257 -0.02094275 0.3610068 -0.5827197 0.7280877 0.5430464 -0.4999955 0.6746148 0.6204457 -0.284895 0.7306722 0.7248549 -0.09197099 0.6827346 0.6705877 0.1824567 0.7190422 0.6756863 0.2649918 0.6879152 0.3354462 0.6285526 0.7017104 0.312381 0.6632388 0.6800973 -0.1661847 0.690852 0.7036378 -0.2062624 0.6988899 0.6848421 -0.5719609 0.4221625 0.7033062 -0.6071858 0.4029403 0.6848098 -0.7095023 -0.0442531 0.7033122 -0.7329118 -0.1058794 0.6720341 -0.4977152 -0.4734568 0.7267175 -0.4236303 -0.628065 0.6527417 -0.07394103 -0.6711093 0.7376619 0.1330731 -0.7290785 0.6713687 -0.9549354 -0.2965763 0.01186773 -0.9232826 -0.3789216 0.06299011 -0.6162319 -0.78635 -0.04372776 -0.3838368 -0.9196662 0.08296648 -0.1096217 -0.9935995 -0.02726215 0.2763763 -0.9599552 0.04584989 0.4019954 -0.915563 -0.01200177 0.738717 -0.6723636 0.04716237 0.8390408 -0.5427877 -0.03731144 0.9932603 -0.07692373 0.08669991 0.9695656 0.2324873 -0.0767616 0.836245 0.5432832 0.07441585 0.4754881 0.8796167 -0.0136246 0.521822 0.8525928 0.02805479 0.0183011 0.999612 -0.02099601 -0.1054413 0.9931626 0.05010049 -0.6211879 0.7834485 0.01828033 -0.6657859 0.7456972 -0.02578384 -0.9711696 0.2343841 0.04351518 -0.9858876 0.1673506 0.004413703 0.2775588 -0.6347429 0.7211538 0.4391918 -0.5992215 0.669361 0.5697889 -0.3703845 0.7335911 0.7150672 -0.1965303 0.6708611 0.6737018 0.161548 0.7211298 0.686488 0.2480072 0.6835399 0.3666489 0.6045215 0.7071933 0.3462002 0.6332843 0.6921679 0.01611193 0.7121583 0.701834 0.006106165 0.716389 0.6976743 -0.3914351 0.6080944 0.6906517 -0.4583262 0.5120625 0.7264497 -0.6310884 0.3700795 0.6817394 -0.6773717 0.114048 0.7267466 -0.7298112 -0.05914064 0.6810859 -0.6630004 -0.2049228 0.7200258 -0.5707177 -0.4766017 0.6686794 -0.4216976 -0.5390532 0.7291042 -0.07931711 -0.7280964 0.6808703 -0.06448081 -0.7379938 0.6717197 0.01164594 -0.007568073 0.9999036 0.005545369 0.005257867 0.9999708 0.005612117 0.005251811 0.9999704 -0.9999536 -0.002407373 0.009321904 -0.9999974 0.002261166 0 -0.9999982 0.001147506 0.001564522 -0.9996094 0.02685343 0.007737145 -0.9999958 -0.0004434574 0.002870365 -0.9999152 0.00652149 0.01127089 -0.99998 -0.0006631783 0.006275505 -0.999994 -0.003430748 -0 -0.9998962 0.009675344 0.01067243 -0.9999331 -0.006397063 0.009639406 -0.9999659 -0.003219057 0.007607382 -0.9997549 -0.01919014 -0.01103998 -0.9999835 -0.0008717735 0.00567466 -0.9999982 7.629381e-07 0.001893986 -0.9991167 0.03518485 -0.02297716 -0.9998639 0.01649398 -0.00035128 -0.9999806 8.039666e-07 -0.00622314 -0.9999472 0.002006405 -0.0100721 -0.9999877 0.004962922 0.0002838279 -0.9999214 0.01219763 0.002905463 -0.999971 0.0005834103 0.00758862 -0.9999701 0.0002958333 0.007724083 -0.9997147 -0.02373449 0.002668992 -0.9999282 -0.008361668 0.008583245 -0.9999043 -0.0002403427 -0.01382812 -0.9999995 -2.215218e-05 0.00100338 -0.9999774 -0.006451449 0.001863046 -0.999999 -0.0003564541 0.001336864 -0.9999973 0.002030822 -0.001134672 -0.9999996 -0.0004939 -0.0007002141 -0.9999996 0.0007676574 9.497556e-05 -0.9999191 0.009193536 0.008796486 -0.9999561 0.002978186 0.008885901 -0.9998544 0.01701871 -0.001189077 -0.9999926 0.003316472 0.001926333 -0.9999947 0.002484741 0.00207167 -0.9999914 -0.004024025 0.001020959 -0.999796 -0.01936422 -0.005736843 -0.9999613 0.0003670118 -0.008782246 -0.9999192 0.0006103155 -0.01269344 -0.9999556 0.0001006408 0.009428333 0.9999995 -2.436104e-05 -0.000925996 0.9999999 -0.0004994783 -0.0001410656 0.9999976 0.0002110189 -0.002155009 0.9999995 -0.0009018491 0.0003300398 0.9999992 -0.001310094 -4.196735e-05 1 -4.842125e-05 -0.0001547241 1 -6.357828e-07 -4.150338e-05 0.999999 0.000983423 0.0009168594 1 1.95163e-06 -3.813028e-05 0.9999995 -0.0001737426 0.000962229 0.9999745 -0.002223912 0.006783822 0.9999853 0.0009521518 -0.005336612 0.9999993 -0.0002506222 -0.001155563 0.9999992 -0.001298168 9.244239e-06 0.9999365 0.01126316 0.0004548127 1 2.920432e-05 -0.0001286921 1 0.0001076197 -0 1 0.0001855712 9.940346e-05 1 9.202227e-06 -6.810137e-05 1 0.0002594326 -0.0001879319 0.9999999 -0.0001294919 -0.0003178886 0.9999999 -0.0003992662 -0.0002827086 0.9999999 -0.0003014517 -0.0003172557 0.9999999 -0.000489336 -0.0001107606 0.9999999 0.0004552282 -0.0003252341 1 0.0001752964 -6.349024e-05 1 1.776688e-05 -5.381686e-05 0.9999923 0.003924081 6.582142e-06 0.9999998 -0.0004405368 -0.0004828548 0.9999992 0.0005098415 0.001159101 0.9999949 -0.0001817077 0.00317728 0.9999977 -0.002093537 0.0004030241 1 -3.247405e-05 0.0001770836 0.9999999 -0.0002526405 0 0.9999998 -0.0003806488 0.0005302069 0.9999998 -0.00025379 0.000614795 0.9999996 -0.0004783861 0.0007340632 0.9999993 -0.0009747104 0.0006134706 0.9999996 -0.0008660505 0.0003323688 0.9999996 -0.0008593196 0.000335319 0.9999999 0.0004650666 0.000311129 0.9999997 0.0006501935 0.0004040066 0.9999998 -0.0003313165 0.000515566 0.9999999 0.000501953 -6.999038e-05 0.9999999 -0.0001947475 0.0001926992 0.9999992 0.001180181 0.0005193315 0.9999997 0.0003476702 0.0006417253 0.9999999 0.0003512741 0.0003872513 0.9999998 0.0002346567 0.0004395506 0.9999999 -0.0002057212 -0.000384857 1 -5.118512e-05 -8.938033e-05 1 3.440069e-05 -8.391363e-05 1 -4.293899e-05 -7.145308e-05 0.9999993 4.399073e-05 0.001135434 1 2.617012e-05 0.0001856191 0.9999999 0.0005298791 6.757336e-05 0.9999989 -0.00148423 -5.975837e-05 0.9999999 -0.0005052099 2.047924e-05 1 2.766382e-05 2.568182e-05 0.9999996 -0.0009251339 0.0001553643 1 4.930368e-05 -6.831999e-05 0.9999997 -0.0007891257 8.358889e-05 0.9999996 -0.0005076114 0.0006439711 0.9999985 0.001718805 -0.0001641261 1 -9.240885e-05 0.0002338753 1 6.165099e-05 -5.034836e-05 1 1.8348e-05 -3.972477e-05 1 5.117902e-05 -3.588533e-05 1 0.0001955407 1.68597e-05 1 7.041572e-05 1.857892e-05 0.005223224 0.9999832 0.002534924 -0.006612409 0.9999782 -7.578381e-05 0.009896197 0.9999507 0.000781786 0.01009057 0.9999488 0.0007619649 0.0103418 0.9999462 0.0007885988 0.04432108 0.9989015 -0.01521184 -0.0007861573 0.9999996 -0.0004549485 -0.008761552 0.9999607 0.001344778 0.02191948 -0.9997597 0.0001853926 0.01212982 -0.9999264 -0.000287404 0.0046755 -0.9999872 -0.001927263 0.06069472 -0.9978974 -0.02273518 0.0115796 -0.9999322 0.00118675 -0.01119861 -0.9999368 -0.0009739125 0.01098784 -0.9999392 0.0009267716 -0.01281235 -0.9999174 -0.0009522977 0.005011645 -0.9999819 -0.003357218 -0.09565202 -0.9917999 0.08475613 0.08062233 -0.9211025 0.3808808 -0.03699872 -0.9044365 0.4250008 0.03425677 -0.7176256 0.695586 -0.03438619 -0.6956211 0.7175854 0.03832842 -0.4190043 0.9071749 -0.04080041 -0.391802 0.9191445 -0.1718493 0.9491121 0.2639201 0.1638125 0.9000158 0.4039021 -0.1295612 0.7164471 0.6855053 -0.02658815 0.6957927 0.7177504 0.1006871 0.3877704 0.9162403 -0.09243714 0.3163297 0.944135 0.0004328473 0.9999625 0.008653182 -0.01737431 0.9972132 -0.07255328 -0.06008145 0.9401118 -0.3355296 0.03940221 0.985637 -0.1642165 0.03897038 0.8168063 -0.5755942 0.01548733 0.826508 -0.5627117 -0.04719628 0.6685144 -0.7422002 0.06470204 0.5502471 -0.8324912 -0.01651106 0.4796409 -0.8773095 -0.03028076 0.2810439 -0.959217 0.01280704 0.2597352 -0.9655949 -0.1498273 -0.2338078 -0.9606695 0.07617132 -0.3623669 -0.9289177 0.003536466 -0.64467 -0.7644528 -0.03838739 -0.6570751 -0.7528471 0.07041928 -0.9144857 -0.3984434 -0.02290194 -0.866801 -0.498128 -0.03043465 -0.9583601 -0.2839358 -0.03832059 -0.9978646 -0.05289418 -0.9999998 4.600701e-05 -0.0006269614 -0.9999996 0.0008588813 -5.674734e-05 -0.9999969 -0.002137614 0.00125776 -0.9999979 -0.001579508 -0.001337276 -0.9999959 0.0001920665 -0.002884892 -1 0.0002713677 -9.153402e-06 -0.9999999 0.0002976698 -6.787332e-05 -1 0.000208342 -0.0001573419 -0.9999999 0.0002681162 5.890649e-05 -0.9999995 0.0008755102 0.0002931581 -0.9999998 -9.138946e-05 0.0006327101 -0.9999983 -0.001804269 0.0002179406 -0.9999997 -0.000441586 -0.0006530655 -0.9999912 0.004087637 -0.000969527 -0.9999967 0.0008729963 0.002378401 -0.9999998 0.0006201255 0.0001551796 -0.999999 0.001103441 -0.0007860685 -0.9999991 0.001130504 -0.0007477679 -0.9999971 0.001119818 -0.002106939 -0.999997 0.0023131 -0.0007812667 -0.999997 -0.002302878 -0.0007393015 -0.9999968 0.002435294 0.000559912 -0.9999972 0.0008001321 0.00221733 -0.9999968 -0.000752439 0.002456961 -1 -0.0002328898 -0.000106213 -0.9999999 -5.26969e-05 -0.0002718584 -0.9999999 -7.011167e-06 0.0002832997 -0.9999999 -0.0002174095 0.0001341679 -0.9997188 -0.006554172 -0.02278895 -0.9995113 0.02930036 -0.01088923 -0.9999998 0.000112875 -0.0006393741 -0.9999996 0.0007085629 -0.0005354623 -1 4.869807e-05 9.532594e-05 -0.9999995 0.001040619 -0.0001415726 -0.9999997 0.0007717842 0.0003026451 -0.9999998 0.0003838939 0.0005662596 -1 0.0002682815 -3.004766e-05 -0.9999964 -0.0004163343 0.002608269 -0.9999971 -0.001374355 0.001966902 -1 -0.0001053886 1.087154e-05 -1 -3.061296e-05 -0.0001009805 -0.9998617 -0.001846431 -0.01652747 -0.9999397 0.007942195 -0.007581156 -0.9999046 0.01227738 0.006317937 -0.9999951 -0.001721076 -0.002606081 -0.9999956 0.0001654401 -0.002992071 -0.9999959 0.0005525114 -0.00280573 -0.9999971 -0.001319788 -0.002060009 -0.9999979 -0.001593753 -0.001338471 -0.9999979 -0.001591247 -0.001340022 -0.9999984 -0.001776969 0.000227065 -0.9995186 -0.01986065 0.02383843 -0.999802 -0.01400021 -0.01414088 -0.9999994 -0.001008541 -7.723383e-05 -1 0.0001419774 -0.0002444824 -0.9999999 -2.899702e-05 -0.0003086783 -0.9999903 0.003498385 0.002682837 -0.9999908 -0.00246338 0.003531743 -0.9999999 -0.0001884555 -0.0001867007 -0.9999999 -9.365908e-05 -0.0002318201 -0.9999975 -0.002136606 -0.0006157329 -0.9999993 -0.0009135982 0.0006724971 -0.9999992 -0.001212199 -0.0003074792 -1 2.405486e-05 -0.0001050989 -0.9999989 0.001297391 0.0008280225 -0.9999992 0.0003840808 0.001216412 -0.9999985 0.001173254 0.00130614 -0.9999986 0.001489477 0.0008096464 -0.999999 0.0009963614 0.001051904 -0.9999992 0.001304609 -2.997552e-05 -0.9999993 0.001106108 -0.0002940291 -0.999999 0.001169347 0.0008178282 -1 -0.0001470772 0.00021864 -0.9999999 -0.0002042195 0.0001396176 -1 2.604331e-05 0.0001123746 -1 -0.0001189369 5.36693e-05 -1 0.0001342806 -4.032873e-05 -1 8.341022e-05 6.568119e-05 -0.999996 -0.002388014 0.001534969 -0.999997 -0.002444111 7.468577e-05 0.09351682 0.9835868 -0.1543095 -0.05747756 0.998327 0.006291502 0.06780346 0.9288371 0.3642313 -0.04950396 0.8878407 0.4574804 0.003251637 0.4707415 0.8822653 0.03098541 0.4547143 0.8900982 -0.02843 -0.09376045 0.9951887 0.07681905 -0.170769 0.982312 -0.1100811 -0.6639322 0.739646 0.2115039 -0.8317462 0.5132877 -0.1672399 -0.9610887 0.219862 0.1469463 -0.9106398 -0.386189 -0.04939149 -0.8641205 -0.5008556 0.009756814 -0.416541 -0.9090645 0.134085 -0.3385217 -0.9313561 -0.1849831 0.2305516 -0.9553152 0.229412 0.5550053 -0.7995869 -0.1489521 0.7955936 -0.5872343 0.7090637 0.6272584 0.322142 0.6621866 0.6158438 0.4269021 0.7279867 0.3222544 0.6051343 0.6702687 0.1741366 0.7213988 0.7306704 -0.06347869 0.679773 0.6666532 -0.3317814 0.6674539 0.7290775 -0.4576279 0.5089427 0.680668 -0.6619571 0.3138531 0.7261133 -0.6698959 0.1549157 0.6611505 -0.7391588 -0.1285474 0.740976 -0.5802452 -0.3380385 0.6632261 -0.4321593 -0.6110397 0.7181339 -0.2903719 -0.6324301 0.6825227 0.05901213 -0.7284781 0.722495 0.1622184 -0.672076 0.675374 0.4547427 -0.5805851 0.7333276 0.5469837 -0.4037813 0.6578475 0.7372915 -0.153746 0.723105 0.6907179 0.005302179 -0.05983783 0.9976407 -0.03365104 0.1556068 0.7564244 0.635302 -0.1579572 0.6360418 0.7553148 0.06507245 -0.06210317 0.9959462 0.105668 -0.08260225 0.9909647 -0.138019 -0.725446 0.6742986 0.1518993 -0.8243759 0.5452806 -0.09612884 -0.985092 -0.1426638 0.07934463 -0.964077 -0.2534956 -0.1109408 -0.6533135 -0.748915 0.09475047 -0.5504386 -0.8294815 0.001075864 0.1429576 -0.9897282 -0.05890866 0.1718726 -0.9833562 0.003246207 0.7871358 -0.6167711 0.03094013 0.7976179 -0.602369 -0.0346076 0.9992115 -0.01945958 0.6708858 0.6985196 0.2489631 0.7228903 0.4432625 0.5300452 0.6848074 0.4029555 0.6071786 0.7033178 -0.04424251 0.7094975 0.6966953 -0.05795069 0.7150227 0.6872063 -0.4479421 0.5719227 0.7322217 -0.4972431 0.4654037 0.6553439 -0.7342414 0.1772396 0.7369396 -0.6685495 -0.09980804 0.6702808 -0.6645354 -0.3303276 0.7362286 -0.4471433 -0.5079667 0.6581537 -0.3010552 -0.6900721 0.722903 0.1210885 -0.6802564 0.696686 0.1812387 -0.6941046 0.6872131 0.5404401 -0.4854508 0.7091939 0.5552766 -0.4344097 0.683208 0.7300287 -0.01687818 0.7264855 0.6817222 -0.08645032 -0.005154666 0.9994179 -0.0337239 0.05491509 0.7844707 0.6177297 -0.004531292 0.7648795 0.6441575 -0.07705829 0.2515921 0.9647608 0.1004533 0.1222925 0.9873974 -0.07094017 -0.3988739 0.9142577 0.07681353 -0.4964552 0.8646571 -0.1101079 -0.8768703 0.4679472 0.1439001 -0.954666 0.2605872 -0.120963 -0.9882742 -0.09317709 0.1631758 -0.8693308 -0.4665166 -0.1829154 -0.6915197 -0.698815 0.1596413 -0.2896147 -0.9437362 -0.1253891 0.001528609 -0.9921065 0.1020896 0.3085324 -0.9457195 -0.1425224 0.5972291 -0.7893065 0.1407021 0.8073691 -0.5730253 -0.128775 0.9852655 -0.1125562 0.6723714 0.6728534 0.308521 0.7283667 0.5231832 0.4424492 0.6699737 0.3727278 0.6420353 0.7341373 0.1719043 0.65688 0.6569369 -0.2143463 0.7228345 0.7078729 -0.2824223 0.6474206 0.693477 -0.635928 0.3386522 0.6992866 -0.6257234 0.3456421 0.6915448 -0.7223171 0.004880113 0.7181236 -0.6929016 -0.06469811 0.6706842 -0.5827508 -0.4588945 0.7177156 -0.4904874 -0.4942736 0.6696119 -0.06820685 -0.7395727 0.7066934 0.002642828 -0.7075151 0.6879241 0.4366686 -0.5797248 0.692021 0.4286857 -0.5808058 0.6820486 0.7108946 -0.1715762 0.7249684 0.684333 -0.07816098 0.2144276 0.9694201 -0.1193539 -0.1317859 0.9759452 0.1736765 0.134438 0.7588198 0.6372747 -0.01299399 0.7023308 0.7117322 -0.1003239 0.08158495 0.9916042 0.136086 -0.05152722 0.9893561 -0.0880451 -0.6633303 0.7431292 0.03820858 -0.7240099 0.6887305 -0.04624185 -0.9976304 0.0509434 -0.006858202 -0.9994934 0.03107602 0.05930531 -0.7091562 -0.7025527 -0.1042 -0.6405037 -0.760853 0.07579633 -0.09325848 -0.9927526 -0.1383835 0.09145258 -0.9861472 0.1909759 0.5153897 -0.835405 -0.2530292 0.7775225 -0.5757039 0.7409685 0.6608721 0.1192215 0.6722854 0.6212832 0.4025412 0.7214268 0.4867722 0.4925405 0.675335 0.2754975 0.6841226 0.7373273 0.05632292 0.6731835 0.6613413 -0.2121762 0.7194504 0.7347958 -0.4523574 0.5054185 0.6798347 -0.5980295 0.4244826 0.7106364 -0.702534 0.03797187 0.7031679 -0.7106199 0.02396542 0.6721416 -0.6092288 -0.4207919 0.7358104 -0.4343769 -0.5195187 0.6669757 -0.256486 -0.6995414 0.7430812 0.06082834 -0.666431 0.6401081 0.3430177 -0.6874594 0.7478934 0.5334985 -0.3950125 0.6401142 0.7471015 -0.1791457 -0.4888471 0.7929997 -0.3635655 -0.6083992 0.7657711 0.208435 -0.5989601 0.5795792 0.552571 -0.998157 -0.01951998 -0.05746045 -0.8605526 -0.2106164 -0.4637779 -0.9981576 -0.01738267 -0.05813021 -0.2889909 -0.9311121 -0.2225185 -0.9423625 -0.3172701 0.1062663 -0.5348693 0.4265929 0.7293376 -0.8792605 0.2037635 0.4305595 -0.9099553 -0.02878348 0.4137061 -0.7858265 0.05459853 0.6160322 -0.9299586 -0.1083225 0.3513447 -0.8991088 -0.2629637 0.3499336 -0.9215532 -0.2479982 0.2987248 -0.8701422 -0.4182212 -0.2606599 -0.9092522 -0.1909798 -0.3698474 -0.9688336 -0.005436972 -0.2476528 -0.818281 0.5280671 0.227071 -0.8869529 0.2790642 0.3680184 -0.7868838 0.4477262 0.4246824 -0.8195487 0.1925756 0.53968 -0.772999 -0.5665294 0.2855118 -0.86667 -0.4983492 0.023047 -0.8121777 -0.575152 -0.097814 -0.8337178 -0.5394759 -0.1178155 -0.7608715 -0.5134063 -0.3968484 -0.5914542 -0.1973158 0.7818239 -0.6287621 -0.442127 0.6396733 -0.7617343 -0.4698408 0.446106 -0.6977072 -0.6585371 0.2820169 -0.6993018 -0.4326537 -0.5690236 -0.7872561 -0.1602501 -0.5954393 -0.6973782 -0.08388698 -0.7117771 -0.8651403 0.1494564 -0.4787432 -0.6825362 0.06239486 -0.7281835 -0.7961545 0.301378 -0.5246992 -0.612736 0.5432889 0.5739266 -0.6826764 0.07722152 0.726629 -0.722727 -0.2843786 0.6299163 -0.4273884 -0.8952286 0.1261149 -0.6137443 0.3127665 -0.7249104 -0.6393583 0.5635831 -0.5230631 -0.4837174 0.4109445 0.7727497 -0.5069245 0.004247446 0.86198 -0.4201623 -0.812947 0.403213 -0.5197707 -0.8540751 0.01985245 -0.4113063 -0.8655196 -0.2858372 -0.445899 -0.7678854 -0.4599196 -0.5349375 -0.4654155 -0.7051455 -0.4460137 -0.5387372 -0.7147266 -0.3848758 -0.2400725 -0.8911991 -0.526221 -0.1119381 -0.842948 -0.3929217 0.07867243 -0.9162004 -0.5142955 0.2357795 -0.8245654 -0.2830276 0.466401 -0.8380725 -0.4746798 0.5924041 -0.6509504 -0.5201539 -0.7675099 -0.3746578 -0.4304164 0.6230122 -0.6531443 -0.4258904 0.8067417 -0.4096159 -0.3435159 0.9348459 -0.08977666 -0.4487162 0.8930108 -0.0344306 -0.2030364 0.9346449 0.2919161 -0.6112112 0.6984065 0.3723564 -0.2199486 0.7510245 0.6225629 -0.465568 0.4032056 0.7878272 -0.4677819 0.02118501 0.88359 -0.1941509 -0.3793364 0.9046598 -0.5415843 -0.4828938 0.6881135 -0.3367814 -0.6549795 0.6764467 -0.5145834 -0.794252 0.3230597 -0.9760801 0.156763 0.1506422 -0.8779749 0.3720666 -0.3012084 -0.4235337 0.9015821 -0.08814128 -0.3641974 0.9239739 0.1167587 -0.9586457 0.07877935 -0.2734817 -0.9014843 -0.3645103 -0.2333632 -0.6039174 -0.08430699 0.7925757 -0.9494947 0.1363354 0.2826172 -0.9154302 0.2023834 0.3478915 -0.8877335 -0.01316164 0.4601696 -0.9394917 -0.09396697 0.3294321 -0.9000474 -0.3103445 0.3059428 -0.8984911 -0.4002092 0.1804056 -0.923965 -0.3721978 0.08807649 -0.8462352 -0.5282446 -0.06959774 -0.8564835 -0.4185852 -0.3020305 -0.9286812 -0.2897042 -0.2315658 -0.9124528 -0.1549958 -0.3786901 -0.9537216 -0.07208655 -0.2919223 -0.7709274 0.4371149 0.4632512 -0.8390117 0.02371073 0.5435965 -0.7650622 -0.2907724 0.5745705 -0.898661 -0.415153 -0.1416207 -0.7862319 0.06730155 -0.6142555 -0.737905 0.112864 -0.6654005 -0.8731542 0.2468269 -0.4203312 -0.8303127 0.3621484 -0.423591 -0.7308421 0.6322314 0.257203 -0.7558934 0.4379047 0.4866875 -0.7650633 0.2280289 0.6022299 -0.5326282 -0.08033297 0.8425282 -0.6808019 -0.6531578 0.3315021 -0.7184054 -0.6327954 0.2889009 -0.7097112 -0.7041792 0.02101282 -0.6291134 -0.3323761 -0.702668 -0.7968011 -0.1225965 -0.591674 -0.5682575 0.6808509 -0.4620882 -0.5032376 0.7073062 -0.4964574 -0.6270774 -0.2863844 0.7244018 -0.6334245 -0.5402756 0.5539635 -0.6820704 -0.5385306 0.4947369 -0.6356368 -0.7536886 -0.1670907 -0.6397502 -0.658178 -0.3968897 -0.6823072 -0.5994305 -0.4184972 -0.6430869 -0.4920646 -0.5867808 -0.7010421 -0.3768901 -0.6053874 -0.4533632 0.3206296 -0.83166 -0.7234142 0.4298562 -0.5402737 -0.5949922 0.6888754 0.4140468 -0.3218633 0.6820202 0.656698 -0.4744402 0.4127259 0.777537 -0.4969665 -0.123614 0.8589202 -0.4715916 -0.07453148 0.8786617 -0.3124469 -0.8585883 0.4064519 -0.4747621 -0.8713068 0.1242001 -0.4576289 -0.8395155 -0.2928984 -0.4859724 0.7039387 -0.517978 -0.5769154 -0.7492342 -0.3252949 -0.2490193 -0.7941032 -0.5544272 -0.3932457 -0.5346979 -0.747968 -0.391373 -0.5358843 -0.7481011 -0.3673114 -0.2545431 -0.8945893 -0.4507203 -0.1887647 -0.8724787 -0.330192 0.05636258 -0.9422294 -0.5267082 0.2659761 -0.8073632 -0.5208765 0.2647426 -0.8115411 -0.1963299 0.5334928 -0.8227028 -0.476135 0.720197 -0.5045907 -0.4767746 0.7200643 -0.504176 -0.4993728 0.8647985 -0.05244305 -0.4856665 0.7812865 0.3920707 -0.5517988 0.4359738 0.7109466 -0.4693142 -0.07338909 0.8799763 -0.306372 -0.4441986 0.8419167 -0.5688726 -0.5194458 0.6376206 -0.3897973 -0.641088 0.6611084 -0.582071 -0.7926382 0.1814329 -0.5753514 -0.6517767 -0.4941235 -0.6892416 -0.6727108 0.2690838 -0.3548333 -0.5832855 0.7306651 -0.9735883 0.01117672 0.228037 -0.9409945 0.09749468 0.3240743 -0.7491766 0.2479396 0.6142154 -0.9820333 0.1349632 0.1318924 -0.978937 0.1771517 0.1014867 -0.7134641 0.686802 0.1388232 -0.7223694 0.4091947 -0.5574423 -0.8382444 0.3399861 -0.4263282 -0.9290326 0.3536736 -0.1086893 -0.9617467 -0.1161026 0.2481199 -0.7619273 0.4367687 -0.4782259 -0.7125626 0.5948516 -0.3720297 -0.9086091 0.417025 0.02279954 -0.7762716 0.1764531 0.6051998 -0.7505571 -0.2466421 0.6130512 -0.7693301 -0.4252313 0.47677 -0.682488 -0.3849095 -0.6213332 -0.8319394 -0.03862011 -0.5535209 -0.6258612 0.1521075 -0.7649583 -0.7816057 0.2748052 -0.5599774 -0.6835732 0.7230666 -0.09950994 -0.7658764 0.6198153 0.1710626 -0.6924018 0.6643699 0.2814111 -0.7886038 0.4912331 0.3698568 -0.7396033 0.4508473 0.4997235 -0.8177152 0.3105204 0.4846844 -0.6352846 0.3118594 0.7065105 -0.8008158 -0.04079059 0.59752 -0.6337041 -0.2224524 0.7409009 -0.7795339 -0.4015199 0.4807376 -0.8278593 -0.4782575 0.2931189 -0.6822204 -0.3848895 -0.6216393 -0.5893134 -0.2306647 -0.7742761 -0.6850114 0.1010502 -0.7214903 -0.5204254 0.8514278 -0.06502443 -0.7287868 0.01977171 0.6844552 -0.4892065 -0.6632591 0.5663608 -0.4815281 -0.8147562 -0.3229601 -0.4173552 -0.6769691 -0.6062405 -0.4187672 0.3564959 -0.8351914 -0.41854 0.5021072 -0.7567778 -0.5764558 0.6983655 -0.4242455 -0.4201789 0.7170823 -0.556096 -0.5180346 0.853156 -0.06135951 -0.2999367 0.9232889 0.239949 -0.3911055 0.7698389 0.5043655 -0.4975578 0.4911857 0.7149636 -0.5114156 0.05687878 0.8574491 -0.5218245 -0.2708623 0.8089084 -0.4535331 -0.8225525 -0.3430965 -0.5316599 -0.5596672 -0.6356968 -0.3305528 -0.5552097 -0.7632019 -0.2893342 -0.2224303 -0.9310266 -0.5626993 -0.0711833 -0.8235911 -0.3327086 0.05329028 -0.9415228 -0.492699 0.3907565 -0.7775327 -0.514406 0.8549843 -0.06624466 -0.4815977 0.8724977 -0.08253063 -0.5162091 0.7652287 0.3846469 -0.3944682 0.5746118 0.7170886 -0.3567897 0.2823396 0.8904973 -0.260299 0.1702494 0.9503996 -0.3830297 -0.2263866 0.8955654 -0.3638888 -0.5067756 0.7815136 -0.4963611 -0.5534592 0.6688113 -0.2519222 -0.8066282 0.534683 -0.2166327 -0.8921679 0.3963669 -0.5934798 -0.7823851 0.188826 -0.1890411 -0.9804966 -0.05375664 -0.9975896 -0.02185298 0.06585889 -0.9100664 -0.2294747 -0.3451385 -0.9345746 -0.1858 -0.3033952 -0.9838009 0.01587066 -0.1785609 -0.8624772 0.4754823 -0.1733488 -0.8137121 0.5647169 0.1377227 -0.9798408 0.1576754 0.1226809 -0.9300579 0.1583918 0.3315183 -0.8599314 0.2608439 -0.4387236 -0.8986549 0.2482385 -0.3616587 -0.9290022 0.3275671 -0.1722057 -0.8279648 0.5233507 -0.201441 -0.7634073 0.3119611 0.5655878 -0.9207917 0.1175789 0.3719109 -0.9169842 -0.0567793 0.3948621 -0.8935868 -0.08286592 0.4411755 -0.9324152 -0.2267119 0.2814315 -0.8307805 -0.3002625 0.4686642 -0.9276465 -0.2466859 -0.280389 -0.7658405 -0.07091621 -0.6391081 -0.7755005 -0.06289404 -0.6282063 -0.8907211 0.1672168 -0.4226753 -0.8565782 0.4919426 -0.1557765 -0.8247517 0.5501416 0.1308779 -0.7402166 0.5727631 0.3521675 -0.8774819 0.2612814 0.4021909 -0.8801728 -0.3860608 0.2761392 -0.6968768 -0.4097843 -0.5885912 -0.810091 -0.2049868 -0.5493022 -0.6327177 0.5765801 -0.5169368 -0.7847216 0.5872519 -0.1983615 -0.7008175 0.7121159 0.04178023 -0.7675246 0.5521637 0.325609 -0.650139 0.483292 0.5863004 -0.7531708 0.1546531 0.6393873 -0.6765614 -0.0623522 0.7337417 -0.7495189 -0.2635317 0.6072664 -0.6224689 -0.4710149 0.625042 -0.5749587 -0.705139 -0.4149716 -0.7264684 -0.4422937 -0.5259469 -0.5440884 0.4572317 -0.7034962 -0.6559315 0.5144351 -0.5523679 -0.628649 0.6898207 -0.359093 -0.6290992 0.7767948 -0.02870478 -0.5445369 0.7664018 0.340746 -0.6857365 0.4726969 0.5534645 -0.627358 0.2441903 0.7394546 -0.6304039 -0.09417944 0.7705331 -0.609655 -0.6391103 0.468891 -0.6894284 -0.6743577 -0.264443 -0.2559791 -0.7086712 -0.6574647 -0.3890285 0.05078233 -0.919825 -0.5798619 0.2247908 -0.7830896 -0.3185144 0.23989 0.9170612 -0.4763103 -0.4676568 0.7445977 -0.4573973 -0.7637245 0.4555355 -0.6063725 -0.7704849 0.196635 -0.5658084 -0.7911926 -0.2321104 -0.2616355 -0.8637753 -0.4306263 -0.4378179 -0.5856457 -0.6821544 -0.311475 -0.4168546 -0.8539412 -0.5075079 -0.1977088 -0.8386579 -0.3874702 -0.1024789 -0.9161686 -0.4782424 0.5328161 -0.6981341 -0.1783627 0.8835695 -0.4330029 -0.5014478 0.8263778 -0.256222 -0.3516691 0.9234782 -0.1533522 -0.4376363 0.8911229 0.1198935 -0.4847383 0.8623918 0.1459767 -0.1853735 0.8752869 0.446665 -0.5065351 0.59009 0.628662 -0.5197238 0.5806168 0.6267146 -0.5769814 0.09290159 0.8114566 -0.2941341 -0.060876 0.9538235 -0.4039057 -0.3620384 0.8401121 -0.5345275 -0.4090958 0.7395411 -0.6198291 -0.713502 0.3266905 -0.2886124 -0.9248092 0.2478526 -0.2631053 -0.9641817 -0.03360453 0.01842053 0.0001345117 0.9998303 0.02213861 -8.298898e-05 0.9997549 8.589502e-05 0.002250904 0.9999975 6.881854e-05 -0.00174209 0.9999985 0.001399565 0.00202755 0.999997 0.00508206 -8.298842e-05 0.9999871 0.001110737 -0.00156495 0.9999982 0.003646652 0.001309217 0.9999925 0.00287205 -0.0009991945 0.9999954 -0.9990548 -0.04331747 0.003613262 -0.9999996 -0.0009765109 -1.439725e-06 -0.9998572 0.01689955 -0.0002061752 -0.9999981 0.001278796 0.001474721 -0.9999751 0.005436284 0.004507716 -0.9999906 -0.003794214 0.002088793 -0.9999998 0.0004741707 0.0003399425 -0.9999971 0.0006541102 0.002333739 0.9995971 0.02829337 -0.002245688 0.9789228 -0.2041755 0.004748926 0.8636512 -0.5040875 -0.001541678 0.6166043 -0.7872596 0.004613539 0.3396139 -0.9405615 -0.002555878 0.05128039 -0.9986734 0.004683389 -0.3942154 -0.919009 -0.004086756 -0.6662744 -0.74568 0.006303606 -0.9367173 -0.3500788 -0.002364626 -0.9986314 -0.05201219 0.005491734 -0.9890506 0.1475761 -0.0003104926 -0.7387024 0.6740314 -0.000617554 -0.6431071 0.7657593 0.005077526 -0.07760284 0.9969811 -0.002518907 0.09182487 0.9957663 0.004197963 0.6954813 0.7185401 -0.002415028 0.803673 0.5950525 0.004725839 0.9970131 -0.07721437 -0.001693567 0.964697 -0.2633201 0.004701516 0.7395374 -0.6731103 -0.002606301 0.4464582 -0.8947871 0.005581697 0.2766672 -0.9609658 -0.0003779835 -0.3851643 -0.9228467 0.001527256 -0.3187474 -0.9478374 -0.002135703 -0.7537766 -0.6571139 0.00471215 -0.9251137 -0.3796731 -0.003579002 -0.9981374 0.06076185 0.005438386 -0.9720902 0.2346064 -0.00068282 -0.6186672 0.7856503 0.002155126 -0.6212901 0.7835773 0.002305022 -0.1055738 0.9944112 -0.000697178 0.1221824 0.9924884 0.006179099 0.47553 0.879694 -0.003072781 0.8385686 0.5447925 0.00194775 0.8657969 0.5003771 0.004293033 -0.006026892 0.006064707 0.9999635 0.5207996 0.8536766 0.001943315 0.532432 0.8464726 0.0004906753 4.582481e-05 3.556512e-05 -1 1.761575e-05 -1.577035e-05 -1 5.12778e-06 -4.590602e-06 -1 1.253308e-05 -3.444241e-06 -1 8.722538e-06 -1.181755e-05 -1 4.481923e-06 3.104022e-07 -1 8.956377e-06 6.202873e-07 -1 4.509462e-06 -7.931118e-06 -1 -2.079953e-05 3.658165e-05 -1 1.293595e-05 4.642388e-05 -1 -8.082131e-06 -2.900473e-05 -1 -2.628879e-05 -2.302341e-05 -1 0 0 -1 -7.762841e-06 8.655079e-06 -1 -7.216727e-06 8.642891e-06 -1 -7.215926e-06 5.752114e-06 -1 0 0 -1 7.161289e-06 9.240136e-06 -1 4.249299e-06 2.822301e-05 -1 -1.544493e-05 5.503012e-06 -1 2.540822e-05 7.242824e-06 -1 2.408839e-05 -3.393795e-05 -1 -2.503602e-05 -6.994575e-06 -1 -6.428858e-06 1.059144e-05 -1 4.603598e-06 -7.584349e-06 -1 1.597807e-05 3.761902e-08 -1 1.309581e-05 1.649592e-05 -1 -8.069823e-07 1.388139e-05 -1 0 -0 -1 1.00846e-05 -5.306511e-06 -1 9.785328e-06 -5.405379e-06 -1 1.026855e-05 -7.896808e-06 -1 0 0 -1 6.180957e-06 6.904154e-06 -1 4.540108e-08 3.092466e-05 -1 5.115945e-05 1.387491e-05 -1 -3.241622e-05 -2.342645e-05 -1 -3.195339e-05 8.180366e-06 -1 -1.531707e-05 3.921315e-06 -1 -4.521502e-06 -1.768423e-06 -1 1.291397e-06 -3.137026e-05 -1 -3.178095e-05 -2.033894e-05 -1 -6.327433e-07 -5.675182e-06 -1 0 0 -1 -0 0 -1 -2.024223e-05 -1.302633e-05 -1 -3.60349e-05 2.643512e-05 -1 -8.166629e-06 2.777941e-05 -1 -8.211377e-06 3.346815e-05 -1 1.595647e-05 2.296687e-05 -1 0 0 -1 -3.784892e-06 4.01272e-06 -1 -1.67363e-05 4.914003e-07 -1 -1.715504e-05 7.702489e-06 -1 0 0 -1 -3.76245e-06 -4.126728e-06 -1 -4.586376e-06 -1.793795e-06 -1 6.22258e-06 4.004197e-06 -1 2.90426e-05 -4.083083e-05 -1 1.624475e-05 -4.36957e-05 -1 1.696562e-05 -1.22194e-05 -1 0 0 -1 -1.073603e-05 -1.055514e-05 -1 -1.056907e-05 -1.111059e-05 -1 1.81721e-06 -7.672181e-06 -1 0 0 -1 0 0 -1 -4.064047e-06 -3.875243e-06 -1 -7.084389e-06 1.635212e-06 -1 6.126326e-06 -1.414073e-06 -1 5.333008e-06 -4.074693e-06 -1 -2.566288e-05 1.960776e-05 -1 6.375757e-06 4.526494e-05 -1 3.896792e-05 5.954837e-06 -1 3.057873e-05 4.672852e-06 -1 2.673157e-05 -1.54238e-05 -1 -0 0 -1 -0.2795278 -0.956335 -0.08536733 -0.7719824 -0.6329769 0.05816716 -0.8315885 -0.5518613 -0.06252657 -0.9933945 -0.08051489 0.08175989 -0.9794633 0.1414729 -0.1436561 -0.8236453 0.5465916 0.1511491 -0.5710231 0.806944 -0.1509107 -0.2763946 0.9523603 0.1289023 0.1087406 0.9860277 -0.1261947 0.396982 0.9090607 0.1265466 0.6985149 0.7075049 -0.1073018 0.9007502 0.4149071 0.1284572 0.973734 0.2057663 -0.09747961 0.925841 -0.3699531 0.07715622 0.8949426 -0.4448532 -0.03440165 0.4593706 -0.8876418 0.0327218 0.3995064 -0.9152517 -0.05204662 -0.167385 -0.9840604 0.06006048 0.9936839 -0.08053941 -0.07813986 0.9613044 -0.264174 0.07814062 0.8031104 -0.5891575 -0.08892142 0.565019 -0.8150151 0.1284674 0.3414257 -0.9310671 -0.1286178 -0.2021047 -0.9690248 0.1419318 -0.3592682 -0.9318229 -0.05130713 -0.7616376 -0.64795 -0.008306725 -0.8166809 -0.5661769 0.1116959 -0.9889061 -0.0307498 -0.1453236 -0.9783349 0.1749343 0.1107202 -0.7015277 0.7105454 -0.05462714 -0.7099108 0.7032974 -0.03741017 -0.1119365 0.99312 0.03439287 -0.09352002 0.9955784 0.008811289 0.4421633 0.8960972 -0.03874762 0.5505881 0.8296664 0.09222981 0.8441663 0.5260991 -0.1029707 0.945635 0.3084997 0.1029677 0.9961666 -0.05115358 -0.07095914 0.8062549 -0.5914667 -0.01096598 0.7182858 -0.6812227 0.1414254 0.3701918 -0.9194214 -0.1327494 -0.03075544 -0.9891496 0.1436567 -0.2810473 -0.9530173 -0.1130062 -0.7046859 -0.6981292 0.1266228 -0.8285684 -0.5498586 -0.1054977 -0.9978422 -0.02461123 0.06087104 -0.983622 0.142079 -0.1109117 -0.8686662 0.4798475 0.1231476 -0.5697767 0.8056784 -0.161978 -0.3374324 0.9340798 0.1167659 0.111524 0.9894724 -0.09223197 0.2372778 0.970669 0.03874265 0.7115852 0.7025447 -0.008806548 0.743475 0.6642975 -0.07716052 0.9901294 0.08196016 0.1136939 0.9904302 0.1256375 -0.05712394 0.9631676 -0.2646881 0.04741784 0.9416064 -0.3354934 -0.02866397 0.6162982 -0.7868842 0.03146166 0.5786193 -0.8152127 -0.02505918 0.08076486 -0.9964181 0.02505987 0.06517728 -0.9978538 0.006299966 -0.4421612 -0.8960982 -0.03874854 -0.5505865 -0.8296676 0.09222946 -0.8441643 -0.5261021 -0.1029727 -0.9389516 -0.3345474 0.0802982 -0.986026 0.1546848 -0.06184772 -0.9888164 0.1428218 -0.04294307 -0.6180982 0.7849272 0.04294216 -0.5769969 0.815889 -0.03741253 0.03369161 0.9989371 0.03145831 0.1117851 0.9917635 -0.06252544 0.5768659 0.8127369 0.08175912 0.7199014 0.6848151 -0.1130045 0.9459499 0.3086006 0.09972147 0.1890261 0.8287674 0.5267008 0.324065 0.8705254 0.3703612 0.3968651 0.7632399 0.5098656 0.6758546 0.5110746 0.5310587 0.7928486 0.4488276 0.4122437 0.190099 -0.8444908 0.5006971 0.1944055 -0.8498283 0.4898963 0.1765401 0.8046668 0.5668731 0.3855 0.6822394 0.62124 0.4812076 0.6112684 0.6283233 0.4924589 0.6785951 0.5449705 0.6555225 0.5035039 0.5628269 0.7339118 0.2719708 0.622419 0.7337252 0.2718154 0.6227068 0.7796068 0.1706531 0.60257 0.749857 0.1322755 0.6482419 0.7651508 0.09866762 0.6362458 0.7960287 -0.2302001 0.5597733 0.8278621 -0.3070489 0.4694308 0.6962097 -0.3816207 0.6079948 0.6830088 -0.3800875 0.6237247 0.7084569 -0.5275334 0.4688254 0.5701895 -0.5657431 0.5956666 0.5192927 -0.5428743 0.6600171 0.4951769 -0.5890168 0.6386384 0.3547161 -0.7422867 0.5684952 0.1287145 0.5581434 0.8197003 0.5301428 0.4050253 0.7449181 0.6306862 -0.01886165 0.7758088 0.571941 -0.1297878 0.809962 0.4285335 -0.2385125 0.8714762 0.313206 -0.5528918 0.7721481 0.110658 -0.5456439 0.8306791 0.124869 0.3393171 0.9323475 0.262521 0.2810831 0.9230791 0.3624688 0.1731305 0.915774 0.479174 -0.05443553 0.8760303 0.3606442 -0.1858746 0.9139948 0.3637339 -0.3348352 0.8692428 0.1015582 -0.2409407 0.9652116 0.1239797 0.04490535 0.9912681 -0.9582881 -0.2795599 0.05941497 -0.7446797 -0.6653772 -0.05220329 -0.6442152 -0.7639947 0.03604108 -0.08235137 -0.9948118 -0.05973072 0.05124439 -0.9979942 0.0371692 0.6409333 -0.767594 0.002022476 0.6660522 -0.7454494 -0.02606952 0.9900982 -0.1403645 0.001788089 0.9923119 -0.1229083 0.01451436 0.9035156 0.4283547 -0.01310844 0.8822715 0.4704531 0.01645556 0.470456 0.88227 -0.01645209 0.4575441 0.8891571 -0.007280424 0.006787832 0.9998049 0.0185529 -0.1227554 0.9911039 -0.05142101 -0.5924177 0.8026252 0.06952732 -0.7661461 0.6397305 -0.06135962 -0.9634429 0.2647657 0.04094952 -0.9972389 0.05120203 -0.05378571 -0.9990911 0.006785165 0.04208441 -0.982733 -0.1801793 -0.04208772 -0.7959082 -0.6047683 0.02802494 -0.7850144 -0.6181566 0.04043157 -0.2824237 -0.9576898 -0.05538217 -0.122786 -0.991314 0.04711845 0.4265516 -0.9037019 -0.03710157 0.4423598 -0.8965012 -0.02456256 0.8633555 -0.5012341 0.05815369 0.9543514 -0.2830031 -0.09551279 0.9718348 0.2232888 0.07535972 0.8479267 0.5253507 -0.07090049 0.6908275 0.7219824 0.03871462 0.2827073 0.9586473 -0.0327428 0.2374535 0.9713933 -0.003290534 -0.3396712 0.9402667 0.02284471 -0.3997348 0.9162896 -0.02500859 -0.8954667 0.4451182 0.00300379 -0.8748695 0.4832748 -0.03238486 -0.9934993 0.09160744 0.06758127 -0.962721 -0.2645637 -0.05633946 -0.8027834 -0.5925304 0.06668161 -0.5679234 -0.8192145 -0.07969069 -0.2032968 -0.9747034 0.09286485 0.2032943 -0.9747039 -0.0928632 0.5425588 -0.8373914 0.06637339 0.8199456 -0.5684392 -0.06757203 0.9148579 -0.4023044 0.03443878 0.9900944 0.1403496 0.003874993 0.9779876 0.2039706 -0.04400282 0.7111645 0.7021253 0.03556801 0.5931621 0.8036283 -0.04837639 0.1756937 0.9825308 0.06135838 -0.06210401 0.9956449 -0.06952985 -0.5937648 0.8019421 0.06581959 -0.6682346 0.7439405 -0.003876712 -0.9594164 0.2798832 -0.03443282 -0.9929195 -0.1119162 0.03981791 -0.971316 -0.2344352 -0.03981733 -0.6886829 -0.7239685 0.03981841 -0.5933824 -0.8039353 -0.0398162 -0.09345647 -0.9949878 0.03556953 0.03368473 -0.9988862 -0.03304075 0.4702718 -0.8819028 0.03304493 0.6018624 -0.7969427 -0.05141991 0.9018285 -0.4275698 0.0623652 0.9872378 -0.1425995 -0.07090048 0.9932856 0.1090174 0.03871669 0.8327743 0.5526438 -0.0327387 0.8063065 0.5914888 -0.00329181 0.3734173 0.9274125 0.02157556 0.3356231 0.9419863 -0.004348944 -0.1258157 0.991722 -0.02565085 -0.2823588 0.9574705 0.05936192 -0.6472839 0.7608804 -0.04565643 -0.83215 0.5522308 0.05067078 -0.9216208 0.3868414 -0.03112453 0.1873191 -0.6730828 -0.7154517 0.1601818 0.8368215 -0.5235185 0.2966879 0.6049467 -0.7389288 0.2731812 0.6345525 -0.7229905 0.2707409 0.7671772 -0.5814969 0.4083964 0.566106 -0.7160562 0.3366348 0.6227458 -0.7063035 0.2015512 -0.9553033 -0.2162699 0.4150754 -0.755561 -0.5067939 0.3015386 -0.7283739 -0.6152608 0.2506781 -0.6705164 -0.6982609 0.2801498 -0.352096 -0.8930534 0.1303832 -0.1994319 -0.9711988 0.4348044 -0.3287179 -0.8383852 0.6978597 -0.2994761 -0.6506196 0.6872671 0.3770248 -0.6208995 0.4801887 -0.6101922 -0.6301463 0.6948751 -0.5358455 -0.4796023 0.4975083 -0.6630195 -0.5593663 0.7757283 -0.4546218 -0.4376811 0.6850849 -0.5140417 -0.5161588 0.2838224 -0.1602061 -0.9453988 0.5317886 -0.1999245 -0.8229405 0.7960203 -0.01553821 -0.6050704 0.806328 0.03745259 -0.5902818 0.5897709 -0.09393808 -0.8020884 0.5076944 -0.0993038 -0.855795 0.6611785 0.1263235 -0.7395169 0.7794614 0.1946287 -0.5954492 0.8224254 0.3047057 -0.480386 0.6198089 0.4618998 -0.6344176 0.6665478 0.3745937 -0.6445103 0.5762652 0.1161829 -0.8089622 0.1016604 -0.003708674 -0.9948123 0.5978669 0.4637939 -0.6537968 0.5853482 0.5843391 -0.5620636 0.4792821 0.6051148 -0.635708 0.3283053 0.1269168 -0.9360062 0.1842334 0.9827326 0.01716537 0.2099753 0.977603 -0.0142417 0.3476946 0.9375176 -0.01300581 0.3507874 0.9364009 -0.01007357 0.4755914 0.8795492 -0.01435576 0.485544 0.8742011 -0.004424501 0.5908697 0.8067153 -0.009133125 0.620668 0.7837014 0.0241548 0.7069808 0.7065318 -0.03148029 0.7831762 0.621453 0.02076424 0.8020135 0.5972531 -0.007932436 0.8797518 0.4754081 -0.004887187 0.8812836 0.4725842 -0.001829301 0.9351479 0.354239 -0.003628568 0.9376627 0.3475348 0.002865805 0.980283 0.1975932 0.001468612 0.9780181 0.2083704 -0.007893215 0.9966996 0.08073593 -0.008467407 0.9985709 0.04982508 0.01932924 0.9952224 -0.09585691 0.01853743 0.9960869 -0.08752913 0.01223122 0.9770395 -0.2128457 0.009525093 0.9858352 -0.1664365 -0.02068293 0.9458539 -0.3231354 -0.03072391 0.9351134 -0.35434 -0.00244585 0.8849105 -0.4657285 -0.005511433 0.8798468 -0.4752338 0.004746428 0.8020266 -0.5972373 0.007797125 0.7822477 -0.6225693 -0.02227213 0.70552 -0.7078487 0.03452017 0.6178643 -0.7861012 -0.01698993 0.5925443 -0.8054476 0.01205343 0.474393 -0.8802233 0.01257488 0.4611882 -0.8869501 0.02500049 0.347305 -0.9373441 -0.02766635 0.2236257 -0.9743903 0.02356005 0.2367841 -0.9715616 0.001240397 0.01308389 0.4609755 0.8873164 0.003845894 0.6113534 0.7913484 0.01180288 0.7958443 0.6053863 0.002074863 0.8822764 0.4707272 0.007743749 -0.4511616 0.8924087 0.005575301 -0.4728885 0.8811047 0.006980762 -0.8650168 0.5016944 0.01282751 -0.8945257 0.4468325 -0.0001445893 0.0002793898 -0.9999999 -0.0002742965 0.0001096051 -0.9999999 -0.0002941545 8.934182e-05 -0.9999999 2.120356e-05 4.855467e-05 -1 0.001033762 -0.0003853065 -0.9999995 7.580854e-05 3.491923e-05 -1 0 0 -1 0 0 -1 -6.290672e-05 -1.251569e-05 -1 0.003107813 0.002548211 -0.9999919 0.0003572429 0.002139602 -0.9999976 -0.005660283 -0.00593419 -0.9999664 -0.005166501 -0.008306823 -0.9999521 -0.001393287 -0.01209435 -0.9999259 -0.01169272 0.0006725299 -0.9999313 0.002021511 -0.0008758922 -0.9999976 -0.003419708 -0.004198519 -0.9999853 0.01401896 0.002177942 -0.9998993 -0.01207262 -0.001702145 -0.9999257 -0.008908669 -0.01220914 -0.9998857 0.002865805 -0.0003255345 -0.9999958 0.00552581 -0.001090785 -0.9999841 -0.001491613 0.01313955 -0.9999126 -0.005785387 0.002520649 -0.99998 -0.09590071 -0.3873264 -0.9169413 -0.002920107 0.003454974 -0.9999898 0.008739273 -0.0160349 -0.9998333 -0.00110421 -0.01137091 -0.9999348 0.002664163 -0.005015468 -0.9999838 0.01873923 0.00266241 -0.9998208 0.01693333 -0.00738711 -0.9998292 0.006455803 0.007200791 -0.9999532 0.001704398 0.02265308 -0.9997419 0.02197751 -0.00301719 -0.9997538 0.01061802 0.002772477 -0.9999397 0.0006533127 0.01193361 -0.9999286 0.004031531 -0.0002389556 -0.9999918 -0.01655922 0.003499328 -0.9998568 -0.01191728 0.01887722 -0.9997508 -0.004001047 -0.002015651 -0.99999 -0.006560038 0.02399709 -0.9996905 0.009889619 -0.002143825 -0.9999488 -0.003460462 0.005850836 -0.9999769 -0.01547169 -0.003474489 -0.9998742 -0.00272376 0.005024003 -0.9999837 -0.003771028 0.003831415 -0.9999856 -0.0003223448 -0.00070069 -0.9999997 -0.005299337 0.0009946902 -0.9999855 -0.001030873 0.0009253827 -0.999999 0.002085883 -0.008115597 -0.9999649 0.004606638 0.00967345 -0.9999427 -0.002504659 0.01755092 -0.9998428 0.0118143 0.005890563 -0.9999129 0.04959507 -0.00921592 -0.9987269 0.005121761 -0.003494223 -0.9999807 0.00437682 -0.00413384 -0.9999819 0.007222161 -0.001526107 -0.9999728 0.03165346 0.009892028 -0.99945 0.009944047 0.008533898 -0.9999142 0.006250613 0.029662 -0.9995405 -0.004116097 -0.01426152 -0.9998899 -8.659498e-05 -0.0006659022 -0.9999998 0 0 -1 0 0 -1 0 0 -1 0.0186413 -0.003326737 -0.9998207 0.007637907 -0.007746616 -0.9999409 -0 0 -1 -0.001939932 -0.000270397 -0.999998 -0.001509621 -0.000492492 -0.9999987 -0.0008307568 -0.001251845 -0.9999989 0.002696305 -0.0135054 -0.9999052 0.001824313 -0.01618562 -0.9998674 0.01896197 -0.00327394 -0.9998149 0.0003474648 -0.002032713 -0.9999979 -0.001383338 -0.004120744 -0.9999905 -0.0007355003 0.002017783 -0.9999977 0.0004101547 0.003563282 -0.9999936 0.02444507 -0.006621171 -0.9996793 -0.008004715 0.02511791 -0.9996525 -0.001899723 0.002413672 -0.9999952 -0.00339216 0.0009245341 -0.9999938 0.005026964 0.00758667 -0.9999586 0.001893464 0.01662893 -0.9998599 -0.0004910998 0.006241811 -0.9999804 -5.183136e-06 5.470096e-06 -1 0 0 -1 0.01452908 0.002025149 -0.9998924 0.01007717 0.003590484 -0.9999428 -5.902992e-06 5.778808e-06 -1 1.415368e-05 -1.493728e-05 -1 -5.545271e-06 -2.196532e-06 -1 -0.003716149 0.0007662498 -0.9999928 -0.004939682 0.0006548737 -0.9999875 0.001275947 -0.01062552 -0.9999428 0.0009970918 0.002111927 -0.9999973 0 0 -1 -2.080867e-12 -2.909262e-06 -1 1.733767e-06 -1.308981e-12 -1 -2.215709e-06 1.261634e-05 -1 6.004653e-06 1.412807e-06 -1 0.002579063 7.082266e-05 -0.9999967 0.01565408 0.003817851 -0.9998702 0 -0 -1 0 0 -1 0.004414857 0.004365711 -0.9999807 0.0001952544 0.006463459 -0.9999791 0.001402207 0.005102366 -0.999986 -2.047377e-05 7.489662e-06 -1 8.560414e-06 -6.141586e-05 -1 0.000333607 -0.002393431 -0.9999971 0.0005187304 -0.001417134 -0.9999989 0.001070336 -0.0005997749 -0.9999993 -0.004464898 -0.006731084 -0.9999673 0.0001509634 0.0002667577 -0.9999999 0.01929217 -0.0009767795 0.9998134 0.0005630612 -0.0004772343 0.9999998 1.721558e-06 4.155124e-07 1 0.0001482523 -2.818318e-05 1 0.0003437687 -0.002621301 0.9999965 0.002020252 -0.006329813 0.9999779 0.0002914401 -0.0008086478 0.9999996 -1.124457e-05 7.818929e-06 1 5.219377e-05 2.049076e-05 1 0.005159914 -0.002142701 0.9999844 0.00449815 -0.005437983 0.9999751 0.0004165565 -9.163649e-05 0.9999999 9.376984e-05 0.0002287788 0.9999999 0.001325571 -0.0006382474 0.9999989 0.0008513542 0.0003931939 0.9999996 0.0002912972 0.001159152 0.9999993 0.0001651055 -2.969489e-05 1 2.582767e-05 1.085862e-05 1 -3.830575e-06 -1.642841e-06 1 0.01654913 -0.004827749 0.9998514 0.01006968 0.002891013 0.999945 0.01194017 0.0007370059 0.9999284 -0.0008983306 -0.0005961478 0.9999994 -0.001260876 -0.0003639263 0.9999992 0.003596701 -0.003994864 0.9999856 0.004246381 -0.002292644 0.9999883 0.00457608 -0.005438556 0.9999748 0.003876403 -0.002774069 0.9999886 0.005128261 -0.005218485 0.9999733 -0.0009934537 0.00264811 0.999996 2.099561e-05 0.0006539626 0.9999998 0.02078436 0.001568426 0.9997827 -0.01304534 -0.003740593 0.9999079 4.497784e-06 -3.127542e-06 1 -2.45014e-06 -5.110047e-07 1 -0.0004213021 -0.001182459 0.9999992 -3.695023e-06 5.337197e-07 1 -0.001858557 -0.004161993 0.9999896 0.000262246 -0.004292232 0.9999908 0.004527382 -0.003599294 0.9999833 1.895089e-05 0.001304415 0.9999991 0.0024279 -0.0008558069 0.9999967 7.759661e-05 -0.0005146191 0.9999999 -1.109854e-05 1.368646e-05 1 0.0006014332 0.0008547154 0.9999995 0.01235422 -0.0005727776 0.9999235 0.01235238 0.003404304 0.9999179 -1.635281e-05 -1.558432e-05 1 -7.425003e-07 -2.517784e-06 1 -0.001694115 0.001903355 0.9999967 -1.182786e-06 1.566158e-06 1 -2.968779e-06 2.857977e-07 1 9.374569e-06 -9.024685e-07 1 1.385114e-05 -1.368417e-05 1 3.495847e-06 2.165925e-06 1 -0.001504499 0.001855314 0.9999971 -0.003193754 0.0009425041 0.9999945 2.873978e-06 3.940635e-06 1 -0.01151862 0.006481269 0.9999126 -0.001603797 0.007689483 0.9999692 0.01179265 0.006338333 0.9999104 0.0005099169 0.004695672 0.9999888 -0.005258155 0.01115146 0.9999239 0.001650965 0.005598369 0.999983 0.008514301 0.005058252 0.9999509 0.006466432 0.004899521 0.999967 0.01159713 -0.9999328 3.487652e-05 0.01208149 -0.9999254 0.001757682 0.007939635 -0.7465619 -0.6652686 0.008344941 -0.4785092 -0.8780429 -0.005131673 -0.5814539 -0.8135631 -0.00104777 -0.1797673 -0.9837086 0.00435036 0.3044771 -0.9525098 0.002192745 0.3284099 -0.9445328 0.005695875 0.6246485 -0.7808852 -0.0002264754 0.6634015 -0.7482636 0.009599248 0.9998894 0.0113549 0.01301767 0.9999152 0.0002795293 0.9998288 -0.01758403 0.005754895 0.9999173 -0.01286196 0.0002836603 0.9999012 -0.01405356 0.0001135758 0.9997656 0.02159848 0.001433571 0.9999372 0.01119416 0.000220329 0.9998986 0.002183041 -0.01407614 0.9677326 -0.249625 0.03436631 0.4229031 -0.5030499 0.75372 0.7405334 -0.5988342 0.304972 0.4530852 -0.7438433 0.4913357 0.3604832 -0.8223786 0.4401651 0.7484835 -0.5848216 0.3126597 0.4712428 -0.5109413 -0.7189362 0.4100491 -0.895883 -0.1710362 0.9492971 -0.3139043 -0.01729473 0.8216059 -0.5693577 0.02820643 0.779865 -0.6259404 -0.003012045 0.4616123 -0.8866997 -0.02603316 0.3869985 -0.9220707 0.00422801 0.6755807 0.603292 0.4238271 0.7611545 0.5758678 0.2983621 -0.07144525 0.633236 0.7706542 0.5330381 0.8437921 0.06233047 0.2433676 0.8198804 0.5182358 0.9726021 0.2227885 0.06641224 0.9453508 0.3257567 0.01394684 0.9561629 0.2928232 0.002615087 0.2159191 0.9763953 -0.005581425 0.2753326 0.9612894 0.01070435 0.5373433 0.8433104 -0.009474503 0.6772162 0.7353937 0.02396439 0.7701002 0.6376199 -0.0196634 0.5842043 0.6063401 -0.539497 0.2602129 0.5906031 -0.7638568 0.2789852 -0.9602948 -0.00108382 0.385996 -0.9224991 0.0015832 0.5531747 -0.8330601 -0.002945039 0.6959854 -0.7180477 -0.003440565 0.8459399 -0.533271 0.002787988 0.887082 -0.4616118 1.998486e-05 0.9752376 -0.2211459 -0.002458532 0.9642159 0.2650953 -0.003488872 0.8420004 0.5394769 -0.0001858293 0.8356624 0.5492433 0.0003078564 0.5639728 0.8257928 -0.0009299547 0.5149595 0.8572142 0.0008640551 0.287195 0.9578669 -0.003164816 0.4987004 -0.8667739 0.0009793325 0.5371944 -0.8434543 -0.00263308 -0.005125132 -0.005721684 0.9999706 0.3285109 -0.9444959 0.002838159 0.5564287 -0.8308934 -0.001839881 0.111536 -0.9937576 -0.002320007 -0.2275465 -0.9737669 -0.0008374953 -0.09191878 -0.9957647 0.00193881 -0.4577304 -0.8890877 0.002410889 -0.5268656 -0.8499482 -0.0007606157 0.7840079 -0.5704894 0.2446904 0.6451775 -0.7406994 0.1873779 0.5175801 0.4650291 0.7182332 0.6641832 0.5973675 0.4494582 0.6674117 0.6222346 0.4091279 0.7210676 0.6691347 0.1797789 0.7181821 0.6413915 0.2698728 0.5889579 -0.5684244 0.5744755 0.7415472 -0.6684361 0.05745306 0.9375119 0.1379354 0.3194451 0.759266 0.08836284 0.6447536 0.9249052 0.04028134 0.3780579 0.9850227 0.09399778 0.1445502 0.8133829 -0.06827616 0.577708 0.8118935 -0.06927202 0.5796814 0.9925743 -0.03407754 0.1167692 0.8863128 -0.2278298 0.4031666 0.9671603 -0.1693367 0.1895416 0.8229665 0.2321825 0.5184762 0.8835835 0.2742193 0.379584 0.9645136 0.2507079 0.08281992 0.8796133 0.3851061 0.2792376 0.7407259 -0.3264664 0.5871498 0.9096477 -0.3694946 0.1897756 0.8944625 -0.3839837 0.2291142 0.5564915 0.2948665 0.7767696 0.7347161 0.4362147 0.5195277 0.8076327 0.4460332 0.3857248 0.8465716 0.5317146 0.02441713 0.7882243 -0.5680463 0.2366981 0.5907674 0.4629338 0.6608223 0.3875295 0.2761428 0.879526 0.3356416 0.2506211 0.9080384 0.1914879 0.1216641 0.9739252 0.7757792 -0.5013358 0.3831828 0.6507272 -0.4853907 0.5839093 0.4451711 -0.3357356 0.830123 0.477287 -0.344581 0.8083694 0.2008609 -0.1520329 0.9677504 0.2880942 -0.1767861 0.9411421 -0.6015975 0.7987975 0.001736852 -0.5603359 0.8282654 -0.0001499644 -0.3140232 0.9494141 -0.001511344 -0.05148314 0.9986708 0.002479983 -0.07847904 0.9969081 0.003906029 0.2596856 0.9656882 -0.003109712 0.5555391 0.8314893 0.001383476 -0.9951552 0.09831601 0.0003553056 -0.9184531 0.3955291 0.0008536077 -0.8996347 0.4366425 -0.0007978194 -0.6978123 0.7162807 0.0001173551 -0.6958203 0.7182159 1.534582e-05 -0.5231876 0.8522146 -0.002254376 -0.3132314 0.9496764 0.0009321384 -0.2248135 0.9744006 -0.001495602 -0.9981738 -0.06032456 0.003163376 -0.4248398 -0.9052671 0.001589509 -0.2556848 -0.966758 -0.002046236 -0.7816175 -0.6237481 0.003534288 -0.5908214 -0.8067992 -0.002280681 -0.8904468 -0.4550788 -0.002769868 -8.330982e-06 1.669687e-05 -1 -6.063561e-06 -1.072123e-06 -1 0 0 -1 -4.950514e-06 7.520705e-05 -1 6.075788e-05 1.359432e-05 -1 0 0 -1 0 -0 -1 4.393607e-05 -2.201324e-05 -1 4.371924e-05 -1.109514e-05 -1 -1.246471e-05 3.163315e-06 -1 -1.070989e-05 8.67317e-06 -1 -0 0 -1 0 -0 -1 -0 0 -1 1.878223e-05 2.933121e-06 -1 1.734331e-05 -1.288601e-05 -1 -1.507191e-05 1.119836e-05 -1 -0.05692355 -0.9982755 0.01434653 -0.2829617 -0.9590333 -0.01370555 -0.6681928 -0.74389 0.01208452 -0.8331473 -0.5528914 -0.01328878 -0.9674783 -0.252619 0.01301271 -0.9966473 0.08077693 -0.0130132 -0.9164977 0.3998192 0.01328852 -0.7872189 0.6165552 -0.01208395 -0.4704952 0.8823198 0.01208531 -0.2716655 0.9623452 -0.009462934 0.09824048 0.9951185 0.009374061 0.2953549 0.95531 -0.01217509 0.6893646 0.724149 0.01961079 0.8978639 0.4398229 -0.01990638 0.9900246 0.1403403 0.01248259 0.9497894 -0.3126254 -0.01286629 0.9154066 -0.4025282 0.001322769 0.5649669 -0.8250719 0.00830405 0.4263548 -0.9044362 -0.01472033 2.513093e-05 -9.836273e-06 -1 -1.271386e-05 1.513863e-05 -1 9.692005e-06 1.945686e-05 -1 -8.75567e-06 -1.757715e-05 -1 -1.87667e-05 -5.097755e-06 -1 1.862023e-05 5.057968e-06 -1 2.162809e-05 -3.12406e-06 -1 4.786805e-05 1.222596e-06 -1 3.422719e-05 -2.741526e-05 -1 4.192266e-05 -5.411157e-05 -1 -2.895429e-05 -2.439673e-05 -1 -2.860223e-06 1.263292e-05 -1 0 0 -1 0 0 -1 -4.915138e-07 -7.112852e-06 -1 2.348837e-05 -1.584967e-05 -1 -0.2537116 -0.9671651 -0.01490732 -0.4283867 -0.9035582 0.008208527 -0.8154415 -0.5787813 -0.008208225 -0.8954144 -0.4450937 0.01116887 -0.9998966 -0.002405121 -0.01417587 -0.978319 0.2067275 0.01247286 -0.7225046 0.6913429 -0.00566735 -0.6719785 0.7403666 -0.01738211 -0.2527914 0.9673501 0.01817546 0.1812862 0.9832527 -0.0186918 0.3989614 0.9168788 0.01276901 0.8260404 0.5635022 -0.01107039 0.8954361 0.4450952 0.009190016 0.9896773 -0.1429535 -0.01015848 0.9783922 -0.2067556 0.0008940031 0.7026643 -0.7114736 0.008258452 0.5488694 -0.8356615 -0.02030406 0.1412591 -0.9898469 0.01577601 -0.02298052 0.0037816 0.9997287 0.008554913 -0.0006103138 0.9999632 -0.001892615 0.0004389985 0.9999982 -0.01316867 0.001603059 0.999912 0.002139004 -0.00111449 0.9999971 -0.004941295 -0.0008177111 0.9999875 -0.0002571796 0.0005461767 0.9999998 -0.01065244 -0.001361693 0.9999424 0.006223211 -0.001269252 0.9999799 0.002218901 -0.001107857 0.9999969 -1 -1.11292e-05 1.430433e-06 -0.9999871 -0.005033581 -0.000567487 -0.999952 0.009787646 0.0005726542 -0.999994 0.003304486 -0.001005479 -0.9999785 0.005668428 0.003285598 -0.9999737 -0.007066472 -0.001606465 -0.9999979 0.0007050054 -0.001942697 -1 0 0 -0.9999921 -0.002748387 -0.00288911 -0.9999936 -0.002421611 -0.002627025 -0.9999918 -0.000253044 -0.004057378 -0.9999969 -0.002035048 0.001431442 -0.9999672 -0.0001486725 -0.008103772 -0.9999883 1.415724e-07 -0.004857777 -0.9999717 0.003321033 0.006756065 -1 1.015682e-05 1.171397e-05 -1 -2.884133e-06 -1.820376e-06 -0.9999982 -0.001340863 0.001391 -0.9999923 -0.0003132382 0.003911992 -0.9999983 -0.001482026 0.001149351 -1 4.999436e-06 -6.211119e-06 -0.9999979 0.0012783 -0.001588114 -1 3.122499e-06 2.071396e-06 -1 0 0 -1 -2.680611e-05 -1.041785e-05 -1 0 0 -1 1.455781e-05 1.597284e-05 -1 -4.601317e-06 2.912617e-06 -1 -1.836423e-06 -2.795929e-06 -0.8934067 -0.4491494 -0.009454264 -0.819121 -0.5702677 -0.06193113 -0.8470501 -0.5314616 -0.007395128 -0.7503455 -0.6610074 -0.007134063 -0.7466352 -0.6650896 -0.01384285 -0.6782298 0.7327734 -0.0552038 -0.7570049 0.6521746 0.04014874 -0.8357431 0.546725 -0.05123599 -0.8849005 0.4650694 0.0257248 0.999974 0.006150201 0.003754243 0.9996321 0.003276448 -0.02692606 0.9998193 -0.003926181 -0.01860178 0.9999572 -0.002141422 -0.00899839 0.03813178 0.9992497 -0.006774988 0.01089457 0.9997273 -0.02065482 -0.0296882 0.9995592 0 -0.07639312 0.9970567 0.006473782 -0.02703075 -0.9996346 -0 -0.02625518 -0.9996552 0.0001655939 0.03540425 -0.9988242 -0.03311638 0.008446126 -0.9999557 -0.004157422 -0.5993982 -0.8004507 0.0006276909 -0.5617962 -0.8260769 -0.04451798 -0.459341 -0.8882293 0.007384865 -0.2777135 -0.9589441 -0.05745882 -0.3268016 -0.9450737 -0.006037314 -0.1134958 -0.9935139 -0.007000002 -0.1081871 -0.994124 -0.003620435 0.01240857 -0.999923 -3.781079e-05 -0.02220253 -0.9995313 0.02107248 0.2420889 -0.9699256 0.02524671 0.1811051 -0.9832994 -0.01797968 0.3947115 -0.9186276 -0.0180636 0.3271877 -0.9433134 0.05575043 0.5410185 -0.8405998 -0.02628539 0.5988611 -0.8002189 0.03186023 0.7250503 -0.6881715 -0.02687186 0.7389683 -0.6736311 -0.01213055 0.8429885 -0.5378398 -0.00993425 0.8416649 -0.539938 -0.008193891 0.9317119 -0.3628756 -0.01530576 0.9114833 -0.4107777 0.02144213 0.9761888 -0.2160781 0.01912178 0.9739064 -0.2267749 0.008920069 -0.5610714 0.8254056 0.06248639 -0.4682563 0.883491 -0.01340897 -0.2441975 0.9670904 0.07144141 -0.3135858 0.9487354 -0.03956096 -0.09971789 0.9941411 0.04171026 -0.01868608 0.9996521 -0.01861392 0.2131244 0.9757292 0.0503052 0.1619123 0.9867885 -0.005735184 0.3588994 0.9333763 -0.0001003096 0.3892693 0.9207783 0.02523372 0.5008052 0.8652024 -0.02487634 0.6173277 0.7863417 0.02393983 0.6009946 0.7992491 0.002530246 0.761284 0.6483049 0.01213844 0.7470365 0.6647722 -0.003787531 0.8488094 0.5286353 0.008200255 0.8685732 0.4943619 0.03445284 0.9305727 0.3660563 -0.006096385 0.9753581 0.2117698 0.06188839 0.965584 0.2600411 -0.005129274 0.04769636 0.8335779 -0.550339 -0.03467289 0.7095609 -0.7037905 0.02603167 -0.05988397 -0.9978659 0.001476813 -0.1135205 -0.9935346 -0.01294489 -0.8163933 -0.5773513 0.02184824 -0.8656089 -0.5002438 -0.01804155 -0.993543 0.1120122 0.03539444 -0.9556153 0.2924838 -0.04722605 -0.6655495 0.7448581 0.04822827 -0.3420142 0.9384564 -0.03618613 0.08243741 0.995939 0.03025341 0.399671 0.9161593 -0.025551 0.7023343 0.7113886 0.0353448 0.9200556 0.3901904 -0.03772901 0.9887515 0.1447306 0.001465223 -0.9999608 0.008727256 -0.003170041 -0.9999344 0.011013 -0.008155329 -0.01121145 0.9999039 0.002752275 -0.005653404 0.9999802 1.826277e-06 -2.383594e-05 1 1 -3.302219e-06 0 1 7.932568e-06 7.994346e-06 1 4.679907e-07 1.383129e-05 1 5.455482e-06 5.654812e-06 1 -2.061591e-06 4.697853e-06 1 3.894228e-06 -1.574385e-05 1 -1.052167e-06 -4.137947e-06 1 -1.576536e-05 1.927827e-05 1 -8.571202e-07 -1.254627e-07 1 2.946693e-06 -1.550289e-06 1 -2.115942e-06 -1.496389e-06 1 8.658071e-06 -5.656542e-06 1 -3.231637e-06 3.205356e-06 1 2.051307e-05 1.181814e-05 -0.005539948 0.9998578 0.0159247 -0.002058056 0.9998434 0.01757517 -0.02184077 0.8656053 -0.5002503 0.01294564 0.8163995 -0.5773424 -0.002050259 0.08308334 -0.9965404 -0.01366545 0.05989801 -0.998111 0.01289345 -0.7844809 -0.6200189 0.002514018 -0.7984382 -0.6020715 -0.01083815 -0.9966756 0.08074741 0.02527118 -0.9786207 0.2041147 -0.02783292 -0.7673069 0.6406758 0.03155127 -0.5935777 0.804158 -0.02660686 -0.09176655 0.995425 0.01804455 0.06223531 0.9978984 -0.01804885 0.5937808 0.8044244 0.01803913 0.6891291 0.7244141 -0.01803787 0.9719294 0.23458 0.01804562 0.993543 0.1120122 8.038525e-05 0.002972757 0.9999955 0.002725984 0.002387443 0.9999935 0.00258634 0.002359563 0.9999939 9.256511e-06 1.442079e-05 1 1 4.599367e-07 -1.468398e-05 1 -5.558415e-07 0 1 0 0 1 0 0 1 -1.014229e-05 -5.233433e-06 1 1.554557e-05 1.984147e-05 1 -3.382355e-07 -4.594323e-06 1 -9.004874e-06 8.62186e-06 1 -4.182578e-07 -1.009486e-07 1 -1.304048e-06 -8.730066e-07 1 -7.73188e-07 3.605513e-07 1 7.387212e-08 -1.230969e-06 1 -1.239503e-06 8.382327e-07 1 -4.983527e-07 -6.526146e-07 0.980148 -0.1976779 -0.01527146 0.9432746 -0.3317198 0.01396661 0.8165678 -0.5764313 -0.03072269 0.5819158 -0.8127262 0.02915584 0.409187 -0.9119722 -0.02954088 -0.8906313 -0.4547251 -0.00101178 -0.89756 -0.4408836 -0.002767411 -0.5401773 -0.8415462 0.002936057 -0.470267 -0.8825089 -0.005216007 0.940969 0.3378258 0.02123883 0.8366387 0.546693 -0.03409272 0.5791101 0.8151354 -0.01363209 0.568062 0.822951 -0.007562905 -0.9053436 0.4246427 -0.005627126 -0.7913333 0.611295 0.01049531 -0.6769035 0.7360578 -0.004512581 -0.3601181 0.9328548 -0.009848453 -0.007944596 -0.770694 0.6371558 0.01141818 -0.7189706 0.6949467 -0.01128314 -0.7546393 0.6560429 0.004835481 -0.7947479 0.6069202 -0.02777198 0.7080277 0.7056383 0.01794766 0.8331789 0.5527121 -0.00843852 0.5489701 0.8357995 0.009720208 0.6068791 0.7947347 0.6087298 0.327199 0.7227648 0.4759985 0.4183917 0.7735463 0.5628025 0.6470265 0.5144027 0.4510372 0.5939172 0.666204 0.4774339 0.7356557 -0.4804865 0.4165109 0.6635913 0.6214221 0.3147198 0.6351112 0.7053973 0.289164 0.8207234 0.4927446 0.1598208 0.5972669 0.7859577 0.09643785 0.7809021 0.6171642 -0.05112518 0.549659 0.8338232 0.05140563 0.8547894 0.5164229 -0.08608367 0.6255263 0.7754396 -0.09200679 0.5941476 0.7990766 -0.2482274 0.8168735 0.5206735 -0.3076596 0.5580897 0.770637 -0.3542614 0.615602 0.703941 -0.3617766 0.7864547 0.5006062 -0.3722847 0.2958161 0.8797141 -0.2513896 0.2797373 0.92658 -0.5580809 0.6130615 0.5591969 -0.5863758 0.625428 0.5147846 -0.4041455 0.3560725 0.8425431 -0.6980957 0.4472676 0.5591191 -0.7325523 0.4922386 0.4701791 -0.2639073 -0.4033917 0.8761439 0.5066141 -0.5362573 0.6751074 -0.5188721 -0.7346851 0.4370463 -0.5037462 -0.7276356 0.4656029 -0.2476219 -0.8683043 0.4298036 -0.09356432 -0.6667722 0.7393649 -0.2621044 -0.6651723 0.699176 0.08107664 -0.813888 0.5753374 -0.2911885 -0.7075163 0.6439177 0.4173639 -0.7587215 0.5001491 0.3008207 -0.7014434 0.64613 0.02172622 -0.614336 0.7887453 -0.001118766 -0.6303961 0.7762728 0.6438154 -0.594541 0.4816874 0.3339588 -0.4518926 0.8272029 0.2243325 -0.6378044 0.7368041 0.6762701 -0.3866006 0.6270557 0.5162591 -0.5546646 0.6525518 -0.294258 -0.2760496 0.9149911 -0.3038259 -0.2249584 0.925788 -0.436976 -0.4564434 0.7750558 -0.7280138 -0.4273289 0.5360839 -0.6299978 -0.5803235 0.5160693 -0.6728963 -0.591631 0.4440534 -0.7560011 -0.4772654 0.4479733 0.3189555 0.3365523 -0.8860022 0.5723482 0.6611678 -0.4850511 0.3719192 0.3783577 -0.8476564 0.4620433 0.5212795 -0.7174843 0.7876923 0.1653948 -0.5934522 0.3813637 0.2324921 -0.8947118 0.790297 0.5424716 -0.2848779 0.6039497 0.3364546 -0.7225255 0.2980522 0.2480485 -0.9217575 0.8753878 0.001844938 -0.4834177 0.7329445 0.02539366 -0.6798142 0.4726601 -0.003347408 -0.8812385 0.2577138 0.3838083 -0.8867214 0.2712267 0.6333452 -0.7247826 0.25477 0.6469404 -0.7187214 0.5957263 0.3668641 -0.7145075 0.594942 0.3142139 -0.7398065 0.203774 0.8042861 -0.5582114 0.7547022 0.1815816 -0.6304386 0.6931468 0.5382195 -0.4794448 0.565093 0.7465714 -0.3511425 -0.001568355 0.4423954 -0.8968188 -0.01641539 0.7109657 -0.7030351 0.009435836 0.8405113 -0.5417118 -0.01570659 0.2253106 -0.9741604 -0.243297 0.8024419 -0.5448795 -0.4020246 0.5938934 -0.6968979 -0.3781368 0.7075402 -0.596992 -0.4440407 0.5626 -0.6973586 -0.6566216 0.6039208 -0.4518051 -0.4129155 0.2478644 -0.8763927 -0.6152952 0.6684234 -0.417878 -0.2791898 0.3212013 -0.9049215 -0.6315613 0.5203776 -0.5747499 -0.5414385 0.4889621 -0.6839301 -0.4888897 0.4183754 -0.765473 -0.7771521 0.4299317 -0.4595577 -0.6313061 0.3053103 -0.7129083 -0.2532409 0.8060763 -0.5348927 0.2703258 0.7265419 -0.6317126 0.8265505 0.2191877 -0.5184313 -0.4463376 0.6340951 -0.6314318 -0.3983269 0.819537 -0.4119403 -0.2485498 0.8192967 -0.5166972 -0.0731857 0.765327 -0.6394674 0.004818688 0.8609812 -0.5086139 0.1513769 0.7683544 -0.6218654 0.3893816 0.7840964 -0.4832958 0.5102296 0.6108421 -0.6054235 0.6863092 0.4532426 -0.5688152 0.7988796 0.1948645 -0.5690511 0.2264321 0.8283768 -0.5123675 0.4402861 0.5903906 -0.6764519 0.5073237 0.4092307 -0.7583882 0.6290534 0.3715989 -0.6827928 -0.2599216 0.507933 -0.8212459 -0.2606721 0.5107749 -0.819243 -0.05214094 0.3177159 -0.9467512 0.06898515 0.3850297 -0.9203223 0.2642576 0.4502828 -0.8528853 0.2842396 0.08759005 -0.9547438 0.002995556 0.4254976 -0.9049546 0.0479873 0.6886626 -0.7234923 0.5334592 0.7665242 -0.3575778 0.5589584 0.3375481 -0.7573816 0.9344252 0.006086585 -0.3561074 0.8517149 0.0007921376 -0.5240048 0.3620213 0.004313881 -0.9321598 0.5212328 0.01194187 -0.853331 0.0283922 0.2907399 -0.9563808 0.4249671 0.4926074 -0.7594346 0.5751978 0.3150464 -0.7549127 0.748167 0.3330779 -0.5738513 0.4483773 0.7417064 -0.498828 0.004699685 0.87916 -0.4765034 0.01954487 0.8179096 -0.5750147 -0.0008879656 0.5289611 -0.8486456 -0.3750696 0.6564543 -0.6545156 -0.3113674 0.8093519 -0.497996 -0.3685306 0.6617078 -0.6529381 -0.3009795 0.2467792 -0.9211468 -0.551634 0.6443 -0.5296957 -0.6976618 0.3924632 -0.599367 -0.589275 0.2509326 -0.7679765 -0.9022061 0.3553302 -0.244468 -0.941635 0.0006125142 -0.3366349 -0.8804792 -0.0001212622 -0.4740848 -0.6402577 0.0007360007 -0.7681599 -0.4660658 -0.0006422874 -0.8847498 -0.09152459 8.931063e-05 -0.9958028 -0.3917023 -0.2393248 -0.8884216 -0.4376544 -0.2253376 -0.870449 -0.3624372 -0.4939096 -0.790375 -0.8083289 -0.3705467 -0.4574928 -0.4285958 -0.8276849 -0.3622753 -0.4741005 -0.6966209 -0.5384682 -0.8228904 -0.4179079 -0.3849731 -0.01942447 -0.8710784 -0.4907597 0.01717697 -0.712096 -0.7018719 -0.0001845706 -0.4035456 -0.9149595 -0.007120508 -0.4571747 -0.8893483 0.693562 -0.1694263 -0.7001902 0.8523306 -0.3191357 -0.4143488 0.4162207 -0.797583 -0.4366024 0.541032 -0.6082566 -0.5807825 0.3363157 -0.3099051 -0.8892978 0.4200594 -0.3516067 -0.8366139 0.7955078 -0.550552 -0.2531002 0.5264253 -0.0006312232 -0.8502211 0.6781031 -0.005897288 -0.7349432 0.8493851 -7.136494e-05 -0.5277737 0.3893679 -0.116514 -0.9136832 -0.4963794 -0.701299 -0.5116515 0.8326682 -0.188805 -0.5205923 0.7375693 -0.1114934 -0.6660035 0.7700039 -0.3785884 -0.5135803 0.5200136 -0.6558625 -0.5472022 0.2830342 -0.7971276 -0.5333659 0.5937685 -0.3347914 -0.7316787 0.5030993 -0.4378166 -0.7451226 0.501774 -0.6462867 -0.5749229 0.05789953 -0.6587723 -0.7501111 -0.1629774 -0.6838329 -0.7112038 -0.2439751 -0.5991982 -0.7625206 -0.472078 -0.6046433 -0.6415206 0.7217826 -0.3197268 -0.6138442 0.3601032 -0.4229682 -0.8315188 0.2394278 -0.3898984 -0.889187 0.1402107 -0.7066441 -0.6935381 0.1372635 -0.7248275 -0.6751177 -0.1741838 -0.6942517 -0.6983371 -0.287415 -0.432597 -0.854548 -0.1740092 -0.6952667 -0.6973701 0.5103257 -0.2393136 -0.8260125 -0.7677678 -0.4383135 -0.4673478 -0.6063596 -0.3009818 -0.7360285 -0.4726861 -0.2602082 -0.841938 -0.5703547 -0.3210147 -0.7560722 -0.6654831 -0.5639772 -0.4889397 -0.5490105 -0.5175639 -0.6562888 -0.4007323 -0.3287051 -0.8551997 -0.2789164 -0.3522442 -0.893381 -0.3085522 -0.4854155 -0.8180264 -0.5100685 -0.7477305 -0.4251224 -0.5069116 -0.7132609 -0.484045 -0.2741624 -0.9135817 -0.300339 0.007965613 -0.9007023 -0.4343638 -0.01666706 -0.8014657 -0.5978083 -0.02025397 -0.5728921 -0.8193805 0.01483711 -0.325154 -0.9455447 0.3020659 -0.2428268 -0.9218413 0.7194658 -0.2697181 -0.6400165 0.7348762 -0.2421723 -0.63349 0.311653 -0.7339912 -0.6034313 0.2136991 -0.8861961 -0.411083 0.642144 -0.5279813 -0.5557759 0.2964087 -0.5777726 -0.7604741 0.7455938 -0.3721746 -0.5527893 0.384378 -0.4683483 -0.7955522 0.8922752 -0.001819847 -0.4514882 0.6960941 -0.02578334 -0.7174874 0.5509282 -0.004721316 -0.8345394 0.008618934 -0.01572758 -0.9998391 0.6397943 -0.5063632 -0.5781519 0.7406445 -0.5043285 -0.4439578 0.6075781 -0.3681767 -0.7037718 0.4485525 -0.3242242 -0.8328741 0.3555305 -0.2176158 -0.9089782 0.4932476 -0.5201846 -0.6972194 0.159187 -0.2149665 -0.9635605 0.2346857 -0.2701481 -0.9337786</float_array> + <technique_common> + <accessor count="3308" source="#cubenormals-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <source id="cubeverts-array0"> + <float_array count="4842" id="cubeverts-array0-array">-0.02721459 0.01528917 0.01506863 -0.02729459 0.01528917 0.01506863 -0.02729459 0.01828917 0.01506863 -0.02421459 0.01528917 0.01506863 -0.02421461 -0.01621083 0.01506863 -0.02728794 -0.01621083 0.01506863 -0.01162474 0.01828269 0.01506863 -0.01285938 0.01787547 0.01506863 -0.01413797 -0.01729291 0.0150686 -0.01307154 -0.01862926 0.01506862 -0.01942339 -0.01615525 0.01506863 -0.01189915 -0.01917946 0.01506859 -0.02729462 -0.01921083 0.01506863 -0.01644809 0.01439718 0.01506865 -0.01938631 0.01521292 0.01506863 -0.01423583 0.01590888 0.01506859 -0.01646199 -0.01529622 0.01506863 -0.01428557 -0.01388879 0.01506863 -0.01377167 0.0169867 0.01506863 -0.01428555 0.01296711 0.01506863 -0.02805084 0.02891451 -0.01500369 -0.02729471 0.02885299 -0.01501021 -0.02799043 0.02587251 -0.01501961 -0.02728455 0.01326436 -0.01506692 -0.02801459 0.01377343 -0.01503137 -0.02804452 -0.02942134 -0.01503744 -0.02801462 -0.01469509 -0.01503137 -0.02729478 -0.03009755 -0.01498979 -0.02728952 -0.01439509 -0.01508376 -0.04179253 -0.01921082 0.01656863 -0.04179253 -0.01921082 0.01506863 -0.02801462 -0.01921083 0.01656863 -0.02801462 -0.01921083 0.01506863 -0.0417925 0.01828918 0.01506863 -0.0417925 0.01828918 0.01656863 -0.02801459 0.01828917 0.01506863 -0.02801459 0.01828917 0.01656863 -0.02981247 0.02111876 0.01654906 -0.02977208 0.02546096 0.0165824 -0.02916056 0.02311602 0.01656863 -0.02801656 0.02125132 0.01656861 -0.03817503 0.02154794 0.01647136 -0.03830846 0.0357354 0.01652743 -0.04179248 0.03578918 0.01656863 -0.03833941 -0.03666764 0.01652578 -0.04179254 -0.03671082 0.01656863 -0.038144 -0.02250165 0.01646251 -0.02983262 -0.02235615 0.01653465 -0.02801801 -0.02216611 0.01656859 -0.02924634 -0.02424473 0.01656863 -0.02977578 -0.02648079 0.01658153 -0.0417925 0.01528918 0.01506863 -0.03101459 0.01528917 0.01506863 -0.03101462 -0.01621083 0.01506863 -0.04179253 -0.01621082 0.01506863 0.02520747 -0.03246087 0.01806863 0.02520746 -0.04246087 0.01806863 0.03645747 -0.03246088 0.01806863 0.03645746 -0.04246088 0.01806863 0.01254878 -0.03245232 0.01806863 0.01402171 -0.03191891 0.01806863 0.01512303 -0.03032351 0.01806863 0.01520747 -0.01921086 0.01806863 0.02302699 -0.01924594 0.01806863 0.02520424 -0.01975867 0.01806863 0.02520751 0.03153913 0.01806863 0.01515372 0.02921734 0.01806863 0.01448424 0.03053679 0.01806863 0.01296227 0.03149938 0.01806863 0.0252075 0.01887293 0.01806863 0.02342781 0.01835712 0.01806863 0.0152075 0.01828914 0.01806863 -0.01469605 -0.03039252 0.01806863 -0.01388791 -0.03162212 0.01806863 -0.02479254 -0.03246083 0.01806863 -0.0125619 -0.03241502 0.01806863 -0.01479253 -0.01921084 0.01806863 -0.02273342 -0.01926023 0.01806863 -0.02478835 -0.01976999 0.01806866 -0.02479249 0.03153917 0.01806863 -0.01263119 0.0314852 0.01806863 -0.01415513 0.03043449 0.01806863 -0.0147451 0.0291618 0.01806863 -0.0147925 0.01828916 0.01806863 -0.02270634 0.01832516 0.01806863 -0.02478869 0.01885748 0.01806865 0.03645752 0.04153912 0.01806863 0.03645752 0.03153913 0.01806863 0.03645752 0.04153912 0.01606863 0.03645752 0.03153913 0.01606863 0.01304619 0.03148519 0.02006863 -0.0126551 0.03145473 0.02006863 -0.02979249 0.03153918 0.01606863 -0.02979249 0.03153918 0.01656863 -0.02979249 0.03153918 0.01806863 -0.02979254 -0.03246083 0.01656863 -0.02979254 -0.03246083 0.01806863 -0.012979 -0.03230636 0.02006863 0.0002074634 -0.03246085 0.02006863 -0.02979254 -0.03246083 0.01606863 0.03645747 -0.03246088 0.01606863 0.01307017 -0.0323764 0.02006863 0.03645746 -0.04246088 0.01606863 -0.02979249 0.03578917 0.01606863 -0.02981796 0.03572692 0.01658657 -0.03604248 0.03578918 0.01606863 -0.03604248 0.03578918 0.01656863 -0.02979254 -0.03671083 0.01606863 -0.03604254 -0.03671082 0.01606863 -0.03604254 -0.03671082 0.01656863 0.0002074559 -0.04246085 0.02006863 0.008925963 -0.04075401 0.02006863 0.007237617 -0.03943168 0.02006863 0.02520751 0.03228913 0.02006863 0.0002075126 0.03228915 0.02006863 0.01520012 -0.02979636 0.02006863 0.01466554 -0.03127514 0.02006863 0.02520746 -0.04246087 0.02006863 0.006704482 -0.03771249 0.02006863 0.006914317 -0.03617931 0.02006863 0.008236609 -0.03449105 0.02006863 0.01436886 0.03063439 0.02006863 0.01516775 0.02929389 0.02006863 0.009955771 -0.03395788 0.02006863 0.01148898 -0.03416772 0.02006863 0.01361351 -0.03660471 0.02006863 0.01362619 -0.03846906 0.02006863 0.01217822 -0.04043072 0.02006863 0.01045908 -0.04096384 0.02006863 0.01296384 -0.03524964 0.02006863 -0.01162643 -0.04048141 0.02006863 -0.01270035 -0.03943035 0.02006863 -0.02479255 -0.04246083 0.02006863 -0.01334991 -0.03768274 0.02006863 -0.02479249 0.03228917 0.02006863 -0.01200378 -0.03470446 0.02006863 -0.01032928 -0.03396815 0.02006863 -0.008657442 -0.04080727 0.02006863 -0.01015292 -0.04095431 0.02006863 -0.01472116 -0.03045348 0.02006863 -0.01425056 0.03035342 0.02006863 -0.008510983 -0.03416771 0.02006863 -0.006326899 -0.03815105 0.02006863 -0.006446096 -0.03632579 0.02006863 -0.01478514 0.02887466 0.02006863 -0.00727078 -0.03501648 0.02006863 -0.007136261 -0.03979135 0.02006863 -0.01295201 -0.03592722 0.02006863 0.00951733 0.03307351 0.02006863 0.00762504 0.03408254 0.02006863 0.006650152 0.03631726 0.02006863 0.007339788 0.03865581 0.02006863 0.009072417 0.03988557 0.02006863 0.0002075196 0.04153915 0.02006863 0.01134256 0.03319271 0.02006863 0.01056793 0.04003261 0.02006863 0.02520752 0.04153913 0.02006863 0.01204147 0.03955972 0.02006863 0.01311539 0.03850859 0.02006863 0.01376488 0.03676104 0.02006863 0.01307524 0.03442246 0.02006863 -0.0101917 0.0329973 0.02006863 -0.01237498 0.03408257 0.02006863 -0.01328519 0.03600242 0.02006863 -0.008093542 0.0334407 0.02006863 -0.02479248 0.04153917 0.02006863 -0.01298418 0.03812565 0.02006863 -0.01149142 0.03963764 0.02006863 -0.009714589 0.04007201 0.02006863 -0.007675844 0.03940688 0.02006863 -0.006327692 0.0373754 0.02006863 -0.006600767 0.03495263 0.02006863 -0.01479252 -0.005025231 0.01806863 0.02518733 -0.01973364 0.01656863 0.02520748 -0.01921087 0.01656863 0.02520748 -0.01921087 0.01506863 0.02520748 -0.01621087 0.01506863 0.02520748 -0.01621087 0.01656863 0.02519468 0.01883409 0.01656863 0.0252075 0.01828913 0.01656863 0.0252075 0.01528913 0.01656863 0.0252075 0.01828913 0.01506863 0.0252075 0.01528913 0.01506863 0.02520752 0.04153913 0.01806863 -0.03604248 0.04153918 0.01606863 -0.03604248 0.04153918 0.01806863 -0.02479248 0.04153917 0.01806863 -0.02479255 -0.04246083 0.01806863 -0.03604255 -0.04246083 0.01806863 -0.03604255 -0.04246083 0.01606863 -0.03604254 -0.03671082 0.01806863 -0.03604248 0.03578918 0.01806863 -0.04179254 -0.03671082 0.01806863 -0.0379362 -0.01154874 0.01806863 -0.0383878 -0.01041858 0.01806863 -0.03564886 0.0106271 0.01806863 -0.03518619 0.00935428 0.01806863 -0.03534572 -0.00982967 0.01806863 -0.03527851 -0.0109073 0.01806863 -0.03683476 -0.01205609 0.01806863 -0.03749512 0.008125707 0.01806863 -0.03823928 0.00890802 0.01806863 -0.04179248 0.03578918 0.01806863 -0.0382387 0.01026232 0.01806863 -0.03796882 -0.009428716 0.01806863 -0.03614947 0.008055625 0.01806863 -0.03581329 -0.01168153 0.01806863 -0.02615452 -0.02048558 0.01806868 -0.03688934 0.0111532 0.01806863 -0.0297398 -0.02620658 0.01806863 -0.02787715 -0.02198838 0.0180685 -0.02916053 -0.02403758 0.01806863 -0.02961046 0.02421798 0.01806863 -0.03716286 -0.008926416 0.01806863 -0.02615442 0.0195639 0.01806868 -0.02794744 0.02113957 0.01806846 -0.03608988 -0.009047377 0.01806863 -0.008223951 0.03636238 0.01806863 -0.006327693 0.03570291 0.01806863 -0.006600775 0.03812569 0.01806863 -0.008618324 0.03765081 0.01806863 -0.008093571 0.03963764 0.01806863 -0.00975798 0.03810371 0.01806863 -0.009540834 0.04004213 0.01806863 -0.011379 0.03973089 0.01806863 -0.01066528 0.03785435 0.01806863 -0.01305942 0.03796437 0.01806863 -0.01125089 0.0371067 0.01806863 -0.01132689 0.03616881 0.01806863 -0.01328595 0.03617873 0.01806863 -0.01266022 0.0344225 0.01806863 -0.01051563 0.03509295 0.01806863 -0.01092759 0.03319273 0.01806863 -0.009432016 0.03304571 0.01806863 -0.008901602 0.03518981 0.01806863 -0.007675817 0.03367149 0.01806863 0.01180279 0.03649689 0.01806863 0.01347445 0.03511392 0.01806863 0.01370098 0.03689957 0.01806863 0.01307529 0.03865575 0.01806863 0.01126529 0.03773404 0.01806863 0.01104379 0.04000394 0.01806863 0.009972111 0.03811751 0.01806863 0.008925963 0.03983229 0.01806863 0.008847106 0.03737339 0.01806863 0.007237691 0.03851001 0.01806863 0.006665666 0.03613993 0.01806863 0.00869401 0.03603323 0.01806863 0.007551295 0.03420855 0.01806863 0.009746487 0.03498934 0.01806863 0.009072444 0.0331927 0.01806863 0.01089769 0.0330735 0.01806863 0.01120058 0.03528994 0.01806863 0.01226645 0.03369397 0.01806863 0.009837186 0.03500473 0.01606863 0.01104175 0.03517873 0.01606863 0.01182154 0.03644231 0.01606863 0.01138388 0.03757125 0.01606863 0.01057786 0.03807355 0.01606863 0.009640042 0.03799755 0.01606863 0.008892309 0.03741195 0.01606863 0.008642973 0.03650465 0.01606863 0.008937527 0.03560176 0.01606863 -0.01068337 0.03518981 0.01606863 -0.009345985 0.03502517 0.01606863 -0.008308928 0.03589614 0.01606863 -0.008379008 0.03724176 0.01606863 -0.009040074 0.03791132 0.01606863 -0.009969279 0.03810769 0.01606863 -0.01093616 0.03762707 0.01606863 -0.01138775 0.03649691 0.01606863 -0.00837908 -0.03816345 0.01806863 -0.006250689 -0.03706164 0.01806863 -0.008258136 -0.03709051 0.01806863 -0.00713635 -0.03513028 0.01806863 -0.008760405 -0.03628453 0.01806863 -0.008956297 -0.03399604 0.01806863 -0.009750296 -0.03586556 0.01806863 -0.01075418 -0.03408303 0.01806863 -0.01088049 -0.03631717 0.01806863 -0.01237504 -0.03500427 0.01806863 -0.01136108 -0.03728406 0.01806863 -0.01328525 -0.03692411 0.01806863 -0.01298426 -0.03904737 0.01806863 -0.01116476 -0.03821322 0.01806863 -0.01049509 -0.03887432 0.01806863 -0.01121774 -0.04072779 0.01806863 -0.009286647 -0.03897436 0.01806863 -0.0094321 -0.04095431 0.01806863 -0.007958589 -0.04048143 0.01806863 -0.006694031 -0.03915977 0.01806863 0.01174224 -0.03776652 0.01806863 0.01355391 -0.03859594 0.01806863 0.01362619 -0.0364527 0.01806863 0.01161014 -0.03669982 0.01806863 0.01241864 -0.03470448 0.01806863 0.01039235 -0.03585454 0.01806863 0.0110636 -0.03405479 0.01806863 0.009517231 -0.03399522 0.01806863 0.009119557 -0.03631722 0.01806863 0.007876865 -0.0348046 0.01806863 0.006861025 -0.03632574 0.01806863 0.008593446 -0.0375577 0.01806863 0.006713997 -0.03782129 0.01806863 0.007186874 -0.03929475 0.01806863 0.009270051 -0.03873083 0.01806863 0.008238069 -0.04036866 0.01806863 0.009985558 -0.04101822 0.01806863 0.01030572 -0.03903626 0.01806863 0.01232416 -0.04032856 0.01806863 0.01129544 -0.0386045 0.01806863 0.009576325 -0.03890765 0.01606863 0.01051318 -0.03899563 0.01606863 0.01135117 -0.03854878 0.01606863 0.01181377 -0.03727596 0.01606863 0.01085049 -0.0359773 0.01606863 0.009504888 -0.03604737 0.01606863 0.008760693 -0.03682966 0.01606863 0.008722843 -0.03804616 0.01606863 -0.01042367 -0.03890763 0.01606863 -0.009346055 -0.03897484 0.01606863 -0.008571838 -0.03844011 0.01606863 -0.008217137 -0.0375591 0.01606863 -0.008522551 -0.03652346 0.01606863 -0.009557135 -0.03588248 0.01606863 -0.01085033 -0.03626598 0.01606863 -0.01136795 -0.03736259 0.01606863 -0.01113022 -0.038273 0.01606863 0.02282227 -0.01922403 0.01656863 -0.008762665 -0.01814531 0.01806757 -0.01042793 -0.01813206 0.01806854 -0.006552468 -0.01582188 0.01806757 -0.007400332 -0.01726942 0.0180685 -0.01058039 -0.01200455 0.01806835 -0.008124234 -0.01222105 0.01806627 -0.002822806 -0.01046518 0.01806863 -0.006706329 -0.01391629 0.01806817 -0.01209604 -0.0172174 0.01806603 -0.01284889 -0.01513959 0.01806824 -0.01234156 -0.0132964 0.01806744 -0.01121537 0.01694444 0.01806816 -0.009109012 0.01732762 0.01806676 -0.006907262 0.01584178 0.01806603 -0.01209603 0.0119999 0.01806603 -0.01281372 0.01382342 0.01806853 -0.01260885 0.01543001 0.01806744 0.002409581 0.004215218 0.01806863 0.004411411 0.001409535 0.01806863 0.002804162 0.005926448 0.01806863 0.002064153 0.007303176 0.01806863 -0.001994602 0.006863091 0.01806863 -0.000830878 0.007919345 0.01806863 -0.007764811 0.01156696 0.0180685 0.0009420218 0.008029933 0.01806863 -0.002384303 0.005377491 0.01806863 -0.004252718 0.001620529 0.01806863 -0.001789764 0.003922681 0.01806863 0.001245852 0.003158952 0.01806863 -0.0005270486 0.003048368 0.01806863 -0.004359149 -0.00261345 0.01806863 -0.002546581 -0.002846014 0.01806863 -0.003393225 -0.001394526 0.01806863 -0.003268164 0.000148418 0.01806863 -0.005735748 0.002113084 0.01806863 -0.00721944 0.00169892 0.01806863 -0.008283298 0.0002736841 0.01806863 -0.01058111 -0.0004608412 0.01806863 -0.008230633 -0.001287843 0.01806863 -0.007498622 -0.002384577 0.01806863 -0.006083377 -0.003041334 0.01806863 0.002223752 -0.002968984 0.01806863 0.0009420146 -0.003970065 0.01806863 0.002204737 -0.004844381 0.01806863 -0.0008308775 -0.004080649 0.01806863 0.002799275 -0.006299191 0.01806863 -0.001994609 -0.005136916 0.01806863 -0.002384312 -0.006622517 0.01806863 -0.001789771 -0.008077331 0.01806863 0.002500123 -0.007602252 0.01806863 0.001643372 -0.008624587 0.01806863 -0.0003166963 -0.009033389 0.01806863 0.008799284 -0.0002992001 0.01806863 0.008408186 -0.001796988 0.01806863 0.007952661 0.001489477 0.01806863 0.006045829 0.002130939 0.01806863 0.004156971 -0.002104381 0.01806863 0.003626995 -0.0001699914 0.01806863 0.007431669 -0.002722025 0.01806863 0.005916631 -0.003041345 0.01806863 -0.006552445 0.01339544 0.01806757 3.063005e-05 -0.001997252 0.01806863 -0.00105048 -0.001295658 0.01806863 0.0003765782 0.001039419 0.01806863 0.001301376 0.0005797206 0.01806863 -0.001288966 -0.000427844 0.01806863 -0.0008557854 0.0006622059 0.01806863 0.001714325 -0.0003668692 0.01806863 0.001350369 -0.001472592 0.01806863 -0.009865688 0.01094765 0.01806776 -0.01938633 -0.01613459 0.01656863 -0.02421461 -0.01621083 0.01656863 -0.01942333 0.01523358 0.01656863 -0.02421459 0.01528917 0.01656863 -0.01085049 0.007364541 0.01656863 -0.01237973 0.01090177 0.01656782 -0.01073473 -0.007415085 0.01656863 -0.01160922 -0.01044642 0.01656863 -0.01644808 -0.01531885 0.01656866 -0.01342444 -0.01314293 0.01657001 -0.01645692 0.01437246 0.01656863 -0.01426463 0.01294961 0.01656863 -0.04179253 -0.01621082 0.01656863 -0.03101462 -0.01621083 0.01656863 -0.0417925 0.01528918 0.01656863 -0.03101459 0.01528917 0.01656863 -0.03519722 0.009581426 0.01656863 -0.03579946 0.0107884 0.01656863 -0.0369693 0.01110772 0.01656863 -0.03814185 0.01043008 0.01656863 -0.0383065 0.009092696 0.01656863 -0.03534573 -0.01109198 0.01656863 -0.03530791 -0.009875492 0.01656863 -0.03775581 -0.009162168 0.01656863 -0.03766529 0.008223968 0.01656863 -0.03675801 0.007974634 0.01656863 -0.03836792 -0.01036257 0.01656863 -0.03573473 0.008344296 0.01656863 -0.03628659 -0.008947313 0.01656863 -0.03798742 -0.01151857 0.01656863 -0.03608991 -0.01187429 0.01656863 -0.03703023 -0.01200758 0.01656863 0.01994544 -0.01615997 0.01506863 0.01884691 -0.01603158 0.01656863 -0.02729462 -0.01921083 0.01656863 -0.02315985 -0.0192639 0.01656827 -0.001533795 -0.01921085 0.01506863 -0.01168805 -0.0191668 -0.01729086 -0.008132386 -0.01917813 -0.01720215 -0.008023438 -0.01918291 0.01506859 0.01994546 0.01523824 0.01656863 0.01884693 0.01510984 0.01506863 -0.02729459 0.01828917 0.01656863 -0.02319861 0.01835311 0.01656829 0.02289119 0.01830377 0.01656863 -0.001533766 0.01828915 0.01506863 -0.007739062 0.0182351 0.01506863 -0.008134768 0.01824683 -0.01728934 -0.01163369 0.01823083 -0.01737511 0.01122357 -0.008141191 0.01656863 0.01116308 0.006558311 0.01656863 0.01208035 0.009670692 0.01656863 0.01412333 0.01249391 0.01656863 0.01700875 0.01444816 0.01656863 0.01522491 -0.01433999 0.01656863 0.01279938 -0.01183782 0.01656863 -0.027295 0.02047844 0.01656862 -0.02589253 0.01939906 0.01656846 -0.02589254 -0.02032073 0.01656846 -0.02729517 -0.02140023 0.01656862 0.01118374 0.006595359 0.01506863 0.0111415 -0.00737536 0.01506863 0.0060807 0.001571931 0.01686863 0.007045905 0.002028551 0.01686863 0.005058602 0.001865699 0.01686863 0.004665692 0.0009040244 0.01686863 0.00395001 0.0007769478 0.01686863 0.004188721 -0.0004163364 0.01686863 0.003634952 -0.0009850387 0.01686863 0.004510437 -0.001587039 0.01686863 0.004776443 -0.002622442 0.01686863 0.005480535 -0.002342314 0.01686863 0.006264256 -0.003034782 0.01686863 0.006683988 -0.002440758 0.01686863 0.007749258 -0.002544905 0.01686863 0.007962867 -0.001537279 0.01686863 0.008731836 -0.001070113 0.01686863 0.008209195 -0.0003170762 0.01686863 0.008532866 0.0006950582 0.01686863 0.007904537 0.0006653422 0.01686863 0.007083809 0.001344577 0.01686862 -0.00143877 0.006691888 0.01686863 -0.001794643 0.007153193 0.01686863 -0.001816428 0.005767269 0.01686863 -0.002384304 0.005700823 0.01686863 -0.001558763 0.004565133 0.01686863 -0.001993992 0.004209821 0.01686863 -0.0006990815 0.003715308 0.01686863 -0.0008308721 0.003158952 0.01686863 0.0006853551 0.003559272 0.01686863 0.0009420238 0.003048367 0.01686863 0.001962875 0.004462741 0.01686863 0.002369078 0.004108106 0.01686863 0.002781418 0.005595919 0.01686863 0.002187375 0.006016999 0.01686863 0.002291543 0.007080935 0.01686863 0.001648457 0.006935973 0.01686863 0.0007835856 0.007492709 0.01686863 0.001034467 0.007977275 0.01686863 -0.0005270297 0.008029937 0.01686863 -0.0006069099 0.007405973 0.01686863 -0.005919303 0.00157194 0.01686863 -0.005849279 0.002113084 0.01686863 -0.007121849 0.001740632 0.01686862 -0.007334314 0.0009040355 0.01686863 -0.00804997 0.0007769836 0.01686863 -0.007825294 -0.0005876349 0.01686863 -0.008373009 -0.0007516855 0.01686863 -0.007237453 -0.001905768 0.01686863 -0.007426448 -0.002509058 0.01686863 -0.00602063 -0.002484763 0.01686863 -0.005501674 -0.003041336 0.01686863 -0.0048185 -0.0022271 0.01686862 -0.004324394 -0.00255754 0.01686863 -0.003968675 -0.001367419 0.01686863 -0.003412317 -0.00149921 0.01686863 -0.003812635 1.702026e-05 0.01686863 -0.003350084 0.0005020872 0.01686863 -0.004582996 0.001177857 0.01686863 -0.004557749 0.001793251 0.01686863 -0.001673979 -0.005733896 0.01686863 -0.0023372 -0.006069784 0.01686863 -0.001772424 -0.006937348 0.01686863 -0.002119075 -0.007609728 0.01686863 -0.001124275 -0.007978691 0.01686863 -0.001030342 -0.008718318 0.01686862 -2.063337e-05 -0.008484767 0.01686863 0.0007316532 -0.009033389 0.01686863 0.00133368 -0.008157889 0.01686863 0.00220961 -0.008074895 0.01686863 0.00216104 -0.007036944 0.01686863 0.002799275 -0.006622522 0.01686863 0.002017379 -0.005478858 0.01686863 0.002408967 -0.005131521 0.01686863 0.001245846 -0.004080652 0.01686863 0.0007835916 -0.004507296 0.01686863 -0.0002953797 -0.003935878 0.01686863 -0.0007745063 -0.004650952 0.01686863 -0.00166785 -0.004667552 0.01686863 0.006953783 -0.002371652 0.01506863 0.005399467 -0.002323381 0.01506863 0.004481434 -0.001508781 0.01506863 0.004170883 -0.0001570905 0.01506863 0.004997983 0.001177853 0.01506863 0.00616297 0.001557918 0.01506863 0.007333698 0.001236179 0.01506863 0.008225168 -4.973463e-05 0.01506863 0.007978045 -0.001431685 0.01506863 -0.0009837258 0.00724039 0.01506863 0.000685342 0.007519034 0.01506863 0.001725346 0.006870894 0.01506863 0.002265906 0.005593658 0.01506863 0.00157237 0.003997355 0.01506863 0.0002520212 0.003520382 0.01506863 -0.000918705 0.003842108 0.01506863 -0.001673704 0.00481646 0.01506863 -0.001783833 0.005928786 0.01506863 -0.005362242 -0.002438014 0.01506863 -0.006776551 -0.002260781 0.01506863 -0.00774607 -0.001036947 0.01506863 -0.007704753 0.0001877958 0.01506863 -0.007002041 0.001177846 0.01506863 -0.005837035 0.001557927 0.01506863 -0.004666318 0.001236198 0.01506863 -0.003910712 0.0002714378 0.01506863 -0.003812635 -0.0009387112 0.01506863 -0.004460843 -0.001978761 0.01506863 -0.001233484 -0.005064021 0.01506863 -0.0003686262 -0.004507295 0.01506863 0.001021879 -0.004594027 0.01506863 0.001933528 -0.005412913 0.01506863 0.002226253 -0.006416331 0.01506863 0.001978043 -0.007431688 0.01506863 0.001114083 -0.008284675 0.01506863 -0.000445316 -0.008413769 0.01506863 -0.001510765 -0.007516654 0.01506863 -0.001829823 -0.006148681 0.01506863 -0.0005693153 0.0008186144 0.01506863 -0.001240153 2.304934e-05 0.01506863 -0.001533782 -0.002202114 0.01506863 0.0119485 0.009387917 0.01506863 0.001449622 0.0004605068 0.01506863 0.0003014689 0.00104599 0.01506863 0.0006345364 -0.00190896 0.01506863 0.001626476 -0.001075886 0.01506863 -0.001144469 -0.001132867 0.01506863 0.01522493 0.01341827 0.01506863 0.01344705 0.01171702 0.01506863 -0.0003961996 -0.001844669 0.01506863 0.01412329 -0.01341562 0.01506863 0.01700872 -0.01536987 0.01506863 0.0120803 -0.01059236 0.01506863 -0.005624844 0.01622085 0.01506863 -0.006433063 0.01745053 0.01506863 -0.01082683 0.007412198 0.01506863 -0.01069467 0.009661111 0.01506861 -0.009558929 0.009556271 0.01506864 -0.01078428 -0.008056887 0.01506863 -0.008432346 0.009948114 0.01506863 -0.005529274 0.01179708 0.01506863 -0.01197767 0.01032164 0.01506855 -0.006611809 -0.01859225 0.01506866 -0.00558586 -0.01696476 0.01506863 -0.005531595 -0.01274608 0.01506863 -0.01111167 -0.01069438 0.01506863 -0.0121781 -0.01149754 0.01506805 -0.00905129 -0.01053218 0.01506864 -0.01427936 0.0130039 -0.01193137 -0.01193888 0.01032176 -0.01193472 -0.01194183 -0.01126089 -0.01193319 -0.01428553 -0.01389 -0.01193137 -0.0342225 0.02553918 0.00556863 -0.03422249 0.02793287 0.00781372 -0.03422249 0.02889615 0.00651507 -0.03422249 0.03095266 0.008701213 -0.03422247 0.03029157 0.009370816 -0.03425037 0.03351871 0.01239726 -0.03422836 0.02552807 0.0119906 -0.03422249 0.03353918 0.00556863 -0.03422249 0.0310527 0.00749272 -0.03422249 0.0293624 0.009567161 -0.03422249 0.02839549 0.009086528 -0.03422249 0.03024179 0.00658516 -0.03122529 0.03360709 0.01344398 -0.03122249 0.03353918 0.00556863 -0.03122249 0.03107397 0.00769299 -0.0312225 0.03053226 0.006749421 -0.0312225 0.0280572 0.00749592 -0.03122249 0.02553918 0.00556863 -0.03122249 0.02860179 0.00672865 -0.03122249 0.02802517 0.008445094 -0.03122953 0.02548112 0.01250685 -0.03122249 0.03012449 0.009483242 -0.03122248 0.03098595 0.008629804 -0.03122249 0.02877812 0.009401286 -0.03122249 0.02950467 0.00643408 -0.0342225 -0.0292401 0.007019441 -0.03422253 -0.02888542 0.00790036 -0.03422253 -0.02646082 0.00556863 -0.03422707 -0.02644933 0.01198854 -0.03422252 -0.02926595 0.009056407 -0.03422253 -0.03036257 0.009574033 -0.03422253 -0.03201064 0.00753761 -0.03422253 -0.03109199 0.00655183 -0.03422254 -0.03446082 0.00556863 -0.0342427 -0.03445204 0.0122856 -0.03422254 -0.03163499 0.009110269 -0.03422253 -0.03001433 0.006484631 -0.03123264 -0.02634256 0.012769 -0.03122253 -0.02646082 0.00556863 -0.03122254 -0.02889229 0.00782182 -0.03122255 -0.02908866 0.008750987 -0.03122255 -0.02937294 0.006854949 -0.03122255 -0.02975822 0.009412107 -0.03122252 -0.03183302 0.007246261 -0.03122254 -0.03201064 0.008459638 -0.03122254 -0.03446083 0.00556863 -0.03121672 -0.0345565 0.01353808 -0.03122254 -0.03022312 0.00645186 -0.03122254 -0.03116343 0.00658515 -0.03122255 -0.03096674 0.00951214 -0.03449886 0.02526248 0.01324899 -0.03476169 0.03374249 0.01384834 -0.03524229 0.02451291 0.01460679 -0.03562156 0.03430014 0.01507368 -0.03652626 0.02324225 0.0158072 -0.03672226 0.03498483 0.01591273 -0.03080626 0.03432174 0.01510593 -0.03118235 0.02503513 0.01375374 -0.03078419 0.02406503 0.01516377 -0.0301982 0.02265468 0.01610939 -0.03447947 -0.02619897 0.013198 -0.03471695 -0.03464532 0.01376606 -0.03512413 -0.02555929 0.01445471 -0.03546548 -0.03512132 0.01488069 -0.03643306 -0.02423998 0.01575498 -0.03658072 -0.03581851 0.01583064 -0.03106205 -0.02561177 0.01437684 -0.03054017 -0.02444697 0.01561134 -0.03065977 -0.03545752 0.0154536 -0.008191443 0.01352189 0.01506863 -0.008107266 0.01368704 0.01651741 -0.008086268 0.01422677 0.01506863 -0.008176635 0.01479918 0.01651741 -0.008469562 0.01525236 0.01506863 -0.008944615 0.0156065 0.0165174 -0.009639355 0.01575415 0.01506863 -0.01005127 0.01573143 0.01652014 -0.01074519 0.01535486 0.01506863 -0.0108839 0.01521309 0.01651813 -0.01128843 0.01433026 0.01651741 -0.01119845 0.01457829 0.01506863 -0.01116917 0.01354388 0.01506863 -0.01095849 0.01312329 0.01651597 -0.01021446 0.01261981 0.01506863 -0.009850643 0.01252892 0.01651878 -0.008922812 0.01272035 0.01506863 -0.008768997 0.01279051 0.01651741 -0.008078979 -0.01497845 0.01506863 -0.008068415 -0.01495445 0.01651849 -0.008312445 -0.01416875 0.0165174 -0.008506886 -0.01393581 0.01506863 -0.009083941 -0.0135642 0.01651815 -0.009639374 -0.01346315 0.01506863 -0.009913321 -0.01347273 0.01651935 -0.0104975 -0.01371021 0.01506863 -0.01068045 -0.01380954 0.01651816 -0.01113071 -0.01440591 0.01506863 -0.01128298 -0.01474078 0.01651597 -0.01121546 -0.01550024 0.01506863 -0.01095849 -0.01609403 0.01651598 -0.01073753 -0.01623589 0.01506863 -0.009978564 -0.01664616 0.01506863 -0.01011035 -0.01661326 0.01652011 -0.009147779 -0.01663097 0.01651598 -0.009090636 -0.0165519 0.01506863 -0.008309179 -0.01593229 0.01506863 -0.008211023 -0.01579455 0.01651741 -0.02801463 -0.030176 0.01651058 -0.02729463 -0.03027236 0.01650146 -0.02801458 0.02898634 0.01652793 -0.02729458 0.0292122 0.01652275 -0.02806743 -0.02546481 0.007788381 -0.02803069 -0.02631919 0.01150874 -0.02803002 -0.03109513 -0.004496271 -0.02813326 -0.03420796 -0.007031361 -0.02804288 -0.03421022 0.00465345 -0.02804375 0.02448703 0.008896037 -0.02806956 0.02485851 0.00639045 -0.02804503 0.02716219 0.01265559 -0.02804789 -0.02996324 0.01320155 -0.02803559 -0.03259178 0.01273274 -0.02801467 -0.03202424 0.01572273 -0.02807764 -0.02918493 0.00322816 -0.02802651 -0.02629148 -0.00643108 -0.02802958 -0.03142198 0.00276454 -0.02803421 -0.02652061 0.00472712 -0.02804953 0.02455156 -0.009415442 -0.02803985 0.03086849 0.01305378 -0.02801458 0.03271556 0.01399568 -0.0280136 0.03327609 0.01198054 -0.02799989 -0.0340906 0.01277617 -0.02801462 -0.03327525 0.01451002 -0.02803616 0.02633864 0.00394948 -0.0280503 0.02540389 -0.006877551 -0.02804875 0.02778811 -0.005081902 -0.02804046 -0.02604283 -0.01256267 -0.02801458 0.03090905 0.01588373 -0.02806882 0.03328519 0.00487297 -0.02805521 0.03328441 -0.006583061 -0.02808966 0.0319861 0.00380317 -0.02802906 0.02916134 0.002777049 -0.02804186 0.03039824 -0.004885141 -0.02806544 -0.02549562 -0.01056853 -0.02729479 -0.02731757 0.00758556 -0.02729594 0.02906095 0.00486237 -0.02729496 0.02714885 0.0059714 -0.02729612 0.03108506 0.0109178 -0.02729563 0.03261496 0.008975688 -0.02729481 0.03327159 0.01246476 -0.02729696 -0.02769813 0.009762698 -0.02729424 0.03297452 -0.01191988 -0.02729458 0.03328918 -0.01003138 -0.02729552 0.03261509 -0.009024249 -0.02729475 0.03260447 0.00729811 -0.02729602 0.03168792 0.00564143 -0.02729544 0.02863207 0.01114464 -0.02729577 0.02635271 0.00770947 -0.02729482 -0.03161412 0.01103232 -0.02729581 -0.02970847 0.01118575 -0.02729551 0.02686712 0.009841865 -0.02729459 0.03110274 0.01572264 -0.0272946 0.03235375 0.0145099 -0.0272957 -0.02778894 -0.01170455 -0.02729522 -0.02727376 -0.009572152 -0.02729474 -0.03360484 -0.01025585 -0.02729466 -0.03419669 -0.01084381 -0.02729551 -0.03304096 -0.01183586 -0.02729519 -0.03026118 -0.00673031 -0.0272956 -0.02825055 -0.00760787 -0.02729698 -0.03363628 0.00742158 -0.02729483 -0.03419239 0.01238077 -0.02729559 -0.03313282 0.009841899 -0.02729491 0.02754934 -0.01241173 -0.02729643 0.0263632 -0.0105785 -0.02729581 -0.02813746 0.00585852 -0.02729552 0.02933952 -0.01313204 -0.02729436 0.03032741 -0.0146136 -0.02729537 0.03144362 -0.01251165 -0.02729437 0.03172921 -0.01368706 -0.02729493 0.03255063 -0.01095275 -0.02729502 -0.02930766 -0.01289486 -0.02729537 -0.03121327 -0.01304897 -0.02729465 -0.03322349 -0.01307744 -0.02729467 -0.03178794 -0.01433037 -0.02729461 -0.03336476 0.01438221 -0.02729694 0.02700237 -0.007914752 -0.02729675 0.02945339 -0.006691601 -0.02729505 0.03152895 -0.007450981 -0.02729567 -0.03340009 -0.00864907 -0.02729505 -0.03211112 -0.007213211 -0.02729537 -0.03223423 0.0053965 -0.02729541 -0.03010163 0.00488176 -0.02729463 -0.03215217 0.01563322 -0.02839512 0.03328932 -0.007819392 -0.02858128 0.03328667 0.009706983 -0.02867076 0.03329002 0.0066335 -0.02819197 0.03328626 0.01081422 -0.02901868 0.033288 -0.009634661 -0.02903248 0.03328459 0.008316066 -0.02852206 -0.03420766 -0.008128962 -0.02810056 -0.03421472 0.0112101 -0.02853433 -0.03420976 0.009834422 -0.02857993 -0.03420593 0.006426469 -0.0289752 -0.03421373 -0.009304831 -0.02888715 -0.03420275 0.00721931 -0.02901624 -0.03420722 0.008358287 -0.02892595 0.03318816 -0.0110291 -0.02869645 0.03275722 -0.01227764 -0.02846763 0.03202639 -0.01334478 -0.02827162 0.03115322 -0.01414372 -0.02816908 0.03037136 -0.01457311 -0.02818564 -0.03154246 -0.01449919 -0.02851279 -0.03315476 -0.01314104 -0.02876004 -0.0338115 -0.01198687 -0.02895654 -0.03413046 -0.01088921 -0.02951463 -0.02959968 -0.01133567 -0.02951332 -0.02974244 -0.0134331 -0.02951462 -0.03112458 -0.01146278 -0.02951519 -0.03190632 -0.0132448 -0.0295104 -0.03338322 -0.01194854 -0.02951463 -0.03202368 -0.01039226 -0.02951518 -0.03405307 -0.0103363 -0.02951463 -0.03199063 -0.00941248 -0.02951517 -0.03347293 -0.00793251 -0.02951463 -0.03132196 -0.00852707 -0.02951471 -0.03201628 -0.006726751 -0.02951332 -0.03056027 -0.0063581 -0.02951463 -0.03007855 -0.00834747 -0.02951622 -0.02898756 -0.006640621 -0.02951464 -0.02914988 -0.00896373 -0.02951023 -0.02775535 -0.00762471 -0.02951332 -0.02695911 -0.009212912 -0.02951463 -0.02883155 -0.01017438 -0.02951185 -0.02716091 -0.01135484 -0.02951027 -0.02815416 -0.01263683 -0.02951463 -0.0306517 0.009726755 -0.02950973 -0.03304191 0.01054686 -0.02951483 -0.03116088 0.01158371 -0.02950974 -0.02901484 0.01134164 -0.02951464 -0.0293378 0.009249188 -0.02951517 -0.02722368 0.009677716 -0.02951463 -0.02879475 0.00796867 -0.02951468 -0.02690783 0.007813389 -0.02951517 -0.02744876 0.00606972 -0.02951463 -0.02959969 0.00666432 -0.02947741 -0.02900084 0.0048593 -0.02951332 -0.0303614 0.00449534 -0.02951463 -0.0307062 0.00647196 -0.02951485 -0.03218409 0.00492595 -0.02951463 -0.0316943 0.006976739 -0.02951624 -0.03338206 0.00595533 -0.02951463 -0.03205784 0.00790382 -0.02951518 -0.03406882 0.00829371 -0.02951462 -0.03190874 0.008854228 -0.02951458 0.03107167 -0.009327181 -0.02951479 0.03305427 -0.00923136 -0.02951459 0.03103263 -0.01058287 -0.02951463 0.03299388 -0.01079967 -0.02949285 0.03237166 -0.01204778 -0.02951457 0.03026439 -0.01139046 -0.02951208 0.0313168 -0.01304131 -0.02950843 0.02983974 -0.01346594 -0.02951458 0.0288754 -0.0114628 -0.02950998 0.02816645 -0.01324277 -0.02951029 0.02683372 -0.01223801 -0.02951458 0.02797632 -0.01039224 -0.0295112 0.02604506 -0.01062112 -0.02951457 0.02814628 -0.009011751 -0.02948074 0.02605643 -0.00933448 -0.02951325 0.02673795 -0.007710742 -0.02951514 0.02851665 -0.006464001 -0.02951458 0.02922368 -0.00834707 -0.02951458 0.03019068 -0.008437909 -0.02950844 0.0304656 -0.006507181 -0.02951514 0.03203074 -0.007312169 -0.02951459 0.02800938 0.008587506 -0.0295097 0.02598166 0.007684381 -0.02951227 0.02651501 0.01000622 -0.02951457 0.02857155 0.009379588 -0.02951479 0.02823937 0.01140874 -0.02951458 0.02950355 0.009683643 -0.02951196 0.03031129 0.01158305 -0.02951457 0.03056425 0.009358136 -0.02951125 0.03222033 0.01041292 -0.02951458 0.0311583 0.00825115 -0.02951215 0.03303612 0.008786174 -0.02951224 0.03292316 0.00692442 -0.02951459 0.03082867 0.00704355 -0.02951513 0.03168593 0.00516014 -0.02951457 0.0298547 0.00648433 -0.0295148 0.0296182 0.00448539 -0.02951458 0.02875357 0.00662071 -0.0295146 0.02808408 0.004817201 -0.0295148 0.02684503 0.00570487 -0.02951458 0.02797632 0.00760776 -0.02884586 -0.03202328 0.008529414 -0.0288448 -0.03201785 0.00767714 -0.02884585 -0.03164112 0.006945899 -0.02884511 -0.03077633 0.006484479 -0.02884583 -0.02980947 0.00657555 -0.02884513 -0.02908016 0.007230311 -0.02884727 -0.02883245 0.008311502 -0.02884511 -0.02939558 0.009282849 -0.02884583 -0.03027838 0.009687348 -0.02884581 -0.03136154 0.009425938 -0.02884979 -0.03199062 -0.01059446 -0.02884584 -0.03092163 -0.01149382 -0.02884583 -0.02980946 -0.01142447 -0.0288498 -0.02886277 -0.01040678 -0.02884513 -0.02904454 -0.0091548 -0.0288498 -0.02998546 -0.008333302 -0.02884585 -0.03136153 -0.00857405 -0.0288451 -0.03196614 -0.009345662 -0.02884723 0.0279777 0.00754668 -0.02884507 0.02870094 0.00668791 -0.02884579 0.02964059 0.00644281 -0.02884584 0.03066189 0.00688838 -0.02884504 0.0311233 0.00775319 -0.0288458 0.03103224 0.008719981 -0.02884724 0.03014303 0.009600286 -0.02884505 0.02902035 0.009598279 -0.02884726 0.02813564 0.008929263 -0.02884724 0.02792592 -0.00960266 -0.02884509 0.02812292 -0.01070804 -0.02884579 0.02881409 -0.01139009 -0.02884724 0.03006112 -0.01149284 -0.02884581 0.03099787 -0.01065651 -0.02884973 0.03106894 -0.009268301 -0.0288458 0.02999994 -0.00836893 -0.02884725 0.02875401 -0.00848427 -0.02912705 0.03277769 -0.00807613 -0.02861274 0.03285982 -0.007604791 -0.02807037 0.02626577 -0.01376457 -0.0282473 0.02797964 -0.01421459 -0.02818093 0.02509433 -0.01151598 -0.02829462 0.02605939 -0.00708707 -0.02818281 0.03205043 -0.005954882 -0.02851941 0.0305367 -0.00592589 -0.02844742 0.02916531 -0.005712511 -0.02840483 0.02772585 -0.006043581 -0.0285159 0.026626 -0.01285527 -0.02876173 0.03177295 -0.006735001 -0.02873369 0.02576727 -0.008855472 -0.0286263 0.02551429 -0.01028727 -0.02876167 0.02600633 -0.01158239 -0.02899557 0.02888561 -0.006197781 -0.02894289 0.02735686 -0.006827502 -0.0288762 0.02640713 -0.00771389 -0.02878294 0.02787801 -0.01347905 -0.02878257 0.02919109 -0.01383293 -0.02878306 0.03054619 -0.01371636 -0.02906187 0.03168081 -0.01299077 -0.02821484 0.03215139 0.011847 -0.02851261 0.03217113 0.004790421 -0.02806907 0.02529781 0.01077669 -0.02823378 0.02907015 0.0034684 -0.02830169 0.02621273 0.00517189 -0.02818097 0.02875049 0.01272096 -0.02848225 0.03035949 0.01218577 -0.02842146 0.02709481 0.01156285 -0.02839827 0.02602808 0.01054899 -0.02833553 0.02528793 0.009219525 -0.02855088 0.02545915 0.00768394 -0.02842398 0.02566337 0.006280039 -0.02842387 0.02707601 0.00458186 -0.02880108 0.03174276 0.01125697 -0.02876176 0.02852659 0.01183431 -0.02880323 0.02919008 0.00421042 -0.02873349 0.03049319 0.00426393 -0.02892363 0.03268136 0.01022212 -0.0289116 0.02988582 0.01186918 -0.02891128 0.02642081 0.01026922 -0.02888477 0.02583659 0.009055499 -0.02890767 0.02792586 0.004613019 -0.0289086 0.03223494 0.00537141 -0.02893626 0.03298511 0.00646821 -0.02905872 0.02740005 0.01113188 -0.02905832 0.02615091 0.00649403 -0.02905835 0.02689377 0.005430049 -0.02905845 0.03111452 0.00468062 -0.02906162 -0.03310227 -0.01257122 -0.0290611 -0.03351905 -0.00778814 -0.02822528 -0.0330991 -0.006190851 -0.02827034 -0.03127797 -0.00551334 -0.02822145 -0.0300569 -0.005364459 -0.02821047 -0.02813996 -0.00590929 -0.02818261 -0.02676698 -0.00710674 -0.02825029 -0.0259765 -0.009139489 -0.02824895 -0.02824662 -0.0139102 -0.02841617 -0.03051481 -0.01422441 -0.02852785 -0.02734864 -0.01264571 -0.02880606 -0.02850694 -0.01326036 -0.02859134 -0.02659998 -0.01132705 -0.02873365 -0.02874607 -0.00640364 -0.02878137 -0.03108891 -0.006062931 -0.02876478 -0.03317436 -0.007128531 -0.02889206 -0.03206236 -0.01340117 -0.02887613 -0.02948768 -0.01364385 -0.02890776 -0.02666156 -0.0096009 -0.0288849 -0.02699023 -0.008307639 -0.0287832 -0.02768647 -0.007166071 -0.02891164 -0.02945964 -0.006248711 -0.02894304 -0.03207108 -0.006496101 -0.02905862 -0.03079106 -0.01365313 -0.02905851 -0.02685314 -0.01090292 -0.02827399 -0.03348802 0.00478267 -0.02821036 -0.0320482 0.00370491 -0.02822805 -0.02642393 0.00595674 -0.02824907 -0.02615795 0.009557324 -0.02818305 -0.02729686 0.01154841 -0.02845201 -0.0289078 0.00412672 -0.02842088 -0.02744606 0.005052691 -0.0284211 -0.02634181 0.006963571 -0.0283353 -0.02858845 0.01205531 -0.02842111 -0.03008784 0.01231691 -0.02834283 -0.03195135 0.01223073 -0.02854982 -0.03337553 0.01095137 -0.02876175 -0.03146684 0.00430113 -0.02874576 -0.03036134 0.00417071 -0.02875953 -0.02657425 0.00809047 -0.02855046 -0.02726682 0.01072729 -0.02888486 -0.03265537 0.004926219 -0.02899526 -0.02755992 0.005628729 -0.02890778 -0.02677667 0.00905383 -0.02883912 -0.0285287 0.01144739 -0.02890784 -0.03144593 0.0117527 -0.02890413 -0.03236997 0.01135627 -0.02908279 -0.03348399 0.005896441 -0.0290584 -0.02685299 0.00709727 -0.02905985 -0.02739793 0.01020814 -0.02905855 -0.03013048 0.01179018 -0.02905115 -0.03384904 0.009654126 -0.03428554 0.02590242 -0.01435498 -0.03428558 -0.02686718 -0.01434788 -0.03120553 0.02580704 -0.01441171 -0.0312056 -0.02667841 -0.01441607 -0.02973046 0.03448288 -0.01443137 -0.03120554 0.03453917 -0.01443137 -0.03120559 -0.03546083 -0.01443137 -0.02972141 -0.03540822 -0.01443138 -0.02866684 0.0337487 -0.01443137 -0.02830719 -0.03366989 -0.01443138 -0.02830712 0.03274674 -0.01443137 -0.0286483 -0.03463987 -0.01443137 -0.01428298 -0.01649336 -0.0154408 -0.01428126 0.01555927 -0.01543414 -0.01428572 0.01442353 -0.01505412 -0.01428719 -0.01516414 -0.01504113 -0.01428373 -0.001173695 -0.01270878 -0.01428241 -0.007270376 -0.0119715 -0.01428383 0.006314342 -0.01196967 -0.01123341 0.01382919 -0.009931373 -0.01098492 0.01502059 -0.009931359 -0.01023722 0.01560621 -0.00993135 -0.009163796 0.01566133 -0.009931382 -0.008256231 0.01485041 -0.009931382 -0.008186147 0.01350479 -0.009931373 -0.00922325 0.0126338 -0.009931373 -0.01043077 0.01274515 -0.009931382 -0.01123826 -0.0152463 -0.009931373 -0.01091894 -0.01407644 -0.009931382 -0.00971198 -0.01347422 -0.009931382 -0.008797466 -0.01378176 -0.00993141 -0.008185105 -0.0144842 -0.009931382 -0.008267064 -0.01583054 -0.009931382 -0.00922325 -0.0165835 -0.009931373 -0.01056059 -0.01641887 -0.009931373 -0.005522279 -0.01268347 -0.01493174 -0.008219955 -0.0110377 -0.01493129 -0.004066472 0.0005870926 -0.01673139 -0.004250382 0.001628502 -0.01673136 -0.003268164 0.000148419 -0.01673137 -0.003773746 -0.0004163242 -0.01673137 -0.003554399 -0.001833269 -0.01673136 -0.004095471 -0.001587037 -0.01673137 -0.005216411 -0.002414402 -0.01673137 -0.00517713 -0.002981575 -0.01673137 -0.006281711 -0.00240717 -0.01673138 -0.006948405 -0.002786238 -0.01673138 -0.007196303 -0.001936537 -0.01673134 -0.008049972 -0.001698663 -0.01673134 -0.007772885 -0.0008552341 -0.01673137 -0.008373007 -0.0001699975 -0.01673137 -0.007602403 0.0005211659 -0.01673137 -0.007582329 0.001420664 -0.01673136 -0.006524796 0.001420957 -0.01673137 -0.005960824 0.002128449 -0.01673137 -0.00513972 0.001492077 -0.01673137 -0.00182912 0.005842897 -0.01673137 -0.002337743 0.005801784 -0.01673136 -0.001881859 0.007081282 -0.01673136 -0.001124256 0.007057001 -0.01673134 -0.000619517 0.007977263 -0.01673136 -0.0001868962 0.007519522 -0.01673137 0.0007103285 0.008064125 -0.01673137 0.001189504 0.007349039 -0.01673136 0.001905446 0.007474418 -0.01673135 0.00216105 0.006115244 -0.01673137 0.002731836 0.006148427 -0.01673137 0.002153815 0.005049944 -0.01673137 0.002445604 0.004166724 -0.01673136 0.00157237 0.003997358 -0.01673137 0.0008167558 0.003014802 -0.01673137 0.0002520204 0.003520382 -0.01673137 -0.0009484029 0.003213758 -0.01673138 -0.0007633343 0.003768582 -0.01673136 -0.001518556 0.004491215 -0.01673139 -0.002172711 0.004500794 -0.01673137 0.006618598 -0.002478533 -0.01673137 0.006816762 -0.0029852 -0.01673137 0.00505159 -0.002786246 -0.01673136 0.005236654 -0.002231417 -0.01673138 0.004383649 -0.001367431 -0.01673137 0.003717513 -0.001293162 -0.01673137 0.00421166 -0.0001541341 -0.01673137 0.003808197 0.0004728251 -0.01673137 0.004632416 0.0008026813 -0.01673139 0.004596493 0.001547387 -0.01673137 0.005796368 0.001556825 -0.01673138 0.006045829 0.002130939 -0.01673136 0.007333694 0.001236181 -0.01673136 0.007749616 0.001628488 -0.01673136 0.008161044 0.0001152548 -0.01673137 0.008731841 0.0001484003 -0.01673138 0.008017374 -0.001442866 -0.01673138 0.008445597 -0.001833288 -0.01673138 -0.001788351 -0.006154137 -0.01673137 -0.002191805 -0.005527163 -0.01673137 -0.00126822 -0.005057078 -0.01673136 -0.00140353 -0.004452622 -0.01673139 -0.0001869301 -0.004480484 -0.01673137 0.0002769883 -0.003836372 -0.01673137 0.001021875 -0.004594024 -0.01673137 0.001707546 -0.004387929 -0.01673138 0.00203132 -0.00555427 -0.01673137 0.002587682 -0.005422492 -0.01673137 0.002187365 -0.0069387 -0.01673137 0.002649912 -0.007423782 -0.01673137 0.001417 -0.008099555 -0.01673136 0.001245849 -0.008841047 -0.01673136 8.069349e-05 -0.008493632 -0.01673137 -0.0002953646 -0.008985822 -0.01673137 -0.00105606 -0.008035926 -0.01673133 -0.001490485 -0.00839611 -0.01673135 -0.001674317 -0.007193129 -0.01673135 -0.002316864 -0.007070125 -0.01673137 -0.004484817 0.001804145 -0.01793138 -0.003393223 0.0004728305 -0.01793138 -0.003268166 -0.001070114 -0.01793137 -0.004250384 -0.002550194 -0.01793137 -0.00596614 -0.003048142 -0.01793137 -0.007582332 -0.002342359 -0.01793137 -0.008416991 -0.0005303407 -0.01793137 -0.007674038 0.001328966 -0.01793137 -0.006194059 0.002094882 -0.01793137 -0.002366447 -0.006517618 -0.01793137 -0.00195625 -0.005024949 -0.01793137 -0.000316701 -0.003888312 -0.01793137 0.001643375 -0.004297115 -0.01793137 0.002780015 -0.005936659 -0.01793137 0.002464955 -0.007698649 -0.01793138 0.00136338 -0.008786242 -0.01793137 -0.000401787 -0.008985198 -0.01793137 -0.00188187 -0.008002976 -0.01793137 0.003717514 0.0003714581 -0.01793137 0.005244547 0.001981575 -0.01793136 0.007245837 0.001919348 -0.01793137 0.008649916 0.000502084 -0.01793136 0.00868905 -0.001084602 -0.01793137 0.007947714 -0.002426642 -0.01793136 0.006264256 -0.003034783 -0.01793137 0.004969681 -0.002718326 -0.0179314 0.003882091 -0.00161674 -0.01793137 -0.002366438 0.00548239 -0.01793136 -0.001956241 0.006975045 -0.01793137 -0.0007261912 0.007938436 -0.01793138 0.0008167548 0.0080635 -0.01793136 0.002296838 0.007081282 -0.01793137 0.002752724 0.005801777 -0.01793137 0.002515106 0.004287105 -0.01793137 0.0009420247 0.003048366 -0.01793136 -0.0006195112 0.003101034 -0.01793138 -0.001881861 0.003997025 -0.01793137 0.003270169 0.00999097 -0.0156589 0.001233379 0.01037047 -0.01552507 0.003966799 0.009528226 -0.01518078 0.004739017 0.009440806 -0.01565099 0.006108909 0.008680313 -0.01557886 0.009366611 0.005432469 -0.01565872 0.007934656 0.007234108 -0.01557018 0.009501469 0.004738194 -0.0151622 0.0101142 0.004038655 -0.01557902 0.004056797 -0.01065285 -0.01556098 0.003753897 -0.0104586 -0.01511835 0.001385184 -0.01130407 -0.01564502 0.001221125 -0.01107806 -0.01518785 0.001338569 0.01007767 -0.0151422 0.005795171 0.008316526 -0.01498467 0.007702291 0.00706109 -0.01514476 0.01065372 0.002583014 -0.01557913 0.01027361 0.002296577 -0.01500622 0.01097272 0.001086167 -0.01556793 0.01052444 0.0006665113 -0.01496375 0.01104741 -0.0004694565 -0.01541651 0.01065308 -0.003520306 -0.01558861 0.01090883 -0.0020361 -0.01534194 0.01013118 -0.004254189 -0.01514824 0.01010019 -0.00497952 -0.01556803 0.009376307 -0.006319848 -0.0155804 0.00866058 -0.006897162 -0.01514845 0.008448984 -0.007565144 -0.01558033 0.007328685 -0.008681151 -0.01556789 0.00663659 -0.008601921 -0.01495819 0.006081625 -0.009596744 -0.01544542 0.001781173 0.009687484 -0.01494602 0.008506795 0.005624078 -0.01493598 0.01002306 -0.003473099 -0.01494673 0.008360727 -0.006700111 -0.01494707 0.001811522 -0.01059213 -0.01494731 -0.003839596 0.0001919536 -0.01493138 -0.004885929 0.001362991 -0.01493135 -0.0064453 0.001492078 -0.01493137 -0.007616344 0.0004457608 -0.01493136 -0.00778835 -0.0007675303 -0.01493137 -0.007268221 -0.001864623 -0.01493138 -0.006186906 -0.002441216 -0.01493135 -0.004810523 -0.002270741 -0.01493137 -0.003910712 -0.00119312 -0.01493136 0.002231409 0.005311033 -0.01493137 0.002039288 0.006358901 -0.01493138 0.001417009 0.007177855 -0.01493137 8.070664e-05 0.007571932 -0.01493137 -0.001334301 0.006904042 -0.01493136 -0.00182912 0.005235401 -0.01493137 -0.001002024 0.003900451 -0.01493137 0.0003342896 0.003506369 -0.01493137 0.001611263 0.004063454 -0.01493134 0.00822626 -0.0005053744 -0.01493137 0.007904537 0.000665346 -0.01493138 0.0066186 0.001556825 -0.01493137 0.005081291 0.001236188 -0.01493137 0.004189815 -4.972394e-05 -0.01493136 0.004510439 -0.001587037 -0.01493136 0.00563138 -0.00241441 -0.01493137 0.007021879 -0.002327677 -0.01493136 0.007933542 -0.001508787 -0.01493137 0.0022314 -0.006688965 -0.01493136 0.001904526 -0.005334655 -0.01493136 0.0007835916 -0.004507296 -0.01493138 -0.0004411436 -0.004548597 -0.01493137 -0.001547902 -0.005384437 -0.01493137 -0.001772403 -0.006938693 -0.01493137 -0.001002036 -0.008099553 -0.01493137 1.533728e-06 -0.008457118 -0.01493137 0.001021889 -0.00832767 -0.01493138 0.001833306 -0.007637392 -0.01493134 0.003368853 -0.01085442 -0.0173677 0.002185233 -0.01108258 -0.01746295 0.003489859 -0.01025092 -0.01790378 0.00327758 0.009965145 -0.01732233 0.002963141 0.00978534 -0.01770595 0.001403388 0.01036874 -0.01725065 0.005646062 0.00829475 -0.01790986 0.00392652 0.009140898 -0.01790755 0.004681898 0.009443859 -0.01735623 0.007557149 0.00698614 -0.01785446 0.006046049 0.00870623 -0.01735642 0.001381911 -0.01130688 -0.01722083 0.006087938 -0.009619473 -0.01727461 0.00472642 -0.01035355 -0.01729531 0.005334953 -0.009701605 -0.01776888 0.007851968 -0.007310705 -0.01792193 0.007857859 -0.007865454 -0.01770137 0.009422727 -0.005769714 -0.0177115 0.01011213 -0.004935692 -0.01735594 0.0106344 -0.003392678 -0.01750599 0.01010009 0.004058324 -0.01729513 0.01013501 0.003277754 -0.01773046 0.009376213 0.005398003 -0.0172829 0.007898144 -0.008196714 -0.01727289 0.009366512 -0.006354198 -0.01720403 0.009858809 -0.003716369 -0.01792854 0.01093827 -0.001995134 -0.01744623 0.01065852 -0.0002197651 -0.01785985 0.0110833 -0.0004600723 -0.01729485 0.01095695 0.001091961 -0.01736897 0.01065311 0.002598636 -0.01727423 0.008448862 0.006643293 -0.01728224 0.008878912 0.005204248 -0.01790982 0.01016751 0.001813483 -0.01791761 0.007315709 0.007777106 -0.01728359 -0.004326093 0.009856359 -0.0149437 -0.004140122 0.0102256 -0.01522986 -0.004016939 0.0104217 -0.01559795 -0.004163572 -0.01067181 -0.01493574 -0.004267565 -0.01111313 -0.01517194 -0.004314076 -0.01137289 -0.01561917 -0.01964993 0.01047796 -0.01792708 -0.01026229 -0.01307463 -0.01793195 -0.004205026 -0.01007989 -0.01792684 -0.002792515 -0.003460845 -0.01793137 -0.005818378 0.01078083 -0.01791265 -0.01322867 -0.01754149 -0.01791265 -0.01153916 -0.01599874 -0.01793137 -0.01051229 -0.01697628 -0.01793138 -0.01203386 -0.01849195 -0.01791093 -0.007325615 -0.0182495 -0.01792042 -0.01435142 -0.01554876 -0.01789818 -0.02110117 -0.01143075 -0.01789462 -0.024667 -0.01209986 -0.01790124 -0.03338556 0.002177758 -0.01793137 -0.02732443 -0.01439917 -0.0178825 -0.02892272 -0.01770524 -0.01791211 -0.01171545 -0.01475512 -0.01793136 -0.0160117 -0.01349801 -0.01790843 -0.03354303 -0.03376552 -0.01792012 -0.02891354 -0.033875 -0.01789442 -0.01800793 -0.01221102 -0.01788854 -0.01128419 -0.01377437 -0.01793138 -0.005461344 -0.01119446 -0.01792014 -0.006119639 -0.01232141 -0.01790782 -0.009265479 -0.01709937 -0.01793136 -0.008157127 -0.01650835 -0.01793137 -0.006138457 -0.01687113 -0.0178945 -0.007586128 -0.01519946 -0.01793137 -0.007900531 -0.01399535 -0.01793137 -0.008834957 -0.01315601 -0.01793136 -0.01060068 0.01601582 -0.01793137 -0.01276855 0.01719953 -0.01791866 -0.007821557 0.01757789 -0.01791091 -0.02884438 0.01614367 -0.0179164 -0.02925044 0.03345434 -0.01792217 -0.0143406 0.01469741 -0.01788564 -0.01148452 0.01514292 -0.01793138 -0.01174422 0.01391399 -0.01793138 -0.01652567 0.01210205 -0.0179086 -0.01110858 0.01263522 -0.01793135 -0.0269078 0.01299494 -0.0178905 -0.02373533 0.0107759 -0.01791446 -0.009797223 0.01206461 -0.01793137 -0.03287084 0.03387237 -0.01790257 -0.03366807 0.03289975 -0.01790265 -0.008595573 0.01237863 -0.01793141 -0.008230838 0.0156604 -0.01793135 -0.009355346 0.01619354 -0.01793137 -0.006632504 0.01679129 -0.0179058 -0.007595191 0.01438164 -0.01793137 -0.006071064 0.01581509 -0.01786891 -0.007854872 0.01315272 -0.01793137 -0.00619149 0.01137747 -0.01791665 -0.02971969 -0.03466787 -0.01792299 -0.03303103 -0.0346421 -0.01790973 0.003207484 -0.003460849 -0.01793137 0.003207488 0.002539147 -0.01793137 -0.004188738 0.009212497 -0.01792173 -0.007601766 0.01057077 -0.01493225 -0.005343862 0.01098826 -0.01493257 -0.005522329 0.01176717 -0.01493189 -0.01129879 -0.007590931 -0.01492969 -0.01271143 -0.004367203 -0.01492576 -0.01332593 -0.0001797365 -0.01493044 -0.005303726 -0.01183664 -0.01493497 -0.01267256 0.003553778 -0.01492883 -0.01155757 0.006152795 -0.01492594 -0.009620468 0.0088127 -0.01493106 -0.004807839 -0.01122915 -0.01494623 -0.004296286 -0.01137274 -0.01721469 -0.004301706 -0.01047827 -0.01785394 -0.00433638 0.009865604 -0.01769499 -0.00414502 0.01044095 -0.01718495 -0.005576531 -0.0165631 -0.0173604 -0.005505904 -0.01250693 -0.01723717 -0.005564425 0.01557467 -0.01733166 -0.005556395 0.01189984 -0.01733114 -0.005391587 -0.01225639 -0.01550977 -0.00495037 -0.01170654 -0.01553753 -0.005128962 -0.01169313 -0.01753279 -0.004889704 -0.01162233 -0.01733003 -0.004571686 0.01054475 -0.01553211 -0.004942548 0.01078079 -0.01555593 -0.005382319 0.01131475 -0.01546462 -0.005306739 0.01116985 -0.01720322 -0.004681139 0.01059521 -0.01724831 -0.005180497 0.01079795 -0.0175612 -0.007303705 -0.01893729 -0.01729058 -0.006745667 -0.01856616 -0.0174538 -0.006086233 -0.01792773 -0.01729839 -0.005730949 -0.01724498 -0.01727886 -0.005825066 0.01652217 -0.01737077 -0.006368148 0.01736986 -0.01720432 -0.007274545 0.01798872 -0.01734721 -0.008902203 0.009697623 -0.01390611 -0.01014177 0.009555859 -0.01277556 -0.01104119 0.009765544 -0.01220842 -0.01075722 0.007627084 -0.01405306 -0.01387585 0.001818981 -0.01292937 -0.01050843 -0.01053878 -0.01252404 -0.009555185 -0.01048785 -0.01324395 -0.01102333 -0.008857109 -0.01324181 -0.008693142 -0.01072276 -0.01420561 -0.01074525 -0.00850429 -0.01423204 -0.01353033 -0.002867757 -0.01336382 -0.01317837 -0.002799924 -0.0142321 -0.013472 -0.000441129 -0.01376508 -0.01341551 0.001886118 -0.01356609 -0.01289646 0.003619517 -0.01372762 -0.01287269 -0.006051975 -0.01298174 -0.01242314 -0.005853396 -0.01378423 -0.01276307 -0.00789453 -0.01236083 -0.01296678 0.007026499 -0.01223906 -0.01230832 0.006621225 -0.01280059 -0.01181754 0.006358896 -0.0135656 -0.01122267 -0.0107744 -0.01213536 -0.01424159 0.01596211 -0.01579407 -0.01371242 0.01704972 -0.01725374 -0.01310297 0.01764017 -0.01735023 -0.01244629 0.01804348 -0.01728818 -0.01426179 -0.01686276 -0.01579859 -0.01250926 -0.0189498 -0.01720131 -0.01359836 -0.01815215 -0.01723613 -0.01125007 -0.01367049 -0.009931373 -0.009798285 -0.01298611 -0.009931382 -0.008429966 -0.01338983 -0.009931382 -0.007640353 -0.0145797 -0.009931382 -0.007740886 -0.0158201 -0.009931359 -0.008515367 -0.01680895 -0.009931382 -0.009669727 -0.01713482 -0.009931373 -0.01100795 -0.01672108 -0.009931373 -0.01175333 -0.01519945 -0.009931382 -0.007706185 0.01337369 -0.009931359 -0.009118753 0.0120916 -0.009931382 -0.01084802 0.01241043 -0.009931373 -0.01169908 0.013658 -0.009931382 -0.01146896 0.01525115 -0.009931382 -0.009974579 0.01623267 -0.009931373 -0.008429955 0.01582748 -0.009931382 -0.007709646 0.01481264 -0.009931382 -0.02179219 0.01036692 -0.01505106 -0.02375885 0.01095559 -0.01509849 -0.01609222 0.0123791 -0.01505664 -0.02515683 -0.01234906 -0.01505895 -0.01997642 -0.01150432 -0.01507932 -0.01904356 0.01075194 -0.01505651 -0.01680036 -0.01279815 -0.01506468 -0.02267332 -0.01149214 -0.01507332 -0.03428553 0.02639952 -0.01370404 -0.03428554 0.02792516 -0.009834541 -0.03428555 0.02845125 -0.01107504 -0.03427793 -0.03382673 -0.00681369 -0.03428559 -0.03199524 -0.009561081 -0.03428559 -0.03187428 -0.01063399 -0.03428554 0.03110771 -0.009754591 -0.0342649 0.03304446 -0.006813711 -0.03427227 0.0328926 -0.01708751 -0.03428555 0.03071335 -0.01104305 -0.03428553 0.03043007 -0.008582022 -0.03426111 -0.03383647 -0.01724013 -0.03428554 0.02944092 -0.01150678 -0.03428554 0.02645364 -0.00750312 -0.03428554 0.02881604 -0.008485161 -0.03428559 -0.03109201 -0.01137816 -0.03428559 -0.03001432 -0.01144537 -0.03428559 -0.03129506 -0.008570971 -0.03428554 0.02696712 -0.006882021 -0.03428558 -0.02813083 -0.00682711 -0.03428558 -0.02981783 -0.008447811 -0.03428558 -0.0273252 -0.01365743 -0.03428556 -0.02914563 -0.01080416 -0.03428558 -0.02889713 -0.00961273 -0.03428558 -0.02742662 -0.00728965 -0.01452276 -0.01630898 -0.01744615 -0.01519174 -0.01535908 -0.01734481 -0.01520233 -0.01536385 -0.01578893 -0.01639474 -0.01399417 -0.01728182 -0.01647959 -0.01392948 -0.01581335 -0.01643395 0.01303887 -0.01727963 -0.01736255 0.01229324 -0.01576835 -0.01554006 0.01398191 -0.01574402 -0.01486182 0.0148681 -0.01735098 -0.02828697 0.01727603 -0.01727484 -0.0283846 0.03314037 -0.01725986 -0.0282929 0.01732754 -0.01577973 -0.02836236 -0.03371509 -0.01738715 -0.02829998 -0.01829509 -0.01728884 -0.02828613 -0.01817619 -0.01577812 -0.02974109 0.03446379 -0.01730774 -0.03265352 0.03449617 -0.01727672 -0.03120554 0.03453917 -0.006813681 -0.03323007 0.03438406 -0.006813681 -0.03120559 -0.03546083 -0.006813681 -0.03283089 -0.03541688 -0.006813681 -0.0327062 -0.03542188 -0.01721047 -0.02990951 -0.03539762 -0.01736423 -0.01770603 -0.0130123 -0.01735548 -0.01828265 -0.01270155 -0.01584513 -0.01876277 -0.01246657 -0.01744621 -0.01985031 -0.01214895 -0.01749071 -0.0198451 -0.01216247 -0.01565623 -0.02098767 -0.01203175 -0.01568294 -0.02093797 -0.01203107 -0.0173548 -0.0220526 -0.0120449 -0.01742869 -0.02208793 -0.01200319 -0.01548749 -0.02323528 -0.01229465 -0.0156829 -0.02324518 -0.01226423 -0.01744632 -0.02474805 -0.01291337 -0.01727367 -0.02423467 -0.01263567 -0.01558782 -0.02575246 -0.01360611 -0.0157934 -0.02615342 -0.01396796 -0.01734521 -0.0269253 -0.01484338 -0.01575295 -0.02692689 -0.01481602 -0.01736915 -0.02757243 -0.01582668 -0.01743057 -0.02752566 -0.01578028 -0.01568311 -0.02795646 -0.01681929 -0.01727464 -0.02798247 -0.01679102 -0.01562784 -0.01825485 0.011798 -0.0172386 -0.01877535 0.01154675 -0.01561661 -0.02043353 0.01113922 -0.01576776 -0.01988351 0.0112579 -0.01728146 -0.02156371 0.01108974 -0.01729042 -0.02207588 0.01111239 -0.01555987 -0.02323349 0.01137291 -0.01570862 -0.02319083 0.01135633 -0.01735711 -0.02433429 0.01179618 -0.01576763 -0.02487203 0.01206447 -0.01726209 -0.02531524 0.01236541 -0.015718 -0.02622733 0.01307838 -0.01561688 -0.02616274 0.01303536 -0.01737028 -0.02700282 0.0139893 -0.01563238 -0.02692423 0.01389081 -0.01741807 -0.02758803 0.01492789 -0.01556441 -0.02777473 0.01537424 -0.01726222 -0.0280097 0.01599771 -0.01569252 -0.03120554 0.02798937 -0.00947034 -0.03120554 0.0290333 -0.00841785 -0.03120555 0.03037341 -0.008570971 -0.03120555 0.0310736 -0.00956105 -0.03120554 0.03095264 -0.01063396 -0.03120553 0.03004508 -0.01144488 -0.03120555 0.02883659 -0.01134485 -0.03120554 0.02816699 -0.01068378 -0.03120553 0.02645854 -0.007458789 -0.03120554 0.02638934 -0.01374191 -0.03120555 0.02704111 -0.006856071 -0.03120559 -0.02730609 -0.01378626 -0.03120559 -0.02741953 -0.00733274 -0.03120559 -0.03202937 -0.0097546 -0.03120559 -0.03135172 -0.008582031 -0.03120559 -0.02973768 -0.00848517 -0.03120559 -0.02892643 -0.009561009 -0.03120559 -0.02900241 -0.01049883 -0.0312056 -0.02969979 -0.01133405 -0.03120558 -0.03090734 -0.01144537 -0.03120559 -0.03177606 -0.01080413 -0.03120559 -0.02807049 -0.00683565 -0.0338035 -0.03479258 -0.006813681 -0.02846334 -0.0342304 -0.01719798 -0.02900525 -0.03499605 -0.01723576 -0.03373041 -0.03487589 -0.01724617 -0.02883509 0.03381768 -0.01745407 -0.03388319 0.033719 -0.01732222 -0.03331688 0.03424007 -0.01727818 -0.0250174 0.01170086 -0.01520799 -0.02038869 0.01083991 -0.0152768 -0.01715951 0.0120558 -0.0152486 -0.0152874 0.01376831 -0.01525769 -0.01809339 -0.01249229 -0.01531334 -0.01632015 -0.01377944 -0.01537184 -0.02588621 -0.01336856 -0.01532143 -0.01488626 -0.01523133 -0.01525406 -0.005394433 0.01064056 -0.01781331 -0.005748069 0.01156268 -0.01767952 -0.006727058 0.01742836 -0.01765753 -0.008221886 0.0179734 -0.01771511 -0.01209029 0.01781208 -0.01778792 -0.013549 0.01695286 -0.01762071 -0.01577669 0.01339259 -0.0176816 -0.01717782 0.01208232 -0.0177144 -0.01866817 0.01137522 -0.01768004 -0.02401772 0.01138115 -0.01768241 -0.02856836 0.01725528 -0.01773224 -0.02037649 0.01079311 -0.01778131 -0.02212621 0.01080193 -0.01778295 -0.02544899 0.01202959 -0.01778353 -0.02810914 0.01522902 -0.01778142 -0.0285292 0.03280148 -0.01764509 -0.02971961 0.03417568 -0.01771681 -0.0325861 0.03430136 -0.01763548 -0.03356784 0.03365016 -0.01773436 -0.03411357 0.03299026 -0.01753124 -0.03403436 -0.03381117 -0.01766127 -0.03368631 -0.03460954 -0.01762959 -0.03282655 -0.03515189 -0.01768492 -0.0295722 -0.03501188 -0.01774733 -0.02871328 -0.03442359 -0.01756331 -0.02853958 -0.01828854 -0.01767445 -0.02847442 -0.0171755 -0.01778862 -0.01628212 -0.01379146 -0.01766893 -0.02491445 -0.01267741 -0.01771462 -0.0134011 -0.01804571 -0.01766002 -0.01216234 -0.01892007 -0.01760842 -0.0080934 -0.01894012 -0.01769498 -0.006316192 -0.01776702 -0.01771675 -0.00570689 -0.01245224 -0.0176346 -0.005334696 -0.01154929 -0.01778565</float_array> + <technique_common> + <accessor count="1614" source="#cubeverts-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <vertices id="cubeverts-array0-vertices"> + <input source="#cubeverts-array0" semantic="POSITION"/> + </vertices> + <triangles count="3308" material="ref_Mesh"> + <input source="#cubenormals-array0" semantic="NORMAL" offset="1"/> + <input source="#cubeverts-array0-vertices" semantic="VERTEX" offset="0"/> + <p>0 0 1 0 2 0 3 1 4 1 5 1 2 2 6 2 7 2 4 3 8 3 5 3 5 4 8 4 9 4 4 5 10 5 8 5 11 6 12 6 5 6 11 7 5 7 9 7 13 8 14 8 15 8 10 9 16 9 8 9 8 10 16 10 17 10 5 11 0 11 3 11 3 12 0 12 2 12 3 13 2 13 14 13 2 14 7 14 18 14 2 15 18 15 14 15 14 16 18 16 15 16 13 17 15 17 19 17 20 18 21 18 22 18 22 19 21 19 23 19 25 20 26 20 27 20 29 21 30 21 31 21 31 22 30 22 32 22 33 23 34 23 35 23 35 24 34 24 36 24 37 25 38 25 39 25 39 26 40 26 37 26 37 27 40 27 36 27 37 28 36 28 41 28 41 29 36 29 34 29 41 30 34 30 42 30 42 31 34 31 43 31 44 32 45 32 46 32 46 33 45 33 29 33 46 34 29 34 47 34 47 35 29 35 31 35 31 36 48 36 47 36 47 37 48 37 49 37 47 38 49 38 50 38 51 39 33 39 52 39 52 40 33 40 35 40 52 41 35 41 53 41 53 42 35 42 32 42 53 43 32 43 54 43 54 44 32 44 30 44 55 45 56 45 57 45 57 46 56 46 58 46 55 47 59 47 60 47 55 48 60 48 61 48 55 49 61 49 62 49 55 50 62 50 63 50 55 51 63 51 64 51 65 52 66 52 67 52 65 53 67 53 68 53 65 54 69 54 70 54 71 55 66 55 70 55 70 56 66 56 65 56 72 57 73 57 74 57 74 58 73 58 75 58 76 59 72 59 77 59 77 60 72 60 74 60 77 61 74 61 78 61 79 62 80 62 81 62 79 63 81 63 82 63 79 64 82 64 83 64 79 65 83 65 84 65 79 66 84 66 85 66 86 67 87 67 88 67 88 68 87 68 89 68 90 69 91 69 80 69 87 70 65 70 89 70 89 71 65 71 68 71 89 72 68 72 92 72 68 73 90 73 80 73 68 74 80 74 92 74 92 75 80 75 79 75 92 76 79 76 93 76 93 77 79 77 94 77 95 78 96 78 74 78 75 79 97 79 98 79 99 80 59 80 100 80 100 81 59 81 55 81 100 82 55 82 57 82 95 83 74 83 99 83 99 84 74 84 75 84 99 85 75 85 59 85 59 86 75 86 98 86 59 87 98 87 101 87 57 88 58 88 100 88 100 89 58 89 102 89 105 90 103 90 106 90 99 91 107 91 95 91 110 92 111 92 112 92 90 93 113 93 114 93 115 94 116 94 117 94 112 95 118 95 110 95 110 96 118 96 98 96 98 97 118 97 119 97 119 98 120 98 98 98 90 99 121 99 113 99 113 100 121 100 122 100 116 101 101 101 117 101 98 102 120 102 123 102 98 103 123 103 101 103 124 104 101 104 123 104 117 105 125 105 126 105 127 106 128 106 117 106 117 107 128 107 110 107 110 108 128 108 111 108 113 109 122 109 117 109 117 110 122 110 115 110 124 111 129 111 101 111 101 112 129 112 117 112 117 113 129 113 125 113 117 114 126 114 127 114 130 115 131 115 132 115 132 116 131 116 133 116 134 117 91 117 114 117 114 118 91 118 90 118 97 119 135 119 136 119 110 120 137 120 138 120 110 121 138 121 132 121 132 122 138 122 130 122 135 123 97 123 139 123 134 124 140 124 91 124 97 125 136 125 141 125 97 126 141 126 98 126 142 127 110 127 98 127 142 128 98 128 143 128 144 129 140 129 134 129 141 130 145 130 98 130 98 131 145 131 143 131 110 132 142 132 146 132 110 133 146 133 137 133 135 134 139 134 147 134 147 135 139 135 132 135 147 136 132 136 133 136 132 137 139 137 134 137 134 138 139 138 144 138 148 139 149 139 114 139 114 140 149 140 150 140 151 141 152 141 153 141 114 142 150 142 153 142 153 143 150 143 151 143 113 144 154 144 148 144 113 145 148 145 114 145 153 146 152 146 155 146 153 147 155 147 156 147 156 148 155 148 157 148 158 149 159 149 156 149 156 150 159 150 113 150 156 151 157 151 158 151 159 152 160 152 113 152 113 153 160 153 154 153 161 154 162 154 134 154 134 155 162 155 163 155 164 156 161 156 114 156 114 157 161 157 134 157 134 158 163 158 165 158 165 159 163 159 166 159 165 160 166 160 167 160 167 161 168 161 165 161 165 162 168 162 153 162 153 163 168 163 169 163 153 164 170 164 114 164 114 165 170 165 171 165 153 166 169 166 170 166 171 167 164 167 114 167 72 168 76 168 139 168 139 169 76 169 172 169 139 170 172 170 144 170 144 171 172 171 83 171 144 172 83 172 82 172 66 173 71 173 122 173 122 174 71 174 115 174 115 175 71 175 62 175 115 176 62 176 61 176 64 177 173 177 174 177 175 178 176 178 174 178 174 179 176 179 177 179 178 180 69 180 179 180 179 181 69 181 180 181 179 182 180 182 181 182 181 183 180 183 182 183 183 184 156 184 65 184 65 185 156 185 113 185 65 186 113 186 69 186 56 187 55 187 117 187 117 188 55 188 64 188 117 189 64 189 113 189 113 190 64 190 174 190 113 191 174 191 69 191 69 192 174 192 177 192 69 193 177 193 180 193 86 194 88 194 183 194 183 195 88 195 184 195 184 196 185 196 186 196 186 197 165 197 153 197 184 198 186 198 183 198 183 199 186 199 153 199 183 200 153 200 156 200 186 201 79 201 165 201 165 202 79 202 134 202 79 203 85 203 134 203 134 204 85 204 78 204 134 205 78 205 132 205 132 206 78 206 74 206 132 207 74 207 187 207 188 208 189 208 187 208 187 209 189 209 102 209 102 210 58 210 56 210 56 211 117 211 110 211 102 212 56 212 187 212 187 213 56 213 110 213 187 214 110 214 132 214 188 215 187 215 190 215 190 216 187 216 74 216 190 217 74 217 96 217 185 218 191 218 186 218 186 219 191 219 94 219 186 220 94 220 79 220 192 221 193 221 194 221 195 222 196 222 85 222 196 223 78 223 85 223 197 224 198 224 78 224 96 225 199 225 190 225 190 226 199 226 192 226 192 227 199 227 193 227 192 228 200 228 201 228 192 229 201 229 202 229 202 230 201 230 203 230 204 231 196 231 194 231 194 232 196 232 205 232 206 233 207 233 198 233 198 234 207 234 78 234 194 235 205 235 200 235 194 236 200 236 192 236 202 237 203 237 208 237 209 238 199 238 96 238 206 239 210 239 207 239 199 240 209 240 211 240 199 241 211 241 206 241 206 242 211 242 210 242 94 243 208 243 212 243 196 244 204 244 213 244 202 245 208 245 191 245 191 246 208 246 94 246 195 247 212 247 208 247 85 248 214 248 195 248 195 249 214 249 215 249 195 250 215 250 212 250 213 251 216 251 196 251 216 252 197 252 196 252 196 253 197 253 78 253 217 254 218 254 219 254 217 255 219 255 220 255 220 256 219 256 221 256 220 257 221 257 222 257 222 258 221 258 223 258 222 259 223 259 224 259 222 260 224 260 225 260 225 261 224 261 226 261 225 262 226 262 227 262 227 263 226 263 228 263 228 264 226 264 229 264 228 265 229 265 230 265 228 266 230 266 231 266 231 267 230 267 232 267 231 268 232 268 233 268 231 269 233 269 234 269 234 270 233 270 235 270 234 271 235 271 218 271 234 272 218 272 217 272 236 273 237 273 238 273 236 274 238 274 239 274 236 275 239 275 240 275 240 276 239 276 241 276 240 277 241 277 242 277 242 278 241 278 243 278 242 279 243 279 244 279 244 280 243 280 245 280 244 281 245 281 246 281 244 282 246 282 247 282 247 283 246 283 248 283 247 284 248 284 249 284 249 285 248 285 250 285 249 286 250 286 251 286 249 287 251 287 252 287 252 288 251 288 253 288 252 289 253 289 237 289 252 290 237 290 236 290 254 291 249 291 255 291 255 292 249 292 252 292 255 293 252 293 256 293 256 294 252 294 236 294 256 295 236 295 240 295 256 296 240 296 257 296 257 297 240 297 258 297 258 298 240 298 242 298 258 299 242 299 259 299 259 300 242 300 244 300 259 301 244 301 260 301 260 302 244 302 261 302 261 303 244 303 247 303 261 304 247 304 262 304 262 305 247 305 249 305 262 306 249 306 254 306 263 307 231 307 264 307 264 308 231 308 234 308 264 309 234 309 265 309 265 310 234 310 217 310 265 311 217 311 266 311 266 312 217 312 220 312 266 313 220 313 267 313 267 314 220 314 222 314 267 315 222 315 268 315 268 316 222 316 225 316 268 317 225 317 269 317 269 318 225 318 227 318 269 319 227 319 270 319 270 320 227 320 228 320 270 321 228 321 263 321 263 322 228 322 231 322 191 323 185 323 106 323 106 324 185 324 184 324 106 325 184 325 105 325 105 326 184 326 268 326 105 327 268 327 103 327 103 328 268 328 92 328 92 329 268 329 269 329 184 330 259 330 260 330 184 331 260 331 268 331 88 332 258 332 184 332 184 333 258 333 259 333 92 334 263 334 264 334 92 335 269 335 270 335 264 336 254 336 92 336 92 337 254 337 89 337 89 338 254 338 255 338 264 339 265 339 262 339 254 340 264 340 262 340 260 341 267 341 268 341 89 342 255 342 256 342 88 343 256 343 257 343 92 344 270 344 263 344 88 345 257 345 258 345 260 346 266 346 267 346 89 347 256 347 88 347 266 348 260 348 261 348 266 349 261 349 265 349 265 350 261 350 262 350 86 351 183 351 87 351 87 352 183 352 65 352 271 353 272 353 273 353 273 354 272 354 274 354 273 355 274 355 275 355 275 356 274 356 276 356 275 357 276 357 277 357 277 358 276 358 278 358 277 359 278 359 279 359 279 360 278 360 280 360 279 361 280 361 281 361 281 362 280 362 282 362 281 363 282 363 283 363 281 364 283 364 284 364 284 365 283 365 285 365 285 366 283 366 286 366 285 367 286 367 287 367 287 368 286 368 288 368 287 369 288 369 289 369 287 370 289 370 271 370 271 371 289 371 290 371 271 372 290 372 272 372 291 373 292 373 293 373 291 374 293 374 294 374 294 375 293 375 295 375 294 376 295 376 296 376 296 377 295 377 297 377 296 378 297 378 298 378 296 379 298 379 299 379 299 380 298 380 300 380 299 381 300 381 301 381 299 382 301 382 302 382 302 383 301 383 303 383 302 384 303 384 304 384 302 385 304 385 305 385 305 386 304 386 306 386 305 387 306 387 307 387 305 388 307 388 308 388 308 389 307 389 309 389 308 390 309 390 310 390 310 391 309 391 292 391 310 392 292 392 291 392 311 393 308 393 312 393 312 394 308 394 310 394 312 395 310 395 313 395 313 396 310 396 291 396 313 397 291 397 314 397 314 398 291 398 294 398 314 399 294 399 315 399 315 400 294 400 296 400 315 401 296 401 316 401 316 402 296 402 299 402 316 403 299 403 317 403 317 404 299 404 302 404 317 405 302 405 318 405 318 406 302 406 305 406 318 407 305 407 311 407 311 408 305 408 308 408 319 409 287 409 320 409 320 410 287 410 321 410 321 411 287 411 271 411 321 412 271 412 322 412 322 413 271 413 273 413 322 414 273 414 323 414 323 415 273 415 275 415 323 416 275 416 324 416 324 417 275 417 277 417 324 418 277 418 325 418 325 419 277 419 279 419 325 420 279 420 281 420 325 421 281 421 326 421 326 422 281 422 284 422 326 423 284 423 327 423 327 424 284 424 285 424 327 425 285 425 319 425 319 426 285 426 287 426 108 427 189 427 109 427 109 428 189 428 188 428 109 429 188 429 190 429 324 430 325 430 99 430 100 431 315 431 99 431 99 432 315 432 316 432 327 433 319 433 107 433 108 434 107 434 189 434 189 435 107 435 319 435 189 436 319 436 320 436 320 437 321 437 318 437 320 438 311 438 189 438 189 439 311 439 102 439 102 440 311 440 312 440 102 441 312 441 313 441 320 442 318 442 311 442 316 443 324 443 99 443 325 444 326 444 99 444 99 445 326 445 107 445 102 446 313 446 314 446 326 447 327 447 107 447 318 448 321 448 322 448 314 449 315 449 100 449 316 450 323 450 324 450 323 451 316 451 317 451 323 452 317 452 322 452 102 453 314 453 100 453 322 454 317 454 318 454 152 455 241 455 155 455 155 456 241 456 157 456 157 457 241 457 239 457 157 458 239 458 158 458 158 459 239 459 159 459 159 460 239 460 238 460 159 461 238 461 237 461 159 462 237 462 160 462 160 463 237 463 253 463 160 464 253 464 154 464 154 465 253 465 251 465 154 466 251 466 148 466 148 467 251 467 250 467 148 468 250 468 149 468 149 469 250 469 248 469 149 470 248 470 246 470 149 471 246 471 150 471 150 472 246 472 245 472 150 473 245 473 151 473 151 474 245 474 243 474 151 475 243 475 152 475 152 476 243 476 241 476 168 477 223 477 221 477 168 478 221 478 169 478 169 479 221 479 219 479 169 480 219 480 170 480 170 481 219 481 218 481 170 482 218 482 171 482 171 483 218 483 235 483 171 484 235 484 164 484 164 485 235 485 233 485 164 486 233 486 161 486 161 487 233 487 232 487 161 488 232 488 162 488 162 489 232 489 230 489 162 490 230 490 163 490 163 491 230 491 229 491 163 492 229 492 226 492 163 493 226 493 166 493 166 494 226 494 224 494 166 495 224 495 167 495 167 496 224 496 168 496 168 497 224 497 223 497 123 498 298 498 297 498 123 499 297 499 124 499 124 500 297 500 295 500 124 501 295 501 129 501 129 502 295 502 293 502 129 503 293 503 125 503 125 504 293 504 126 504 126 505 293 505 292 505 126 506 292 506 309 506 126 507 309 507 127 507 127 508 309 508 307 508 127 509 307 509 128 509 128 510 307 510 111 510 111 511 307 511 306 511 111 512 306 512 112 512 112 513 306 513 304 513 112 514 304 514 303 514 112 515 303 515 118 515 118 516 303 516 301 516 118 517 301 517 119 517 119 518 301 518 300 518 119 519 300 519 120 519 120 520 300 520 298 520 120 521 298 521 123 521 136 522 276 522 141 522 141 523 276 523 274 523 141 524 274 524 145 524 145 525 274 525 143 525 143 526 274 526 272 526 143 527 272 527 142 527 142 528 272 528 290 528 142 529 290 529 146 529 146 530 290 530 289 530 146 531 289 531 137 531 137 532 289 532 288 532 137 533 288 533 138 533 138 534 288 534 286 534 138 535 286 535 130 535 130 536 286 536 283 536 130 537 283 537 131 537 131 538 283 538 133 538 133 539 283 539 282 539 133 540 282 540 147 540 147 541 282 541 280 541 147 542 280 542 135 542 135 543 280 543 278 543 135 544 278 544 136 544 136 545 278 545 276 545 59 546 101 546 60 546 60 547 101 547 116 547 60 548 116 548 61 548 61 549 116 549 115 549 97 550 75 550 73 550 97 551 73 551 139 551 139 552 73 552 72 552 80 553 91 553 140 553 80 554 140 554 81 554 81 555 140 555 82 555 82 556 140 556 144 556 90 557 68 557 67 557 90 558 67 558 121 558 121 559 67 559 122 559 122 560 67 560 66 560 174 561 173 561 328 561 191 562 106 562 202 562 202 563 106 563 42 563 202 564 42 564 43 564 95 565 50 565 96 565 96 566 50 566 209 566 62 567 329 567 330 567 331 568 332 568 62 568 332 569 329 569 62 569 333 570 334 570 335 570 335 571 334 571 336 571 337 572 338 572 76 572 76 573 338 573 172 573 172 574 338 574 339 574 172 575 339 575 333 575 62 576 330 576 76 576 76 577 330 577 337 577 83 578 340 578 341 578 341 579 71 579 83 579 71 580 341 580 342 580 172 581 343 581 344 581 172 582 344 582 83 582 83 583 344 583 345 583 345 584 340 584 83 584 346 585 347 585 71 585 346 586 71 586 348 586 71 587 349 587 348 587 350 588 351 588 352 588 353 589 71 589 351 589 351 590 71 590 352 590 353 591 349 591 71 591 354 592 355 592 356 592 354 593 350 593 352 593 347 594 346 594 357 594 347 595 357 595 358 595 359 596 360 596 361 596 358 597 355 597 362 597 358 598 362 598 360 598 360 599 362 599 361 599 363 600 355 600 352 600 363 601 352 601 364 601 365 602 366 602 367 602 366 603 365 603 364 603 366 604 364 604 352 604 368 605 367 605 366 605 359 606 369 606 333 606 333 607 369 607 368 607 333 608 368 608 366 608 360 609 359 609 333 609 370 610 371 610 372 610 360 611 373 611 371 611 370 612 372 612 62 612 62 613 372 613 374 613 360 614 375 614 373 614 360 615 376 615 375 615 335 616 377 616 376 616 374 617 378 617 62 617 62 618 378 618 379 618 62 619 379 619 380 619 62 620 380 620 335 620 335 621 380 621 377 621 381 622 382 622 62 622 383 623 381 623 71 623 71 624 381 624 62 624 347 625 384 625 71 625 71 626 384 626 383 626 385 627 386 627 370 627 370 628 386 628 347 628 382 629 387 629 62 629 387 630 388 630 62 630 62 631 388 631 370 631 370 632 388 632 385 632 342 633 389 633 71 633 71 634 389 634 352 634 352 635 355 635 354 635 390 636 391 636 360 636 347 637 392 637 393 637 391 638 394 638 360 638 360 639 394 639 358 639 358 640 394 640 395 640 358 641 395 641 392 641 347 642 358 642 392 642 347 643 393 643 396 643 370 644 397 644 390 644 347 645 396 645 370 645 370 646 396 646 397 646 371 647 370 647 360 647 360 648 370 648 390 648 355 649 358 649 356 649 333 650 335 650 360 650 360 651 335 651 376 651 172 652 333 652 366 652 172 653 366 653 352 653 172 654 352 654 398 654 172 655 398 655 343 655 336 656 331 656 335 656 335 657 331 657 62 657 109 658 190 658 44 658 44 659 190 659 192 659 44 660 192 660 45 660 399 661 10 661 400 661 400 662 10 662 4 662 14 663 401 663 3 663 3 664 401 664 402 664 400 665 402 665 401 665 403 666 401 666 404 666 401 667 403 667 400 667 400 668 403 668 405 668 400 669 405 669 399 669 399 670 405 670 406 670 407 671 406 671 408 671 406 672 407 672 399 672 401 673 409 673 410 673 401 674 410 674 404 674 54 675 411 675 53 675 53 676 411 676 412 676 413 677 51 677 414 677 414 678 51 678 52 678 414 679 415 679 416 679 417 680 418 680 413 680 418 681 419 681 413 681 413 682 419 682 411 682 412 683 420 683 421 683 422 684 423 684 424 684 419 685 425 685 411 685 412 686 421 686 415 686 412 687 415 687 414 687 421 688 426 688 415 688 422 689 424 689 427 689 414 690 416 690 417 690 414 691 417 691 413 691 422 692 419 692 423 692 419 693 422 693 425 693 425 694 428 694 411 694 412 695 429 695 420 695 426 696 421 696 427 696 411 697 428 697 430 697 427 698 424 698 426 698 411 699 430 699 412 699 412 700 430 700 429 700 411 701 54 701 30 701 45 702 192 702 29 702 29 703 192 703 202 703 202 704 43 704 34 704 33 705 51 705 34 705 34 706 51 706 413 706 34 707 413 707 202 707 202 708 413 708 411 708 202 709 411 709 29 709 29 710 411 710 30 710 176 711 431 711 177 711 177 712 431 712 432 712 433 713 12 713 434 713 434 714 12 714 11 714 435 715 175 715 328 715 328 716 175 716 174 716 328 717 63 717 62 717 436 718 437 718 11 718 11 719 437 719 438 719 328 720 62 720 435 720 77 721 434 721 76 721 76 722 434 722 11 722 76 723 11 723 62 723 62 724 11 724 438 724 62 725 438 725 435 725 180 726 439 726 182 726 182 727 439 727 440 727 2 728 441 728 442 728 71 729 70 729 443 729 71 730 444 730 83 730 83 731 444 731 445 731 83 732 445 732 6 732 6 733 445 733 446 733 6 734 446 734 447 734 2 735 442 735 6 735 6 736 442 736 84 736 6 737 84 737 83 737 179 738 181 738 443 738 443 739 181 739 444 739 443 740 444 740 71 740 180 741 177 741 439 741 439 742 177 742 432 742 439 743 432 743 448 743 448 744 449 744 439 744 439 745 449 745 450 745 439 746 450 746 451 746 451 747 452 747 439 747 453 748 454 748 432 748 432 749 454 749 448 749 455 750 456 750 441 750 441 751 456 751 442 751 179 752 443 752 178 752 457 753 458 753 433 753 433 754 434 754 457 754 173 755 64 755 63 755 173 756 63 756 328 756 434 757 77 757 78 757 434 758 78 758 457 758 457 759 78 759 207 759 457 760 207 760 458 760 458 761 207 761 210 761 458 762 210 762 48 762 48 763 210 763 211 763 48 764 211 764 49 764 49 765 211 765 209 765 49 766 209 766 50 766 212 767 38 767 94 767 94 768 38 768 93 768 38 769 212 769 39 769 39 770 212 770 215 770 39 771 215 771 40 771 40 772 215 772 455 772 455 773 215 773 214 773 455 774 214 774 456 774 456 775 214 775 85 775 456 776 85 776 442 776 442 777 85 777 84 777 443 778 70 778 178 778 178 779 70 779 69 779 420 780 198 780 421 780 421 781 198 781 197 781 421 782 197 782 216 782 421 783 216 783 427 783 427 784 216 784 213 784 427 785 213 785 422 785 422 786 213 786 204 786 422 787 204 787 194 787 422 788 194 788 425 788 425 789 194 789 428 789 428 790 194 790 193 790 428 791 193 791 199 791 428 792 199 792 430 792 430 793 199 793 429 793 429 794 199 794 206 794 429 795 206 795 420 795 420 796 206 796 198 796 415 797 196 797 195 797 415 798 195 798 416 798 416 799 195 799 208 799 416 800 208 800 417 800 417 801 208 801 418 801 418 802 208 802 203 802 418 803 203 803 419 803 419 804 203 804 201 804 419 805 201 805 423 805 423 806 201 806 200 806 423 807 200 807 424 807 424 808 200 808 205 808 424 809 205 809 426 809 426 810 205 810 196 810 426 811 196 811 415 811 459 812 449 812 460 812 460 813 449 813 448 813 461 814 462 814 463 814 461 815 463 815 464 815 464 816 463 816 465 816 464 817 465 817 466 817 466 818 465 818 467 818 466 819 467 819 468 819 468 820 467 820 469 820 468 821 469 821 470 821 470 822 469 822 471 822 470 823 471 823 472 823 472 824 471 824 473 824 472 825 473 825 474 825 474 826 473 826 475 826 474 827 475 827 476 827 476 828 475 828 477 828 476 829 477 829 478 829 478 830 477 830 462 830 478 831 462 831 479 831 479 832 462 832 461 832 480 833 481 833 482 833 482 834 481 834 483 834 482 835 483 835 484 835 484 836 483 836 485 836 484 837 485 837 486 837 486 838 485 838 487 838 486 839 487 839 488 839 488 840 487 840 489 840 488 841 489 841 490 841 490 842 489 842 491 842 490 843 491 843 492 843 490 844 492 844 493 844 493 845 492 845 494 845 493 846 494 846 495 846 495 847 494 847 496 847 496 848 494 848 497 848 496 849 497 849 498 849 496 850 498 850 499 850 499 851 498 851 481 851 499 852 481 852 480 852 500 853 501 853 502 853 500 854 502 854 503 854 503 855 502 855 504 855 503 856 504 856 505 856 505 857 504 857 506 857 505 858 506 858 507 858 507 859 506 859 508 859 507 860 508 860 509 860 509 861 508 861 510 861 509 862 510 862 511 862 511 863 510 863 512 863 511 864 512 864 513 864 513 865 512 865 514 865 513 866 514 866 515 866 515 867 514 867 516 867 515 868 516 868 517 868 517 869 516 869 518 869 517 870 518 870 500 870 500 871 518 871 501 871 519 872 520 872 521 872 521 873 520 873 522 873 521 874 522 874 523 874 523 875 522 875 524 875 523 876 524 876 525 876 525 877 524 877 526 877 525 878 526 878 527 878 527 879 526 879 528 879 527 880 528 880 529 880 529 881 528 881 530 881 529 882 530 882 531 882 531 883 530 883 532 883 531 884 532 884 533 884 531 885 533 885 534 885 534 886 533 886 535 886 534 887 535 887 536 887 536 888 535 888 537 888 536 889 537 889 519 889 519 890 537 890 520 890 462 891 383 891 384 891 462 892 384 892 463 892 463 893 384 893 347 893 463 894 347 894 465 894 465 895 347 895 386 895 465 896 386 896 467 896 467 897 386 897 385 897 467 898 385 898 469 898 469 899 385 899 388 899 469 900 388 900 471 900 471 901 388 901 387 901 471 902 387 902 473 902 473 903 387 903 382 903 473 904 382 904 475 904 475 905 382 905 381 905 475 906 381 906 477 906 477 907 381 907 383 907 477 908 383 908 462 908 532 909 372 909 533 909 533 910 372 910 371 910 533 911 371 911 535 911 535 912 371 912 373 912 535 913 373 913 537 913 537 914 373 914 375 914 537 915 375 915 520 915 520 916 375 916 376 916 520 917 376 917 522 917 522 918 376 918 377 918 522 919 377 919 524 919 524 920 377 920 380 920 524 921 380 921 526 921 526 922 380 922 379 922 526 923 379 923 528 923 528 924 379 924 378 924 528 925 378 925 530 925 530 926 378 926 374 926 530 927 374 927 532 927 532 928 374 928 372 928 518 929 355 929 363 929 518 930 363 930 501 930 501 931 363 931 364 931 501 932 364 932 502 932 502 933 364 933 504 933 504 934 364 934 365 934 504 935 365 935 506 935 506 936 365 936 367 936 506 937 367 937 508 937 508 938 367 938 368 938 508 939 368 939 369 939 508 940 369 940 510 940 510 941 369 941 359 941 510 942 359 942 512 942 512 943 359 943 514 943 514 944 359 944 361 944 514 945 361 945 362 945 514 946 362 946 516 946 516 947 362 947 355 947 516 948 355 948 518 948 494 949 349 949 353 949 494 950 353 950 497 950 497 951 353 951 498 951 498 952 353 952 351 952 498 953 351 953 481 953 481 954 351 954 350 954 481 955 350 955 483 955 483 956 350 956 354 956 483 957 354 957 485 957 485 958 354 958 356 958 485 959 356 959 487 959 487 960 356 960 358 960 487 961 358 961 489 961 489 962 358 962 357 962 489 963 357 963 491 963 491 964 357 964 346 964 491 965 346 965 348 965 491 966 348 966 492 966 492 967 348 967 494 967 494 968 348 968 349 968 472 969 538 969 539 969 472 970 539 970 470 970 470 971 539 971 468 971 468 972 539 972 540 972 468 973 540 973 541 973 468 974 541 974 466 974 466 975 541 975 464 975 464 976 541 976 542 976 464 977 542 977 461 977 461 978 542 978 543 978 461 979 543 979 544 979 461 980 544 980 479 980 479 981 544 981 478 981 478 982 544 982 545 982 478 983 545 983 476 983 476 984 545 984 474 984 474 985 545 985 546 985 474 986 546 986 538 986 474 987 538 987 472 987 480 988 547 988 499 988 499 989 547 989 548 989 499 990 548 990 496 990 496 991 548 991 549 991 496 992 549 992 495 992 495 993 549 993 493 993 493 994 549 994 550 994 493 995 550 995 490 995 490 996 550 996 551 996 490 997 551 997 488 997 488 998 551 998 552 998 488 999 552 999 486 999 486 1000 552 1000 553 1000 486 1001 553 1001 484 1001 484 1002 553 1002 554 1002 484 1003 554 1003 482 1003 482 1004 554 1004 555 1004 482 1005 555 1005 480 1005 480 1006 555 1006 547 1006 511 1007 556 1007 509 1007 509 1008 556 1008 557 1008 509 1009 557 1009 507 1009 507 1010 557 1010 558 1010 507 1011 558 1011 505 1011 505 1012 558 1012 559 1012 505 1013 559 1013 503 1013 503 1014 559 1014 560 1014 503 1015 560 1015 500 1015 500 1016 560 1016 561 1016 500 1017 561 1017 562 1017 500 1018 562 1018 517 1018 517 1019 562 1019 563 1019 517 1020 563 1020 515 1020 515 1021 563 1021 564 1021 515 1022 564 1022 513 1022 513 1023 564 1023 565 1023 513 1024 565 1024 511 1024 511 1025 565 1025 556 1025 519 1026 566 1026 536 1026 536 1027 566 1027 567 1027 536 1028 567 1028 534 1028 534 1029 567 1029 568 1029 534 1030 568 1030 531 1030 531 1031 568 1031 569 1031 531 1032 569 1032 570 1032 531 1033 570 1033 529 1033 529 1034 570 1034 571 1034 529 1035 571 1035 527 1035 527 1036 571 1036 572 1036 527 1037 572 1037 525 1037 525 1038 572 1038 573 1038 525 1039 573 1039 523 1039 523 1040 573 1040 574 1040 523 1041 574 1041 521 1041 521 1042 574 1042 575 1042 521 1043 575 1043 519 1043 519 1044 575 1044 566 1044 460 1045 546 1045 545 1045 576 1046 577 1046 554 1046 576 1047 554 1047 553 1047 576 1048 553 1048 552 1048 540 1049 539 1049 578 1049 538 1050 546 1050 460 1050 460 1051 545 1051 459 1051 459 1052 545 1052 579 1052 541 1053 580 1053 581 1053 543 1054 542 1054 550 1054 579 1055 545 1055 544 1055 582 1056 583 1056 540 1056 554 1057 577 1057 578 1057 578 1058 577 1058 584 1058 544 1059 543 1059 550 1059 542 1060 541 1060 551 1060 551 1061 541 1061 552 1061 552 1062 541 1062 581 1062 552 1063 581 1063 576 1063 549 1064 585 1064 586 1064 549 1065 586 1065 579 1065 580 1066 541 1066 583 1066 583 1067 541 1067 540 1067 578 1068 584 1068 587 1068 587 1069 582 1069 578 1069 578 1070 582 1070 540 1070 542 1071 551 1071 550 1071 444 1072 548 1072 547 1072 544 1073 550 1073 579 1073 579 1074 550 1074 549 1074 444 1075 547 1075 555 1075 182 1076 440 1076 181 1076 181 1077 440 1077 444 1077 444 1078 440 1078 548 1078 548 1079 440 1079 585 1079 548 1080 585 1080 549 1080 571 1081 588 1081 589 1081 569 1082 539 1082 538 1082 589 1083 431 1083 175 1083 175 1084 431 1084 176 1084 539 1085 569 1085 568 1085 578 1086 567 1086 566 1086 435 1087 574 1087 573 1087 589 1088 175 1088 572 1088 589 1089 572 1089 571 1089 570 1090 460 1090 571 1090 571 1091 460 1091 590 1091 571 1092 590 1092 588 1092 569 1093 538 1093 460 1093 569 1094 460 1094 570 1094 539 1095 568 1095 578 1095 578 1096 568 1096 567 1096 573 1097 572 1097 435 1097 435 1098 572 1098 175 1098 591 1099 592 1099 444 1099 444 1100 592 1100 445 1100 565 1101 564 1101 578 1101 593 1102 594 1102 555 1102 555 1103 594 1103 595 1103 560 1104 559 1104 593 1104 593 1105 559 1105 596 1105 596 1106 559 1106 558 1106 596 1107 558 1107 557 1107 578 1108 564 1108 563 1108 578 1109 563 1109 554 1109 555 1110 595 1110 597 1110 562 1111 561 1111 554 1111 593 1112 555 1112 554 1112 563 1113 562 1113 554 1113 561 1114 560 1114 554 1114 554 1115 560 1115 593 1115 591 1116 444 1116 598 1116 598 1117 444 1117 555 1117 555 1118 597 1118 598 1118 593 1119 599 1119 594 1119 438 1120 600 1120 435 1120 435 1121 600 1121 601 1121 574 1122 596 1122 575 1122 575 1123 596 1123 557 1123 575 1124 557 1124 556 1124 435 1125 601 1125 574 1125 574 1126 601 1126 602 1126 578 1127 556 1127 565 1127 596 1128 603 1128 604 1128 566 1129 575 1129 578 1129 578 1130 575 1130 556 1130 574 1131 605 1131 596 1131 605 1132 603 1132 596 1132 574 1133 602 1133 605 1133 403 1134 593 1134 405 1134 405 1135 593 1135 596 1135 13 1136 19 1136 410 1136 410 1137 409 1137 13 1137 13 1138 409 1138 401 1138 13 1139 401 1139 14 1139 404 1140 599 1140 593 1140 404 1141 593 1141 403 1141 19 1142 606 1142 410 1142 410 1143 606 1143 404 1143 404 1144 606 1144 607 1144 404 1145 607 1145 599 1145 408 1146 406 1146 604 1146 604 1147 406 1147 596 1147 596 1148 406 1148 405 1148 407 1149 16 1149 10 1149 407 1150 10 1150 399 1150 604 1151 608 1151 408 1151 408 1152 608 1152 609 1152 408 1153 609 1153 17 1153 408 1154 17 1154 407 1154 407 1155 17 1155 16 1155 432 1156 431 1156 589 1156 432 1157 589 1157 453 1157 453 1158 589 1158 588 1158 453 1159 588 1159 454 1159 454 1160 588 1160 590 1160 454 1161 590 1161 448 1161 448 1162 590 1162 460 1162 449 1163 459 1163 579 1163 449 1164 579 1164 450 1164 450 1165 579 1165 586 1165 450 1166 586 1166 451 1166 451 1167 586 1167 585 1167 451 1168 585 1168 452 1168 452 1169 585 1169 440 1169 452 1170 440 1170 439 1170 394 1171 577 1171 395 1171 395 1172 577 1172 576 1172 395 1173 576 1173 581 1173 395 1174 581 1174 392 1174 392 1175 581 1175 580 1175 392 1176 580 1176 393 1176 393 1177 580 1177 396 1177 396 1178 580 1178 583 1178 396 1179 583 1179 397 1179 397 1180 583 1180 582 1180 397 1181 582 1181 390 1181 390 1182 582 1182 587 1182 390 1183 587 1183 391 1183 391 1184 587 1184 584 1184 391 1185 584 1185 394 1185 394 1186 584 1186 577 1186 53 1187 412 1187 52 1187 52 1188 412 1188 414 1188 3 1189 402 1189 4 1189 4 1190 402 1190 400 1190 610 1191 611 1191 612 1191 613 1192 614 1192 615 1192 616 1193 611 1193 610 1193 617 1194 618 1194 615 1194 615 1195 618 1195 613 1195 614 1196 619 1196 615 1196 615 1197 619 1197 616 1197 619 1198 620 1198 616 1198 616 1199 620 1199 611 1199 610 1200 612 1200 617 1200 612 1201 621 1201 617 1201 617 1202 621 1202 618 1202 622 1203 623 1203 617 1203 615 1204 622 1204 617 1204 623 1205 624 1205 625 1205 626 1206 627 1206 628 1206 627 1207 626 1207 629 1207 627 1208 629 1208 630 1208 630 1209 631 1209 622 1209 622 1210 631 1210 632 1210 622 1211 632 1211 623 1211 623 1212 632 1212 624 1212 630 1213 633 1213 631 1213 625 1214 634 1214 623 1214 623 1215 634 1215 627 1215 627 1216 634 1216 628 1216 630 1217 629 1217 633 1217 616 1218 610 1218 630 1218 630 1219 610 1219 627 1219 623 1220 627 1220 617 1220 617 1221 627 1221 610 1221 635 1222 636 1222 637 1222 637 1223 636 1223 638 1223 638 1224 636 1224 639 1224 638 1225 639 1225 640 1225 641 1226 642 1226 643 1226 638 1227 640 1227 644 1227 644 1228 640 1228 645 1228 644 1229 645 1229 641 1229 644 1230 641 1230 643 1230 643 1231 642 1231 646 1231 643 1232 646 1232 637 1232 646 1233 635 1233 637 1233 647 1234 648 1234 638 1234 638 1235 648 1235 637 1235 649 1236 648 1236 647 1236 649 1237 647 1237 650 1237 648 1238 649 1238 651 1238 652 1239 650 1239 647 1239 653 1240 654 1240 655 1240 655 1241 654 1241 656 1241 648 1242 651 1242 657 1242 648 1243 657 1243 655 1243 655 1244 657 1244 658 1244 655 1245 658 1245 653 1245 656 1246 659 1246 647 1246 647 1247 659 1247 652 1247 656 1248 654 1248 659 1248 643 1249 655 1249 644 1249 644 1250 655 1250 656 1250 648 1251 655 1251 637 1251 637 1252 655 1252 643 1252 615 1253 616 1253 660 1253 660 1254 661 1254 615 1254 662 1255 661 1255 660 1255 662 1256 663 1256 661 1256 663 1257 662 1257 664 1257 663 1258 664 1258 665 1258 41 1259 665 1259 664 1259 41 1260 42 1260 665 1260 622 1261 615 1261 661 1261 666 1262 622 1262 661 1262 661 1263 663 1263 666 1263 665 1264 104 1264 666 1264 666 1265 663 1265 665 1265 106 1266 665 1266 42 1266 616 1267 630 1267 660 1267 660 1268 630 1268 667 1268 660 1269 667 1269 662 1269 662 1270 667 1270 668 1270 668 1271 664 1271 662 1271 664 1272 668 1272 669 1272 669 1273 41 1273 664 1273 37 1274 41 1274 669 1274 38 1275 37 1275 669 1275 38 1276 669 1276 93 1276 669 1277 666 1277 104 1277 666 1278 669 1278 668 1278 668 1279 667 1279 666 1279 666 1280 667 1280 622 1280 630 1281 622 1281 667 1281 638 1282 644 1282 670 1282 670 1283 644 1283 671 1283 670 1284 671 1284 672 1284 672 1285 673 1285 674 1285 672 1286 671 1286 673 1286 674 1287 673 1287 675 1287 674 1288 675 1288 46 1288 46 1289 675 1289 44 1289 647 1290 638 1290 670 1290 647 1291 670 1291 676 1291 670 1292 672 1292 676 1292 676 1293 672 1293 677 1293 672 1294 674 1294 677 1294 677 1295 674 1295 47 1295 47 1296 674 1296 46 1296 671 1297 644 1297 656 1297 656 1298 673 1298 671 1298 656 1299 678 1299 673 1299 678 1300 675 1300 673 1300 109 1301 44 1301 675 1301 678 1302 109 1302 675 1302 677 1303 47 1303 50 1303 678 1304 677 1304 50 1304 678 1305 50 1305 95 1305 678 1306 676 1306 677 1306 656 1307 676 1307 678 1307 676 1308 656 1308 647 1308 649 1309 636 1309 635 1309 649 1310 635 1310 651 1310 651 1311 635 1311 646 1311 651 1312 646 1312 657 1312 657 1313 646 1313 642 1313 657 1314 642 1314 658 1314 658 1315 642 1315 641 1315 658 1316 641 1316 653 1316 653 1317 641 1317 654 1317 654 1318 641 1318 645 1318 654 1319 645 1319 659 1319 659 1320 645 1320 640 1320 659 1321 640 1321 652 1321 652 1322 640 1322 639 1322 652 1323 639 1323 650 1323 650 1324 639 1324 636 1324 650 1325 636 1325 649 1325 632 1326 618 1326 624 1326 624 1327 618 1327 625 1327 625 1328 618 1328 621 1328 625 1329 621 1329 634 1329 634 1330 621 1330 612 1330 634 1331 612 1331 628 1331 628 1332 612 1332 611 1332 628 1333 611 1333 626 1333 626 1334 611 1334 629 1334 629 1335 611 1335 620 1335 629 1336 620 1336 633 1336 633 1337 620 1337 619 1337 633 1338 619 1338 631 1338 631 1339 619 1339 614 1339 631 1340 614 1340 613 1340 631 1341 613 1341 632 1341 632 1342 613 1342 618 1342 679 1343 680 1343 681 1343 681 1344 680 1344 682 1344 681 1345 682 1345 683 1345 683 1346 682 1346 684 1346 683 1347 684 1347 685 1347 685 1348 684 1348 686 1348 685 1349 686 1349 687 1349 687 1350 686 1350 688 1350 687 1351 688 1351 689 1351 687 1352 689 1352 690 1352 690 1353 689 1353 691 1353 691 1354 689 1354 692 1354 691 1355 692 1355 693 1355 693 1356 692 1356 694 1356 693 1357 694 1357 695 1357 695 1358 694 1358 696 1358 695 1359 696 1359 679 1359 679 1360 696 1360 680 1360 686 1361 340 1361 688 1361 688 1362 340 1362 345 1362 688 1363 345 1363 689 1363 689 1364 345 1364 344 1364 689 1365 344 1365 692 1365 692 1366 344 1366 343 1366 692 1367 343 1367 694 1367 343 1368 398 1368 694 1368 694 1369 398 1369 696 1369 696 1370 398 1370 352 1370 696 1371 352 1371 680 1371 680 1372 352 1372 389 1372 680 1373 389 1373 682 1373 682 1374 389 1374 342 1374 682 1375 342 1375 684 1375 684 1376 342 1376 341 1376 684 1377 341 1377 686 1377 686 1378 341 1378 340 1378 697 1379 698 1379 699 1379 697 1380 699 1380 700 1380 700 1381 699 1381 701 1381 700 1382 701 1382 702 1382 702 1383 701 1383 703 1383 702 1384 703 1384 704 1384 704 1385 703 1385 705 1385 704 1386 705 1386 706 1386 706 1387 705 1387 707 1387 706 1388 707 1388 708 1388 708 1389 707 1389 709 1389 708 1390 709 1390 710 1390 710 1391 709 1391 711 1391 711 1392 709 1392 712 1392 711 1393 712 1393 713 1393 711 1394 713 1394 714 1394 714 1395 713 1395 715 1395 715 1396 713 1396 716 1396 715 1397 716 1397 697 1397 697 1398 716 1398 698 1398 703 1399 333 1399 705 1399 705 1400 333 1400 339 1400 705 1401 339 1401 707 1401 707 1402 339 1402 338 1402 707 1403 338 1403 709 1403 709 1404 338 1404 337 1404 709 1405 337 1405 712 1405 337 1406 330 1406 712 1406 712 1407 330 1407 713 1407 713 1408 330 1408 329 1408 713 1409 329 1409 332 1409 713 1410 332 1410 716 1410 716 1411 332 1411 331 1411 716 1412 331 1412 698 1412 698 1413 331 1413 336 1413 698 1414 336 1414 699 1414 699 1415 336 1415 334 1415 699 1416 334 1416 701 1416 701 1417 334 1417 703 1417 703 1418 334 1418 333 1418 458 1419 717 1419 718 1419 719 1420 40 1420 720 1420 720 1421 40 1421 455 1421 721 1422 722 1422 32 1422 32 1423 722 1423 31 1423 31 1424 722 1424 48 1424 723 1425 724 1425 725 1425 48 1426 722 1426 717 1426 35 1427 726 1427 727 1427 40 1428 728 1428 36 1428 36 1429 728 1429 35 1429 717 1430 722 1430 729 1430 717 1431 729 1431 730 1431 730 1432 731 1432 717 1432 732 1433 733 1433 734 1433 35 1434 727 1434 735 1434 35 1435 735 1435 32 1435 32 1436 735 1436 721 1436 732 1437 735 1437 733 1437 26 1438 736 1438 24 1438 24 1439 736 1439 22 1439 723 1440 725 1440 734 1440 737 1441 738 1441 739 1441 719 1442 737 1442 728 1442 719 1443 728 1443 40 1443 730 1444 740 1444 741 1444 730 1445 741 1445 731 1445 727 1446 742 1446 735 1446 735 1447 742 1447 736 1447 736 1448 742 1448 743 1448 743 1449 742 1449 744 1449 26 1450 25 1450 745 1450 733 1451 735 1451 736 1451 734 1452 733 1452 723 1452 737 1453 746 1453 738 1453 737 1454 719 1454 746 1454 747 1455 748 1455 749 1455 744 1456 742 1456 750 1456 744 1457 750 1457 751 1457 751 1458 750 1458 748 1458 748 1459 750 1459 749 1459 26 1460 745 1460 736 1460 736 1461 745 1461 752 1461 736 1462 752 1462 733 1462 753 1463 754 1463 755 1463 756 1464 757 1464 758 1464 1 1465 5 1465 759 1465 760 1466 761 1466 762 1466 763 1467 764 1467 761 1467 720 1468 455 1468 765 1468 1 1469 755 1469 2 1469 2 1470 755 1470 766 1470 753 1471 755 1471 1 1471 753 1472 1 1472 759 1472 12 1473 767 1473 5 1473 5 1474 767 1474 768 1474 5 1475 768 1475 759 1475 758 1476 757 1476 761 1476 761 1477 757 1477 763 1477 766 1478 769 1478 2 1478 2 1479 769 1479 441 1479 441 1480 769 1480 455 1480 455 1481 769 1481 765 1481 720 1482 765 1482 756 1482 756 1483 770 1483 720 1483 756 1484 758 1484 771 1484 756 1485 771 1485 770 1485 772 1486 28 1486 773 1486 774 1487 775 1487 776 1487 777 1488 778 1488 753 1488 754 1489 753 1489 778 1489 775 1490 779 1490 780 1490 780 1491 779 1491 781 1491 782 1492 783 1492 23 1492 783 1493 28 1493 23 1493 777 1494 753 1494 784 1494 754 1495 778 1495 773 1495 12 1496 433 1496 458 1496 785 1497 21 1497 786 1497 785 1498 786 1498 787 1498 787 1499 786 1499 788 1499 787 1500 788 1500 760 1500 787 1501 760 1501 789 1501 789 1502 760 1502 762 1502 21 1503 785 1503 782 1503 21 1504 782 1504 23 1504 28 1505 772 1505 27 1505 27 1506 772 1506 790 1506 27 1507 790 1507 791 1507 776 1508 775 1508 792 1508 776 1509 792 1509 791 1509 791 1510 792 1510 793 1510 791 1511 793 1511 27 1511 780 1512 781 1512 767 1512 780 1513 767 1513 794 1513 773 1514 795 1514 754 1514 754 1515 795 1515 796 1515 773 1516 28 1516 783 1516 773 1517 783 1517 795 1517 797 1518 762 1518 764 1518 764 1519 762 1519 761 1519 798 1520 799 1520 800 1520 800 1521 799 1521 801 1521 775 1522 800 1522 779 1522 754 1523 796 1523 764 1523 764 1524 796 1524 797 1524 774 1525 798 1525 775 1525 775 1526 798 1526 800 1526 12 1527 458 1527 767 1527 767 1528 458 1528 718 1528 718 1529 802 1529 767 1529 767 1530 802 1530 794 1530 784 1531 801 1531 777 1531 777 1532 801 1532 799 1532 761 1533 803 1533 748 1533 761 1534 748 1534 747 1534 761 1535 747 1535 758 1535 758 1536 747 1536 804 1536 747 1537 805 1537 804 1537 758 1538 804 1538 806 1538 761 1539 807 1539 803 1539 805 1540 808 1540 804 1540 780 1541 725 1541 775 1541 775 1542 725 1542 724 1542 775 1543 724 1543 809 1543 810 1544 811 1544 780 1544 780 1545 811 1545 725 1545 811 1546 812 1546 725 1546 775 1547 809 1547 813 1547 811 1548 814 1548 812 1548 814 1549 811 1549 815 1549 810 1550 780 1550 740 1550 740 1551 780 1551 794 1551 740 1552 794 1552 741 1552 741 1553 794 1553 802 1553 741 1554 802 1554 731 1554 731 1555 802 1555 718 1555 731 1556 718 1556 717 1556 758 1557 739 1557 738 1557 758 1558 738 1558 771 1558 771 1559 738 1559 746 1559 771 1560 746 1560 770 1560 770 1561 746 1561 720 1561 720 1562 746 1562 719 1562 739 1563 758 1563 806 1563 816 1564 807 1564 761 1564 760 1565 817 1565 816 1565 760 1566 816 1566 761 1566 788 1567 818 1567 760 1567 760 1568 818 1568 817 1568 788 1569 819 1569 818 1569 819 1570 788 1570 786 1570 819 1571 786 1571 820 1571 20 1572 820 1572 786 1572 20 1573 786 1573 21 1573 27 1574 821 1574 25 1574 793 1575 821 1575 27 1575 792 1576 822 1576 821 1576 792 1577 821 1577 793 1577 775 1578 823 1578 792 1578 792 1579 823 1579 822 1579 775 1580 824 1580 823 1580 775 1581 813 1581 824 1581 825 1582 826 1582 827 1582 827 1583 826 1583 828 1583 827 1584 828 1584 829 1584 827 1585 829 1585 830 1585 830 1586 829 1586 831 1586 830 1587 831 1587 832 1587 832 1588 831 1588 833 1588 832 1589 833 1589 834 1589 834 1590 833 1590 835 1590 834 1591 835 1591 836 1591 834 1592 836 1592 837 1592 837 1593 836 1593 838 1593 837 1594 838 1594 839 1594 839 1595 838 1595 840 1595 839 1596 840 1596 841 1596 839 1597 841 1597 842 1597 842 1598 841 1598 843 1598 842 1599 843 1599 825 1599 825 1600 843 1600 844 1600 825 1601 844 1601 826 1601 845 1602 846 1602 847 1602 845 1603 847 1603 848 1603 845 1604 848 1604 849 1604 849 1605 848 1605 850 1605 849 1606 850 1606 851 1606 851 1607 850 1607 852 1607 851 1608 852 1608 853 1608 851 1609 853 1609 854 1609 854 1610 853 1610 855 1610 854 1611 855 1611 856 1611 854 1612 856 1612 857 1612 857 1613 856 1613 858 1613 857 1614 858 1614 859 1614 859 1615 858 1615 860 1615 859 1616 860 1616 861 1616 861 1617 860 1617 862 1617 861 1618 862 1618 863 1618 863 1619 862 1619 846 1619 863 1620 846 1620 845 1620 864 1621 865 1621 866 1621 866 1622 865 1622 867 1622 866 1623 867 1623 868 1623 866 1624 868 1624 869 1624 869 1625 868 1625 870 1625 869 1626 870 1626 871 1626 869 1627 871 1627 872 1627 872 1628 871 1628 873 1628 872 1629 873 1629 874 1629 872 1630 874 1630 875 1630 875 1631 874 1631 876 1631 875 1632 876 1632 877 1632 877 1633 876 1633 878 1633 877 1634 878 1634 879 1634 877 1635 879 1635 880 1635 877 1636 880 1636 881 1636 881 1637 880 1637 882 1637 882 1638 880 1638 883 1638 882 1639 883 1639 884 1639 882 1640 884 1640 864 1640 864 1641 884 1641 865 1641 885 1642 886 1642 887 1642 885 1643 887 1643 888 1643 888 1644 887 1644 889 1644 888 1645 889 1645 890 1645 890 1646 889 1646 891 1646 890 1647 891 1647 892 1647 892 1648 891 1648 893 1648 892 1649 893 1649 894 1649 894 1650 893 1650 895 1650 894 1651 895 1651 896 1651 894 1652 896 1652 897 1652 897 1653 896 1653 898 1653 897 1654 898 1654 899 1654 899 1655 898 1655 900 1655 899 1656 900 1656 901 1656 901 1657 900 1657 902 1657 901 1658 902 1658 903 1658 901 1659 903 1659 904 1659 904 1660 903 1660 886 1660 904 1661 886 1661 885 1661 863 1662 905 1662 861 1662 861 1663 905 1663 906 1663 861 1664 906 1664 859 1664 859 1665 906 1665 907 1665 859 1666 907 1666 908 1666 859 1667 908 1667 857 1667 857 1668 908 1668 909 1668 857 1669 909 1669 854 1669 854 1670 909 1670 910 1670 854 1671 910 1671 851 1671 851 1672 910 1672 911 1672 851 1673 911 1673 849 1673 849 1674 911 1674 912 1674 849 1675 912 1675 913 1675 849 1676 913 1676 845 1676 845 1677 913 1677 914 1677 845 1678 914 1678 863 1678 863 1679 914 1679 905 1679 906 1680 779 1680 907 1680 907 1681 779 1681 800 1681 907 1682 800 1682 908 1682 908 1683 800 1683 801 1683 908 1684 801 1684 909 1684 909 1685 801 1685 784 1685 909 1686 784 1686 910 1686 910 1687 784 1687 753 1687 910 1688 753 1688 911 1688 911 1689 753 1689 759 1689 911 1690 759 1690 912 1690 912 1691 759 1691 768 1691 912 1692 768 1692 913 1692 913 1693 768 1693 767 1693 913 1694 767 1694 914 1694 914 1695 767 1695 781 1695 914 1696 781 1696 905 1696 905 1697 781 1697 779 1697 905 1698 779 1698 906 1698 832 1699 915 1699 830 1699 830 1700 915 1700 827 1700 827 1701 915 1701 916 1701 827 1702 916 1702 917 1702 827 1703 917 1703 825 1703 825 1704 917 1704 918 1704 825 1705 918 1705 842 1705 842 1706 918 1706 919 1706 842 1707 919 1707 839 1707 839 1708 919 1708 920 1708 839 1709 920 1709 837 1709 837 1710 920 1710 834 1710 834 1711 920 1711 921 1711 834 1712 921 1712 922 1712 834 1713 922 1713 832 1713 832 1714 922 1714 915 1714 915 1715 774 1715 776 1715 915 1716 776 1716 916 1716 916 1717 776 1717 791 1717 916 1718 791 1718 917 1718 917 1719 791 1719 790 1719 917 1720 790 1720 772 1720 917 1721 772 1721 918 1721 918 1722 772 1722 773 1722 918 1723 773 1723 919 1723 919 1724 773 1724 778 1724 919 1725 778 1725 920 1725 920 1726 778 1726 777 1726 920 1727 777 1727 921 1727 921 1728 777 1728 799 1728 921 1729 799 1729 798 1729 921 1730 798 1730 922 1730 922 1731 798 1731 915 1731 915 1732 798 1732 774 1732 885 1733 923 1733 904 1733 904 1734 923 1734 901 1734 901 1735 923 1735 924 1735 901 1736 924 1736 925 1736 901 1737 925 1737 899 1737 899 1738 925 1738 926 1738 899 1739 926 1739 897 1739 897 1740 926 1740 927 1740 897 1741 927 1741 894 1741 894 1742 927 1742 928 1742 894 1743 928 1743 892 1743 892 1744 928 1744 929 1744 892 1745 929 1745 890 1745 890 1746 929 1746 930 1746 890 1747 930 1747 888 1747 888 1748 930 1748 931 1748 888 1749 931 1749 885 1749 885 1750 931 1750 923 1750 923 1751 766 1751 755 1751 923 1752 755 1752 924 1752 924 1753 755 1753 754 1753 924 1754 754 1754 925 1754 925 1755 754 1755 764 1755 925 1756 764 1756 926 1756 926 1757 764 1757 927 1757 927 1758 764 1758 763 1758 927 1759 763 1759 757 1759 927 1760 757 1760 928 1760 928 1761 757 1761 756 1761 928 1762 756 1762 929 1762 929 1763 756 1763 765 1763 929 1764 765 1764 930 1764 930 1765 765 1765 931 1765 931 1766 765 1766 769 1766 931 1767 769 1767 766 1767 931 1768 766 1768 923 1768 877 1769 932 1769 875 1769 875 1770 932 1770 933 1770 875 1771 933 1771 872 1771 872 1772 933 1772 934 1772 872 1773 934 1773 935 1773 872 1774 935 1774 869 1774 869 1775 935 1775 936 1775 869 1776 936 1776 866 1776 866 1777 936 1777 937 1777 866 1778 937 1778 864 1778 864 1779 937 1779 882 1779 882 1780 937 1780 938 1780 882 1781 938 1781 881 1781 881 1782 938 1782 939 1782 881 1783 939 1783 877 1783 877 1784 939 1784 932 1784 932 1785 783 1785 933 1785 933 1786 783 1786 782 1786 933 1787 782 1787 934 1787 934 1788 782 1788 785 1788 934 1789 785 1789 935 1789 935 1790 785 1790 787 1790 935 1791 787 1791 936 1791 936 1792 787 1792 789 1792 936 1793 789 1793 937 1793 937 1794 789 1794 762 1794 937 1795 762 1795 797 1795 937 1796 797 1796 938 1796 938 1797 797 1797 796 1797 938 1798 796 1798 939 1798 939 1799 796 1799 795 1799 939 1800 795 1800 932 1800 932 1801 795 1801 783 1801 868 1802 816 1802 817 1802 803 1803 807 1803 940 1803 941 1804 803 1804 940 1804 22 1805 942 1805 20 1805 943 1806 20 1806 942 1806 944 1807 942 1807 22 1807 944 1808 22 1808 736 1808 945 1809 736 1809 743 1809 946 1810 751 1810 748 1810 946 1811 947 1811 751 1811 751 1812 947 1812 744 1812 744 1813 947 1813 948 1813 744 1814 948 1814 949 1814 744 1815 949 1815 743 1815 743 1816 949 1816 945 1816 942 1817 944 1817 950 1817 942 1818 950 1818 943 1818 20 1819 943 1819 820 1819 748 1820 803 1820 941 1820 748 1821 941 1821 946 1821 946 1822 941 1822 951 1822 946 1823 951 1823 947 1823 736 1824 945 1824 952 1824 736 1825 952 1825 953 1825 736 1826 953 1826 944 1826 944 1827 953 1827 954 1827 944 1828 954 1828 950 1828 949 1829 948 1829 955 1829 945 1830 949 1830 956 1830 945 1831 956 1831 957 1831 945 1832 957 1832 952 1832 943 1833 950 1833 958 1833 943 1834 958 1834 959 1834 943 1835 959 1835 820 1835 820 1836 959 1836 819 1836 819 1837 959 1837 960 1837 819 1838 960 1838 818 1838 941 1839 940 1839 951 1839 948 1840 947 1840 955 1840 949 1841 955 1841 956 1841 952 1842 878 1842 953 1842 818 1843 960 1843 961 1843 818 1844 961 1844 817 1844 947 1845 951 1845 883 1845 947 1846 883 1846 955 1846 957 1847 879 1847 952 1847 953 1848 878 1848 876 1848 953 1849 876 1849 954 1849 950 1850 954 1850 874 1850 950 1851 874 1851 958 1851 958 1852 874 1852 873 1852 958 1853 873 1853 959 1853 959 1854 873 1854 871 1854 959 1855 871 1855 960 1855 960 1856 871 1856 870 1856 960 1857 870 1857 961 1857 817 1858 961 1858 868 1858 954 1859 876 1859 874 1859 961 1860 870 1860 868 1860 816 1861 868 1861 867 1861 816 1862 867 1862 807 1862 807 1863 867 1863 865 1863 807 1864 865 1864 940 1864 940 1865 865 1865 884 1865 940 1866 884 1866 951 1866 951 1867 884 1867 883 1867 955 1868 883 1868 880 1868 955 1869 880 1869 956 1869 956 1870 880 1870 879 1870 956 1871 879 1871 957 1871 952 1872 879 1872 878 1872 806 1873 962 1873 739 1873 805 1874 747 1874 963 1874 896 1875 808 1875 805 1875 895 1876 804 1876 808 1876 965 1877 749 1877 750 1877 966 1878 742 1878 727 1878 967 1879 728 1879 737 1879 962 1880 737 1880 739 1880 737 1881 962 1881 968 1881 737 1882 968 1882 967 1882 728 1883 967 1883 969 1883 964 1884 969 1884 970 1884 726 1885 970 1885 971 1885 726 1886 971 1886 972 1886 726 1887 972 1887 727 1887 727 1888 973 1888 966 1888 742 1889 966 1889 974 1889 742 1890 974 1890 750 1890 750 1891 974 1891 965 1891 962 1892 806 1892 975 1892 967 1893 968 1893 976 1893 967 1894 976 1894 969 1894 727 1895 972 1895 973 1895 965 1896 977 1896 978 1896 965 1897 978 1897 749 1897 749 1898 978 1898 963 1898 749 1899 963 1899 747 1899 806 1900 804 1900 979 1900 806 1901 979 1901 975 1901 962 1902 975 1902 968 1902 968 1903 980 1903 976 1903 970 1904 981 1904 971 1904 971 1905 981 1905 982 1905 971 1906 982 1906 972 1906 974 1907 983 1907 965 1907 965 1908 983 1908 977 1908 963 1909 984 1909 805 1909 805 1910 984 1910 985 1910 969 1911 976 1911 986 1911 969 1912 986 1912 970 1912 970 1913 986 1913 981 1913 973 1914 972 1914 987 1914 973 1915 987 1915 966 1915 966 1916 987 1916 988 1916 966 1917 988 1917 974 1917 974 1918 988 1918 983 1918 978 1919 989 1919 963 1919 963 1920 989 1920 984 1920 804 1921 895 1921 979 1921 979 1922 893 1922 975 1922 968 1923 975 1923 891 1923 968 1924 891 1924 980 1924 980 1925 891 1925 976 1925 981 1926 887 1926 982 1926 972 1927 982 1927 886 1927 972 1928 886 1928 987 1928 805 1929 985 1929 896 1929 987 1930 886 1930 903 1930 987 1931 903 1931 988 1931 988 1932 903 1932 983 1932 983 1933 903 1933 902 1933 983 1934 902 1934 977 1934 977 1935 902 1935 900 1935 977 1936 900 1936 978 1936 978 1937 900 1937 989 1937 989 1938 900 1938 898 1938 989 1939 898 1939 984 1939 984 1940 898 1940 985 1940 985 1941 898 1941 896 1941 808 1942 896 1942 895 1942 979 1943 895 1943 893 1943 975 1944 893 1944 891 1944 976 1945 891 1945 889 1945 976 1946 889 1946 986 1946 986 1947 889 1947 887 1947 986 1948 887 1948 981 1948 982 1949 887 1949 886 1949 822 1950 823 1950 990 1950 813 1951 809 1951 991 1951 992 1952 724 1952 723 1952 993 1953 723 1953 994 1953 994 1954 723 1954 995 1954 995 1955 723 1955 733 1955 995 1956 733 1956 996 1956 996 1957 733 1957 997 1957 997 1958 733 1958 752 1958 998 1959 745 1959 25 1959 745 1960 998 1960 1000 1960 745 1961 1000 1961 752 1961 723 1962 993 1962 992 1962 998 1963 1001 1963 1000 1963 752 1964 1000 1964 1002 1964 752 1965 1002 1965 997 1965 995 1966 1003 1966 994 1966 993 1967 1004 1967 992 1967 992 1968 1005 1968 724 1968 822 1969 1006 1969 821 1969 821 1970 1006 1970 999 1970 999 1971 1007 1971 998 1971 998 1972 1007 1972 1001 1972 997 1973 1002 1973 1008 1973 997 1974 1008 1974 1009 1974 997 1975 1009 1975 996 1975 996 1976 1009 1976 1010 1976 996 1977 1010 1977 995 1977 995 1978 1010 1978 1003 1978 994 1979 1003 1979 1011 1979 994 1980 1011 1980 993 1980 992 1981 1004 1981 1012 1981 992 1982 1012 1982 1005 1982 724 1983 1005 1983 809 1983 822 1984 990 1984 1006 1984 999 1985 1006 1985 1013 1985 999 1986 1013 1986 1007 1986 1002 1987 1014 1987 1008 1987 993 1988 1011 1988 1004 1988 1005 1989 991 1989 809 1989 823 1990 824 1990 829 1990 823 1991 829 1991 990 1991 1007 1992 826 1992 1001 1992 1000 1993 1001 1993 844 1993 1000 1994 844 1994 1002 1994 1002 1995 844 1995 843 1995 1002 1996 843 1996 1014 1996 1009 1997 1008 1997 841 1997 1010 1998 1009 1998 840 1998 1010 1999 840 1999 1003 1999 1011 2000 838 2000 1004 2000 1004 2001 836 2001 1012 2001 824 2002 831 2002 829 2002 990 2003 829 2003 828 2003 990 2004 828 2004 1006 2004 1006 2005 828 2005 1013 2005 1013 2006 828 2006 826 2006 1013 2007 826 2007 1007 2007 1001 2008 826 2008 844 2008 1014 2009 843 2009 1008 2009 1008 2010 843 2010 841 2010 1009 2011 841 2011 840 2011 840 2012 838 2012 1003 2012 1003 2013 838 2013 1011 2013 838 2014 836 2014 1004 2014 1012 2015 836 2015 835 2015 1012 2016 835 2016 1005 2016 1005 2017 835 2017 833 2017 1005 2018 833 2018 991 2018 991 2019 833 2019 813 2019 813 2020 833 2020 831 2020 813 2021 831 2021 824 2021 810 2022 740 2022 730 2022 725 2023 1015 2023 734 2023 734 2024 1015 2024 1016 2024 734 2025 1016 2025 732 2025 735 2026 1017 2026 721 2026 722 2027 721 2027 1018 2027 722 2028 1018 2028 1019 2028 722 2029 1019 2029 729 2029 732 2030 1020 2030 735 2030 735 2031 1020 2031 1021 2031 735 2032 1021 2032 1017 2032 1017 2033 1022 2033 721 2033 1019 2034 1023 2034 729 2034 729 2035 1023 2035 1024 2035 729 2036 1024 2036 1025 2036 729 2037 1025 2037 730 2037 730 2038 1025 2038 810 2038 810 2039 1025 2039 1026 2039 725 2040 812 2040 1015 2040 1016 2041 1027 2041 732 2041 732 2042 1027 2042 1028 2042 732 2043 1028 2043 1020 2043 721 2044 1022 2044 1029 2044 721 2045 1029 2045 1018 2045 1018 2046 1030 2046 1019 2046 1019 2047 1030 2047 1023 2047 810 2048 1026 2048 811 2048 1015 2049 1031 2049 1016 2049 1016 2050 1031 2050 1027 2050 1017 2051 1021 2051 1032 2051 1017 2052 1032 2052 1022 2052 1018 2053 1029 2053 1033 2053 1018 2054 1033 2054 1030 2054 1023 2055 1030 2055 1034 2055 1023 2056 1034 2056 1024 2056 1025 2057 1024 2057 1035 2057 1025 2058 1035 2058 1036 2058 1025 2059 1036 2059 1026 2059 1015 2060 812 2060 1037 2060 1015 2061 1037 2061 1031 2061 1020 2062 855 2062 1021 2062 1021 2063 855 2063 1032 2063 1022 2064 1032 2064 1038 2064 1022 2065 1038 2065 1029 2065 1030 2066 1033 2066 1039 2066 1030 2067 1039 2067 1034 2067 1024 2068 1034 2068 1040 2068 1024 2069 1040 2069 1035 2069 811 2070 1026 2070 1041 2070 812 2071 814 2071 1037 2071 1031 2072 1037 2072 860 2072 1020 2073 1028 2073 856 2073 1020 2074 856 2074 855 2074 1034 2075 848 2075 1040 2075 1026 2076 1036 2076 846 2076 1026 2077 846 2077 1041 2077 811 2078 1041 2078 815 2078 814 2079 862 2079 860 2079 814 2080 860 2080 1037 2080 860 2081 858 2081 1031 2081 1031 2082 858 2082 1027 2082 1027 2083 858 2083 856 2083 1027 2084 856 2084 1028 2084 1032 2085 855 2085 853 2085 1032 2086 853 2086 1038 2086 1038 2087 853 2087 852 2087 1038 2088 852 2088 1029 2088 1029 2089 852 2089 1033 2089 1033 2090 852 2090 850 2090 1033 2091 850 2091 1039 2091 1039 2092 850 2092 1034 2092 1034 2093 850 2093 848 2093 1040 2094 848 2094 847 2094 1040 2095 847 2095 1035 2095 1035 2096 847 2096 1036 2096 1036 2097 847 2097 846 2097 1041 2098 846 2098 862 2098 1041 2099 862 2099 815 2099 815 2100 862 2100 814 2100 1042 2101 1043 2101 1044 2101 1044 2102 1043 2102 1045 2102 1044 2103 1046 2103 1047 2103 1048 2104 1049 2104 1045 2104 1044 2105 1050 2105 1046 2105 1045 2106 1051 2106 1044 2106 1045 2107 1049 2107 1053 2107 1052 2108 1050 2108 1044 2108 1045 2109 1053 2109 1051 2109 8 2110 17 2110 1054 2110 1054 2111 17 2111 609 2111 19 2112 15 2112 606 2112 606 2113 15 2113 1055 2113 606 2114 1055 2114 1056 2114 609 2115 1057 2115 1054 2115 1057 2116 609 2116 1059 2116 606 2117 1056 2117 1060 2117 691 2118 1061 2118 690 2118 690 2119 1061 2119 1062 2119 690 2120 1062 2120 687 2120 687 2121 1062 2121 1063 2121 687 2122 1063 2122 685 2122 685 2123 1063 2123 1064 2123 685 2124 1064 2124 683 2124 683 2125 1064 2125 1065 2125 683 2126 1065 2126 681 2126 681 2127 1065 2127 1066 2127 681 2128 1066 2128 679 2128 679 2129 1066 2129 695 2129 695 2130 1066 2130 1067 2130 695 2131 1067 2131 693 2131 693 2132 1067 2132 1068 2132 693 2133 1068 2133 691 2133 691 2134 1068 2134 1061 2134 708 2135 1069 2135 706 2135 706 2136 1069 2136 1070 2136 706 2137 1070 2137 704 2137 704 2138 1070 2138 1071 2138 704 2139 1071 2139 702 2139 702 2140 1071 2140 700 2140 700 2141 1071 2141 1072 2141 700 2142 1072 2142 1073 2142 700 2143 1073 2143 697 2143 697 2144 1073 2144 1074 2144 697 2145 1074 2145 715 2145 715 2146 1074 2146 1075 2146 715 2147 1075 2147 714 2147 714 2148 1075 2148 711 2148 711 2149 1075 2149 1076 2149 711 2150 1076 2150 710 2150 710 2151 1076 2151 708 2151 708 2152 1076 2152 1069 2152 1059 2153 609 2153 608 2153 1077 2154 1078 2154 602 2154 602 2155 1078 2155 605 2155 1079 2156 1080 2156 1081 2156 1079 2157 1081 2157 1082 2157 1082 2158 1081 2158 1083 2158 1082 2159 1083 2159 1084 2159 1084 2160 1083 2160 1085 2160 1085 2161 1083 2161 1086 2161 1085 2162 1086 2162 1087 2162 1087 2163 1086 2163 1088 2163 1087 2164 1088 2164 1089 2164 1089 2165 1088 2165 1090 2165 1089 2166 1090 2166 1091 2166 1091 2167 1090 2167 1092 2167 1091 2168 1092 2168 1093 2168 1093 2169 1092 2169 1094 2169 1093 2170 1094 2170 1095 2170 1095 2171 1094 2171 1096 2171 1095 2172 1096 2172 1097 2172 1097 2173 1096 2173 1080 2173 1097 2174 1080 2174 1079 2174 1098 2175 1099 2175 1100 2175 1098 2176 1100 2176 1101 2176 1101 2177 1100 2177 1102 2177 1101 2178 1102 2178 1103 2178 1103 2179 1102 2179 1104 2179 1103 2180 1104 2180 1105 2180 1105 2181 1104 2181 1106 2181 1105 2182 1106 2182 1107 2182 1107 2183 1106 2183 1108 2183 1107 2184 1108 2184 1109 2184 1109 2185 1108 2185 1110 2185 1109 2186 1110 2186 1111 2186 1111 2187 1110 2187 1112 2187 1111 2188 1112 2188 1113 2188 1113 2189 1112 2189 1114 2189 1113 2190 1114 2190 1115 2190 1115 2191 1114 2191 1116 2191 1116 2192 1114 2192 1117 2192 1116 2193 1117 2193 1098 2193 1098 2194 1117 2194 1099 2194 1118 2195 1119 2195 1120 2195 1118 2196 1120 2196 1121 2196 1121 2197 1120 2197 1122 2197 1122 2198 1120 2198 1123 2198 1122 2199 1123 2199 1124 2199 1124 2200 1123 2200 1125 2200 1124 2201 1125 2201 1126 2201 1126 2202 1125 2202 1127 2202 1126 2203 1127 2203 1128 2203 1128 2204 1127 2204 1129 2204 1128 2205 1129 2205 1130 2205 1130 2206 1129 2206 1131 2206 1130 2207 1131 2207 1132 2207 1132 2208 1131 2208 1133 2208 1132 2209 1133 2209 1134 2209 1134 2210 1133 2210 1135 2210 1134 2211 1135 2211 1118 2211 1118 2212 1135 2212 1119 2212 1136 2213 1137 2213 1138 2213 1138 2214 1137 2214 1139 2214 1138 2215 1139 2215 1140 2215 1140 2216 1139 2216 1141 2216 1140 2217 1141 2217 1142 2217 1142 2218 1141 2218 1143 2218 1142 2219 1143 2219 1144 2219 1144 2220 1143 2220 1145 2220 1144 2221 1145 2221 1146 2221 1146 2222 1145 2222 1147 2222 1146 2223 1147 2223 1148 2223 1148 2224 1147 2224 1149 2224 1148 2225 1149 2225 1150 2225 1150 2226 1149 2226 1151 2226 1150 2227 1151 2227 1152 2227 1152 2228 1151 2228 1153 2228 1152 2229 1153 2229 1154 2229 1154 2230 1153 2230 1155 2230 1154 2231 1155 2231 1136 2231 1136 2232 1155 2232 1137 2232 1096 2233 1156 2233 1080 2233 1080 2234 1156 2234 1157 2234 1080 2235 1157 2235 1081 2235 1081 2236 1157 2236 1158 2236 1081 2237 1158 2237 1083 2237 1083 2238 1158 2238 1159 2238 1083 2239 1159 2239 1086 2239 1086 2240 1159 2240 1160 2240 1086 2241 1160 2241 1088 2241 1088 2242 1160 2242 1161 2242 1088 2243 1161 2243 1090 2243 1090 2244 1161 2244 1162 2244 1090 2245 1162 2245 1092 2245 1092 2246 1162 2246 1163 2246 1092 2247 1163 2247 1094 2247 1094 2248 1163 2248 1164 2248 1094 2249 1164 2249 1096 2249 1096 2250 1164 2250 1156 2250 1155 2251 1165 2251 1137 2251 1137 2252 1165 2252 1166 2252 1137 2253 1166 2253 1139 2253 1139 2254 1166 2254 1167 2254 1139 2255 1167 2255 1141 2255 1141 2256 1167 2256 1168 2256 1141 2257 1168 2257 1143 2257 1143 2258 1168 2258 1145 2258 1145 2259 1168 2259 1169 2259 1145 2260 1169 2260 1147 2260 1147 2261 1169 2261 1170 2261 1147 2262 1170 2262 1171 2262 1147 2263 1171 2263 1149 2263 1149 2264 1171 2264 1172 2264 1149 2265 1172 2265 1151 2265 1151 2266 1172 2266 1153 2266 1153 2267 1172 2267 1173 2267 1153 2268 1173 2268 1155 2268 1155 2269 1173 2269 1165 2269 1123 2270 1174 2270 1125 2270 1125 2271 1174 2271 1127 2271 1127 2272 1174 2272 1175 2272 1127 2273 1175 2273 1129 2273 1129 2274 1175 2274 1176 2274 1129 2275 1176 2275 1131 2275 1131 2276 1176 2276 1177 2276 1131 2277 1177 2277 1133 2277 1133 2278 1177 2278 1178 2278 1133 2279 1178 2279 1135 2279 1135 2280 1178 2280 1179 2280 1135 2281 1179 2281 1119 2281 1119 2282 1179 2282 1180 2282 1119 2283 1180 2283 1120 2283 1120 2284 1180 2284 1181 2284 1120 2285 1181 2285 1182 2285 1120 2286 1182 2286 1123 2286 1123 2287 1182 2287 1174 2287 1117 2288 1183 2288 1099 2288 1099 2289 1183 2289 1184 2289 1099 2290 1184 2290 1100 2290 1100 2291 1184 2291 1185 2291 1100 2292 1185 2292 1102 2292 1102 2293 1185 2293 1186 2293 1102 2294 1186 2294 1104 2294 1104 2295 1186 2295 1106 2295 1106 2296 1186 2296 1187 2296 1106 2297 1187 2297 1108 2297 1108 2298 1187 2298 1188 2298 1108 2299 1188 2299 1189 2299 1108 2300 1189 2300 1110 2300 1110 2301 1189 2301 1190 2301 1110 2302 1190 2302 1112 2302 1112 2303 1190 2303 1191 2303 1112 2304 1191 2304 1114 2304 1114 2305 1191 2305 1192 2305 1114 2306 1192 2306 1117 2306 1117 2307 1192 2307 1183 2307 1193 2308 1194 2308 1195 2308 1193 2309 1195 2309 1196 2309 1196 2310 1195 2310 1197 2310 1198 2311 1199 2311 1200 2311 1198 2312 1200 2312 1201 2312 1202 2313 1203 2313 1204 2313 1204 2314 1203 2314 1205 2314 1194 2315 1206 2315 1195 2315 1197 2316 1195 2316 1207 2316 1197 2317 1207 2317 1199 2317 1199 2318 1207 2318 1208 2318 1199 2319 1208 2319 1200 2319 1201 2320 1200 2320 1209 2320 1209 2321 1200 2321 1210 2321 1209 2322 1210 2322 1211 2322 1211 2323 1210 2323 1212 2323 1211 2324 1212 2324 1213 2324 1214 2325 1215 2325 1216 2325 1214 2326 1216 2326 1217 2326 1217 2327 1216 2327 1218 2327 1218 2328 1216 2328 1219 2328 1218 2329 1219 2329 1220 2329 1220 2330 1219 2330 1221 2330 1221 2331 1219 2331 1222 2331 1221 2332 1222 2332 1223 2332 1202 2333 1223 2333 1203 2333 1206 2334 1224 2334 1195 2334 1208 2335 1225 2335 1200 2335 1213 2336 1212 2336 1215 2336 1216 2337 1215 2337 1226 2337 1219 2338 1216 2338 1227 2338 1223 2339 1222 2339 1203 2339 1205 2340 1203 2340 1228 2340 1195 2341 1224 2341 1207 2341 1208 2342 1207 2342 1225 2342 1200 2343 1225 2343 1210 2343 1215 2344 1212 2344 1226 2344 1216 2345 1226 2345 1227 2345 1219 2346 1227 2346 1222 2346 1203 2347 1222 2347 1228 2347 1210 2348 1225 2348 1212 2348 1082 2349 1229 2349 1079 2349 1079 2350 1229 2350 1230 2350 1079 2351 1230 2351 1097 2351 1097 2352 1230 2352 1231 2352 1097 2353 1231 2353 1095 2353 1095 2354 1231 2354 1093 2354 1093 2355 1231 2355 1232 2355 1093 2356 1232 2356 1233 2356 1093 2357 1233 2357 1091 2357 1091 2358 1233 2358 1234 2358 1091 2359 1234 2359 1089 2359 1089 2360 1234 2360 1235 2360 1089 2361 1235 2361 1087 2361 1087 2362 1235 2362 1085 2362 1085 2363 1235 2363 1236 2363 1085 2364 1236 2364 1084 2364 1084 2365 1236 2365 1237 2365 1084 2366 1237 2366 1082 2366 1082 2367 1237 2367 1229 2367 1109 2368 1238 2368 1107 2368 1107 2369 1238 2369 1239 2369 1107 2370 1239 2370 1240 2370 1107 2371 1240 2371 1105 2371 1105 2372 1240 2372 1241 2372 1105 2373 1241 2373 1103 2373 1103 2374 1241 2374 1242 2374 1103 2375 1242 2375 1101 2375 1101 2376 1242 2376 1098 2376 1098 2377 1242 2377 1243 2377 1098 2378 1243 2378 1116 2378 1116 2379 1243 2379 1244 2379 1116 2380 1244 2380 1115 2380 1115 2381 1244 2381 1245 2381 1115 2382 1245 2382 1113 2382 1113 2383 1245 2383 1111 2383 1111 2384 1245 2384 1246 2384 1111 2385 1246 2385 1238 2385 1111 2386 1238 2386 1109 2386 1134 2387 1247 2387 1132 2387 1132 2388 1247 2388 1248 2388 1132 2389 1248 2389 1130 2389 1130 2390 1248 2390 1249 2390 1130 2391 1249 2391 1128 2391 1128 2392 1249 2392 1250 2392 1128 2393 1250 2393 1126 2393 1126 2394 1250 2394 1251 2394 1126 2395 1251 2395 1124 2395 1124 2396 1251 2396 1122 2396 1122 2397 1251 2397 1252 2397 1122 2398 1252 2398 1121 2398 1121 2399 1252 2399 1253 2399 1121 2400 1253 2400 1118 2400 1118 2401 1253 2401 1254 2401 1118 2402 1254 2402 1134 2402 1134 2403 1254 2403 1255 2403 1134 2404 1255 2404 1247 2404 1146 2405 1256 2405 1144 2405 1144 2406 1256 2406 1257 2406 1144 2407 1257 2407 1142 2407 1142 2408 1257 2408 1258 2408 1142 2409 1258 2409 1140 2409 1140 2410 1258 2410 1259 2410 1140 2411 1259 2411 1138 2411 1138 2412 1259 2412 1260 2412 1138 2413 1260 2413 1136 2413 1136 2414 1260 2414 1261 2414 1136 2415 1261 2415 1154 2415 1154 2416 1261 2416 1262 2416 1154 2417 1262 2417 1152 2417 1152 2418 1262 2418 1150 2418 1150 2419 1262 2419 1263 2419 1150 2420 1263 2420 1264 2420 1150 2421 1264 2421 1148 2421 1148 2422 1264 2422 1265 2422 1148 2423 1265 2423 1146 2423 1146 2424 1265 2424 1256 2424 1266 2425 1267 2425 1268 2425 1269 2426 1270 2426 1271 2426 1272 2427 1273 2427 1274 2427 1274 2428 1273 2428 1270 2428 1274 2429 1270 2429 1269 2429 1275 2430 1272 2430 1276 2430 1276 2431 1272 2431 1274 2431 1277 2432 1267 2432 1266 2432 1278 2433 1279 2433 1280 2433 1280 2434 1279 2434 1266 2434 1280 2435 1266 2435 1268 2435 1281 2436 1282 2436 1280 2436 1281 2437 1280 2437 1268 2437 1282 2438 1281 2438 1283 2438 1284 2439 1283 2439 1285 2439 1286 2440 1287 2440 1288 2440 1289 2441 1278 2441 1280 2441 1290 2442 1289 2442 1282 2442 1282 2443 1289 2443 1280 2443 1284 2444 1290 2444 1283 2444 1283 2445 1290 2445 1282 2445 1281 2446 1291 2446 1283 2446 1283 2447 1291 2447 1285 2447 1292 2448 1293 2448 1294 2448 1294 2449 1293 2449 1295 2449 1293 2450 1292 2450 1285 2450 1293 2451 1285 2451 1291 2451 1295 2452 1293 2452 1287 2452 1295 2453 1287 2453 1296 2453 1296 2454 1287 2454 1286 2454 1297 2455 1288 2455 1298 2455 1298 2456 1288 2456 1287 2456 1287 2457 1293 2457 1299 2457 1293 2458 1291 2458 1299 2458 1298 2459 1275 2459 1297 2459 1297 2460 1275 2460 1300 2460 1276 2461 1300 2461 1275 2461 1298 2462 1287 2462 1299 2462 1271 2463 1194 2463 1193 2463 1271 2464 1193 2464 1269 2464 1269 2465 1193 2465 1274 2465 1274 2466 1193 2466 1196 2466 1274 2467 1196 2467 1276 2467 1276 2468 1196 2468 1197 2468 1276 2469 1197 2469 1300 2469 1300 2470 1197 2470 1199 2470 1300 2471 1199 2471 1297 2471 1297 2472 1199 2472 1198 2472 1297 2473 1198 2473 1288 2473 1288 2474 1198 2474 1286 2474 1286 2475 1198 2475 1201 2475 1286 2476 1201 2476 1296 2476 1296 2477 1201 2477 1209 2477 1296 2478 1209 2478 1295 2478 1295 2479 1209 2479 1211 2479 1295 2480 1211 2480 1294 2480 1294 2481 1211 2481 1213 2481 1294 2482 1213 2482 1292 2482 1292 2483 1213 2483 1215 2483 1292 2484 1215 2484 1285 2484 1285 2485 1215 2485 1214 2485 1285 2486 1214 2486 1284 2486 1284 2487 1214 2487 1217 2487 1284 2488 1217 2488 1290 2488 1290 2489 1217 2489 1218 2489 1290 2490 1218 2490 1220 2490 1290 2491 1220 2491 1289 2491 1289 2492 1220 2492 1221 2492 1289 2493 1221 2493 1278 2493 1278 2494 1221 2494 1223 2494 1278 2495 1223 2495 1279 2495 1279 2496 1223 2496 1202 2496 1279 2497 1202 2497 1266 2497 1266 2498 1202 2498 1277 2498 1277 2499 1202 2499 1204 2499 1301 2500 1224 2500 1206 2500 1301 2501 1206 2501 1302 2501 1302 2502 1206 2502 1194 2502 1302 2503 1194 2503 1303 2503 1228 2504 1304 2504 1205 2504 1304 2505 1305 2505 1205 2505 1205 2506 1305 2506 1306 2506 1205 2507 1306 2507 1204 2507 1307 2508 1164 2508 1163 2508 1307 2509 1163 2509 1162 2509 1307 2510 1162 2510 1308 2510 1161 2511 1160 2511 1308 2511 1308 2512 1160 2512 1309 2512 1162 2513 1161 2513 1308 2513 1160 2514 1159 2514 1310 2514 1310 2515 1159 2515 1158 2515 1310 2516 1158 2516 1157 2516 1157 2517 1156 2517 1311 2517 1311 2518 1156 2518 1164 2518 1312 2519 1313 2519 1314 2519 1314 2520 1315 2520 1312 2520 1314 2521 1316 2521 1315 2521 1313 2522 1312 2522 1317 2522 1318 2523 1319 2523 1320 2523 1319 2524 1321 2524 1320 2524 1320 2525 1321 2525 1322 2525 1313 2526 1317 2526 1323 2526 1323 2527 1317 2527 1324 2527 1320 2528 1322 2528 1325 2528 1325 2529 1322 2529 1326 2529 1323 2530 1324 2530 1327 2530 1323 2531 1327 2531 1328 2531 1328 2532 1327 2532 1318 2532 1328 2533 1318 2533 1308 2533 1308 2534 1329 2534 1330 2534 1316 2535 1314 2535 1331 2535 1316 2536 1331 2536 1332 2536 1316 2537 1332 2537 1333 2537 1333 2538 1332 2538 1334 2538 1335 2539 1336 2539 1330 2539 1330 2540 1336 2540 1308 2540 1333 2541 1334 2541 1330 2541 1330 2542 1334 2542 1335 2542 1337 2543 1338 2543 1339 2543 1340 2544 1320 2544 1341 2544 1342 2545 1343 2545 1344 2545 1342 2546 1344 2546 1345 2546 1345 2547 1344 2547 1346 2547 1345 2548 1346 2548 1307 2548 1320 2549 1340 2549 1347 2549 1320 2550 1347 2550 1348 2550 1342 2551 1338 2551 1343 2551 1320 2552 1348 2552 1307 2552 1343 2553 1338 2553 1337 2553 1349 2554 1307 2554 1346 2554 1350 2555 1341 2555 1320 2555 1350 2556 1320 2556 1351 2556 1349 2557 1352 2557 1311 2557 1339 2558 1353 2558 1354 2558 1339 2559 1354 2559 1337 2559 1353 2560 1355 2560 1356 2560 1356 2561 1355 2561 1357 2561 1358 2562 1359 2562 1311 2562 1358 2563 1311 2563 1352 2563 1359 2564 1358 2564 1356 2564 1359 2565 1356 2565 1357 2565 1339 2566 1355 2566 1353 2566 1360 2567 1325 2567 1326 2567 1360 2568 1361 2568 1325 2568 1160 2569 1310 2569 1309 2569 1169 2570 1168 2570 1362 2570 1362 2571 1168 2571 1167 2571 1310 2572 1167 2572 1166 2572 1268 2573 1170 2573 1169 2573 1268 2574 1171 2574 1170 2574 1166 2575 1165 2575 1310 2575 1310 2576 1165 2576 1309 2576 1309 2577 1165 2577 1173 2577 1172 2578 1309 2578 1173 2578 1309 2579 1172 2579 1268 2579 1268 2580 1172 2580 1171 2580 1169 2581 1362 2581 1268 2581 1362 2582 1291 2582 1281 2582 1362 2583 1281 2583 1268 2583 1299 2584 1291 2584 1298 2584 1273 2585 1272 2585 1363 2585 1363 2586 1272 2586 1275 2586 1275 2587 1298 2587 1363 2587 1364 2588 1185 2588 1184 2588 1364 2589 1184 2589 1183 2589 1273 2590 1187 2590 1186 2590 1273 2591 1186 2591 1364 2591 1364 2592 1186 2592 1185 2592 1157 2593 1192 2593 1191 2593 1363 2594 1189 2594 1188 2594 1363 2595 1188 2595 1273 2595 1273 2596 1188 2596 1187 2596 1157 2597 1183 2597 1192 2597 1157 2598 1191 2598 1190 2598 1363 2599 1190 2599 1189 2599 1364 2600 1183 2600 1157 2600 1364 2601 1157 2601 1311 2601 1307 2602 1349 2602 1311 2602 1307 2603 1311 2603 1164 2603 1167 2604 1310 2604 1362 2604 1362 2605 1310 2605 1157 2605 1362 2606 1157 2606 1363 2606 1363 2607 1157 2607 1190 2607 1175 2608 1174 2608 1363 2608 1291 2609 1178 2609 1177 2609 1291 2610 1177 2610 1298 2610 1363 2611 1174 2611 1362 2611 1362 2612 1174 2612 1182 2612 1298 2613 1177 2613 1176 2613 1298 2614 1176 2614 1175 2614 1298 2615 1175 2615 1363 2615 1362 2616 1182 2616 1181 2616 1181 2617 1180 2617 1362 2617 1362 2618 1180 2618 1291 2618 1291 2619 1180 2619 1179 2619 1291 2620 1179 2620 1178 2620 1318 2621 1320 2621 1308 2621 1308 2622 1320 2622 1307 2622 1237 2623 1304 2623 1229 2623 1304 2624 1237 2624 1236 2624 1253 2625 1257 2625 1256 2625 1235 2626 1078 2626 1077 2626 1263 2627 1304 2627 1264 2627 1264 2628 1304 2628 1228 2628 1365 2629 1366 2629 1367 2629 1252 2630 1258 2630 1257 2630 1238 2631 1251 2631 1239 2631 1222 2632 1256 2632 1265 2632 1222 2633 1265 2633 1228 2633 1078 2634 1235 2634 1368 2634 1368 2635 1235 2635 1234 2635 1368 2636 1234 2636 1369 2636 1369 2637 1234 2637 1233 2637 1369 2638 1233 2638 1370 2638 1370 2639 1233 2639 1232 2639 1251 2640 1238 2640 1246 2640 1258 2641 1252 2641 1245 2641 1212 2642 1247 2642 1255 2642 1212 2643 1255 2643 1226 2643 1077 2644 1371 2644 1235 2644 1304 2645 1262 2645 1261 2645 1304 2646 1261 2646 1229 2646 1226 2647 1255 2647 1254 2647 1226 2648 1254 2648 1227 2648 1265 2649 1264 2649 1228 2649 1372 2650 1301 2650 1373 2650 1373 2651 1301 2651 1366 2651 1373 2652 1366 2652 1374 2652 1374 2653 1366 2653 1365 2653 1235 2654 1371 2654 1375 2654 1375 2655 1304 2655 1235 2655 1252 2656 1257 2656 1253 2656 1252 2657 1251 2657 1245 2657 1304 2658 1263 2658 1262 2658 1261 2659 1260 2659 1229 2659 1227 2660 1254 2660 1222 2660 1222 2661 1254 2661 1253 2661 1222 2662 1253 2662 1256 2662 1232 2663 1301 2663 1370 2663 1370 2664 1301 2664 1372 2664 1235 2665 1304 2665 1236 2665 1231 2666 1230 2666 1243 2666 1225 2667 1249 2667 1248 2667 1225 2668 1248 2668 1212 2668 1212 2669 1248 2669 1247 2669 1251 2670 1246 2670 1245 2670 1229 2671 1245 2671 1244 2671 1301 2672 1232 2672 1231 2672 1229 2673 1260 2673 1259 2673 1229 2674 1259 2674 1245 2674 1245 2675 1259 2675 1258 2675 1229 2676 1244 2676 1230 2676 1230 2677 1244 2677 1243 2677 1231 2678 1243 2678 1301 2678 1301 2679 1243 2679 1242 2679 1239 2680 1251 2680 1250 2680 1249 2681 1225 2681 1207 2681 1249 2682 1207 2682 1250 2682 1250 2683 1207 2683 1224 2683 1301 2684 1242 2684 1224 2684 1224 2685 1242 2685 1241 2685 1224 2686 1241 2686 1240 2686 1239 2687 1250 2687 1224 2687 1239 2688 1224 2688 1240 2688 1376 2689 1277 2689 1306 2689 1306 2690 1277 2690 1204 2690 1277 2691 1376 2691 1267 2691 1377 2692 1268 2692 1267 2692 1267 2693 1376 2693 1377 2693 1268 2694 1377 2694 1309 2694 1270 2695 1273 2695 1364 2695 1270 2696 1364 2696 1378 2696 1271 2697 1270 2697 1378 2697 1271 2698 1378 2698 1379 2698 1303 2699 1194 2699 1379 2699 1379 2700 1194 2700 1271 2700 1077 2701 1380 2701 1381 2701 602 2702 601 2702 1077 2702 1077 2703 601 2703 1380 2703 591 2704 598 2704 1382 2704 1382 2705 598 2705 1367 2705 1382 2706 1367 2706 1383 2706 1371 2707 1077 2707 1384 2707 1304 2708 1375 2708 1305 2708 1371 2709 1385 2709 1375 2709 1375 2710 1385 2710 1306 2710 1375 2711 1306 2711 1305 2711 1371 2712 1384 2712 1385 2712 1386 2713 1377 2713 1376 2713 1376 2714 1387 2714 1386 2714 1077 2715 1381 2715 1384 2715 1384 2716 1381 2716 1387 2716 1384 2717 1387 2717 1385 2717 1385 2718 1387 2718 1306 2718 1306 2719 1387 2719 1376 2719 1388 2720 1366 2720 1301 2720 1366 2721 1389 2721 1390 2721 1388 2722 1301 2722 1302 2722 1389 2723 1366 2723 1388 2723 1388 2724 1302 2724 1303 2724 1367 2725 1366 2725 1390 2725 1390 2726 1391 2726 1383 2726 1390 2727 1383 2727 1367 2727 1303 2728 1379 2728 1388 2728 1388 2729 1379 2729 1392 2729 1388 2730 1392 2730 1389 2730 1389 2731 1392 2731 1391 2731 1389 2732 1391 2732 1390 2732 1393 2733 1392 2733 1378 2733 1378 2734 1392 2734 1379 2734 438 2735 437 2735 1394 2735 438 2736 1394 2736 600 2736 1394 2737 1395 2737 600 2737 600 2738 1395 2738 1396 2738 600 2739 1396 2739 601 2739 1396 2740 1397 2740 601 2740 601 2741 1397 2741 1380 2741 591 2742 1382 2742 1398 2742 591 2743 1398 2743 1399 2743 591 2744 1399 2744 592 2744 592 2745 1399 2745 1400 2745 592 2746 1400 2746 445 2746 445 2747 1400 2747 446 2747 1365 2748 1367 2748 598 2748 1365 2749 598 2749 597 2749 606 2750 1060 2750 607 2750 1401 2751 597 2751 595 2751 597 2752 1401 2752 1365 2752 595 2753 1402 2753 1401 2753 594 2754 1403 2754 1402 2754 594 2755 1402 2755 595 2755 1403 2756 594 2756 599 2756 599 2757 607 2757 1403 2757 1373 2758 1374 2758 1404 2758 1365 2759 1401 2759 1374 2759 1406 2760 1407 2760 1408 2760 1408 2761 1407 2761 1409 2761 1408 2762 1409 2762 1410 2762 1410 2763 1409 2763 1078 2763 1410 2764 1078 2764 1368 2764 1401 2765 1402 2765 1404 2765 1401 2766 1404 2766 1374 2766 1412 2767 1369 2767 1370 2767 1058 2768 1411 2768 1413 2768 1413 2769 1411 2769 1412 2769 1413 2770 1412 2770 1370 2770 1405 2771 1058 2771 1413 2771 1405 2772 1413 2772 1414 2772 1414 2773 1413 2773 1370 2773 1415 2774 1414 2774 1370 2774 1415 2775 1370 2775 1372 2775 1411 2776 1416 2776 1417 2776 1411 2777 1417 2777 1412 2777 1412 2778 1417 2778 1369 2778 1417 2779 1368 2779 1369 2779 1420 2780 1415 2780 1421 2780 1421 2781 1415 2781 1372 2781 1421 2782 1372 2782 1373 2782 1418 2783 1408 2783 1416 2783 1416 2784 1408 2784 1417 2784 1417 2785 1408 2785 1410 2785 1417 2786 1410 2786 1368 2786 1404 2787 1421 2787 1373 2787 1406 2788 1408 2788 1418 2788 1406 2789 1418 2789 1422 2789 1422 2790 1418 2790 1059 2790 1422 2791 1059 2791 608 2791 1421 2792 1404 2792 1402 2792 1421 2793 1402 2793 1420 2793 1420 2794 1402 2794 1403 2794 1420 2795 1403 2795 1419 2795 1419 2796 1403 2796 607 2796 1419 2797 607 2797 1060 2797 608 2798 604 2798 603 2798 608 2799 603 2799 1422 2799 603 2800 1406 2800 1422 2800 605 2801 1407 2801 1406 2801 605 2802 1406 2802 603 2802 1409 2803 1407 2803 605 2803 1078 2804 1409 2804 605 2804 15 2805 1423 2805 1055 2805 18 2806 1423 2806 15 2806 1424 2807 1423 2807 18 2807 1424 2808 18 2808 7 2808 1424 2809 7 2809 1425 2809 1425 2810 7 2810 1426 2810 1426 2811 7 2811 6 2811 1426 2812 6 2812 447 2812 8 2813 1054 2813 1427 2813 11 2814 9 2814 1428 2814 11 2815 1428 2815 436 2815 9 2816 8 2816 1429 2816 9 2817 1429 2817 1428 2817 8 2818 1427 2818 1429 2818 1070 2819 1430 2819 1071 2819 1071 2820 1430 2820 1431 2820 1071 2821 1431 2821 1432 2821 1071 2822 1432 2822 1072 2822 1072 2823 1432 2823 1073 2823 1073 2824 1432 2824 1433 2824 1073 2825 1433 2825 1074 2825 1074 2826 1433 2826 1434 2826 1074 2827 1434 2827 1435 2827 1074 2828 1435 2828 1075 2828 1075 2829 1435 2829 1436 2829 1075 2830 1436 2830 1076 2830 1076 2831 1436 2831 1437 2831 1076 2832 1437 2832 1069 2832 1069 2833 1437 2833 1438 2833 1069 2834 1438 2834 1070 2834 1070 2835 1438 2835 1430 2835 1431 2836 1308 2836 1336 2836 1431 2837 1336 2837 1432 2837 1432 2838 1336 2838 1335 2838 1432 2839 1335 2839 1433 2839 1433 2840 1335 2840 1334 2840 1433 2841 1334 2841 1434 2841 1434 2842 1334 2842 1332 2842 1434 2843 1332 2843 1435 2843 1435 2844 1332 2844 1331 2844 1435 2845 1331 2845 1436 2845 1436 2846 1331 2846 1314 2846 1314 2847 1437 2847 1436 2847 1437 2848 1314 2848 1313 2848 1437 2849 1313 2849 1438 2849 1438 2850 1313 2850 1323 2850 1438 2851 1323 2851 1430 2851 1430 2852 1323 2852 1328 2852 1430 2853 1328 2853 1308 2853 1430 2854 1308 2854 1431 2854 1066 2855 1439 2855 1440 2855 1066 2856 1440 2856 1067 2856 1067 2857 1440 2857 1068 2857 1068 2858 1440 2858 1441 2858 1068 2859 1441 2859 1061 2859 1061 2860 1441 2860 1442 2860 1061 2861 1442 2861 1443 2861 1061 2862 1443 2862 1062 2862 1062 2863 1443 2863 1063 2863 1063 2864 1443 2864 1444 2864 1063 2865 1444 2865 1064 2865 1064 2866 1444 2866 1445 2866 1064 2867 1445 2867 1065 2867 1065 2868 1445 2868 1446 2868 1065 2869 1446 2869 1066 2869 1066 2870 1446 2870 1439 2870 1444 2871 1354 2871 1445 2871 1445 2872 1354 2872 1353 2872 1445 2873 1353 2873 1446 2873 1446 2874 1353 2874 1356 2874 1446 2875 1356 2875 1439 2875 1439 2876 1356 2876 1358 2876 1439 2877 1358 2877 1352 2877 1439 2878 1352 2878 1440 2878 1440 2879 1352 2879 1349 2879 1349 2880 1441 2880 1440 2880 1441 2881 1349 2881 1346 2881 1441 2882 1346 2882 1442 2882 1442 2883 1346 2883 1344 2883 1442 2884 1344 2884 1443 2884 1443 2885 1344 2885 1343 2885 1443 2886 1343 2886 1337 2886 1443 2887 1337 2887 1444 2887 1444 2888 1337 2888 1354 2888 28 2889 1447 2889 1448 2889 1448 2890 23 2890 28 2890 1057 2891 1056 2891 1449 2891 1450 2892 1447 2892 28 2892 1447 2893 1451 2893 1452 2893 1452 2894 1451 2894 1453 2894 1057 2895 1449 2895 1452 2895 1057 2896 1452 2896 1453 2896 1450 2897 1454 2897 1447 2897 1447 2898 1454 2898 1451 2898 1455 2899 1456 2899 1457 2899 1458 2900 1459 2900 1460 2900 1461 2901 1462 2901 1463 2901 1461 2902 1463 2902 1464 2902 1462 2903 1461 2903 1465 2903 1458 2904 1460 2904 1466 2904 1467 2905 1464 2905 1463 2905 1456 2906 1468 2906 1469 2906 1460 2907 1470 2907 1466 2907 1471 2908 1043 2908 1466 2908 1471 2909 1466 2909 1470 2909 1458 2910 1472 2910 1459 2910 1466 2911 1043 2911 1463 2911 1463 2912 1043 2912 1042 2912 1462 2913 1465 2913 1473 2913 1473 2914 1465 2914 1469 2914 1468 2915 1456 2915 1455 2915 1474 2916 1475 2916 1458 2916 1458 2917 1475 2917 1472 2917 1455 2918 1457 2918 1042 2918 1042 2919 1457 2919 1467 2919 1042 2920 1467 2920 1463 2920 1471 2921 1476 2921 1043 2921 1469 2922 1468 2922 1473 2922 1476 2923 1477 2923 1478 2923 1476 2924 1478 2924 1479 2924 1476 2925 1471 2925 1477 2925 1479 2926 1478 2926 1475 2926 1475 2927 1474 2927 1479 2927 1429 2928 1427 2928 1480 2928 1480 2929 1427 2929 1481 2929 1481 2930 1427 2930 1482 2930 1481 2931 1482 2931 1483 2931 1483 2932 1482 2932 1484 2932 1485 2933 1486 2933 1487 2933 1485 2934 1487 2934 1488 2934 1488 2935 1487 2935 1423 2935 1488 2936 1423 2936 1424 2936 1489 2937 1490 2937 1491 2937 1491 2938 1490 2938 1052 2938 1492 2939 1493 2939 1051 2939 1051 2940 1493 2940 1494 2940 1046 2941 1495 2941 1047 2941 1047 2942 1495 2942 1496 2942 1047 2943 1496 2943 1497 2943 1497 2944 1496 2944 1498 2944 1499 2945 1500 2945 1048 2945 1048 2946 1500 2946 1501 2946 1048 2947 1501 2947 1049 2947 1049 2948 1501 2948 1502 2948 1483 2949 1484 2949 1503 2949 1503 2950 1484 2950 1504 2950 1503 2951 1504 2951 1505 2951 1505 2952 1504 2952 1506 2952 1506 2953 1504 2953 1507 2953 1506 2954 1507 2954 1508 2954 1506 2955 1508 2955 1509 2955 1509 2956 1508 2956 1510 2956 1510 2957 1508 2957 1511 2957 1510 2958 1511 2958 1512 2958 1510 2959 1512 2959 1513 2959 1513 2960 1512 2960 1514 2960 1514 2961 1512 2961 1515 2961 1514 2962 1515 2962 1516 2962 1514 2963 1516 2963 1517 2963 1517 2964 1516 2964 1518 2964 1517 2965 1518 2965 1519 2965 1519 2966 1518 2966 1520 2966 1520 2967 1518 2967 1521 2967 1520 2968 1521 2968 1522 2968 1522 2969 1521 2969 1523 2969 1522 2970 1523 2970 1494 2970 1522 2971 1494 2971 1493 2971 1486 2972 1485 2972 1524 2972 1486 2973 1524 2973 1525 2973 1525 2974 1524 2974 1526 2974 1526 2975 1524 2975 1527 2975 1526 2976 1527 2976 1528 2976 1526 2977 1528 2977 1529 2977 1529 2978 1528 2978 1530 2978 1530 2979 1528 2979 1531 2979 1530 2980 1531 2980 1532 2980 1532 2981 1531 2981 1533 2981 1532 2982 1533 2982 1534 2982 1534 2983 1533 2983 1535 2983 1535 2984 1533 2984 1536 2984 1535 2985 1536 2985 1537 2985 1537 2986 1536 2986 1538 2986 1537 2987 1538 2987 1539 2987 1539 2988 1538 2988 1540 2988 1539 2989 1540 2989 1541 2989 1541 2990 1540 2990 1491 2990 1491 2991 1540 2991 1489 2991 1542 2992 1456 2992 1469 2992 1542 2993 1469 2993 1543 2993 1543 2994 1469 2994 1465 2994 1543 2995 1465 2995 1544 2995 1544 2996 1465 2996 1545 2996 1545 2997 1465 2997 1461 2997 1545 2998 1461 2998 1546 2998 1546 2999 1461 2999 1464 2999 1546 3000 1464 3000 1547 3000 1547 3001 1464 3001 1467 3001 1547 3002 1467 3002 1548 3002 1548 3003 1467 3003 1457 3003 1548 3004 1457 3004 1549 3004 1549 3005 1457 3005 1456 3005 1549 3006 1456 3006 1542 3006 1468 3007 1455 3007 1550 3007 1550 3008 1455 3008 1551 3008 1473 3009 1552 3009 1462 3009 1462 3010 1552 3010 1497 3010 1497 3011 1498 3011 1462 3011 1497 3012 1545 3012 1047 3012 1047 3013 1545 3013 1546 3013 1551 3014 1044 3014 1047 3014 1047 3015 1546 3015 1547 3015 1552 3016 1543 3016 1497 3016 1497 3017 1543 3017 1544 3017 1047 3018 1547 3018 1551 3018 1551 3019 1547 3019 1548 3019 1551 3020 1549 3020 1542 3020 1551 3021 1542 3021 1550 3021 1497 3022 1544 3022 1545 3022 1551 3023 1548 3023 1549 3023 1543 3024 1552 3024 1542 3024 1542 3025 1552 3025 1550 3025 1476 3026 1479 3026 1553 3026 1553 3027 1479 3027 1554 3027 1555 3028 1459 3028 1556 3028 1556 3029 1459 3029 1472 3029 1556 3030 1472 3030 1475 3030 1556 3031 1475 3031 1557 3031 1557 3032 1475 3032 1478 3032 1557 3033 1478 3033 1558 3033 1558 3034 1478 3034 1559 3034 1559 3035 1478 3035 1477 3035 1559 3036 1477 3036 1560 3036 1560 3037 1477 3037 1471 3037 1560 3038 1471 3038 1561 3038 1561 3039 1471 3039 1470 3039 1561 3040 1470 3040 1562 3040 1562 3041 1470 3041 1460 3041 1562 3042 1460 3042 1555 3042 1555 3043 1460 3043 1459 3043 1499 3044 1563 3044 1500 3044 1500 3045 1563 3045 1474 3045 1474 3046 1458 3046 1500 3046 1458 3047 1564 3047 1500 3047 1048 3048 1045 3048 1553 3048 1555 3049 1499 3049 1048 3049 1554 3050 1558 3050 1553 3050 1553 3051 1558 3051 1559 3051 1553 3052 1559 3052 1560 3052 1553 3053 1560 3053 1561 3053 1553 3054 1561 3054 1048 3054 1048 3055 1561 3055 1562 3055 1048 3056 1562 3056 1555 3056 1499 3057 1555 3057 1556 3057 1499 3058 1556 3058 1563 3058 1563 3059 1556 3059 1557 3059 1554 3060 1557 3060 1558 3060 1554 3061 1563 3061 1557 3061 1492 3062 1051 3062 1565 3062 1565 3063 1051 3063 1053 3063 1565 3064 1053 3064 1566 3064 1566 3065 1053 3065 1049 3065 1566 3066 1049 3066 1502 3066 1458 3067 1466 3067 1567 3067 1458 3068 1567 3068 1564 3068 1564 3069 1567 3069 1500 3069 1500 3070 1567 3070 1501 3070 1052 3071 1490 3071 1050 3071 1050 3072 1490 3072 1568 3072 1050 3073 1568 3073 1495 3073 1050 3074 1495 3074 1046 3074 1463 3075 1462 3075 1569 3075 1569 3076 1462 3076 1498 3076 1569 3077 1498 3077 1570 3077 1570 3078 1498 3078 1496 3078 1468 3079 1550 3079 1473 3079 1473 3080 1550 3080 1552 3080 1042 3081 1044 3081 1551 3081 1042 3082 1551 3082 1455 3082 1045 3083 1043 3083 1553 3083 1553 3084 1043 3084 1476 3084 1474 3085 1563 3085 1479 3085 1479 3086 1563 3086 1554 3086 1537 3087 1539 3087 23 3087 1535 3088 1537 3088 23 3088 1534 3089 1535 3089 1571 3089 1571 3090 1535 3090 23 3090 23 3091 1448 3091 1571 3091 1534 3092 1571 3092 1532 3092 1571 3093 1448 3093 1530 3093 1571 3094 1530 3094 1532 3094 1448 3095 1447 3095 1529 3095 1448 3096 1529 3096 1530 3096 1447 3097 1572 3097 1529 3097 1529 3098 1572 3098 1526 3098 1447 3099 1452 3099 1572 3099 1572 3100 1452 3100 1525 3100 1572 3101 1525 3101 1526 3101 1452 3102 1449 3102 1573 3102 1452 3103 1573 3103 1525 3103 1525 3104 1573 3104 1486 3104 1055 3105 1574 3105 1056 3105 1449 3106 1574 3106 1573 3106 1573 3107 1574 3107 1487 3107 1573 3108 1487 3108 1486 3108 1449 3109 1056 3109 1574 3109 1574 3110 1055 3110 1487 3110 1487 3111 1055 3111 1423 3111 1453 3112 1575 3112 1576 3112 1450 3113 28 3113 1577 3113 1576 3114 1575 3114 1484 3114 1484 3115 1575 3115 1504 3115 1575 3116 1507 3116 1504 3116 1508 3117 1507 3117 1451 3117 1451 3118 1507 3118 1575 3118 1511 3119 1508 3119 1451 3119 1451 3120 1575 3120 1453 3120 1577 3121 1516 3121 1515 3121 1515 3122 1512 3122 1454 3122 1454 3123 1512 3123 1511 3123 1454 3124 1511 3124 1451 3124 1518 3125 1516 3125 1577 3125 1577 3126 1515 3126 1450 3126 1450 3127 1515 3127 1454 3127 1521 3128 1518 3128 28 3128 28 3129 1518 3129 1577 3129 1054 3130 1057 3130 1578 3130 1578 3131 1057 3131 1576 3131 1576 3132 1057 3132 1453 3132 1054 3133 1578 3133 1482 3133 1482 3134 1578 3134 1576 3134 1482 3135 1576 3135 1484 3135 1427 3136 1054 3136 1482 3136 1311 3137 1579 3137 1364 3137 1392 3138 1393 3138 1391 3138 1378 3139 1364 3139 1579 3139 1378 3140 1579 3140 1393 3140 1383 3141 1391 3141 1580 3141 1580 3142 1311 3142 1359 3142 1391 3143 1393 3143 1580 3143 1580 3144 1393 3144 1579 3144 1580 3145 1579 3145 1311 3145 1383 3146 1580 3146 1382 3146 1382 3147 1580 3147 1357 3147 1580 3148 1359 3148 1357 3148 1355 3149 1339 3149 1581 3149 1339 3150 1582 3150 1400 3150 1339 3151 1400 3151 1581 3151 1355 3152 1581 3152 1398 3152 1355 3153 1398 3153 1357 3153 1582 3154 446 3154 1400 3154 1357 3155 1398 3155 1382 3155 1581 3156 1399 3156 1398 3156 1581 3157 1400 3157 1399 3157 1339 3158 1583 3158 1582 3158 1582 3159 1583 3159 447 3159 1582 3160 447 3160 446 3160 1339 3161 1338 3161 1583 3161 447 3162 1583 3162 1426 3162 1583 3163 1338 3163 1425 3163 1583 3164 1425 3164 1426 3164 1338 3165 1584 3165 1425 3165 1425 3166 1584 3166 1424 3166 1338 3167 1342 3167 1584 3167 1485 3168 1585 3168 1586 3168 1586 3169 1585 3169 1345 3169 1485 3170 1488 3170 1585 3170 1585 3171 1488 3171 1342 3171 1585 3172 1342 3172 1345 3172 1488 3173 1424 3173 1584 3173 1488 3174 1584 3174 1342 3174 1524 3175 1587 3175 1527 3175 1533 3176 1531 3176 1588 3176 1489 3177 1540 3177 1589 3177 1485 3178 1586 3178 1524 3178 1524 3179 1586 3179 1587 3179 1527 3180 1587 3180 1590 3180 1527 3181 1590 3181 1528 3181 1528 3182 1590 3182 1591 3182 1528 3183 1591 3183 1531 3183 1533 3184 1588 3184 1592 3184 1533 3185 1592 3185 1536 3185 1540 3186 1538 3186 1593 3186 1540 3187 1593 3187 1589 3187 1531 3188 1591 3188 1588 3188 1536 3189 1592 3189 1347 3189 1536 3190 1347 3190 1538 3190 1538 3191 1347 3191 1593 3191 1586 3192 1345 3192 1587 3192 1587 3193 1345 3193 1307 3193 1587 3194 1307 3194 1590 3194 1588 3195 1591 3195 1348 3195 1588 3196 1348 3196 1592 3196 1589 3197 1593 3197 1340 3197 1590 3198 1307 3198 1591 3198 1591 3199 1307 3199 1348 3199 1592 3200 1348 3200 1347 3200 1593 3201 1347 3201 1340 3201 1490 3202 1489 3202 1594 3202 1594 3203 1489 3203 1589 3203 1594 3204 1589 3204 1341 3204 1341 3205 1589 3205 1340 3205 1350 3206 1595 3206 1341 3206 1341 3207 1595 3207 1568 3207 1341 3208 1568 3208 1594 3208 1568 3209 1490 3209 1594 3209 1595 3210 1495 3210 1568 3210 1496 3211 1495 3211 1596 3211 1596 3212 1495 3212 1595 3212 1596 3213 1595 3213 1350 3213 1596 3214 1350 3214 1570 3214 1596 3215 1570 3215 1496 3215 1350 3216 1597 3216 1570 3216 1350 3217 1351 3217 1597 3217 1597 3218 1569 3218 1570 3218 1597 3219 1598 3219 1569 3219 1597 3220 1351 3220 1598 3220 1569 3221 1598 3221 1463 3221 1466 3222 1463 3222 1598 3222 1466 3223 1598 3223 1599 3223 1599 3224 1598 3224 1351 3224 1599 3225 1351 3225 1325 3225 1325 3226 1351 3226 1320 3226 1361 3227 1600 3227 1325 3227 1325 3228 1600 3228 1599 3228 1361 3229 1601 3229 1600 3229 1599 3230 1600 3230 1466 3230 1601 3231 1501 3231 1567 3231 1601 3232 1567 3232 1600 3232 1600 3233 1567 3233 1466 3233 1502 3234 1501 3234 1601 3234 1502 3235 1601 3235 1602 3235 1602 3236 1601 3236 1361 3236 1602 3237 1361 3237 1360 3237 1326 3238 1492 3238 1603 3238 1603 3239 1492 3239 1565 3239 1502 3240 1602 3240 1566 3240 1602 3241 1603 3241 1566 3241 1360 3242 1326 3242 1602 3242 1602 3243 1326 3243 1603 3243 1566 3244 1603 3244 1565 3244 1326 3245 1322 3245 1604 3245 1326 3246 1604 3246 1492 3246 1492 3247 1604 3247 1493 3247 1604 3248 1322 3248 1605 3248 1483 3249 1503 3249 1606 3249 1493 3250 1604 3250 1522 3250 1522 3251 1604 3251 1605 3251 1522 3252 1605 3252 1520 3252 1514 3253 1517 3253 1607 3253 1514 3254 1607 3254 1513 3254 1519 3255 1520 3255 1321 3255 1519 3256 1321 3256 1517 3256 1517 3257 1321 3257 1607 3257 1509 3258 1510 3258 1318 3258 1509 3259 1318 3259 1506 3259 1503 3260 1505 3260 1327 3260 1503 3261 1327 3261 1606 3261 1520 3262 1605 3262 1321 3262 1607 3263 1321 3263 1319 3263 1513 3264 1607 3264 1319 3264 1513 3265 1319 3265 1510 3265 1510 3266 1319 3266 1318 3266 1505 3267 1506 3267 1327 3267 1606 3268 1327 3268 1324 3268 1506 3269 1318 3269 1327 3269 1605 3270 1322 3270 1321 3270 1429 3271 1480 3271 1608 3271 1608 3272 1480 3272 1317 3272 1608 3273 1317 3273 1312 3273 1480 3274 1481 3274 1317 3274 1481 3275 1483 3275 1606 3275 1481 3276 1606 3276 1317 3276 1317 3277 1606 3277 1324 3277 1312 3278 1315 3278 1608 3278 1608 3279 1315 3279 1609 3279 1608 3280 1609 3280 1429 3280 1429 3281 1609 3281 1428 3281 1609 3282 436 3282 1428 3282 437 3283 436 3283 1610 3283 1610 3284 436 3284 1609 3284 1610 3285 1609 3285 1315 3285 1610 3286 1315 3286 1316 3286 1333 3287 1611 3287 1316 3287 1397 3288 1611 3288 1333 3288 1380 3289 1397 3289 1333 3289 1610 3290 1395 3290 1394 3290 1394 3291 437 3291 1610 3291 1611 3292 1396 3292 1395 3292 1316 3293 1395 3293 1610 3293 1397 3294 1396 3294 1611 3294 1611 3295 1395 3295 1316 3295 1381 3296 1380 3296 1612 3296 1612 3297 1380 3297 1333 3297 1612 3298 1333 3298 1330 3298 1329 3299 1308 3299 1309 3299 1387 3300 1381 3300 1386 3300 1381 3301 1612 3301 1386 3301 1386 3302 1612 3302 1613 3302 1612 3303 1330 3303 1613 3303 1613 3304 1330 3304 1329 3304 1377 3305 1386 3305 1613 3305 1309 3306 1377 3306 1613 3306 1309 3307 1613 3307 1329 3307</p> + </triangles> + </mesh> + </geometry> + </library_geometries> + <library_materials> + <material name="Mesh" id="mat_Mesh"> + <instance_effect url="#effect_Mesh"/> + </material> + </library_materials> + <library_visual_scenes> + <visual_scene id="myscene"> + <node name="node0" id="node0"> + <instance_geometry url="#geometry0"> + <bind_material> + <technique_common> + <instance_material symbol="ref_Mesh" target="#mat_Mesh"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#myscene"/> + </scene> +</COLLADA> diff --git a/kinton_description/meshes/arm/base.stl b/kinton_description/meshes/arm/base.stl new file mode 100644 index 0000000000000000000000000000000000000000..03fa295c31e987bb3f91a512d013fc7d08f2b660 Binary files /dev/null and b/kinton_description/meshes/arm/base.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/BrazoHinton_Dynamixel_PiezasIrir.png b/kinton_description/meshes/arm/dynamixel/BrazoHinton_Dynamixel_PiezasIrir.png new file mode 100644 index 0000000000000000000000000000000000000000..a9cfa43a745d41b70e6b757a627474dc0e3f403b Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/BrazoHinton_Dynamixel_PiezasIrir.png differ diff --git a/kinton_description/meshes/arm/dynamixel/MotorWheel.stl b/kinton_description/meshes/arm/dynamixel/MotorWheel.stl new file mode 100644 index 0000000000000000000000000000000000000000..58093af33cd05593282a2c4eb566b2bdda02ea4b Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/MotorWheel.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/SoporteLadoQuadRotor_v1.stl b/kinton_description/meshes/arm/dynamixel/SoporteLadoQuadRotor_v1.stl new file mode 100644 index 0000000000000000000000000000000000000000..43199f4260081553d024b29ad0273a41cee53eab Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/SoporteLadoQuadRotor_v1.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/XL-320.stl b/kinton_description/meshes/arm/dynamixel/XL-320.stl new file mode 100644 index 0000000000000000000000000000000000000000..3b9d48b8e67801b336afc5e45fb3dfd8386d20e3 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/XL-320.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/base.stl b/kinton_description/meshes/arm/dynamixel/base.stl new file mode 100644 index 0000000000000000000000000000000000000000..f603d386c75dd2c3f8e72243e2b477a8f91b1158 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/base.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/link1.stl b/kinton_description/meshes/arm/dynamixel/link1.stl new file mode 100644 index 0000000000000000000000000000000000000000..bb528924ef54064ee4413c55cb6a11729e386034 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/link1.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/union_M1_M2_v2.stl b/kinton_description/meshes/arm/dynamixel/union_M1_M2_v2.stl new file mode 100644 index 0000000000000000000000000000000000000000..478269ae7b7d29bc80d2fe6246c3af0d3d066cc0 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/union_M1_M2_v2.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/union_M2_M3.stl b/kinton_description/meshes/arm/dynamixel/union_M2_M3.stl new file mode 100644 index 0000000000000000000000000000000000000000..9c47b76cf38ad65dd45d41cba750410011254e68 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/union_M2_M3.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/union_M3_M4.stl b/kinton_description/meshes/arm/dynamixel/union_M3_M4.stl new file mode 100644 index 0000000000000000000000000000000000000000..e3cf6c6a8679cf590c0949815d10421e255a376c Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/union_M3_M4.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/union_M4_M5.stl b/kinton_description/meshes/arm/dynamixel/union_M4_M5.stl new file mode 100644 index 0000000000000000000000000000000000000000..8a98f2f2fb76d0c756f00bceadb20219729c3650 Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/union_M4_M5.stl differ diff --git a/kinton_description/meshes/arm/dynamixel/union_M5_M6.stl b/kinton_description/meshes/arm/dynamixel/union_M5_M6.stl new file mode 100644 index 0000000000000000000000000000000000000000..dd200bb8188eaeaeee5f9d1c96947a4e3c350e5a Binary files /dev/null and b/kinton_description/meshes/arm/dynamixel/union_M5_M6.stl differ diff --git a/kinton_description/meshes/arm/link1.dae b/kinton_description/meshes/arm/link1.dae new file mode 100644 index 0000000000000000000000000000000000000000..d031d5305fbea67313ea1bd7b0ba519e6b88fd3a --- /dev/null +++ b/kinton_description/meshes/arm/link1.dae @@ -0,0 +1,107 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor/> + <created>2019-07-22T14:46:34.440919</created> + <modified>2019-07-22T14:46:34.440927</modified> + <unit name="meter" meter="1.0"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_effects> + <effect name="effect_Mesh001" id="effect_Mesh001"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color>0.0 0.0 0.0 1.0</color> + </emission> + <ambient> + <color>0.0 0.0 0.0 1.0</color> + </ambient> + <diffuse> + <color>0.0512073002756 0.0512073002756 0.0512073002756 1.0</color> + </diffuse> + <specular> + <color>1 1 1 1.0</color> + </specular> + <shininess> + <float>0.0</float> + </shininess> + <reflective> + <color>0.0 0.0 0.0 1.0</color> + </reflective> + <reflectivity> + <float>0.0</float> + </reflectivity> + <transparent> + <color>0.0 0.0 0.0 1.0</color> + </transparent> + <transparency> + <float>1.0</float> + </transparency> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>0</double_sided> + </technique> + </extra> + </profile_COMMON> + </effect> + </library_effects> + <library_geometries> + <geometry id="geometry0" name="Mesh001"> + <mesh> + <source id="cubenormals-array0"> + <float_array count="20151" id="cubenormals-array0-array">1 0 -0 1 0 0 -1 -4.768365e-06 0 -1 -4.768365e-06 0 1 0 -0 1 0 0 -1 0 0 -1 0 0 0 -1 0 2.765441e-06 -1 2.384667e-06 2.506568e-06 -1 -1.676329e-07 0 -1 0 1.062604e-06 -1 1.073527e-06 4.691345e-06 -1 -1.985077e-06 1.863262e-06 -1 -2.730239e-06 1.488398e-06 -1 -7.393372e-07 1.342274e-06 -1 -6.667524e-07 6.561368e-07 -1 -1.660098e-06 0 -1 -0 0 -1 0 -0 -1 0 0 -1 0 -0 -1 0 0 -1 0 8.931199e-07 -1 6.215842e-07 1.632909e-06 -1 -8.560262e-07 -8.243755e-07 1 8.711023e-07 -5.594116e-07 1 5.911199e-07 4.434354e-07 1 1.038924e-06 0 1 0 0 1 0 -7.305617e-07 1 -1.981503e-07 -1.070989e-06 1 7.438032e-07 -1.011041e-06 1 7.021698e-07 -1.026092e-06 1 6.839068e-07 -8.579485e-07 1 -2.22491e-07 -7.20297e-05 1 -1.867939e-05 -8.740088e-05 1 -4.676377e-05 -0.0001123294 1 -3.11553e-05 -1.524725e-06 1 3.357917e-07 -1.808613e-06 1 1.117084e-06 -1.193756e-06 1 7.373194e-07 -6.421434e-07 1 1.401571e-06 0 1 0 0 1 0 -1.190283e-06 1 1.074051e-07 -1.472426e-06 1 -1.433239e-07 -1.649976e-06 1 3.087843e-09 0 1 0 -2.391076e-07 1 -1.277923e-06 -4.593754e-07 1 -2.020756e-07 -5.88309e-07 1 -2.587924e-07 -5.795908e-07 1 2.314816e-07 -0 1 0 7.348663e-05 1 1.802967e-05 6.156242e-05 1 -4.772636e-06 3.446854e-05 1 1.35648e-05 -1.099315e-06 1 1.266422e-06 -5.409312e-07 1 -3.475118e-07 -1.25392e-06 1 -8.055588e-07 -1.460932e-06 1 -3.06112e-07 0.4987945 -0.864732 -0.05867398 0 -0.999999 0.001401313 -0.441668 -0.8961889 -0.04213008 1 3.826723e-06 -4.191825e-06 1 0 0 1 -6.604206e-05 1.668411e-05 1 8.437311e-06 -2.010133e-06 1 1.071927e-05 -1.638137e-06 1 -3.853843e-06 6.3662e-06 1 2.86119e-06 3.244637e-05 1 3.040637e-06 -5.418469e-06 1 -2.399448e-07 3.953225e-06 1 1.315395e-05 2.772721e-06 1 -1.711667e-05 -3.608025e-06 1 1.310255e-05 -2.040945e-05 1 3.521574e-06 3.101445e-05 1 1.092025e-05 3.611358e-05 0.3675754 -0.9294288 -0.03241095 -0.03117401 -0.99949 0.006927768 9.536743e-07 -1 0 -1 1.400509e-05 2.439272e-08 -1 -8.307568e-06 3.553901e-06 -1 -2.004022e-05 -3.016031e-06 -1 -7.595851e-07 1.496322e-06 -1 7.120444e-06 2.480994e-05 -1 1.799898e-05 1.053606e-06 -1 0 0 -1 0 0 -1 -3.505344e-05 1.222665e-05 -1 -4.119247e-07 -1.692057e-05 -1 -8.076917e-07 -1.861668e-05 -1 1.205801e-05 1.456209e-05 -1 6.308795e-06 -8.690713e-06 -1 -2.10529e-06 -1.195612e-05 0.0001055502 0.9999985 0.001741702 0.0001701417 0.9999985 0.001748082 0.0002579426 0.9999984 0.001740993 0 -1 0 0 -1 0 1.689077e-06 -1 -6.026065e-07 2.874838e-06 -1 4.804147e-08 3.857465e-06 -1 -1.395735e-06 0 -1 -0 1.166635e-06 -1 1.439787e-06 1.009806e-06 -1 -6.368012e-07 0 -1 -0 0 -1 0 0 -1 -0 0 -1 0 -0 -1 0 0 -1 0 1.045644e-06 -1 5.743828e-07 1.255216e-06 -1 1.625622e-07 -0.4395691 0.8972198 -0.04213856 0.01086189 0.9999381 0.002414166 -1.907356e-06 1 0 1 -0.0001838029 -6.258105e-06 1 4.049798e-06 -2.002977e-06 1 -2.836432e-06 -6.35281e-06 1 -7.289598e-06 1.755794e-06 1 0 0 1 -0 0 1 9.642638e-07 1.102287e-05 1 2.583376e-06 4.083778e-06 1 -1.163039e-05 1.549106e-05 1 -1.219462e-05 1.808706e-05 1 7.118762e-07 1.040408e-05 1 6.598893e-06 1.450175e-06 1 1.423578e-05 -1.866718e-08 1 7.618623e-07 1.706357e-06 1 5.000402e-06 -1.078698e-05 -0.5002376 0.8639019 -0.05861595 0 0.9999982 0.001892221 -1 -2.894558e-05 -3.176912e-06 -1 0 -0 -1 -3.138984e-06 5.770061e-07 -1 -6.082306e-07 -2.277909e-06 -1 -7.643093e-07 -1.865823e-06 -1 -3.784633e-06 -9.239001e-06 -1 0 0 -1 0 0 -1 7.007519e-06 1.383438e-06 -1 -3.147815e-05 0.000121314 -1 -9.359633e-07 -2.274261e-06 -1 0 0 -1 0 0 0.0001051655 -0.999999 0.001419839 0.0001714674 -0.999999 0.001414514 -1.043273e-05 -0.999999 0.001447372 1 0 -0 1 0 0 1 4.025719e-05 -1.590034e-05 1 5.290299e-05 -8.388307e-05 1 7.817204e-05 -6.985455e-05 1 9.394594e-06 3.234995e-06 1 7.704729e-06 -2.898216e-07 1 0.0001375116 -5.172645e-06 1 2.470866e-05 7.855435e-05 1 0 0 1 -0 0 1 8.100377e-06 -1.249847e-05 1 9.205834e-06 -2.26048e-05 1 5.608214e-05 -1.478269e-05 1 2.260692e-05 5.084059e-06 1 2.25872e-05 4.982774e-06 1 0 0 1 2.745219e-06 -1.124039e-05 1 5.910837e-06 -2.143988e-06 1 1.041398e-05 -2.153703e-06 1 7.436719e-06 2.341146e-06 1 0 0 1 -2.462393e-06 1.621247e-06 1 -1.468461e-06 -1.986941e-05 1 7.602705e-06 -5.211964e-06 1 -0 0 1 0 0 1 -7.058395e-06 -3.431315e-06 1 -4.657956e-06 -3.668676e-06 1 2.54313e-06 0 1 2.54313e-06 0 1 9.463046e-07 -6.221949e-07 0.9993685 0.005791294 0.03505556 0.9995664 -0.0153896 0.02510368 -1 1.469543e-05 -1.851463e-05 -1 3.361898e-06 1.536511e-05 -1 7.820259e-06 1.482497e-05 -1 9.349633e-07 3.754659e-05 -1 0.0001296346 6.80438e-05 -1 0.0001529458 0.0001628567 -1 0.0001841463 0.0001516388 -1 1.01476e-05 -1.437127e-05 -1 6.877649e-06 -9.740285e-06 -1 6.794605e-05 -1.072684e-06 -1 8.46253e-05 -7.881563e-05 -1 -3.298544e-05 -1.281554e-05 -1 2.095814e-05 5.195716e-05 -1 -1.401179e-05 -5.854719e-05 -1 -4.360585e-05 -5.869686e-05 -1 -3.484329e-05 -2.564655e-05 -1 -3.770077e-05 -2.456552e-05 -1 -5.747241e-06 4.338984e-06 -1 2.31993e-05 -1.751473e-05 -1 1.188576e-05 1.30716e-05 -1 1.008803e-05 -4.875778e-06 -1 1.984876e-06 1.127249e-05 -1 1.81629e-05 2.186988e-05 -1 -1.309476e-05 -3.390155e-05 -1 -5.419169e-05 1.876566e-05 -1 2.513781e-05 -2.814302e-06 -1 -2.794048e-06 -1.32183e-05 -1 -1.569022e-05 3.081959e-05 -1 1.047078e-05 1.394836e-05 -1 -4.624082e-06 -6.159845e-06 -1 -4.742935e-06 -5.265647e-07 -1 -0 -0 -1 -1.867902e-05 -1.539755e-05 -1 -5.533315e-05 2.023981e-05 -0.999954 0.001186201 0.009510404 -1 0 0 -1 0 0 -1 1.06532e-05 4.150967e-06 -0.04128416 -0.02396248 0.9988601 -0.01668378 -0.01540045 0.9997422 0.07369513 0.06802642 0.994958 0.0614572 0.01626757 0.9979771 -0.03241214 -0.1165395 0.9926571 0.0229305 0.08244776 0.9963315 0.03867783 0.0370254 0.9985655 -0.0103886 0.009589453 0.9999 -0.9859098 -0.1654429 0.02470619 -0.9769085 0.05995004 -0.2050748 -0.9481212 -0.1193828 0.294642 -0.9725745 0.09080335 -0.2141345 -0.8269182 0.5520757 -0.1068584 -0.7996088 0.5991584 0.04043483 -0 0 1 0 0 1 0 0 1 -0.8297049 -0.5539525 0.06874843 -0.8463261 -0.5320525 -0.02554046 4.883852e-06 4.982212e-06 -1 2.84371e-06 -1.943003e-07 -1 2.270587e-06 1.293702e-07 -1 -0.9953979 0.03153984 0.09048938 -0.9969159 0.03475348 0.07036299 -0 3.57529e-07 1 -4.773322e-06 -1.019289e-07 1 -2.476162e-06 -3.350101e-06 1 -0.995465 -0.02933634 0.09049203 -0.9992598 -0.01939918 0.03322086 0 0 -1 0 0 -1 0.0002925237 0.9997771 0.0211115 -7.33437e-07 0.9997847 -0.02074768 -7.706458e-07 1 -1.284402e-08 -1.089463e-06 0.9997748 -0.02122285 0 0.9997748 -0.02122348 -6.379592e-07 0.9997748 -0.02122302 -9.536743e-07 1 0 -7.629395e-07 1 0 -7.629395e-07 1 0 -7.947286e-07 1 -5.298192e-08 -7.945576e-07 0.9997848 -0.02074785 -5.028986e-05 0.9997777 -0.02108585 0.03786732 0.9992828 -0 0.03786732 0.9992827 0 0.0390692 0.9992365 0.0001298426 0.0397839 0.9992083 0 -7.11663e-07 0.9997593 0.02194026 -2.723198e-07 1 2.866935e-07 -1.192329e-07 1 -5.743562e-07 -7.33595e-07 1 1.413968e-06 -1.401703e-06 1 -7.963764e-07 -6.437166e-07 1 6.658551e-08 -8.963764e-07 1 -1.493955e-08 -3.440157e-07 1 -2.386451e-07 -6.422385e-07 1 3.486254e-07 -7.876958e-07 1 -2.373618e-07 -1.31128e-06 1 0 -4.286354e-07 1 -6.257957e-07 -7.2248e-07 1 1.524784e-07 -1.401626e-06 1 -2.18736e-06 5.447287e-07 -0.9997721 -0.02135018 7.865355e-07 -1 0 5.447545e-07 -0.9998195 0.01899828 0 -0.9998195 0.01899796 9.267002e-07 -0.9998196 0.01899863 1.075156e-06 -1 -4.563339e-07 -0 -1 -0 0 -1 0 0.03837296 -0.9992635 0 0.03866626 -0.9992522 5.319014e-05 7.332042e-07 -0.9998195 0.01899809 7.745577e-07 -1 1.936397e-08 4.768374e-07 -1 -4.768368e-07 7.152557e-07 -1 0 7.334312e-07 -0.9997768 -0.02112895 7.151774e-07 -0.9997767 -0.021129 -2.23053e-05 -0.9997735 -0.02128634 9.575184e-07 -0.999772 -0.02135056 0 -0.999772 -0.02134985 7.223132e-07 -0.9997692 0.02148531 0.03915778 -0.999233 0 0.03915779 -0.9992331 0 0 -1 0 8.726488e-07 -1 5.762705e-07 3.625576e-07 -1 2.254958e-07 0.0002597753 -0.9997844 0.0207629 -0 -1 -0 9.526742e-07 -1 0 6.751001e-07 -1 -8.220191e-08 1.064534e-06 -1 -4.47037e-07 7.33595e-07 -1 1.862833e-07 9.441595e-07 -1 -5.658609e-07 1.094218e-06 -1 1.349706e-07 7.33595e-07 -1 5.965965e-07 2.312948e-07 -1 -1.140251e-06 -0.03658171 -0.0002481043 0.9993306 0 0 1 0 0 1 -0.01797297 -0.04532917 0.9988104 -0.01240687 -0.01977927 0.9997274 -0.01522564 -0.00426127 0.999875 -0.03275194 -0.000180292 0.9994635 -0.02614611 3.323436e-08 0.9996581 -0.01899735 -0.01628464 0.9996869 0.005630981 0.02867482 0.9995729 -0.009730402 0.002424783 0.9999497 -0.02336338 0.04755939 0.9985951 2.95377e-05 3.971381e-05 1 -7.711669e-07 6.016829e-07 1 0 -0 1 0 -0 1 0 0 1 0.005282631 0.02152157 0.9997544 -0.0002650253 -0.02212538 0.9997551 0.01129332 -0.02686375 0.9995753 0 0 1 0 0 1 0.007140167 0.002203146 0.999972 -1.594668e-05 0.0001558409 1 0 0 1 0 0 1 0.007868696 -0.0181329 0.9998046 -0.000188246 0.0276293 0.9996182 0.001905789 0.001689718 0.9999968 -0.002327327 0.04270086 0.9990851 0 0 1 -0 0 1 -1.559594e-06 -6.533367e-07 1 -1.203083e-06 5.138055e-08 1 -4.163327e-07 6.270455e-06 1 0.003002571 0.003807112 0.9999883 0.00248856 0.02301611 0.999732 0 0 1 -2.302733e-06 -2.846498e-06 1 0.004309203 0.002626302 0.9999872 -6.293852e-06 -3.861013e-05 1 -0.004193999 0.05057569 0.9987115 1.055502e-05 1.378167e-06 1 0.003746186 0.00334634 0.9999874 0.001968016 -0.02815395 0.9996016 1.752144e-05 7.339988e-06 1 2.723048e-06 -3.995177e-06 1 0.006977403 -0.002690164 0.999972 -0.0006658044 -0.00631101 0.9999799 0 0 1 -0.002846015 -0.04675465 0.9989024 4.408286e-06 -2.577124e-06 1 0.001638035 -0.01861085 0.9998255 0.00512257 -0.005234596 0.9999732 -0 0 1 -4.571865e-06 5.91856e-06 1 1.314771e-06 -5.044091e-07 -1 0 0 -1 0 -0 -1 0 0 -1 0 0 -1 -1.492924e-06 -5.36022e-07 -1 0 0 -1 8.937679e-07 -3.007756e-06 -1 0 0 -1 0 0 -1 0 0 -1 1.100673e-06 2.525024e-06 -1 0 0 -1 -0 0 -1 0 0 -1 0 0 -1 -0 -0 -1 0 0 -1 0 -0 -1 5.208108e-07 -1.100671e-06 -1 -1.061853e-06 -1.11789e-06 -1 0 0 -1 -1.035334e-07 1.705791e-06 -1 4.985483e-07 5.527973e-07 -1 4.069952e-08 1.675694e-06 -1 0.02861165 -0.9987585 -0.04077923 -0.6293836 -0.7755396 0.04913889 -0.7818151 -0.6205871 -0.06030629 -0.9645227 -0.2589428 0.05142626 -0.995867 0.06655788 -0.06179817 -0.8773495 0.4762553 0.05864178 -0.73365 0.6779698 -0.04598521 -0.381427 0.9235094 0.04054607 -0.1148138 0.9918674 -0.05492654 0.1749016 0.9833979 0.04835351 0.6240751 0.7800419 -0.04544127 0.7151952 0.6987244 0.01673457 0.984299 0.1764492 -0.004603538 0.9874433 0.1570125 -0.01739815 0.8188989 -0.5736339 0.0186748 0.7882933 -0.6150159 -0.01868187 0.1104095 -0.9937105 0.01868579 -0.1984723 -0.9783503 0.05864695 -0.4334508 -0.9000031 -0.04598902 -0.7713369 -0.6351343 0.04054315 -0.9147721 -0.400219 -0.05492488 -0.9915062 -0.1207384 0.04834981 -0.9040089 0.4237608 -0.05652253 -0.8489569 0.5279953 0.02220653 -0.1651468 0.986263 -0.003431302 -0.1728452 0.984943 0.003432603 0.6245661 0.7806562 -0.0222065 0.6912931 0.7216093 0.03733506 0.9758617 0.2166437 -0.02755924 0.9980249 0.008314197 0.06226771 0.9138826 -0.397472 -0.082672 0.6024736 -0.7915021 0.1027132 0.2839842 -0.9556788 -0.07766075 -0.2459211 -0.9691121 -0.01856498 -0.3876576 -0.9199955 0.05770531 -0.7274817 -0.6839857 -0.05416667 -0.9371551 -0.3439502 0.05864012 -0.9936388 -0.1027935 -0.04599342 -0.9452496 0.3238198 0.04054517 -0.8377182 0.5442822 -0.04455392 -0.5999093 0.7984131 0.05143217 -0.3385209 0.9395518 -0.05144016 0.1726163 0.9836251 0.05181856 0.2200015 0.9752849 0.02046349 0.7844366 0.6178343 -0.05422299 0.8909401 0.4494671 0.06484725 0.9816176 -0.1822948 -0.05652982 0.9546049 -0.2970462 0.02220412 0.4352223 -0.9003196 -0.002466156 0.4427504 -0.8966348 0.004260948 0.05896042 -0.9955082 -0.07407447 -0.1984722 -0.9783055 0.05939166 -0.6879893 -0.7242966 -0.04544469 -0.7718756 -0.6355537 0.01672613 -0.992661 -0.1208784 -0.003546979 -0.9979222 -0.04215106 -0.04873091 -0.8468987 0.5267284 0.07293621 -0.6524203 0.7538676 -0.07766134 -0.2221417 0.9732493 0.05864332 0.0242553 0.9986472 -0.0459943 0.4909552 0.8696553 0.05160245 0.6686039 0.7413574 -0.05794915 0.9555731 0.2900529 0.05243232 0.997529 0.04686379 -0.05234209 0.9534192 -0.2984718 0.04366138 0.7690028 -0.6364629 -0.05957935 0.5550216 -0.8291883 0.06631502 0 1 0 -5.745135e-07 1 1.410015e-08 -7.076534e-07 1 7.819479e-08 0 1 0 0 1 -0 0 1 0 -8.063525e-07 1 -5.312045e-08 -8.033618e-07 1 -4.83981e-08 0 1 0 -1.254582e-07 1 2.072542e-07 -5.481539e-08 1 2.667663e-07 0 1 0 0 1 -0 -6.004183e-07 5.315377e-07 -1 1.724501e-06 1.444964e-06 -1 1.5477e-06 -4.40503e-07 -1 -0 0 -1 0 0 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 0 -0 -1 0 0 -1 -0 -0 -1 0 -0 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 0 -0 -1 0 0 -1 -0 -0 -1 0 0 -1 -0 0 -1 0 0 -1 -0 0 -1 -0 -0 -1 0 0 -1 -0 0 -1 0 0 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 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.431832e-07 -9.181434e-07 -1 -3.01762e-06 -9.370273e-07 -1 1.760143e-08 8.153182e-07 -1 1.571248e-08 7.278235e-07 -1 1.869847e-06 -1.218781e-06 -1 -1.820862e-07 -2.006661e-06 -1 0 -0 -1 -0 0 -1 -1.483797e-06 -1.371404e-06 -1 -1.646541e-06 -1.320179e-06 -1 0 0 -1 -0 0 -1 -0 0 -1 -0.02272216 0.282198 -0.9590871 -0.2986604 0.004013581 -0.954351 -0.218229 -0.1466432 -0.964817 -0.06875165 -0.2845852 -0.9561823 0.1141445 -0.2457273 -0.962595 0.2429741 0.07686878 -0.9669824 0.166382 0.2607054 -0.950973 0.1799069 -0.1061842 -0.9779357 -0.1622058 -0.1567109 -0.9742336 0.1647288 -0.05055398 -0.9850425 -0.01953532 -0.005114144 -0.999796 -0.1179188 0.1620985 -0.9797037 -0.1944336 0.1590139 -0.9679412 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0 -0 -1 -0 0 -1 -0 0 -1 -0 0 -1 0 -0 -1 0 0 -1 -2.777099e-06 -5.882414e-07 -1 0 0 -1 -2.327908e-07 1.254215e-06 -1 1.873786e-06 1.373068e-06 -1 7.068206e-07 -1 1.514106e-08 1.412447e-06 -1 -2.144871e-07 1.600649e-06 -1 3.428809e-08 1.935471e-07 -1 -2.427609e-07 4.028199e-07 -1 -4.971669e-07 4.822881e-07 -1 -1.490146e-07 -1.009361e-06 -1 -1.312809e-06 1.24033e-06 -1 1.539072e-07 1.040347e-06 -1 2.283464e-07 1.137268e-07 -1 5.932316e-07 2.060034e-06 -1 -3.112837e-08 6.986978e-07 -1 2.338138e-07 0 -1 0 -0.2183364 0.0658356 -0.9736503 -0.3847729 -0.1191291 -0.9152912 -0.8128632 0.113965 -0.5711965 -0.9713939 -0.1116554 -0.2095872 -0.9910818 0.09192124 0.09647451 -0.844099 -0.1090585 0.5249792 -0.652362 0.08932262 0.7526255 -0.2220776 -0.06341114 0.9729648 -0.08718392 0.04379575 0.9952291 0.4407451 -0.0622302 0.8954725 0.6226048 0.08209875 0.7782179 0.8527477 -0.06850703 0.5178108 0.9863709 0.1057233 0.1260756 0.9860189 -0.1032733 -0.1307723 0.6690616 0.1011835 -0.736287 0.5553524 -0.07061722 -0.8286115 -0.3319448 -0.07645012 -0.9401957 -0.4338085 0.02188505 -0.9007393 -0.9074633 -0.02575768 -0.4193412 -0.9029744 -0.03698504 -0.4280998 -0.961114 0.08502083 0.2627378 -0.8547497 -0.154707 0.495448 -0.514483 0.1138108 0.8499144 -0.05595078 -0.09943341 0.99347 0.05202679 -0.002126339 0.9986434 0.6917335 0.03309022 0.7213944 0.7329405 -0.03600341 0.6793394 0.9948345 0.003878012 -0.1014362 0.9956342 -0.006681228 -0.09310237 0.6960944 0.02917674 -0.717357 0.553139 -0.1135928 -0.8253084 0.2003251 0.09707712 -0.9749081 -0.9944148 -0.07785463 0.07125881 -0.843285 0.5120431 -0.1633474 -0.6193147 0.7266127 0.2974613 -0.4386424 0.891155 -0.115912 0.1928776 0.9811695 -0.01023177 0.2496959 0.9599103 0.1273742 0.7622187 0.6386654 -0.1054945 0.8482185 0.4966542 0.1840107 0.9732906 0.01491904 -0.2290917 0.9535063 -0.2640821 0.1452116 0.783496 -0.6072196 -0.1319785 0.6796511 -0.7277614 0.09185711 0.2568099 -0.9618471 -0.09433303 0.07917781 -0.9824856 0.1686794 -0.2968558 -0.9371654 -0.1832961 -0.6384849 -0.7437981 0.1977405 -0.7954448 -0.5951852 -0.1141142 -0.9899055 -0.09336192 0.1066331 -0.4582503 -0.8867938 -0.06002942 -0.946362 -0.3166864 0.06409878 -0.9547812 -0.2970977 0.01121846 -0.8903854 0.4494343 -0.07226761 -0.8897949 0.4514012 -0.06709788 -0.4226356 0.8823289 0.2070622 -0.1945197 0.9448141 -0.2636063 0.4055971 0.8988228 0.1661581 0.5315201 0.840265 -0.1069634 0.8989131 0.4167628 0.135144 0.958914 0.1809645 -0.2184852 0.9674847 -0.1583682 0.1972126 0.7864066 -0.5761722 -0.2226886 0.5320811 -0.797922 0.2832142 0.2225029 -0.9476362 -0.2290807 -0.3610593 -0.917621 0.1661561 -0.7934411 0.5813345 0.1802812 -0.6020226 0.7839862 -0.1514413 0.6423686 0.757491 -0.1164898 0.9756411 0.2192385 -0.007674688 0.976903 0.1306894 0.1690584 0.9300362 -0.338653 -0.1426421 0.7837795 -0.585149 0.2080631 0.5564222 -0.8123987 -0.1743636 0.1090577 -0.9816384 0.1565008 0.03285285 -0.9994494 0.004656399 -0.6028873 -0.794799 -0.06943654 -0.6499553 -0.7567931 0.06944374 -0.9925262 -0.1215043 -0.01133322 -0.9679517 -0.1899041 0.1643345 -0.9470575 0.2837547 -0.1502174 0.4786272 0.8746632 0.07668256 0.8930022 0.4191156 -0.163979 0.3844458 -0.9099327 -0.15564 0.2297903 -0.9707831 0.06911339 -0.2643732 -0.9640898 -0.02525422 -0.3288993 -0.9297842 -0.1653077 -0.7688684 -0.5980821 0.2261396 -0.9167691 -0.284674 -0.2801698 -0.9897299 -0.009503422 0.1426341 -0.8458399 0.5280349 -0.07572272 -0.8318204 0.5421871 -0.1187763 -0.3239264 0.9328491 0.1576835 -0.1715617 0.9726293 -0.1567123 0.464917 0.8787664 0.1078046 -0.5219697 -0.8243415 -0.2191091 -0.6293956 -0.7681078 0.1177786 -0.895869 -0.4362589 0.08424334 -0.6527886 0.717337 0.2435048 -0.4221525 0.8698506 -0.2552394 -0.1644376 0.9607078 0.2236086 -0.09431724 -0.9809746 0.1696855 -0.234305 -0.9716803 -0.03063839 -0.535623 -0.8417987 0.06695567 -0.99729 0.03753209 -0.06327721 -0.908111 0.4164781 0.04336262 -0.1095492 0.9933286 -0.03601598 0.003900136 0.9999921 -0.00068803 0.904768 0.4255908 0.01635239 0.9606923 0.2760783 -0.02917134 0.7616889 -0.6472858 0.02917119 0.6947584 -0.7192422 0.001184182 -0.2018985 -0.9791536 -0.02225391 -0.6103907 -0.7908843 0.04387769 -0.8629912 -0.5040793 -0.03391537 -0.9086708 0.4167162 0.02578997 -0.8690482 0.4947256 0.001296754 -0.1133323 0.9935328 -0.006934814 0.06746546 0.9970449 0.03673989 0.8241997 0.563631 -0.0549087 0.9891278 0.1331451 0.06243906 0.7369525 -0.6743204 -0.04683089 0.4653193 -0.8846519 0.02947757 -0.9369097 0.3493911 0.01122815 -0.8848979 0.4652095 -0.0231465 -0.1435857 0.9896253 0.004989347 -0.137476 0.9904832 0.006581418 0.6544133 0.7561358 -0.001252972 0.7160349 0.697742 -0.02121486 0.9986884 -0.04219178 0.02900337 0.90758 -0.4181775 -0.03776515 0.6667303 -0.7449182 0.02382394 0.08865344 -0.9957206 -0.02609424 -0.1970676 -0.9800942 0.02407954 -0.7744946 -0.6319172 -0.02895789 -0.8759725 -0.4822288 0.01129847 0.05676817 -0.9983076 -0.01261917 -0.7331229 -0.6800022 -0.01129969 -0.884636 -0.4629225 0.05587324 -0.9677259 0.2469685 -0.05013165 -0.5446656 0.8362991 0.06279557 -0.1823817 0.9826246 -0.03443563 0.6667403 0.7449881 0.02121629 0.8063086 0.5908444 -0.02773521 0.9861929 -0.1609076 0.03914503 0.8407518 -0.5398707 -0.04094237 0.2660743 -0.9632664 0.03636259 -0.1362645 0.06223717 -0.9887156 -0.6090669 -0.03872292 -0.7921731 -0.7083507 0.05055325 -0.7040481 -0.918945 -0.06381378 -0.3891889 -0.9908119 0.1286063 -0.04185743 -0.9499242 -0.1072411 0.2935021 -0.6217942 0.07161366 0.7798996 -0.6541774 0.02576404 0.7559022 -0.02427555 -0.02188633 0.9994657 -0.00618653 -0.005577646 0.9999653 0.5576972 0.02786383 0.8295766 0.6306891 -0.05702687 0.7739374 0.9750073 0.05703249 0.2147281 0.9935306 -0.1069089 0.03830753 0.8759794 0.1139557 -0.4686942 0.6468719 -0.0962119 -0.756505 0.4169289 0.05351933 -0.907362 0.04989935 -0.06208321 -0.9968228 -0.002467526 -0.07077598 -0.9974892 -0.5880772 0.03975471 -0.8078271 -0.5562452 -0.005125737 -0.8310024 -0.9539301 0.02916573 -0.2986078 -0.9859644 -0.1136052 -0.1223441 -0.9607112 0.09707399 0.2600203 -0.6685233 -0.08545573 0.7387653 -0.58462 0.02733725 0.8108466 0.08724249 -0.02535775 0.9958643 0.1345005 0.01765217 0.9907563 0.6329476 -0.01594744 0.7740304 0.6677189 0.02001295 0.7441444 0.9838467 -0.0257563 0.1771504 0.9875889 -0.002386308 0.1570422 0.8061672 0.03487646 -0.590659 0.7285684 -0.08861032 -0.6792175 0.197935 0.09307218 -0.9757865 0 1 0 -0 1 0 0 1 0 2.817617e-07 1 -2.537486e-06 -9.839571e-07 1 -1.297936e-06 0 1 0 0 1 0 0 1 0 -3.667361e-06 1 -1.100745e-06 -3.662667e-06 1 4.85767e-07 -3.551162e-06 1 4.324699e-07 -3.619999e-06 1 1.323056e-06 0 1 0 0 1 -0 -1.118906e-06 1 7.053133e-07 -1.117151e-06 1 -2.337046e-07 -0 1 -0 0 1 0 -0 1 0 0 1 0 7.182929e-07 1 -3.310744e-06 -9.266079e-07 1 -1.73912e-06 0 1 0 0 1 0 -3.870702e-06 1 -1.227231e-06 -3.363978e-06 1 3.430011e-07 -3.551056e-06 1 4.32421e-07 -3.650021e-06 1 1.71162e-06 0 1 0 -7.068692e-07 1 -3.301983e-06 -1.447785e-06 1 -7.316431e-07 -0 1 -0 0.01468946 -0.03328966 -0.9993378 -0.0001029986 4.723515e-05 -1 -7.463472e-05 -9.670433e-05 -1 5.96446e-06 8.814634e-05 -1 0.03255349 -0.01511891 -0.9993557 -0 0 -1 0 0 -1 0.0001555413 6.546475e-05 -1 -4.657421e-05 -0.0001183669 -1 0.1612374 0.05395578 -0.9854397 0.06834764 0.004648207 -0.9976508 -0.0002464639 0.0001250334 -1 0.2091734 -0.03160769 -0.9773676 -0.000104141 4.776117e-05 -1 -0.0001161328 -8.622774e-05 -1 -4.658774e-05 -7.321844e-05 -1 0 0 -1 0 0 -1 -0.0002419626 0.0006568257 -0.9999997 0.0001221435 -0.0001037979 -1 -0.005190609 0.03428792 -0.9993985 6.407657e-05 -0.0007951005 -0.9999996 -0.001452162 0.2787852 -0.9603524 0.03771081 0.04393092 -0.9983225 0.0001358765 -0.0001454947 -1 0.000376435 -0.000104257 -0.9999999 -5.574277e-05 -3.068677e-05 -1 -9.851105e-06 -4.89934e-05 -1 0.0001863239 -0.0001730253 -1 0.0004474517 -1.890359e-05 -0.9999999 -0.003490262 -0.00174085 -0.9999924 0.0001714034 -0.000191504 -1 -0.002849105 -0.003291973 -0.9999906 -0.002277151 -0.005600849 -0.9999818 0 0 -1 -0.08325792 -0.01296805 -0.9964437 -0.006180928 0.001008482 -0.9999803 -0.009007254 0.03260887 -0.9994276 -0.01089754 -0.02412525 -0.9996496 -1.527496e-05 2.345371e-05 -1 -0.01640271 -0.01832771 -0.9996975 -0.02135935 -0.005633511 -0.999756 0 0 -1 -8.648638e-05 -8.156873e-06 -1 0 -0 -1 0 0 -1 0 0 -1 -7.425521e-05 0.0001550213 -1 0 -0 -1 -3.546215e-05 0.0002468796 -1 0 0 -1 -1.255009e-05 -0.0001599254 -1 0 0 -1 -0 0 -1 0 0 -1 -0.000163796 0.0001200093 -1 4.226679e-05 1.146393e-05 -1 5.250223e-05 7.023713e-06 -1 -0.0003441544 3.9387e-05 -0.9999999 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.004163875 -0.007870382 -0.9999604 -0.001725401 -0.01084454 -0.9999397 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.006493784 0.05187471 -0.9986325 -0.00621192 0.02624317 -0.9996362 0 0 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 -0 0 -1 -0 0 -1 0 0 -1 -7.654037e-05 -0.0003044372 -1 0.000915502 -0.0001538148 -0.9999996 -8.724756e-05 -2.228441e-05 -1 0 0 -1 -0.00671277 0.01558014 -0.9998561 0 0 -1 -0.0001227456 2.96456e-05 -1 -8.209096e-05 -1.188347e-05 -1 0.0006976933 -0.0003006734 -0.9999997 3.693877e-06 1.680221e-06 -1 2.798785e-07 6.67467e-07 -1 -2.798978e-07 -6.675131e-07 -1 -9.213474e-07 -2.657094e-07 -1 2.749931e-06 7.930587e-07 -1 3.650074e-06 -4.426978e-06 -1 -4.524901e-07 -8.527116e-07 -1 -9.501424e-07 -1.790531e-06 -1 -1.575992e-06 -8.432978e-07 -1 -1.566725e-06 -8.256388e-07 -1 -2.096675e-06 -3.802687e-07 -1 -1.64894e-06 -2.990641e-07 -1 -1.536678e-06 1.347345e-06 -1 1.0631e-06 -9.321162e-07 -1 6.645557e-07 -1.432078e-06 -1 4.752198e-07 3.415447e-06 -1 -1.514983e-07 -9.1849e-07 -1 7.019413e-07 -2.31528e-06 -1 -2.456575e-06 -4.764694e-06 -1 -7.262605e-07 6.169437e-08 -1 -1.700386e-06 1.444444e-07 -1 -1.574602e-06 2.971576e-07 -1 -2.707519e-07 -5.895635e-07 -1 0 -0 -1 0 0 -1 0 -0 -1 -0 0 -1 -0 -0 -1 -1.666323e-07 -2.283835e-06 -1 -5.266074e-06 -1.789e-06 -1 -8.360587e-07 1.354137e-06 -1 -0 0 -1 0 0 -1 1.208762e-06 3.839451e-07 -1 9.042849e-07 2.872326e-07 -1 2.475364e-06 -4.146692e-06 -1 -2.139896e-08 -1.842831e-06 -1 -8.179235e-07 -2.593382e-06 -1 -1.508752e-07 6.411305e-06 -1 7.370417e-06 1.752038e-06 -1 1.887887e-06 4.487739e-07 -1 1.994713e-06 1.406678e-07 -1 -2.021548e-06 -1.425602e-07 -1 -8.204857e-07 2.368824e-06 -1 -1.904263e-06 5.497796e-06 -1 -1.303502e-06 6.521717e-06 -1 -1.641632e-07 8.213456e-07 -1 2.841457e-06 2.255473e-06 -1 1.401675e-06 3.024156e-07 -1 0.08920195 -0.9951289 0.04197063 -0.5780446 -0.8120443 -0.08030226 -0.7629117 -0.6336039 0.1284987 -0.9584656 -0.2682617 -0.09684619 -0.9773044 0.184436 0.1042092 -0.9164746 0.3943776 -0.06738336 -0.5092515 0.858884 0.05459881 -0.4663562 0.8845897 0.003605344 0.2224078 0.9744347 -0.03180991 0.2543715 0.9671031 0.002591475 0.7540262 0.6553944 0.04361841 0.8463825 0.5263897 -0.08093478 0.9951746 0.06649312 0.07215316 0.9913191 -0.1206998 -0.05213318 0.8004952 -0.5976404 0.04509232 0.7520484 -0.6586196 -0.0253676 0.08086503 -0.9962305 0.03139451 -0.2458424 -0.9688708 -0.02916872 -0.3351285 -0.9410672 0.04562265 -0.7679662 -0.6384577 -0.0509876 -0.8237736 -0.5659158 0.03370867 -0.9915849 0.1294542 -0.0009587549 -0.9654971 0.2350888 -0.1120207 -0.7426987 0.6618624 0.1016694 -0.3634782 0.926783 -0.0946409 -0.1346704 0.986361 0.09463649 0.3536123 0.928425 -0.113954 0.706525 0.6961164 0.1274533 0.8620425 0.5023384 -0.06737082 0.9896004 -0.1306595 0.06015901 0.9769894 -0.2107926 -0.03252992 0.4622186 -0.8860909 0.03459492 0.4427475 -0.8966213 0.006700881 0.03270055 -0.9945866 -0.09863167 -0.3835403 -0.9123123 0.1434678 -0.6022958 -0.7940256 -0.08223805 -0.9758376 -0.2105398 0.05842735 -0.9868427 -0.1615217 0.007222528 -0.9069369 0.4204445 -0.02630107 -0.862996 0.5028808 0.04846402 -0.4109616 0.9097685 -0.05858261 -0.3287018 0.9437894 0.03488145 0.4141464 0.9102098 -0.0009547703 0.4303441 0.9024564 -0.0193987 0.8691675 0.4942027 0.01765321 0.8776522 0.4792934 0.002133506 0.9829941 -0.1808595 -0.03181872 0.9702212 -0.2401233 0.0318037 0.5313683 -0.8471144 -0.006707817 0.5866464 -0.8058796 0.0800251 -6.05677e-09 -1.146754e-06 -1 -1.172261e-06 2.205791e-06 -1 1.307254e-07 -9.364337e-07 -1 2.925475e-08 -1.442054e-06 -1 2.646079e-08 -1.304331e-06 -1 -8.060422e-07 1.784212e-06 -1 3.967127e-07 5.555576e-07 -1 1.929769e-06 -1 2.051644e-07 5.831797e-07 -1 -4.12151e-07 0 -1 0 3.426253e-07 -1 -1.833347e-06 1.678256e-06 -1 2.144186e-07 -6.117195e-07 -1 1.371597e-06 0 -1 0 -0 -1 0 0 -1 -0 -5.300287e-07 -1 -1.096631e-06 6.391875e-07 -1 -3.00538e-07 8.096033e-07 -1 -3.806655e-07 9.626945e-07 -1 -7.857468e-07 1.043166e-06 -1 -3.440011e-07 2.019576e-06 -1 -6.659888e-07 1.581151e-06 -1 6.679664e-08 1.922619e-06 -1 2.341192e-07 0 -1 -0 -0 -1 0 7.501201e-07 -1 -3.615646e-07 6.358134e-07 -1 -9.121949e-07 5.842806e-07 -1 -9.493533e-07 8.041857e-07 -1 -1.30666e-06 7.81107e-07 -1 -1.631842e-08 1.21517e-06 -1 -2.538659e-08 4.457846e-07 -1 7.078921e-07 0 -1 0 1.667308e-06 -1 -3.239387e-07 1.658061e-06 -1 -1.459508e-07 2.166065e-07 -1 -8.023854e-07 0 -1 0 4.676519e-07 -1 8.337158e-07 1.446809e-06 -1 1.081288e-07 1.407813e-06 -1 -2.550463e-07 -0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 -0 0 1 0 0 1 -0.2968752 0.1832998 -0.9371586 -0.6561082 -0.2234045 -0.7208416 -0.8190853 0.1956773 -0.5392678 -0.9805986 -0.1956652 -0.01188897 -0.9472426 0.2234209 0.229814 -0.7497084 -0.2081647 0.6281757 -0.4808605 0.2080729 0.8517505 -0.1898892 -0.1751237 0.966061 0.217974 0.2010007 0.9550319 0.4990266 -0.2627591 0.8257905 0.8164203 0.2750162 0.5077638 0.9580089 -0.270589 0.09487213 0.988169 0.09507869 -0.1203418 0.7719353 0.01058043 -0.635613 0.7253242 -0.1164734 -0.6784827 0.2568059 0.09434736 -0.9618468 0.07917117 -0.168675 -0.9824869 0.05871124 0.1187587 -0.9911858 -0.5113648 -0.1351455 -0.8486705 -0.7065417 0.258681 -0.658698 -0.8836595 -0.1633535 -0.4387043 -0.979178 0.08069567 0.1862761 -0.9699751 0.1307235 0.2050845 -0.6617273 -0.1351402 0.7374646 -0.4838271 0.1773355 0.8570085 -0.1030112 -0.2003545 0.974293 0.2145063 0.2658822 0.939837 0.700543 -0.2936192 0.6504055 0.8426861 0.1232724 0.5241031 0.9925452 0.01568 -0.1208647 0.964085 -0.1657427 -0.2075315 0.7424317 0.1615011 -0.6501634 0.5961546 -0.1426591 -0.7900938 0.07840134 0.07575995 -0.9940391 -0.4198053 -0.884227 -0.2047097 -0.2923921 -0.4006009 -0.8683466 -0.460566 0.01798164 -0.8874434 -0.3529059 0.2157952 -0.9104338 -0.7010601 0.6102021 -0.3690098 -0.2542805 0.4510763 -0.8554949 -0.3007944 0.5671178 -0.7667465 -0.1359545 0.8426142 -0.5210736 -0.008280339 0.4136495 -0.9103986 0.2942929 0.7329428 -0.6133406 0.5563905 0.7060971 -0.4380144 0.3059529 0.2944491 -0.9053687 0.772855 0.5258684 -0.3551866 0.7544827 0.2739059 -0.5964322 0.3912223 0.0912006 -0.9157662 0.5354681 -0.1096666 -0.837405 0.8875522 -0.3985763 -0.2310586 0.4569424 -0.321862 -0.8292216 0.3422272 -0.5330035 -0.7738138 0.2230176 -0.8984013 -0.3783363 -0.1651546 -0.9618708 -0.2180106 -0.377104 -0.8949351 0.2385028 -0.862449 -0.4724137 -0.1816783 -0.932381 -0.3421971 0.1164761 -0.9580454 0.261886 -0.116468 -0.9345927 0.3494267 0.06661528 -0.4575858 0.8890449 -0.01464263 -0.4895607 0.8671547 0.09150457 0.1607077 0.9733903 -0.1633536 0.4229263 0.8684606 0.2586688 0.6791708 0.7121673 -0.1776086 0.9416742 0.2858284 0.1776282 0.9658783 -0.01333343 -0.2586529 0.9254907 -0.319139 0.2040027 0.5781293 -0.7954687 -0.1816483 0.4286759 -0.8867705 0.1728439 -0.3558219 -0.9175117 0.1776599 -0.5213373 -0.8310828 -0.1936716 -0.8708839 -0.4659618 0.1563354 -0.9481738 -0.2968007 -0.1134709 -0.9718751 0.2140143 0.09826853 -0.965263 0.2612389 0.004650247 -0.6317418 0.7725587 -0.06368029 -0.5288064 0.8359383 0.1468707 -0.116274 0.9829254 -0.1426119 0.1162851 0.9829217 0.1426279 0.5045758 0.8538538 -0.1278163 0.64891 0.7486623 0.1357223 0.9276562 0.315145 -0.2003435 0.9751193 0.09492772 0.2003276 0.8841965 -0.440828 -0.1544904 0.8324665 -0.5510917 0.0574235 0.3798051 -0.9249305 -0.0158624 0.3302306 -0.9353177 -0.1269983 -0.02790338 -0.9909896 -0.1310005 -0.1906269 -0.947904 0.2552243 -0.7702112 -0.6113731 -0.1816527 -0.8512334 -0.5212523 0.06080856 -0.9987434 0.04861274 -0.01217693 -0.9895878 0.0963222 -0.1069487 -0.7172653 0.67606 0.1687407 -0.5646209 0.7858865 -0.2521619 0.05535273 0.9746993 0.216558 0.294499 0.9337653 -0.2033535 0.6633114 0.7210235 0.2003573 0.8416308 0.4904316 -0.2261289 0.9853483 -0.04163462 0.1653943 0.9778574 -0.1798858 -0.1069397 0.6573366 -0.7344686 0.1687142 0.5876236 -0.8072168 -0.05567386 6.675002e-07 2.924516e-06 1 6.460726e-07 2.981894e-06 1 4.632386e-07 2.138039e-06 1 -4.321722e-06 3.061666e-06 1 -1.330606e-06 -9.589871e-07 1 -1.528566e-06 -1.10166e-06 1 -6.061657e-06 -2.35676e-07 1 -5.119097e-06 -9.617414e-06 1 -1.083749e-06 4.289624e-08 1 -1.262185e-06 4.995899e-08 1 2.812591e-07 -3.566138e-06 1 1.555053e-06 -3.719214e-06 1 -3.672936e-06 8.784548e-06 1 -1.909762e-05 -2.553859e-06 1 4.002941e-06 5.352995e-07 1 1.184806e-06 2.212035e-06 1 1.937028e-06 3.616437e-06 1 -0.7406464 -0.2344656 -0.6296577 -0.4739377 -0.2700234 -0.8381351 -0.7763917 0.0009454403 -0.63025 -0.6561064 -0.001762075 -0.7546663 -0.593107 0.3048154 -0.7451923 -0.5436869 0.2945006 -0.7859224 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -0 1 -3.874408e-07 3.330872e-06 1 -4.573416e-06 1.730029e-06 1 -8.060876e-07 -9.735186e-07 1 -1.414722e-06 -1.708572e-06 1 -3.752842e-07 -1.847014e-06 1 5.516115e-07 2.714835e-06 1 -6.689806e-07 2.196173e-06 1 -7.422977e-06 2.436862e-05 1 -8.894668e-06 2.267929e-05 1 -1.712793e-06 1.57574e-05 1 -3.214251e-06 7.826378e-07 1 -9.403963e-08 9.345141e-07 1 4.924078e-06 -2.05841e-06 1 7.789843e-06 7.591551e-06 1 -1.697563e-06 1.892432e-06 1 0 -0 1 0 0 1 -1.59609e-06 -2.089206e-07 1 2.281915e-06 -3.205667e-06 1 4.203677e-06 -1.176481e-06 1 4.627915e-07 1.183903e-06 1 -5.758195e-07 -1.473049e-06 1 9.035992e-07 -1.329068e-06 1 -8.170319e-07 1.201739e-06 1 1.788683e-05 9.675768e-05 1 1.51619e-05 9.871711e-05 1 -8.737288e-07 4.658852e-06 1 -6.451988e-06 7.190733e-06 1 -5.539646e-06 8.050517e-07 1 -3.116927e-06 1.302968e-06 1 -0.9941876 -0.1069 -0.01278032 -0.9641566 0.1451349 0.222121 0.03025295 0.06945158 -0.9971265 -0.0585977 -0.1345225 -0.9891764 -0.6833782 0.1239701 -0.7194621 -0.7509092 -0.06082512 -0.6575984 -0.9925935 0.01219916 -0.1208691 -0.9935538 0.04782639 -0.1027793 -0.8480148 -0.05201904 0.5274135 -0.8385217 -0.007877653 0.5448111 -0.2510923 0.07224909 0.9652631 -0.1632047 -0.1530211 0.9746531 0.6399907 0.1631251 0.7508675 0.7099969 -0.08097392 0.6995338 0.9973388 0.005230099 -0.07271654 0.9940768 0.0562991 -0.09296052 0.6877502 -0.0520058 -0.7240822 0.6741789 -0.007863525 -0.7385262 -0.1687279 -0.1776028 -0.9695299 -0.3763987 0.1348391 -0.9165929 -0.6916547 -0.1164336 -0.7127811 -0.8258495 0.1381383 -0.5467086 -0.9745154 -0.1381451 -0.1767364 -0.992546 0.116428 0.03601419 -0.8912367 -0.1535787 0.4267444 -0.7941875 0.1667584 0.5843439 -0.2501573 -0.1269908 0.959841 -0.1731921 0.05201953 0.9835133 0.4909519 -0.0520161 0.8696324 0.533639 0.05969111 0.8436032 0.9698118 -0.06407358 0.2352863 0.976537 -0.01120258 0.2150577 0.8797774 0.06661184 -0.4706959 0.8637657 -0.007684219 -0.5038349 0.5024694 -0.07134598 -0.8616463 0.3545878 0.1956497 -0.9143241 -0.6016178 -0.2599096 0.7553166 -0.6923888 -0.3502581 0.6308067 -0.02147911 0.02829717 0.9993688 -0.7490677 0.4926654 0.4429204 -0.5585353 0.244841 0.7925221 -0.813218 0.5435546 -0.2079059 -0.8028883 0.5849945 -0.1146818 -0.4246936 0.6262091 -0.6538328 0.5444014 0.8383245 0.02896677 0 1 0 0 1 0 -1.123842e-06 1 -3.159902e-07 0.0198769 0.9997907 -0.004829917 0.04506757 0.9989838 0.0005464079 -8.015905e-07 1 4.173203e-07 0 1 -0 -6.531405e-07 1 2.406692e-06 -1.005439e-06 1 9.643858e-10 0.01401193 0.9998329 -0.0117405 0.005860028 0.9994739 -0.03189982 0.006026701 0.9995115 -0.03066664 0.5444014 0.8383245 0.02896579 0 1 0 0 1 0 0 1 0 -1.104795e-06 1 -6.602177e-07 0 1 0 -6.531405e-07 1 2.817895e-06 -1.21493e-06 1 -1.023199e-06 -9.104623e-07 1 1.800757e-07 0.01242169 0.9998271 -0.0138434 0.03242781 0.9994659 -0.00404429 0.005862769 0.9996803 -0.02459476 0.004058393 0.9992544 -0.03839427 0.02708759 0.9996197 -0.005153068 -1.604441e-07 1 -4.632006e-07 -1.300739e-06 1 -8.347597e-08 0 1 -0 -1.108372e-06 1 2.095473e-07 0 1 -0 0 1 0 -1.121969e-06 1 0 -7.529008e-07 1 1.045695e-07 -6.882186e-07 1 0 0.6286835 0.3416306 0.6986026 0.5893936 0.335147 0.7350453 0.6116246 0.3043635 -0.7302591 0.6832892 0.3777928 -0.6248108 0.9994642 -0.02980912 0.01351787 0.993507 -0.1097174 -0.0300972 0.9963435 0.07982515 -0.03045636 0.9575422 0.2865457 0.03169262 0.9408849 0.3385375 -0.01131212 0.8273963 0.5615045 -0.0113119 0.8037537 0.5944429 0.02485338 0.6177546 0.7859345 -0.02619395 0.5596927 0.828142 0.03041105 0.3330104 0.9419104 -0.04369161 0.2503411 0.9681067 0.009921591 0.1557322 0.9873392 -0.03014659 -0.08645403 0.9956989 0.03330573 -0.1583281 0.9870588 -0.0254411 -0.4376699 0.8986326 0.0300739 -0.4722088 0.881359 -0.01500799 -0.7541811 0.6564941 -0.01503919 -0.80208 0.5932238 0.06894359 -0.9250757 0.372571 -0.07365959 -0.9770851 0.2113367 -0.02532974 -0.9871942 0.1553018 0.03645241 -0.9936304 -0.1071541 -0.03487882 -0.9775027 -0.2106721 0.01028433 -0.9430342 -0.3269331 -0.06165478 -0.8515084 -0.5242991 -0.006624846 -0.8269016 -0.5609232 -0.03998677 -0.6983909 -0.715063 -0.03057763 -0.6277555 -0.7774588 0.03848223 -0.4279529 -0.9027068 -0.04446198 -0.3328953 -0.9421813 0.03840699 -0.07678736 -0.9964762 -0.03374809 6.315205e-07 -0.9995872 0.02872815 0.2424567 -0.9694316 -0.03764219 0.359364 -0.9311777 0.0613643 0.5788537 -0.8119378 -0.07540138 0.731124 -0.6816598 0.02824058 0.7653465 -0.6435196 -0.01127732 0.9319376 -0.3608601 0.03566911 0.912218 -0.409549 -0.01131083 0.756959 -0.4066648 0.5115045 0.5447537 -0.3812435 0.7469249 0.7934374 -0.4110377 -0.4488932 2.226333e-08 -0.03523898 -0.9993789 -0.01415091 -0.02905827 -0.9994776 0.01372506 -0.02666449 -0.9995501 -8.863015e-05 -0.0214038 -0.9997709 -0 -0 -1 0 -0 -1 0 0 -1 -6.878665e-07 -2.36043e-06 -1 -6.786439e-08 -4.37594e-07 -1 -0.01938856 -0.0412867 -0.9989591 0.002042059 -0.0007646907 -0.9999976 -0.01105707 -0.07999288 -0.9967341 6.458782e-07 4.672637e-06 -1 0.00734462 -0.01903125 -0.9997919 -0.0004210409 -0.01925964 -0.9998145 1.738376e-07 6.380086e-08 -1 3.820163e-08 -1.338022e-06 -1 3.105809e-07 7.18333e-07 -1 0.005422166 0.02696206 -0.9996218 -0.004372824 -0.0004266961 -0.9999903 0.001574218 -0.000103879 -0.9999987 1.585954e-07 -1.256156e-08 -1 0 0 -1 7.723522e-07 -7.699865e-07 -1 -1.388637e-06 4.788467e-07 -1 -0.0291587 0.001590066 -0.9995735 -0.007091837 -0.0021526 -0.9999725 0 -0 -1 0 0 -1 -3.327997e-05 -1.652981e-05 -1 -0.0001680878 0.02536445 -0.9996783 -0.03062905 0.0107001 -0.9994736 -0.0330478 0.001396392 -0.9994528 -0.03653706 0.000728232 -0.999332 -0.02400239 0.0003441871 -0.9997119 0 -0 -1 -8.799717e-06 4.29077e-06 -1 0 0 -1 -0.01375281 0.04276903 -0.9989903 -0.008716161 0.009738917 -0.9999146 -0 0 -1 9.111106e-07 7.578424e-07 -1 -1.054289e-06 5.099695e-07 -1 0.02509325 -0.003554866 -0.9996787 0.002725882 0.002014838 -0.9999942 -0 0 -1 0 -0 -1 0.0005324382 -0.000496416 -0.9999997 -0.0005881265 0.01223177 -0.999925 -0.001697069 0.0136334 -0.9999056 0.01162542 0.01719859 -0.9997845 0.005445817 0.02104855 -0.9997637 -0.004223939 0.04860689 -0.9988091 -1.490509e-07 7.25489e-09 -1 -0.005936677 0.05561978 -0.9984344 0.001937465 0.001186407 -0.9999975 -0.08152269 -0.1154117 -0.9899668 -0.5878567 -0.8088328 -0.01462876 -0.5811066 -0.8137835 0.008465632 -0.9841937 -0.1610897 -0.07357175 -0.9913465 -0.07011755 0.1109762 -0.903754 0.4189809 -0.08765659 -0.8030193 0.5688882 0.1775567 -0.3938099 0.8717166 -0.2915886 -0.08134375 0.9530856 0.2915663 0.4235971 0.8882819 -0.1775409 0.6398477 0.7393437 0.20968 0.8583357 0.4687413 -0.2086661 0.9803642 -0.06982572 0.1844191 0.9898148 -0.1205176 0.0757771 0.7640777 -0.6291589 -0.1426336 0.6180754 -0.7693522 0.1614935 0.1966479 -0.9694144 -0.1468521 0.07846551 -0.9948789 0.063712 -0.9407961 -0.3381419 -0.02372448 -0.8569497 -0.5152283 0.01330398 -0.7645824 -0.6443139 -0.01653345 -0.8810981 0.4697638 -0.05466322 -0.3605201 0.929454 -0.07836085 -0.523079 0.8287665 0.1988328 -0.8201757 0.5328988 -0.2081604 -0.9537541 0.1799988 0.2407354 -0.9869656 -0.07446943 -0.1426648 -0.7979906 -0.5978931 0.07572927 -0.8241436 -0.5661587 -0.01586159 -0.3633446 -0.929881 0.05746249 -0.3014753 -0.9517421 -0.05744067 0.2579317 -0.9660861 0.01219981 0.3287672 -0.929812 0.1654144 0.7823111 -0.573173 -0.2438485 0.9142874 -0.3458561 0.2108603 0.9845158 0.1285383 -0.1191919 0.9625089 0.2604912 0.07563622 0.7243662 0.6783437 -0.1230588 0.6298887 0.7703019 0.09937301 0.1196827 0.99281 -0.002070266 0.1277771 0.991695 0.01462852 -0.1616949 0.9809875 0.1073228 -0.3358604 0.9355679 -0.1091349 -0.661008 0.7366927 0.142661 -0.8255963 0.5363964 -0.1751277 -0.9661504 0.1234808 0.2265082 -0.9795949 -0.1013365 -0.1735647 -0.7069472 -0.7026479 0.08069443 -0.7150282 -0.6968271 0.05627184 -0.05067523 -0.9971285 -0.0562749 -0.06037954 -0.994909 -0.08068692 0.5711179 -0.8023145 0.173539 0.7069657 -0.6942139 -0.1351539 0.9698927 -0.2279136 0.08581141 0.9629666 -0.2695051 -0.00788947 0.91652 0.394403 0.06661334 0.8517284 0.4946573 -0.1728379 0.4580809 0.8699199 0.1827604 0.2464612 0.9557697 -0.1605033 -0.8312864 -0.555644 0.0149254 -0.8426559 -0.535986 -0.05147847 -0.1448178 -0.9622474 0.2304513 -0.5348088 -0.7989622 -0.2750252 -0.818324 -0.5362241 0.2069046 -0.9537732 -0.2053031 -0.2194708 -0.9760454 0.07563962 0.203995 -0.7810431 0.6027225 -0.163393 -0.6624652 0.7345613 0.1468317 -0.2807493 0.9491205 -0.1426535 0.03309946 0.9699428 0.241071 0.3216639 0.9286513 -0.1847674 0.8007379 0.5953107 0.0665127 0.8120288 0.5653289 0.1449568 0.9848065 -0.1215952 -0.1239785 0.9488907 -0.2640597 0.1728555 0.6869255 -0.7079527 -0.1641228 0.4797963 -0.8638554 0.1534582 0.1693976 -0.973528 -0.1534524 -0.03282014 -0.9985034 0.04374587 -0.07858134 -0.9962981 -0.03485484 -0.9789681 -0.1298283 -0.1573717 -0.8586261 0.498659 0.118746 -0.7973544 0.5899982 -0.1269961 -0.2189769 0.959421 0.1776528 -0.06384096 0.9886591 -0.1359315 0.489235 0.8665995 0.09825721 0.5324322 0.8464596 0.004681069 0.9445599 0.3209079 -0.0694607 0.9568723 0.2904538 0.00566555 0.9500178 -0.2973754 0.09504777 0.9010077 -0.4155154 -0.1246284 0.5777494 -0.8115936 0.08672687 0.5156639 -0.8556727 -0.04376041 -0.03229561 -0.9825256 0.1833041 -0.3760189 -0.9156914 -0.1418418 -0.5617706 -0.8201575 0.1084218 -0.8390599 -0.5195142 -0.161504 -0.1434619 0.9788063 -0.1461396 0.4617687 0.8790156 0.1187484 0.5087242 0.8608934 0.007885101 0.9445612 0.3208982 -0.06948712 0.9622834 0.2630398 0.06943144 0.9151434 -0.4031015 -0.004651121 0.8906062 -0.4440194 -0.09832287 0.5512329 -0.8266043 0.1134359 0.3544337 -0.9138908 -0.1979403 0.5444146 -0.8383237 -0.02874367 0.03044319 -0.9995257 0.00465871 4.019919e-07 -1 -1.075732e-07 5.505218e-07 -1 2.316143e-07 0.03529546 -0.9993702 0.003651179 8.359884e-07 -1 1.27931e-07 8.791416e-07 -1 1.846213e-07 9.544798e-07 -1 1.465825e-06 0.006341819 -0.999121 0.04143809 0.01346226 -0.999809 0.01417237 0 -1 0 0 -1 0 6.531406e-07 -1 -1.505535e-06 0.5444146 -0.8383237 -0.02874367 0.009391839 -0.9996943 0.0228692 0.006340806 -0.9989613 0.04512439 0.01714921 -0.9997885 0.01135193 4.308412e-07 -1 -2.527939e-07 0.03887642 -0.9992355 0.004126133 0 -1 0 7.399968e-07 -1 1.489263e-07 9.32213e-07 -1 4.845108e-07 6.531405e-07 -1 -1.359031e-06 -0 -1 0 0 -1 0 8.855682e-07 -1 1.644339e-07 5.990349e-07 -1 -1.639079e-07 1.602602e-06 -1 -3.789718e-07 1.612066e-06 -1 -3.844867e-07 1.621042e-06 -1 1.083571e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 7.865356e-07 -1 0 7.529008e-07 -1 5.437626e-08 5.609846e-07 -1 0 0 0 -1 0 0 -1 0 0 -1 -9.007043e-06 -7.058847e-06 -1 -2.835579e-05 2.098172e-05 -1 1.676052e-05 3.574819e-06 -1 6.131762e-06 -1.70701e-05 -1 -0 0 -1 -1.023938e-05 -4.261637e-06 -1 -9.633523e-06 -6.180073e-07 -1 -0 -0 -1 6.70934e-06 5.439495e-06 -1 5.410524e-05 -3.740391e-05 -1 2.337824e-05 -4.843913e-05 -1 1.20673e-05 4.765995e-06 -1 0 0 -1 0 0 -1 8.851895e-06 -1.829158e-05 -1 0 0 -1 0 0 -1 -2.888384e-05 -2.513551e-05 -1 -3.493758e-05 -1.163484e-05 -1 -1.438208e-05 -1.227458e-05 -1 4.757123e-06 4.060032e-06 -1 -6.380095e-06 1.760307e-05 -1 -1.843681e-05 1.721696e-05 -1 4.211106e-06 -1.615662e-05 -1 -1.704137e-05 -2.552139e-05 -1 -1.734749e-05 -1.780846e-05 -1 -9.404106e-06 -1.534278e-05 -1 0 0 -1 -0 0 -1 0 0 -1 8.744952e-06 -1.82859e-05 -1 1.322136e-05 -9.262447e-06 -1 2.580723e-05 -6.908287e-06 -1 2.489145e-05 -4.639565e-06 -1 -9.37449e-06 1.747329e-06 -1 -7.211216e-06 1.039574e-05 -1 -0 0 -1 1.070345e-05 7.051432e-06 -1 1.13795e-05 1.111716e-05 -1 1.47708e-05 1.029068e-05 -1 0 0 -1 5.084349e-07 -8.026024e-06 -1 9.257344e-06 -1.581334e-05 -1 1.292137e-05 -1.357198e-05 -1 1.176703e-05 -2.727483e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8883861 -0.4586631 0.01996073 -0.8417751 -0.539753 -0.009030946 -0.8335662 0.5510795 0.03845654 -0.8209049 0.5693731 0.04392421 -0.9975417 0.03615343 0.06002998 -0.9980493 0.01548449 -0.0604795 1 1.271565e-06 0 1 1.271565e-06 0 0 -0 -1 0 -0 -1 -0.5397329 0.8409483 0.03865792 -0.5733243 0.8190144 -0.02268619 -0 0 1 0 0 1 0 0 1 0.9811096 0.1904387 -0.03401702 1 8.898277e-07 -0 0 -0 -1 -0 0 -1 -0.9977853 0.06651764 0 -0 0 1 0 0 1 0 0 1 0.9811099 0.1904375 -0.0340168 1 8.898277e-07 -0 0 -0 -1 -0 0 -1 -1 -1.112619e-06 -0 -1 -1.112619e-06 0 -0.002442773 -0.1340809 -0.9909673 -0.215848 0.1638984 -0.9625731 -0.5610602 -0.1193056 -0.8191323 -0.837277 0.1829318 -0.5152701 -0.9420493 -0.1787699 -0.2838742 -0.9172491 0.1607758 0.3644245 -0.8775039 -0.05561065 0.4763342 -0.3817508 0.003708175 0.9242578 -0.3363213 0.07875919 0.9384481 0.2022419 -0.09997793 0.974219 0.3263515 0.07618554 0.9421733 0.8025031 0.004547172 0.5966306 0.8203827 -0.0556265 0.5691027 0.9946729 0.006315151 -0.1028882 0.9916005 0.04165199 -0.1224482 0.6881003 -0.04163612 -0.72442 0.6247783 0.1018964 -0.7741247 0 -0 -1 0 0 -1 0.4210129 0.6160641 -0.6657426 0.882031 0.4711913 -0.0001483133 0.8870146 0.4617412 0.000322572 0.5436575 -0.006891489 -0.8392789 0.7176673 0.0003842389 -0.696386 0.9593083 0.007781372 -0.2822535 0.5823488 -0.004775947 -0.812925 0.8802392 -0.4745302 -0.000167889 0.8858911 -0.4638928 -0.0007088004 0.1995842 -0.2744785 -0.9406528 -0.5443974 -0.8384928 -0.02369177 -0.5507647 -0.8345473 -0.01374523 0 0 1 -4.973302e-06 -3.21484e-07 1 -4.01478e-06 1.837768e-06 1 7.376092e-06 -3.376411e-06 1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.9997981 -0.01727485 -0.01026718 -0.9920886 -0.03603197 -0.1202574 0 -0 1 0 -0 1 0 0 -1 0 0 -1 0 0 -1 0.9813155 -0.1894077 0.03383286 1 8.898357e-07 0 0 -0 1 0 0 1 -0.9998611 -6.356946e-07 -0.01666434 -0.9977851 -0.06651957 0 0 0 -1 0 0 -1 0 0 -1 0.9813154 -0.1894077 0.03383286 1 8.898356e-07 0 0 -0 1 0 0 1 -1 -6.357828e-07 -0 -1 -6.357828e-07 0 -0.41631 -0.07619084 -0.9060248 -0.571593 0.1803612 -0.8004693 -0.878884 -0.1885702 -0.4381828 -0.9702206 0.2210987 -0.09893133 -0.9287137 -0.194772 0.3155228 -0.6947019 0.2211246 0.6844656 -0.5297297 -0.1010733 0.8421227 0.00618892 -0.04782901 0.9988363 0.1617464 0.2014538 0.9660509 0.6203915 -0.1885471 0.7612913 0.8339249 0.1885578 0.5186668 0.9825578 -0.1594822 0.09563246 0.9885519 0.09097505 -0.1203686 0.7988293 -0.07875716 -0.5963801 0.7719584 -0.003704947 -0.6356622 0.1984892 0.05561571 -0.9785239 0.1665485 -0.00452981 -0.9860228 0 0 -1 0 0 -1 1 0 0 0.9610301 -0.2745812 -0.03203443 -0 0 1 0 0 1 -0.9899496 -0.1414208 0 -0.0002332154 -0.9948263 -0.1015893 -0.2532852 -0.9574247 0.1385088 -0.7769333 -0.6167097 -0.1266636 -0.9225973 -0.3709949 0.1057209 -0.996994 0.03619236 -0.06850617 -0.9444399 0.3235112 0.05808363 -0.821716 0.5669264 -0.05811437 -0.5987234 0.7968856 0.08064509 -0.3086951 0.9462184 -0.0968404 0.1144926 0.9891628 0.09191544 0.355012 0.9320717 -0.07217108 0.7696449 0.6321163 0.08986563 0.8479499 0.5293692 -0.02737183 0.9974519 -0.0399223 -0.05912606 0.9725429 -0.2093749 0.1015988 0.6933975 -0.717019 -0.07129946 0.5548275 -0.8289061 0.07128166 0.06056648 -0.9979244 -0.02187707 -0.5395765 -0.8416523 0.02187568 -0.5797886 -0.814473 -0.02188268 -0.9485461 -0.315883 0.02187091 -0.9747422 -0.2098387 -0.07645592 -0.9076904 0.4012201 0.1229658 -0.7447807 0.6503361 -0.1495481 -0.2505645 0.9613329 0.1142652 -0.004477295 0.9967098 -0.08093031 0.5151004 0.8524054 0.08986999 0.6674634 0.7400866 -0.08224711 0.9865413 0.1546844 0.05299783 0.9972482 0.016673 -0.07223701 0.8579023 -0.5043553 0.09812901 0.6906334 -0.7141333 -0.1141898 0.1687342 -0.9826919 0.07645485 -0.1362323 -0.9884934 -0.06573857 -0.3858365 -0.9156621 0.1126643 -0.6852051 -0.7238693 -0.08066779 -0.9458364 -0.3165071 0.07222711 -0.9700963 -0.2427109 0.002128736 -0.9297955 0.3669192 -0.0291664 -0.8768458 0.4759759 0.06773809 -0.5856153 0.8079202 -0.06572381 -0.3809012 0.9222755 0.06574203 0.05442082 0.9962192 -0.06771768 0.175036 0.9841297 0.02917552 0.7153023 0.6988118 -0.002127859 0.7827445 0.6143509 -0.09941895 0.9737645 0.2035826 0.1016698 0.9518211 -0.2874181 -0.1068988 0.9031721 -0.4281926 0.03051668 0.4078085 -0.913053 -0.005117932 0.4430881 -0.8955964 0.03974927 -0.5420701 -0.8402632 0.01085007 -0.5492668 -0.8353472 0.02238013 -0.999998 0.00103054 0.001717482 -0.999967 0.008122027 0.0002542006 -0.9999719 0.007503115 0 -1 -1.105709e-06 -0 -1 -1.105709e-06 0 -0.9989387 0.04462843 -0.01139575 -0.9993801 0.007581968 -0.034379 -0.9999069 -0.001865678 -0.01352042 -0.9999582 -1.105814e-06 -0.009146016 -0.9983644 0.04773333 0.03146325 -0.8270302 -0.1849734 -0.530854 -0.9989623 -0.006891245 0.04502031 -0.9999914 0.0008469475 -0.004059615 -0.9997516 -0.004048867 0.02191521 -0.9987497 0.008078795 0.04933289 -0.9999883 0.004259537 0.00226698 -0.9995871 -1.105253e-06 0.02873433 -1 -1.105709e-06 -0 -1 -1.105709e-06 0 -1 -1.105709e-06 -0 -0.9999731 -0.006407013 0.003564579 -0.9999965 -1.105705e-06 -0.002625988 -0.9999648 -0.008352811 0.0007976478 -0.5365846 0.8435267 0.02323127 -0.5618546 0.8270496 -0.01755975 0.5375758 0.8432153 -0.0001044237 0.5394401 0.842024 0.0002640927 1 0.0001361427 -8.409794e-06 0.9999999 0.0003328279 -0.0001306774 0.5416854 -0.8405811 -0.0005994014 0.5379586 -0.8429713 0.0001419863 0 -0 1 0 0 1 -1.370726e-05 -1.712153e-05 1 -1.615538e-05 6.935055e-06 1 0 0 1 9.283734e-06 1.211525e-06 1 1.612182e-05 -3.8572e-05 1 -3.878015e-09 -1.654244e-05 1 -6.496089e-05 -8.747935e-05 1 -6.410102e-05 -4.224578e-05 1 2.72449e-06 -2.932088e-05 1 5.496278e-05 -5.462824e-05 1 2.852522e-05 -1.218946e-06 1 6.254322e-06 -1.644503e-05 1 1.817727e-07 -4.364923e-05 1 0 0 1 1.94401e-05 -8.799706e-06 1 7.409902e-06 2.05652e-05 1 7.986455e-06 1.121918e-05 1 1.829801e-05 1.262466e-05 1 1.020111e-05 -2.966914e-06 1 0 0 1 3.348183e-06 3.197702e-06 1 1.382051e-05 -1.369644e-05 1 0 -0 1 0 0 1 0 -0 1 -1.344738e-05 -5.293125e-06 1 -1.755233e-05 1.382456e-05 1 3.09352e-06 4.909458e-06 1 -0 0 1 -6.968784e-06 1.031511e-05 1 -5.554829e-06 -1.829037e-05 1 0 0 1 -0 0 1 0 -0 1 0 0 1 1.06614e-05 -2.271299e-06 1 1.254021e-05 -3.786723e-06 1 1.153269e-05 -5.102695e-06 1 -1.359963e-05 -1.067391e-05 1 -2.678505e-05 5.759321e-06 1 4.216762e-05 4.378074e-05 1 5.308285e-05 1.109589e-05 1 -1.347144e-05 -1.450988e-05 1 0 0 1 -8.065607e-06 1.047869e-05 1 -7.700089e-06 2.697604e-05 1 -3.742489e-05 2.414219e-05 1 -2.388556e-06 -9.471155e-06 1 -6.435048e-06 -2.551637e-05 1 -0.3898765 -0.5700011 0.7232531 -0.7382705 0.0006114902 0.6745045 -0.7068012 0.001288818 0.707411 -0.3506787 0.5100235 0.7854301 -0.01503708 0.03912535 0.9991211 0.4169647 0.6100857 0.6737477 0.6893277 -0.0008147476 0.7244492 0.6682747 -0.0003646323 0.7439145 0.1655104 -0.0002497462 0.986208 0.4619016 -0.6837212 0.5649533 -0.04889619 0.9618918 0.2690226 -0.3674196 0.8739917 -0.3180276 -0.6908897 0.6866845 0.2261322 -0.9640482 0.2079928 -0.1653784 -0.9935541 0.1027635 0.04785276 -0.8630227 -0.5028959 -0.04782866 -0.8546935 -0.5189899 -0.01218839 -0.4133787 -0.9085261 0.06081397 -0.3263657 -0.9370782 -0.1239744 0.381565 -0.9129074 0.1449426 0.4393416 -0.8983071 -0.004820372 0.9119673 -0.3924437 -0.1195981 0.9459656 -0.2077348 0.2489882 0.9418966 0.2636129 -0.2081806 0.7401268 0.6146933 0.2726984 0.5117899 0.815905 -0.2690168 0.02973432 0.9802169 0.1956802 -0.5477794 0.8036864 -0.2324344 -0.6975252 0.6912637 0.1887143 -0.9910001 0.04232306 -0.1269946 -0.9998462 -0.007565628 -0.01582186 -0.8217404 -0.5669575 0.05746107 -0.7622045 -0.6386797 -0.1055116 -0.3374671 -0.9365951 0.09436911 -0.1912947 -0.973175 -0.1278159 0.2177895 -0.9655167 0.1426366 0.4591402 -0.8709356 -0.1751044 0.7695504 -0.6061128 0.2010456 0.9062219 -0.3594114 -0.2226778 0.9675406 0.119471 0.2226925 0.8776374 0.4145017 -0.2407095 0.6594332 0.7223577 0.2081999 0.2698241 0.9366287 -0.2234315 -0.08791195 0.9806554 -0.1748898 -0.2985127 0.9341375 0.195646 -0.7701505 0.6008903 -0.2140074 -0.8797934 0.4485471 0.1573821 -0.9870562 -0.1288801 -0.09544615 -0.9782504 -0.2044834 0.03482547 -0.7461117 -0.6649061 -0.03488742 -0.6905472 -0.716964 0.09543224 -0.1908112 -0.9706898 -0.1461247 0.05413817 -0.9611689 0.2705982 0.451856 -0.8584535 -0.2426596 0.8369993 -0.4851565 0.2530914 0.9268698 -0.3675835 -0.07612351 0.926967 0.3751371 0.002071394 0.9022595 0.4169377 0.1099575 0.5512482 0.8265879 -0.113481 0.3848602 0.9096414 0.1563175 1.931578e-05 -2.934369e-06 1 0 0 1 2.012067e-06 2.194458e-05 1 2.046495e-05 1.020313e-05 1 0 -0 1 -2.40095e-05 -3.018469e-05 1 -2.113482e-05 1.445478e-05 1 0 0 1 -0 0 1 -1.401343e-05 1.796571e-05 1 -4.019508e-06 2.22219e-05 1 -6.786016e-06 -6.513576e-08 1 0 0 1 0 0 1 0 -0 1 -1.323409e-05 -4.035473e-06 1 1.7254e-05 2.401569e-05 1 0.09094796 -0.9955842 -0.02324695 0.1662227 -0.9840227 0.06379107 0.6912946 -0.7148121 -0.1056204 0.7968304 -0.5948957 0.1056424 0.9966968 0.01665705 -0.07948657 0.9945059 0.09680493 0.03983701 0.6691972 0.7420163 -0.03983775 0.5789617 0.8058516 0.1241231 0.02399576 0.9879459 -0.1529286 -0.3233841 0.9267913 0.1909991 -0.5842056 0.8059511 -0.09563909 -0.9289899 0.3666346 0.050566 -0.9342167 0.3477371 0.07948679 -0.9494972 -0.295457 -0.1056424 -0.8899329 -0.4436905 0.1056319 -0.4845548 -0.8724312 -0.06380082 -0.4174193 -0.9084165 0.02325008 0 0 1 -6.068489e-06 -1.270053e-05 1 9.620661e-06 2.013475e-05 1 1.360734e-05 1.515286e-05 1 1.60657e-05 1.661248e-05 1 2.353897e-05 6.276756e-06 1 -1.8863e-05 -5.029892e-06 1 0 0 1 3.079642e-05 -4.997704e-05 1 3.361563e-05 -2.764806e-05 1 -1.806622e-05 -1.181101e-05 1 2.834989e-05 -1.343985e-05 1 -5.059437e-06 -1.413241e-05 1 -2.857407e-05 -6.888415e-06 1 5.656672e-06 1.420146e-05 1 1.34847e-05 -1.246171e-05 1 1.359763e-05 -2.633826e-05 1 -0.09088331 -0.9949535 0.04251749 0.03017317 -0.994681 -0.09848471 0.4566388 -0.8844976 0.09562998 0.6504344 -0.753519 -0.09562489 0.9002848 -0.4267984 0.08561839 0.9560613 -0.286307 -0.0630484 0.9697274 0.2337744 0.07055819 0.9343357 0.3493418 -0.07054793 0.5577381 0.8256218 0.0853049 0.508743 0.8608915 -0.006817596 -0.2017893 0.9757317 -0.08502185 -0.2715172 0.9618226 0.03428697 -0.7812477 0.6184986 0.0843292 -0.8822781 0.4450938 -0.1532217 -0.9907005 -0.01201212 0.1355297 -0.9656578 -0.241574 -0.09564087 -0.6652184 -0.7443988 0.05792161 -0.6951586 -0.7188175 -0.007471166 -8.763514e-06 1.933132e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.584744e-06 -9.272651e-06 1 -2.64873e-05 1.268272e-05 1 9.482877e-07 1.575701e-05 1 0 0 1 -1.015962e-05 1.694645e-05 1 1.55488e-05 2.573057e-05 1 2.060502e-05 4.107597e-05 1 4.330091e-05 -5.053007e-06 1 -2.215667e-05 2.585576e-06 1 -1.820646e-05 4.927444e-06 1 -2.678652e-05 1.999791e-05 1 -1.005695e-05 1.399352e-05 1 0.1383512 -0.9854738 0.09848998 0.2847563 -0.9556 -0.07577921 0.7985537 -0.5961732 0.08300268 0.8750742 -0.4698326 -0.1162004 0.9810517 0.1258544 0.147303 0.9248648 0.3442659 -0.1615738 0.5133166 0.8494501 0.122232 0.3548822 0.9276618 -0.1161992 -0.2494508 0.9571198 0.1472963 -0.435979 0.8914436 -0.1234933 -0.9378575 0.3401861 0.06853271 -0.8944386 0.4282775 -0.1286777 -0.9661947 -0.2057344 0.155374 -0.8368172 -0.5149802 -0.1858291 -0.5581155 -0.8177995 0.140396 -0.3005936 -0.948945 -0.09563883 3.211042e-05 -1.077105e-05 1 0 0 1 7.462845e-06 -7.812634e-06 1 1.242848e-05 -6.626609e-05 1 5.634086e-06 -1.129931e-06 1 2.348597e-05 -1.563672e-05 1 -0.0001100069 -5.343418e-05 1 -6.713343e-05 -9.973494e-05 1 1.762557e-05 -3.534857e-06 1 2.38076e-05 -1.742921e-05 1 -2.681789e-05 4.872852e-07 1 -1.102998e-05 1.611418e-05 1 1.463309e-05 -2.137812e-05 1 1.5336e-05 -2.059791e-05 1 -8.116109e-06 1.090081e-05 1 9.749343e-07 2.054218e-05 1 -7.401813e-07 -1.559586e-05 1 -1.628291e-05 -1.421073e-05 1 0.1710772 -0.9831908 -0.06378502 0.3306851 -0.935232 0.1264452 0.6887769 -0.7098266 -0.1474193 0.936664 -0.3221868 0.1373182 0.9862238 -0.09222946 -0.1373184 0.8910072 0.4158424 0.1821572 0.6555848 0.724479 -0.2129289 0.3331388 0.9295458 0.1579972 -0.1419286 0.9782824 -0.1510627 -0.3266466 0.9430085 0.06353689 -0.7840062 0.6207129 0.007056192 -0.8432696 0.514687 -0.154899 -0.9861333 0.01791819 0.1649847 -0.9288412 -0.3431751 -0.1395885 -0.8052101 -0.5878494 0.07790823 -0.5285719 -0.8440648 -0.0903677 -0.362444 -0.9275955 0.09055901 0.992961 -0.1039115 0.05684037 0.9917613 0.1227009 -0.03679728 0.9555408 0.2948384 -0.003479719 0.9308059 0.3620499 0.05020306 0.852967 0.5206676 -0.03677777 0.7174531 0.6944584 0.05466801 0.6189649 0.783111 -0.06016287 0.3353275 0.9399979 0.06292351 0.2381265 0.9706951 -0.03235488 -0.05274528 0.9985732 0.008331735 -0.04218391 0.9991041 -0.00339221 -0.3524608 0.9351919 0.03446061 -0.4478606 0.8925048 -0.05344206 -0.6393868 0.767769 0.04141485 -0.7399623 0.671373 -0.04140241 -0.8586192 0.5109379 0.04142036 -0.9302384 0.3625813 -0.05649041 -0.9790546 0.1955591 0.05664546 -0.995865 -0.0797995 -0.04341676 -0.9897709 -0.14199 0.01386946 -0.8995494 -0.4365989 -0.01386576 -0.885932 -0.4636076 0.01387537 -0.6842879 -0.7290335 -0.01613019 -0.6809052 -0.7322931 -0.01072528 -0.3977851 -0.9166852 0.0381477 -0.2971019 -0.9532791 -0.05467621 -0.06966957 -0.99671 0.04141509 0.06967197 -0.9967099 -0.04141462 0.2663557 -0.9629847 0.04141508 0.3977388 -0.9165634 -0.04141648 0.5719559 -0.8192382 0.04141521 0.6983011 -0.7135723 -0.05648069 0.8288443 -0.5540906 0.07746512 0.9311857 -0.3590222 -0.06321678 0.9926027 -0.1110794 0.04900197 0 0 -1 0.0001616184 1.990133e-05 1 -1.641897e-06 -2.956202e-06 1 0.000173448 5.397217e-05 1 1.62441e-05 7.520404e-05 1 4.592017e-06 2.12593e-05 1 -3.781005e-06 -8.774338e-06 1 0 0 1 0 0 1 0 0 1 -6.83304e-06 -8.068795e-06 1 7.793897e-06 -1.058131e-05 1 0 -0 1 0 0 1 1.290057e-05 -3.117719e-06 1 -2.029245e-05 4.904132e-06 1 1.039603e-05 6.642041e-05 1 7.055004e-06 8.026302e-05 1 -0 0 1 -0 0 1 0.000508829 -2.20563e-05 0.9999999 -7.173603e-06 -8.593262e-06 1 -2.176593e-06 1.419705e-05 1 0 0 1 1.564347e-06 -8.990391e-06 1 6.023963e-06 -7.233511e-06 1 0 0 1 1.778541e-05 -7.709474e-07 1 -2.757226e-06 -6.007797e-06 1 1.522391e-05 -2.776403e-07 1 -1.173869e-07 -4.833017e-06 1 -2.09927e-06 -4.574159e-06 1 0 0 1 -3.368005e-06 -5.378295e-06 1 1.330107e-05 6.183423e-07 1 2.48719e-05 9.299437e-06 1 1.279151e-05 -3.83061e-06 1 -2.479547e-06 -1.355705e-05 1 -4.945914e-06 -1.147767e-05 1 0 0 1 0 0 1 0 0 1 -4.798074e-06 -1.524525e-06 1 -3.733968e-06 -9.760593e-06 1 -1.69779e-05 -6.272751e-06 1 -1.13036e-05 -5.506375e-06 1 0 0 1 1.563236e-06 8.547077e-06 1 -6.494741e-06 -2.417562e-06 1 7.104035e-06 -2.159484e-05 1 1.01758e-05 1.257806e-05 1 0 0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 -6.128205e-06 4.568109e-06 1 -0.3230769 -0.9444325 -0.06056984 -0.5598482 -0.8267249 0.05564067 -0.7832161 -0.6201029 -0.04522057 -0.9288549 -0.3665845 0.05333261 -0.9973957 -0.04854919 -0.05333666 -0.9691082 0.2424555 0.04521833 -0.8346559 0.5469154 -0.06506155 -0.686277 0.7249626 0.05876364 -0.1089427 0.9936315 -0.02877657 -0.1187371 0.9927234 -0.02004202 0.5396069 0.8417448 0.01702653 0.5798349 0.8145562 -0.01702066 0.9654052 0.2599839 0.02002861 0.9707124 0.2402374 0.001853846 0.853555 -0.5202956 -0.02713504 0.8032946 -0.5938327 0.0456111 0.3056724 -0.9513665 -0.03829031 0.1664522 -0.9847342 0.05091364 -0.136723 -0.9903969 -0.02051261 -0.2467468 -0.9671763 0.06071298 -0.6669725 -0.7433231 -0.05117044 -0.8368763 -0.543741 0.06311657 -0.9748443 -0.2164123 -0.05333259 -0.9932169 0.1027466 0.05443563 -0.9384868 0.3417447 -0.04952927 -0.708145 0.7038278 0.05618896 -0.5646338 0.8243438 -0.04057097 -0.08028268 0.9961544 0.0350861 -0.03286096 0.9994586 0.001655968 0.5797575 0.8144434 -0.02373264 0.6923395 0.7167434 0.08333731 0.9513302 0.2978109 -0.07924315 0.9896463 -0.1264941 0.06782094 0.9651559 -0.2612123 -0.01556012 0.6006564 -0.7992552 0.02007483 0.5836015 -0.8120393 0.001239394 -0.3632697 -0.9289367 0.07149603 -0.6635211 -0.7388839 -0.1174327 -0.9120604 -0.3940591 0.1134167 -0.991022 0.09266633 -0.09637677 -0.8864011 0.4512639 0.1032178 -0.6484129 0.7550063 -0.09760249 -0.140015 0.9852122 0.09875607 0.08021002 0.9951711 -0.05657579 0.6510515 0.7580704 0.03822625 0.7297643 0.6826293 -0.03822469 0.9908734 0.1223541 0.0565641 0.9976798 -0.03788758 -0.05656401 0.7850251 -0.6182842 0.03821257 0.7343088 -0.6786018 -0.01703507 0.2190545 -0.9755878 0.01560886 0.1237094 -0.9913784 -0.04318457 -0.14958 -0.9867548 0.0627745 -0.4792438 -0.8760058 -0.05421498 -0.7520853 -0.6559569 0.06394047 -0.8899842 -0.451472 -0.06403985 -0.9969404 0.04481932 0.06403951 -0.9646683 0.2589963 -0.04833328 -0.7818535 0.6215858 0.04833454 -0.6526765 0.7560869 -0.0484335 -0.1664777 0.9854565 0.03407028 -0.06056487 0.9976838 -0.03096641 0.442975 0.8954232 0.04461413 0.5791248 0.8135495 -0.05245695 0.9380807 0.344301 0.03822704 0.9700068 0.2400538 -0.03822372 0.9353813 -0.3497295 0.05245062 0.8349834 -0.5442464 -0.0812319 0.5049868 -0.8597434 0.07635114 0.1774977 -0.9812979 -0.07449074 0 -0 -1 -0 0 -1 -1.654247e-05 -4.74594e-06 -1 -1.534885e-05 -1.895292e-06 -1 -3.644624e-06 -6.32981e-06 -1 -2.804349e-06 -4.870461e-06 -1 3.314729e-05 -1.816307e-05 -1 1.794917e-06 -4.457657e-05 -1 3.789019e-06 -2.492013e-05 -1 -5.417663e-06 -1.38538e-05 -1 -3.723194e-06 -1.262691e-05 -1 0 0 -1 0 0 -1 3.159229e-06 4.140545e-06 -1 1.96166e-06 5.332711e-06 -1 -2.841814e-06 -7.725384e-06 -1 -4.333152e-06 -5.860998e-06 -1 -0 0 -1 -8.962921e-06 -4.508256e-06 -1 -2.473314e-05 1.335666e-05 -1 2.503203e-07 9.101372e-06 -1 -5.513036e-07 -2.00448e-05 -1 -3.348799e-06 -1.312632e-05 -1 -1.03774e-05 -1.759137e-05 -1 -8.024099e-06 -1.360215e-05 -1 -2.286524e-05 2.365369e-06 -1 -3.419405e-06 -4.209339e-06 -1 4.457538e-06 5.487297e-06 -1 -1.060131e-05 3.781727e-05 -1 -1.448289e-05 3.487005e-05 -1 0 0 -1 -0 0 -1 0 -0 -1 8.878426e-06 -1.046516e-05 1 5.515594e-06 -6.50133e-06 1 0 0 1 -1.456152e-06 1.32811e-05 1 -7.250052e-06 1.681704e-06 1 0 0 1 0 0 1 -8.693748e-06 7.379246e-06 1 0 0 1 1.761758e-06 -1.042863e-05 1 0 0 1 6.847685e-06 -2.249877e-06 1 -6.590254e-06 -2.516768e-06 1 0 0 1 -6.322598e-06 6.925107e-06 1 9.208248e-06 -2.1844e-06 1 0 -0 1 -0 0 1 0 0 1 0 0 1 0 0 1 -0.2562275 0.96619 -0.02871173 -0.3307684 0.9435739 0.01613799 -0.8944963 0.4466282 -0.01998896 -0.8905732 0.4540542 -0.026722 -0.9777085 -0.2043804 0.04811196 -0.877008 -0.4741567 -0.07766807 -0.7147148 -0.6982911 0.03965097 -0.194209 -0.9803436 -0.03477447 -0.08451677 -0.9957265 0.03722316 0.6070312 -0.7927155 -0.05581358 0.7267911 -0.6850551 0.04974269 0.9948106 -0.0968163 -0.03128146 0.9997382 -0.01816485 0.01392205 0.8337779 0.551953 -0.01273566 0.7890748 0.6137743 0.02533711 0.4060285 0.9132569 -0.03320629 0.2578232 0.9656213 0.03320722 -2.657488e-05 0.000130111 1 8.57242e-06 -1.119463e-05 1 1.300203e-05 -1.026879e-05 1 1.086544e-05 -8.581349e-06 1 4.706494e-05 2.694201e-05 1 1.273507e-05 2.857268e-05 1 1.346946e-05 1.199768e-06 1 5.880469e-06 -4.65625e-06 1 0 0 1 -0 0 1 -0 0 1 0 0 1 -0 0 1 0 -0 1 8.107363e-05 0.0001513615 1 2.404596e-05 0.0001213811 1 1.542572e-05 0.0001483321 1 0.1473317 -0.9689906 -0.1983701 0.5199104 -0.8335507 0.1867792 0.7933525 -0.5837293 -0.1727768 0.9258521 -0.3461697 0.1515401 0.9882549 -0.03584537 -0.148551 0.9341123 0.3110682 0.1751311 0.80556 0.5660504 -0.1751004 0.5313475 0.8288554 0.1751245 0.271154 0.9464714 -0.1751215 -0.107308 0.9786836 0.1751096 -0.3836332 0.9067323 -0.1751063 -0.6983033 0.694047 0.1751317 -0.8681079 0.4644617 -0.1751111 -0.9731377 0.04111028 0.2265239 -0.9674729 -0.1840465 -0.1735602 -0.619823 -0.7792645 0.09255483 -0.6562673 -0.7539027 -0.03072313 -0.02047768 -0.9961558 0.08517191 0 -0 1 -6.288057e-06 -5.208903e-06 1 3.970206e-05 1.685237e-06 1 -1.799135e-05 -3.51602e-06 1 0 0 1 0 0 1 0 0 1 -0.2758753 0.9576753 0.08216304 -0.649834 0.7566566 -0.07201769 -0.913726 0.3979346 0.08217473 -0.9903017 0.1222938 -0.06593023 -0.867665 -0.4942443 0.05366604 -0.7463373 -0.6620584 -0.06825895 -0.3382582 -0.9388129 0.06489905 0.1130852 -0.9915562 -0.06346516 0.2200513 -0.9754874 -0.001357198 0.746428 -0.6652073 0.01856459 0.8363502 -0.5451501 -0.05770291 0.9857432 -0.1592997 0.05416591 0.9757601 0.2128269 -0.05096126 0.8951752 0.4444095 0.03407951 0.6870586 0.7258025 -0.03407825 0.4892218 0.8706693 0.05096216 0.08012922 0.9943482 -0.06964979 -1.177393e-05 1.625592e-06 1 0 -0 1 6.560925e-06 -7.143403e-06 1 2.85086e-05 1.4213e-05 1 -1.102406e-05 1.301324e-05 1 -8.940689e-06 -2.532347e-05 1 -1.050527e-06 -1.303631e-05 1 1.441148e-05 -2.150295e-05 1 3.505526e-06 4.538749e-06 1 -0 0 1 -1.823856e-05 -2.392876e-06 1 -1.027185e-05 -9.111921e-06 1 -0.000136459 -0.0002369598 0.9999999 2.10703e-05 -0.0001441245 1 -1.963648e-05 -7.216426e-05 1 0.1763395 -0.968003 -0.1785345 0.3205468 -0.9257143 0.2007556 0.8740249 -0.4720002 -0.1153098 0.9256321 -0.3445405 0.1565149 0.9759169 0.1311227 -0.1743362 0.8753613 0.4364123 0.2080552 0.6472346 0.7231662 -0.2410771 0.3171169 0.8981969 0.3044326 -0.1357655 0.9520312 -0.2742342 -0.5400961 0.8058614 0.2426594 -0.6949803 0.7162021 -0.06369474 -0.9955493 0.0930972 0.01464511 -0.9946263 0.07084195 0.07549833 -0.6668429 -0.7413179 -0.07594855 -0.6005203 -0.7861618 0.1460301 0.9994745 -0.02612826 0.01918683 0.9999001 -0.009586227 -0.01038613 0.9970238 -0.0162365 0.07536494 0.9998556 0.01658767 -0.003684019 0.9993673 0.02412391 -0.02613318 0.9949586 -0.0680215 0.07369103 0.83399 -0.551301 -0.02297623 0.8400329 -0.5415663 -0.03241061 0.8075173 0.5897601 -0.009939714 0.8304098 0.5553536 -0.04474399 0.8475481 0.5306603 -0.007871885 -0.3017447 0.4051151 -0.8630365 -0.7920253 0.5652136 -0.2307155 -0.4172731 0.8579361 -0.2997144 -0.5480788 0.7287358 -0.4105531 -0.6596549 0.6250172 -0.4173835 -0.02070896 0.9994044 -0.02760546 -0.1082986 0.9848741 -0.1352569 -0.4955744 0.6237478 -0.6044374 -0.3659601 0.9305287 -0.01376792 -0.6092901 0.792847 -0.01261535 -0.7798231 0.6259181 0.01012253 -0.1132651 0.7309043 -0.6730155 -0.1204417 0.520387 -0.8453941 -0.1570317 0.3112471 -0.9372654 -0.8549974 0.4128805 -0.3138617 -0.09908592 0.9944803 -0.03450705 -0.8832725 0.2823921 -0.3742784 -0.6003621 0.7416556 -0.2991862 -0.5012953 0.8327757 -0.2349208 -0.6709528 0.630183 -0.3907579 -0.3453965 0.903437 -0.2539743 -0.688683 0.4583826 -0.561784 -0.4042592 0.8737629 -0.2703941 -0.7595535 0.3935021 -0.5179138 -0.6863463 0.5215755 -0.506841 -0.6988575 0.4340162 -0.5685316 -0.3190565 0.9119557 -0.257953 -0.6229947 0.2599104 -0.7377834 -0.4625936 0.678408 -0.5707625 -0.3509196 0.7818783 -0.5152881 -0.6188021 0.5154063 -0.592824 -0.3263389 0.7312029 -0.5990368 -0.1174423 0.9707119 -0.2095841 -0.3564322 0.5454682 -0.7585648 -0.2770877 0.6774238 -0.6814099 -0.2384901 0.648793 -0.7226272 -0.1190938 0.9093952 -0.3985186 -0.2193605 0.5919769 -0.7755284 -0.2569705 0.4623027 -0.848671 0.03687242 0.996381 -0.07658418 -0.3408114 0.8620103 0.3752145 -0.1947923 0.9431508 0.2693 -0.5404688 0.8085096 0.2328211 -0.5222728 0.7675354 0.3716456 -0.1001695 0.7968866 0.5957666 -0.5990915 0.6740661 0.432116 -0.7655635 0.6261276 0.1479079 -0.387654 0.5206099 0.7607166 -0.2658276 0.5538401 0.789048 -0.07333609 0.9951948 -0.06487699 -0.9427571 0.01848429 -0.3329677 -0.6545721 0.6691721 -0.3517726 -0.7324551 0.5994308 -0.3227882 -0.6250224 0.6367034 -0.4516146 -0.6328086 0.60917 -0.4779804 -0.1630762 0.9641944 -0.20913 -0.4823607 0.5546873 -0.6779751 -0.2171654 0.8477229 -0.4839474 -0.295651 0.7268068 -0.6199536 -0.1973906 0.4250383 -0.8833909 0.001018611 0.9056793 0.423962 -0.004203595 0.827408 0.5615856 0.005309059 0.4554862 0.890227 0.006463453 0.991661 -0.1287117 -0.002286767 0.919665 -0.3926972 0.008733233 0.8041551 -0.5943554 -0.01244383 0.4632054 -0.8861637 0.661268 0.6413598 0.3890787 0.5181932 0.7132419 0.4719765 0.5321336 0.4976689 0.6849521 0.1749235 0.9524243 0.2495792 0.1770877 0.8597199 0.4790841 0.3033496 0.6158084 0.7271581 0.2409159 0.3976161 0.8853592 0.2874543 0.9206538 -0.2641335 0.2696671 0.8847697 -0.3800817 0.644066 0.7333658 -0.217609 0.595354 0.7287917 -0.3382549 0.7724528 0.6126136 -0.1673955 0.3738454 0.6481413 -0.6634399 0.6957444 0.521614 -0.4938204 0.4703424 0.5210018 -0.7122746 0.2555916 0.6125818 -0.7479414 0.7303807 0.6289124 0.2664828 0.6745864 0.6899518 0.2624874 0.5765775 0.762077 0.2946132 0.6824158 0.5637834 0.4652493 0.5899874 0.6853604 0.4268441 0.4872032 0.8052028 0.3380556 0.3122963 0.9499805 -0.002849227 0.5656323 0.8246506 0.003394595 0.7937141 0.608291 -0.0002043568 0.8358351 0.5489784 0.001539532 0.3391313 0.8825705 0.3256673 0.542634 0.5648214 0.6217113 0.6312425 0.3812328 0.6754218 0.3901161 0.7646605 0.5129364 0.4494543 0.3416107 0.8254047 0.4288603 0.5518382 0.7152296 0.1612799 0.9102669 0.3813174 0.2206824 0.5401816 0.812098 0.2387412 0.6872995 0.686019 0.1484724 0.8581008 0.4915476 0.1738201 0.5253512 0.8329421 -0.0151551 0.8454428 0.5338508 0.1936206 0.9676176 0.1619485 0.5562944 0.7917516 0.2523212 0.2581373 0.6452884 0.7190049 0.2816377 0.6302034 0.7235494 0.3939244 0.7019775 0.593339 0.5413613 0.5620363 0.6253343 0.7052798 0.5695951 0.4220685 0.6761987 0.6546122 0.3379913 0.8982347 0.3822085 0.2170046 0.02101058 0.8723885 0.4883615 0.005778656 0.9286102 0.3710116 0.00771692 0.5298256 0.8480715 0.01218023 0.5030003 0.8642005 -0.6444615 -0.5204177 -0.5602096 -0.2690314 -0.9488564 -0.165208 -0.7754605 -0.4884501 -0.4000969 -0.6990094 -0.6926726 -0.1777379 -0.7240469 -0.6596122 -0.2016624 0.04857837 -0.9841477 0.1705682 -0.02697021 -0.9908705 -0.1320919 -0.563612 -0.7739254 -0.2887576 -0.4647254 -0.8151013 -0.3458902 -0.08349413 -0.9873937 -0.1344701 -0.3027786 -0.933349 -0.1928333 -0.5350686 -0.7975442 -0.2786121 -0.7023187 -0.5066459 -0.5000584 -0.4690044 -0.7415987 -0.4796522 -0.8054876 -0.4987083 -0.3201246 -0.5420608 -0.5224498 -0.6581917 -0.8475165 -0.4198082 -0.324772 -0.712072 -0.5742369 -0.4039871 -0.7936654 -0.1186117 -0.5966796 -0.6264434 -0.5199451 -0.5807114 -0.5655953 -0.4105808 -0.71521 -0.2928239 -0.8707378 -0.3950569 -0.4392145 -0.5890963 -0.6782745 -0.4405278 -0.609937 -0.6587201 -0.4335521 -0.6231591 -0.6509264 -0.2513191 -0.7551629 -0.6054484 -0.3347518 -0.6456923 -0.6863109 -0.3371903 -0.4723845 -0.8143436 -0.2552848 -0.646165 -0.7192361 -0.2997018 -0.4481774 -0.842209 -0.2608979 -0.612239 -0.7463885 -0.7193667 -0.6946154 0.004592948 -0.6811236 -0.7321671 -0.001395782 -0.003868364 -0.9999216 -0.01191651 -0.465315 -0.8574316 -0.2197567 -0.1226631 -0.7935738 -0.5959819 -0.3138751 -0.4050284 -0.85874 -0.2253339 -0.8872351 -0.40254 -0.3090954 -0.8340324 -0.4570011 -0.482421 -0.5751463 -0.660664 -0.6082958 -0.4118355 -0.678504 -0.5154756 -0.8122562 -0.2729922 -0.7279422 -0.558266 -0.3980441 -0.8216254 -0.4173036 -0.388316 -0.2274671 -0.8598374 0.4570978 -0.3228041 -0.9197577 0.223256 -0.3366309 -0.9051981 0.259415 -0.2242585 -0.6307509 0.7428738 -0.2887442 -0.6842632 0.6696348 -0.4692219 -0.5003538 0.7276515 -0.7190766 -0.6546004 0.2332959 -0.5737405 -0.5997473 0.5577857 -0.7976437 -0.2400178 0.5533137 -0.8581695 -0.3556232 0.3702394 0.01131332 -0.542667 -0.8398718 -0.006906342 -0.8155532 -0.5786409 0.006101014 -0.9114973 -0.4112609 0.003824489 -0.4616575 0.8870501 -0.001871652 -0.7277385 0.6858521 0.001694398 -0.8243952 0.5660121 -0.003232813 -0.9860082 0.1666656 0.2005206 -0.9658449 -0.1641192 0.3542078 -0.9114234 -0.2093903 0.2879983 -0.7928687 -0.5370439 0.3796724 -0.6261063 -0.6810579 0.6631018 -0.6307166 -0.4031038 0.8333761 -0.4432756 -0.3301379 0.2083107 -0.3913361 -0.8963608 0.4876408 -0.4859957 -0.7252687 0.6774831 -0.431839 -0.5954257 0.2284507 -0.3143777 0.9213994 0.2123042 -0.7878441 0.5781251 0.3347179 -0.5064459 0.7946549 0.4630592 -0.3943727 0.7937546 0.1964708 -0.9519669 0.2348581 0.2255471 -0.9309494 0.2871614 0.5508464 -0.6324853 0.5445462 0.6549751 -0.533141 0.5355075 0.8146231 -0.5799905 0.000506329 0.7672427 -0.6413541 -0.001880005 0.5280288 -0.8492262 -0.0006337409 0.5106262 -0.8598022 -0.001029431 0.1181909 -0.9929907 0.0006576668 0.007774233 -0.9999691 -0.001098993 0.6967543 -0.4857174 0.5278372 0.3124903 -0.9185463 0.2421208 0.7517332 -0.4792281 0.4530315 0.6347525 -0.6886826 0.3504362 0.2953792 -0.93987 0.1714514 0.8185384 -0.4863895 0.3056473 0.7349927 -0.6099108 0.2963016 0.4749091 -0.8618847 0.1778093 0.5201617 -0.8292616 0.2043457 0.4218214 -0.8635047 0.2764532 0.3908649 -0.8877934 0.2429971 0.2593904 -0.798485 0.5432664 0.3308589 -0.7607781 0.5583449 0.1463023 -0.6213986 0.7697139 0.8896633 -0.3785984 0.2552693 0.6634012 -0.6420123 0.3843424 0.7167862 -0.3970343 0.5732201 0.4663655 -0.5716177 0.6750975 0.1385579 -0.4514601 0.8814678 0.1762947 -0.7761621 0.6053862 0.3415879 -0.4929597 0.8001928 0.3428607 -0.557887 0.7557836 0.2958622 -0.4808763 0.8253626 0.2085836 -0.8491188 0.4852732 0.5109884 -0.5267622 0.6792734 0.5129694 -0.5131041 0.6881763 0.2106399 -0.9411185 0.264437 0.6027884 -0.6214153 0.5004889 0.4836581 -0.767823 0.4201461 0.00619624 -0.6856018 0.7279504 0.01366519 -0.6492222 0.7604761 0.01645161 -0.9848291 0.1727453 0.749231 0.02090902 0.6619785 0.5914871 0.003524871 0.8063068 0.5335239 -0.07104227 0.8427961 0.3864214 0.02989205 0.9218379 0.2387661 -0.04056558 0.9702294 0.1953678 -0.007044086 0.9807047 0.6573109 -0.04097721 0.7525046 0.5338291 0.06262641 0.8432701 0.4950313 0.01163496 0.8687973 0.3147637 0.0001787121 0.9491701 0.2356764 0.05188851 0.9704453 0.1415801 0.001446089 0.9899257 0.9237097 -0.04055353 0.3809407 0.9321639 -0.005376835 0.3619967 0.8167486 -0.08673488 0.5704374 0.8690459 0.01583563 0.4944778 0.9387084 -0.02181177 0.3440214 0.923024 0.03611228 0.3830437 0.9020807 -0.004612408 0.4315428 0.8190753 0.05395618 0.5711431 0.8168656 0.04628645 0.5749679 -0.9737648 0.216018 -0.07154292 -0.9445202 0.328449 -0.001720824 -0.9443365 0.3289776 -0.001498018 -0.5417267 -0.8405547 9.521174e-05 -0.8961888 0.4436261 0.006441338 -0.5303934 0.847737 0.004994933 -0.6542057 0.7562993 -0.005129038 -0.3340109 0.9425569 -0.004827181 -0.9769198 -0.2073522 -0.0513102 -0.4822815 -0.8759686 0.009143638 -0.7359089 -0.6770419 -0.00723257 -0.869579 -0.4937592 0.005853353 -0.989446 0.1449009 -0.000463649 -0.9926544 -0.1205004 -0.01081266 -0.948762 -0.3159913 0.0004494802 -0.9479522 -0.3184103 0.001224913 -0.3131176 -0.9497063 -0.003920248 0.00272621 0.3123092 -0.9499766 -0.0004759513 0.2983684 -0.9544507 0.1408623 0.3150454 -0.938565 0.005576799 0.2927592 -0.9561699 -0.0004460996 0.2989187 -0.9542785 0.0006380645 0.6262839 -0.7795948 0.005639373 0.9188426 -0.3945839 -0.0003412382 0.9473355 -0.3202429 0.003445383 -0.9983158 -0.05791042 -0.003221992 -0.9024174 -0.4308509 0.003336642 -0.9333934 -0.3588395 0.005398 -0.6347001 -0.7727397 -0.002075206 0.1599921 -0.9871161 0.008578413 -0.09956014 -0.9949946 0.0002574304 -0.2609483 -0.9653527 -0.005119088 -0.2695799 -0.9629644 0.1185688 -0.2419621 -0.9630139 -0.9175712 -0.009110503 -0.397467 -0.7981924 0.04288135 -0.6008744 -0.6216338 -0.0451547 -0.7820054 -0.5569176 0.0127513 -0.8304698 -0.2755027 0.05592726 -0.959672 0.9630811 0.0330665 -0.2671731 0.9145953 -0.01800639 -0.4039693 0.8416243 0.05372242 -0.5373849 0.5444536 -0.02650489 -0.8383721 0.5383851 -0.01992193 -0.8424634 0.2112192 0.05962935 -0.9756181 0.967505 0.0342614 0.2505198 0.8997321 -0.03200678 0.4352675 0.8502504 0.02713843 0.5256785 0.6539402 0.04234757 0.7553601 0.5168999 -0.04056443 0.8550841 0.3824556 0.03614969 0.9232664 0.2843026 0.04754632 0.9575549 0.5367893 -0.06126913 0.8414888 0.6457217 0.04074128 0.7624851 0.842283 0.06039459 0.5356416 -0.2002196 0.04535273 0.9787008 -0.4099438 -0.02579701 0.9117458 -0.5528529 0.0499226 0.8317821 -0.7042814 0.02707769 0.7094043 -0.7978234 -0.02873929 0.6022058 -0.8525391 0.02795558 0.5219154 -0.9508834 0.06962491 0.3016175 -0.9731743 0.04633734 -0.2253543 -0.8488839 -0.03135527 -0.5276486 -0.8340235 -0.008937523 -0.5516564 -0.6214651 0.06158558 -0.7810175 -0.4262106 -0.02523494 -0.9042719 -0.464904 0.004758674 -0.8853483 -0.9758218 -0.0397992 -0.2149136 -0.91164 -0.01755023 -0.4106145 -0.844952 0.05670645 -0.5318274 -0.7379768 -0.04041111 -0.6736149 -0.4465171 -0.01589004 -0.8946339 -0.4263514 0.002402967 -0.9045544 -0.9561398 -0.05870284 0.2869681 -0.7836401 0.0277128 0.6205965 -0.7789605 0.03382639 0.62616 -0.5324616 -0.04426374 0.8452961 -0.3807532 0.0169847 0.9245207 -0.2408831 -0.03627519 0.969876 0.773264 -0.03797764 0.6329458 0.6418602 0.05308945 0.7649817 0.5355408 -0.0299791 0.8439772 0.2422435 -0.0486757 0.9689937 0.2635084 -0.05968016 0.9628092 0.4986088 -0.00639818 0.8668035 0.5443139 0.03477754 0.8381605 0.7721418 -0.06036443 0.6325766 0.9140535 0.03875851 0.4037375 0.9600776 -0.02978407 0.2781438 0.2528121 -0.02797526 -0.9671109 0.4038782 0.02838487 -0.9143723 0.5147112 -0.03516953 -0.8566419 0.7687781 -0.01737346 -0.6392795 0.8351253 0.05125818 -0.5476663 0.933153 -0.04955326 -0.3560477 -0.9054095 -0.002677044 -0.424531 -0.8979522 -0.01624508 -0.4397931 -0.6728022 -0.04611024 -0.7383841 -0.530596 0.06624245 -0.8450324 -0.2867614 -0.05738157 -0.956282 -0.09891752 0.0204544 -0.9948853 -0.142699 -0.005843576 -0.9897488 -0.159039 -0.003475468 -0.9872662 -0.2722259 -0.00637089 -0.9622123 -0.3299275 0.02223389 -0.9437444 -0.2219729 0.02445838 -0.974746 -0.4255386 0.02874558 -0.9044836 -0.3756005 0.003681002 -0.9267743 -0.4644884 -0.001144924 -0.8855785 -0.5708342 0.02314383 -0.8207391 -0.5978022 0.0609771 -0.7993212 -0.6650367 -0.01494209 -0.7466611 -0.7204458 -0.03495987 -0.6926296 -0.7931798 0.03122164 -0.6081868 -0.8079861 0.07507817 -0.5843986 -0.8705441 -0.01946526 -0.4917053 -0.90791 0.01670083 -0.4188323 -0.9412138 0.004213837 -0.3377852 -0.9439655 0.01528562 -0.3296899 -0.9131465 0.01027781 -0.4075021 -0.9336748 0.01054791 -0.3579666 -0.9426838 -0.002639675 -0.3336771 -0.9427583 -0.002882491 -0.3334644 -0.8935069 0.007382128 -0.4489889 -0.9104693 -0.01349191 -0.4133566 -0.8521305 -0.01930618 -0.5229731 -0.7936446 -0.1184198 -0.5967454 -0.8026891 0.004604334 -0.5963799 -0.7464519 -0.04200786 -0.6641123 -0.7227508 -0.003659311 -0.691099 -0.6451179 0.009704499 -0.7640215 -0.5965624 -0.0343916 -0.8018295 -0.5477647 0.002208942 -0.8366295 -0.4709707 -0.03561835 -0.8814294 -0.4376638 -0.003327611 -0.8991325 -0.3317318 -0.02235765 -0.9431088 -0.3599156 0.002092201 -0.9329826 -0.2202842 -0.01118775 -0.9753715 -0.2545674 0.01049599 -0.9669981 -0.1617032 0.008594558 -0.986802 -0.0006456458 0.9999391 -0.01101524 -0.03381643 0.9994189 0.004279905 -0.002937462 0.9999922 -0.002623521 -0.002397617 0.9999918 -0.003258323 0.2627902 -0.002316956 0.9648501 0.2747089 -0.009423408 0.9614812 0.2834256 0.001699218 0.9589927 -0.004455999 -0.9999845 -0.00333945 -0.008565357 -0.9999633 6.826376e-05 0.2623958 0.001551318 0.9649591 0.2747154 0.006418129 0.9615042 0.2809323 -0.000796981 0.9597272 0.009008143 0.008122982 0.9999264 0.02606359 -0.02704746 0.9992943 -0.008040124 0.0009491971 -0.9999672 -0.005988462 0.007938652 -0.9999506 0.9999552 0.003221749 0.008898997 0.999764 0.01354813 -0.01697993 0.9997659 -0.02159689 -0.001340302 0.999597 -0.02838997 0 1 -0 0 1 6.357828e-07 -8.477115e-08 1 1.362394e-06 0 -0.2580101 -0.06410253 0.9640133 -0.5578152 0.08420854 0.8256823 -0.7700507 -0.1025252 0.6296908 -0.9241618 0.08138675 0.3732307 -0.9893762 -0.08622532 0.1170466 -0.9794539 0.1016191 -0.1741942 -0.8714814 -0.1016105 -0.479787 -0.6631529 0.1132082 -0.7398729 -0.4472558 -0.1254303 -0.8855673 -0.01618527 0.1204832 -0.9925835 0.2826164 -0.1399835 -0.948964 0.5560847 0.0941072 -0.8257806 0.8674867 -0.1135446 -0.4843288 0.9137071 0.01066609 -0.4062334 0.9703162 0.0816306 0.2276466 0.8991939 -0.1722026 0.4022394 0.5825194 0.1616188 0.7965869 0.3226645 -0.1337504 0.9370157 -0.106767 0.06343433 0.9922584 3.330201e-08 -1 7.366899e-07 7.311422e-07 -1 9.556274e-08 6.499013e-07 -1 8.494428e-08 6.62744e-07 -1 1.213049e-06 1.621962e-06 -1 5.533244e-07 2.058496e-07 -1 -8.110616e-07 0 -1 -0 1.641816e-06 -1 1.811448e-07 1.614117e-06 -1 -1.570998e-07 4.156804e-08 -1 6.267175e-07 -0 -1 0 1.106117e-06 -1 -3.659153e-07 9.129616e-07 -1 -9.929762e-07 6.855279e-07 -1 -7.456096e-07 1.042193e-06 -1 -3.911124e-07 9.881882e-07 -1 7.746671e-08 1.193133e-06 -1 9.353285e-08 -3.785532e-08 -1 -8.374159e-07 -0.6455216 -0.1187568 0.7544526 -0.8253021 0.104996 0.5548444 -0.955357 -0.08623728 0.2825886 -0.994804 0.1016232 -0.006148304 -0.8999462 -0.1562161 -0.4070545 -0.7523725 0.1730225 -0.635609 -0.2983292 -0.1369831 -0.944582 -0.06920087 0.07184166 -0.9950126 0.2324309 -0.08139113 -0.9692014 0.4589169 0.1095943 -0.881694 0.8213671 -0.1057253 -0.5605161 0.8986285 0.07195553 -0.4327694 0.9871519 -0.07949229 0.1386081 0.9510949 0.1246396 0.2826366 0.5912342 -0.1526464 0.7919225 0.396567 0.1226531 0.9097751 -0.04984637 -0.07617709 0.9958475 -0.2392682 0.1088572 0.9648321 0 -1 0 1.243479e-06 -1 8.444373e-07 -0 -1 0 -5.251297e-07 -1 1.548785e-06 4.986908e-07 -1 1.448745e-06 1.64677e-06 -1 -1.311088e-06 1.065869e-06 -1 -1.415027e-07 6.771453e-07 -1 1.326193e-07 4.664956e-07 -1 3.981203e-07 1.204762e-06 -1 2.978065e-07 1.339349e-06 -1 1.601666e-07 1.230557e-06 -1 7.383773e-08 6.11642e-07 -1 3.670067e-08 6.120917e-07 -1 9.154304e-08 6.153003e-07 -1 9.202292e-08 6.17974e-07 -1 1.210306e-07 0 -1 0 -8.51495e-07 1 2.036169e-05 -4.768372e-07 1 0 -5.024373e-07 1 8.533364e-09 0.0001114044 1 -0.000318003 -5.113822e-07 1 -1.350717e-07 0.00321484 0.9999939 -0.001365786 -0.04002621 0.9967529 -0.06986836 -7.846656e-05 1 -0.0001356774 -4.694732e-07 1 -1.240023e-07 9.173732e-07 -1 -1.595971e-07 0 -1 0 1.181691e-06 -1 7.616651e-07 9.070571e-07 -1 5.846485e-07 7.735169e-07 -1 7.907347e-07 6.408054e-07 -1 6.550692e-07 1.342014e-07 -1 1.035454e-06 0 -1 0 1.497232e-06 -1 -2.172376e-08 1.360675e-06 -1 8.260394e-08 1.605683e-06 -1 4.386358e-07 1.488924e-06 -1 4.067401e-07 1.194336e-06 -1 8.609376e-07 8.634283e-07 -1 2.791722e-07 -0 -1 0 1.345661e-06 -1 -1.284904e-06 1.716326e-06 -1 -1.034166e-06 5.745906e-07 -1 3.848143e-07 -0.464491 -0.1117962 0.8784928 -0.8374341 0.1344432 0.5297444 -0.9397941 -0.1540129 0.3050691 -0.985185 0.1257906 -0.116564 -0.8524261 -0.1338741 -0.5054181 -0.7734072 0.04335845 -0.6324249 -0.2563792 -0.003565201 -0.9665697 -0.2141938 -0.06161658 -0.9748459 0.2967626 0.07842134 -0.9517258 0.4433931 -0.07735854 -0.8929827 0.8447413 0.07504784 -0.5298867 0.8555499 0.04780524 -0.5155085 0.9824028 -0.125929 0.1379373 0.9162202 0.1884948 0.3535677 0.5911584 -0.1534886 0.7918162 0.3689301 0.1099377 0.9229324 0.004724865 -0.05259332 0.9986049 -0.2396244 0.09502625 0.966204 -3.019378e-07 -2.006215e-06 1 1.432766e-07 9.519961e-07 1 -1.104242e-06 2.124427e-06 1 5.915752e-06 3.315434e-06 1 4.287078e-06 -1.788882e-06 1 -1.455738e-05 -8.131379e-06 1 -1.776413e-05 -6.795364e-06 1 -1.398114e-06 -8.634899e-07 1 0 0 1 1.109944e-06 3.104248e-07 1 -2.847882e-07 -1.147186e-06 1 -6.295322e-06 -2.535886e-05 1 -6.554082e-06 -2.372881e-05 1 0.001475847 0.9999989 0.0001093077 0.001470313 0.9999989 0.0001782261 -1.00853e-05 2.232396e-05 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 4.226001e-06 4.879992e-06 -1 -1.885077e-05 -3.233412e-07 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 1.897566e-06 -1.359829e-05 -1 1.017249e-05 -1.288988e-06 -1 -8.718978e-06 1.104809e-06 -1 0.9957978 0.08024568 0.04412834 0.7261994 0.6874615 0.005571346 0.6810203 0.7311895 -0.03966273 0.2425666 0.9696303 0.03128258 0.1208127 0.992104 -0.03367597 -0.3949903 0.9179115 0.03769879 -0.551549 0.8308766 -0.07374068 -0.8939673 0.4372138 0.09831916 -0.9899657 0.1124285 -0.0856019 -0.9426222 -0.3282898 0.06073893 -0.8544505 -0.51725 -0.04865069 -0.5023766 -0.862139 0.06583385 -0.2057552 -0.973144 -0.103225 0.1505438 -0.9851759 0.08224901 0.6593386 -0.7494857 -0.05952852 0.7580698 -0.6510532 0.03820889 0.9968655 -0.05068088 -0.06075219 -0.1596317 0.9871765 0.0005408334 -0.1777198 0.9840768 0.002905295 -0.7625475 0.6469276 -0.00246942 -0.8111302 0.5848393 0.005554398 -0.9986211 0.05202225 -0.007040045 -0.9808729 -0.1943065 0.01155437 -0.8699502 -0.4930649 -0.008588515 -0.5021856 -0.8647124 0.009055911 -0.3952728 -0.9185574 -0.003445891 0.2426643 -0.9701102 0.0002400048 0.2885152 -0.9574617 0.005097491 0.7262129 -0.6874447 -0.005895018 0.8250275 -0.5650617 0.005895852 0.9986939 -0.05077253 -0.005711053 0.999997 -0.002460367 -0.0001076879 0.6813183 0.7319752 0.004196785 0.6377206 0.7702558 -0.00430725 0.8964605 0.4426702 -0.02004308 0.8873964 0.4610035 -0.00186508 0.3258853 0.9450455 0.02622632 0.2105324 0.9757651 -0.05965387 -0.318967 0.9455343 0.06499867 -0.4787856 0.8767734 -0.04508402 -0.8758374 0.4821376 -0.02126587 -0.9286774 0.3642235 0.06999696 -0.9828871 -0.1730893 -0.0630327 -0.9332218 -0.3554515 0.05245198 -0.5203971 -0.8526385 -0.0468458 -0.4770559 -0.878871 -0.001860825 0.3459752 -0.9377993 0.02887127 0.3991091 -0.9164487 -0.02887677 0.9525438 -0.304396 0.001865733 0.958379 -0.2847947 0.02004409 0.9318396 0.09356663 -0.3505997 0.8098761 -0.07286284 -0.582058 0.4045196 0.04863756 -0.9132351 0.234103 -0.04578852 -0.971133 -0.1782142 0.05116671 -0.9826605 -0.4529207 -0.07541763 -0.8883552 -0.7364503 0.07546082 -0.6722697 -0.9646869 -0.09103186 -0.2471688 -0.9972488 0.04277343 -0.06054104 -0.8146641 0.003633712 0.5799217 -0.777373 -0.04562611 0.6273831 -0.2985457 0.03367606 0.953801 -0.09283057 -0.07602329 0.9927754 0.2893207 0.08826742 0.9531539 0.6999445 -0.07966721 0.70974 0.8837439 0.08085091 0.4609336 0.9884258 -0.06628877 0.1364557 0.9700078 -0.06755432 -0.2334978 0.8873307 0.09715069 -0.4507838 0.4235126 -0.06656776 -0.9034411 0.3216114 0.02126321 -0.946633 -0.4269542 -0.02282603 -0.9039851 -0.4990757 0.04982051 -0.8651251 -0.9419949 -0.06002926 -0.3302154 -0.9902293 0.07364328 -0.1184169 -0.9564617 -0.06281273 0.2850189 -0.7936485 0.08791296 0.6019911 -0.47066 -0.100254 0.8766004 -0.1611474 0.06958554 0.9844742 0.3482998 -0.0562578 0.9356935 0.4206309 -0.001656182 0.9072304 0.9137938 0.025964 0.4053478 0.9127551 0.02816816 0.4075349 0.01861024 0.01193638 0.9997556 0.02516343 -0.001810371 0.9996817 0.008207382 0.008677508 -0.9999287 -0.009586969 -0.0538225 -0.9985045 0.9999596 0.001202045 -0.00889889 0.9999303 -0.00631708 0.00997705 1 -0 0 1 1.271565e-06 -1.483494e-07 1 2.384185e-06 0 0.9997566 0.02206283 0 0.9998177 0.01908447 -0.0006054791 0.9097998 0.08464464 -0.4063248 0.8551135 -0.07951396 -0.512307 0.3995387 0.07946063 -0.9132661 0.3421696 -0.00718613 -0.9396107 -0.2162638 -0.06480554 -0.9741818 -0.416905 0.1877352 -0.8893514 -0.7516823 -0.1681965 -0.6377174 -0.9696318 0.1400181 -0.2005218 -0.9943848 -0.1057297 0.004482953 -0.8541354 0.1251961 0.5047562 -0.6939136 -0.1382044 0.7066707 -0.3476768 0.1200533 0.9298969 -0.06620739 -0.1200804 0.990554 0.3412388 0.1382 0.9297617 0.5704184 -0.1252005 0.811756 0.9150362 0.1184887 0.3855765 0.9653771 -0.08466607 0.246736 0 1 0 0 1 0 -1.659611e-06 1 -2.235061e-07 -1.675034e-06 1 -1.722758e-06 0 1 -0 -2.054685e-06 1 2.344649e-06 -2.412973e-06 1 3.342497e-07 0 1 0 0 1 0 0 1 0 0 1 0 -7.403158e-07 1 1.870655e-06 -1.411955e-06 1 -1.121811e-06 0 1 0 -2.000816e-06 1 2.131154e-06 -2.016144e-06 1 2.027975e-08 0 1 0 0.970315 -0.08161757 -0.2276566 0.9165307 0.1330187 -0.377197 0.5867497 -0.1199289 -0.8008382 0.4262373 0.09994074 -0.8990737 -0.1848334 -0.08106244 -0.979421 -0.204353 -0.05157463 -0.9775377 -0.695496 0.09753028 -0.7118801 -0.8369949 -0.1381955 -0.5294729 -0.9822704 0.120077 -0.1439662 -0.9822704 -0.120071 0.143972 -0.8370014 0.1381839 0.5294656 -0.6495087 -0.1534956 0.7446996 -0.2423949 0.1355265 0.9606651 0.1289012 -0.1737744 0.9763129 0.3410975 0.07911672 0.9366926 0.8731332 -0.0004521147 0.4874816 0.8729039 0.0004545385 0.487892 0 1 0 -0 1 0 0 1 0 -1.590018e-06 1 4.257129e-07 -1.549202e-06 1 -5.879357e-07 0 1 -0 -1.804869e-06 1 2.622046e-06 -2.936849e-06 1 8.769522e-07 0 1 0 0 1 0 -8.254032e-07 1 1.165217e-06 -9.986563e-07 1 7.730196e-07 0 1 0 0 1 0 -1.71919e-06 1 1.050502e-06 -1.616405e-06 1 -5.238852e-08 0 1 0 -0 1 0 9.536743e-07 -1 -8.486985e-09 9.78704e-07 -1 0 5.758571e-06 -1 9.478118e-06 1.038112e-06 -1 -4.585256e-07 -0.0001489648 -0.9999998 0.0005978875 -0.04002449 -0.9963826 -0.07496518 0.003217249 -0.9999943 -0.001031133 1.157752e-06 -1 -3.710611e-07 4.049103e-06 -1 1.135729e-05 0 1 0 -1.338992e-06 1 -3.654158e-07 -1.205641e-06 1 1.618619e-07 0 1 0 0 1 0 -1.793486e-06 1 3.501831e-07 -2.189594e-06 1 -1.704556e-06 0 1 -0 0 1 0 -0 1 0 -1.551071e-06 1 -4.580401e-07 -1.731439e-06 1 3.970757e-08 0 1 0 -1.523504e-06 1 2.18008e-06 -1.581894e-06 1 9.062629e-08 0 1 0 -0 1 0 0.9500533 -0.1330194 -0.2823202 0.8807883 0.1218474 -0.4575643 0.3716597 -0.08672206 -0.9243097 0.2672322 0.08106009 -0.9602168 -0.3748375 -0.1077278 -0.9208102 -0.5174419 0.1077121 -0.8489122 -0.9103121 -0.06506278 -0.4087769 -0.9405347 0.02371725 -0.3388686 -0.9842719 -0.0237084 0.1750616 -0.9750575 0.02974935 0.2199497 -0.6783598 -0.0325935 0.7340066 -0.6652581 -0.008275347 0.7465675 -0.1594368 0.03911253 0.986433 -0.0942808 -0.03910899 0.9947772 0.455707 0.008303268 0.8900911 0.4969102 0.07295746 0.8647296 0.8964511 -0.09993564 0.4317273 0.9596149 0.1199159 0.2544786 -0.04000513 -0.9963993 0.07475352 9.536743e-07 -1 0 9.831017e-07 -1 9.809138e-09 6.30928e-07 -1 0 6.357837e-07 -1 -1.539434e-08 0.003215639 -0.9999942 0.001066042 1.029895e-06 -1 4.982371e-07 0.02193745 -0.9989545 -0.04010772 0.003183187 -0.9999897 0.003214981 3.926889e-05 -1 4.856406e-05 5.074607e-05 -1 -1.228723e-06 -1.992854e-05 -1 3.854914e-05 1.021794e-06 -1 3.599368e-05 2.43691e-05 -1 -9.912179e-06 3.111913e-05 -1 -1.587586e-05 -3.6429e-06 -1 -1.561118e-05 -1.191476e-05 -1 0 -1.094702e-05 -1 3.649422e-06 1.197809e-06 -1 3.970951e-07 2.658089e-07 1.297658e-06 1 -2.045741e-06 6.547582e-06 1 -9.608151e-07 1.899541e-06 1 2.298688e-06 -6.009228e-08 1 -1.477628e-06 2.164237e-07 1 -6.2528e-06 2.194635e-06 1 -7.91187e-06 1.551375e-06 1 -1.770887e-06 7.524318e-06 1 -2.034437e-06 5.885557e-06 1 0 0 1 3.588666e-07 -2.114025e-06 1 -1.287511e-06 -1.498675e-06 1 -4.655757e-07 -5.419345e-07 1 -1.314534e-06 8.689602e-07 1 0.0008293477 -0.9999996 5.025657e-05 0.0009537602 -0.9999987 0.001311544 0.001047096 -0.9999995 0.000155132 -1.156106e-05 1.780357e-07 -1 0 0 -1 -3.742711e-06 -4.200101e-06 -1 6.788549e-06 -1.377152e-06 -1 4.638701e-06 -2.120739e-06 -1 -1.684e-05 -2.299269e-06 -1 4.070354e-06 -2.274909e-05 -1 1.9568e-06 -1.09365e-05 -1 3.327188e-06 -4.541055e-06 -1 0.9196888 0.3891284 -0.05245543 0.7917592 0.6026847 0.09944142 0.4945954 0.8657187 -0.07685371 -0.04852808 0.9972653 0.05574103 -0.008326994 0.9997646 0.02003627 -0.6421373 0.7664005 -0.01702875 -0.720834 0.6905462 0.0595341 -0.9726895 0.2194378 -0.07564552 -0.9879384 -0.1348894 0.07604349 -0.9402691 -0.3387634 -0.03366626 -0.6649083 -0.7461655 0.03367384 -0.567609 -0.8227039 -0.03127736 -0.1293882 -0.9909589 0.035483 -0.03623243 -0.9990858 -0.02269079 0.574922 -0.8182034 0.002806774 0.5909247 -0.8065135 0.01854702 0.9611912 -0.2753578 -0.0170154 0.9793209 -0.1986689 0.03822651 0.4432876 -0.8963713 0.003821783 0.4970218 -0.8677317 -0.003338618 0.9137685 -0.4062348 0.0006329461 0.9209563 -0.3896581 0.002471894 0.9585694 0.2848441 -0.002909876 0.9525479 0.3043886 -0.000270735 0.4542222 0.8908798 0.003940547 0.3461058 0.9381417 -0.01004576 -0.2343388 0.9721078 0.009578963 -0.5021797 0.8646685 -0.01279918 -0.7740719 0.6330318 0.009136767 -0.9749006 0.2225248 -0.007176076 -0.9930726 0.1174814 0.002260167 -0.8845935 -0.466356 -0.002470474 -0.8609198 -0.5087346 0.002470614 -0.3338458 -0.942623 -0.002966383 -0.3155737 -0.9489009 -0.0004667431 0.9973899 -0.06053976 0.03934687 0.9376633 0.3429387 -0.05639739 0.7729106 0.6243882 0.11291 0.3706846 0.9218698 -0.1129122 -0.03833532 0.99392 0.1032155 -0.3494524 0.9346379 -0.06584124 -0.7740067 0.630739 0.05551469 -0.8603147 0.5083668 -0.03770619 -0.9976438 -0.05450776 0.04166225 -0.983876 -0.173259 -0.04437692 -0.6858883 -0.726579 0.04050081 -0.5691767 -0.820524 -0.05270968 -0.09881957 -0.9929802 0.06499982 0.07517368 -0.9961497 -0.04510575 0.6222008 -0.7826067 -0.01982433 0.6966419 -0.714842 0.06075291 0.9808678 -0.1923305 -0.03012509 0.955853 0.1057765 0.2741464 0.6649166 -0.08697867 0.741836 0.5199639 0.04437893 0.8530347 -0.1523309 -0.04820333 0.9871534 -0.2401636 0.02475882 0.9704167 -0.7982531 -0.001634202 0.6023199 -0.8254749 -0.03506597 0.5633486 -0.9960824 0.04057565 0.07857257 -0.996084 -0.04056873 -0.07855507 -0.856198 0.02695831 -0.5159441 -0.778882 -0.04264287 -0.6257192 -0.4177518 0.06957248 -0.9058935 -0.1309962 -0.08503162 -0.9877295 0.3208701 0.07161617 -0.9444118 0.5685174 -0.07160991 -0.8195485 0.8728432 0.0856046 -0.4804337 0.9864889 -0.1059576 -0.1249505 0.9897723 0.07138602 0.1235101 0.8760182 -0.05422134 0.4792202 0.6776817 0.05444402 0.7333371 0.4786894 -0.04952561 0.8765863 0.06657725 0.05618534 0.9961981 -0.1508261 -0.05618572 0.9869624 -0.6202009 0.07001216 0.7813125 -0.7570752 -0.06404605 0.650181 -0.9989656 0.04547124 0.0002409084 -0.9965989 -0.01851507 -0.08029739 -0.6977946 0.02003037 -0.7160178 -0.70467 0.02878567 -0.708951 -0.07256615 -0.0662277 -0.9951623 0.1263905 0.07917807 -0.9888156 0.6562577 -0.05551512 -0.7524918 0.7818435 0.05779118 -0.6207905 0.9863617 -0.06880771 -0.1495199 0 -0 -1 0 -0 -1 -0 0 -1 -0.4889908 0.003394196 -0.8722823 4.088972e-06 -6.53861e-07 -1 0 -0 1 0 0 1 2.293544e-06 -5.886242e-06 1 -0.006501957 0.001068345 0.9999783 -0.9997667 0.02141416 0.00279736 -0.9998423 0.01729647 0.004031558 -0.008896908 -0.01002501 0.9999102 0.02629431 0.05279001 0.9982594 -0.002340013 -0.02490571 0.9996871 8.0459e-09 -0.0126551 0.9999199 0 -0 1 -0 0 1 0 0 1 -0.1081172 -0.1252243 0.9862198 -0.3334011 0.1105777 0.9362779 -0.7266083 -0.1004418 0.6796705 -0.8069189 0.04338918 0.5890664 -0.9998206 -0.005358202 -0.01817162 -0.9986525 -0.03541204 -0.03793695 -0.7472281 0.03539613 -0.6636243 -0.7344014 0.005357833 -0.6786943 -0.1148759 -0.04730542 -0.9922528 -0.05450175 0.04728399 -0.9973935 0.5868917 -0.003164995 -0.8096592 0.6443195 -0.1071527 -0.7572125 0.9235139 0.1195112 -0.3644711 0.9896135 -0.09470665 -0.1081464 0.951157 0.08770022 0.2959883 0.9303547 0.001091439 0.366659 0.5391403 -0.04535438 0.8409939 0.4321553 0.118486 0.8939814 7.961525e-07 -1 1.140504e-07 6.046116e-07 -1 9.664957e-07 4.22982e-07 -1 6.761535e-07 7.905685e-07 -1 4.338017e-07 4.191851e-06 -1 -7.934163e-06 2.362471e-05 -1 -2.581742e-06 1.763049e-05 -1 6.172686e-06 -3.539916e-06 -1 6.109768e-06 4.510539e-07 -1 -7.78503e-07 6.324208e-07 -1 -3.578973e-08 5.715694e-07 -1 -3.234605e-08 5.543368e-07 -1 5.942099e-09 7.083911e-07 -1 7.593452e-09 5.710138e-07 -1 2.261062e-07 0 -1 0 7.775575e-07 -1 -2.362099e-07 9.620386e-07 -1 1.378139e-07 0.03271177 -0.09441885 0.994995 -0.4129833 0.1199099 0.9028102 -0.5769976 -0.09992769 0.8106098 -0.9268424 0.06506127 0.3697705 -0.9613097 -0.05914647 0.269045 -0.9660946 0.08507861 -0.243768 -0.9282311 -0.06478489 -0.3663194 -0.5868589 -0.00718325 -0.8096573 -0.557444 0.04138368 -0.8291824 0.03487515 -0.01074785 -0.9993339 0.02429173 0.005341061 -0.9996907 0.6912584 -0.04923837 -0.7209281 0.7323722 0.05351868 -0.6787981 0.9973468 -0.003547399 0.07270995 0.9884211 -0.08932768 0.1226549 0.7254472 0.09234753 0.6820544 0.5860434 -0.09213693 0.8050242 0.2452028 0.07946439 0.9662097 1.350999e-06 -1 -9.465769e-07 1.525917e-06 -1 4.611555e-08 0 -1 0 0 -1 0 1.117478e-06 -1 2.918471e-08 1.167554e-06 -1 5.42031e-07 8.439953e-07 -1 3.918204e-07 1.107957e-06 -1 -1.70704e-07 9.312245e-07 -1 -5.301701e-07 1.341931e-06 -1 -7.639956e-07 1.182433e-06 -1 -4.339574e-07 2.849329e-06 -1 3.535781e-07 1.225739e-06 -1 5.417818e-07 1.273926e-06 -1 8.081723e-07 1.256139e-06 -1 -8.801135e-07 1.22538e-06 -1 -9.070341e-07 6.951746e-07 -1 4.410153e-07 -8.174351e-07 1 0 -8.514949e-07 1 -3.137081e-08 -7.947296e-07 1 0 -8.967963e-07 1 -3.061996e-07 -4.768372e-07 1 -4.243562e-09 -4.893522e-07 1 0 -5.190556e-07 1 -2.292669e-07 0.00180142 0.9999974 0.00134334 0.0009022508 0.9999931 0.003593338 0.001805854 0.9999917 0.00365677 -1.701065e-05 1 -5.124904e-06 -0.0120752 0.9997267 -0.02001803 0.00199182 0.9999962 0.001914242 -0.02224355 0.9995197 -0.0215776 0.00363475 0.9999773 0.00567714 -8.897234e-07 1 4.170215e-08 2.181707e-05 1 -5.747045e-06 -9.922932e-05 0.9999987 0.001628374 0.002021079 0.9999976 0.0007911582 5.388569e-07 -1 4.597933e-07 -1.17017e-07 -1 7.003823e-07 0 -1 0 0 -1 0 5.655931e-07 -1 -6.17265e-07 1.681918e-06 -1 1.160444e-06 7.095862e-07 -1 1.374422e-06 7.978854e-07 -1 -1.540567e-08 1.245108e-06 -1 -2.404069e-08 9.290363e-07 -1 -1.296518e-06 1.626045e-06 -1 -7.975176e-07 0 -1 0 6.745931e-07 -1 5.264637e-07 1.260207e-06 -1 1.982171e-07 8.106435e-07 -1 -3.044109e-07 5.972091e-07 -1 -2.242626e-07 6.365715e-07 -1 5.431708e-07 5.243939e-07 -1 -2.147855e-07 5.805354e-07 -1 -2.377804e-07 -0.08833749 0.08931211 0.9920785 -0.1390392 0.003534248 0.9902806 -0.8002601 -0.05181981 0.5974098 -0.8481779 0.08696919 0.5225235 -0.9972723 -0.0643187 -0.03620724 -0.990475 0.03354735 -0.1335435 -0.831054 -0.01313286 -0.5560367 -0.8227331 -0.02978109 -0.5676471 -0.3815756 0.02976088 -0.9238584 -0.368506 0.01315388 -0.9295322 0.1084557 -0.0366003 -0.9934273 0.1478407 0.01055136 -0.9889549 0.6317129 0.06480094 -0.7724892 0.7245549 -0.08509789 -0.6839435 0.9813993 0.07504655 -0.1767018 0.9860707 0.04778372 -0.1593152 0.8900645 -0.1118643 0.4418952 0.7196115 0.1791451 0.6708699 0.5139203 -0.0923536 0.8528521 -4.341885e-07 1 -4.331005e-07 -8.296392e-07 1 0 -9.536743e-07 1 -3.658008e-07 -0.0007103221 0.9999945 0.003216123 -5.459362e-07 1 -5.445681e-07 -1 2.93269e-06 8.49988e-06 -1 -2.929191e-06 -8.48974e-06 -1 -1.031069e-06 1.005086e-05 -1 1.21643e-05 -2.018312e-06 -1 0 0 -1 -7.949399e-06 4.169008e-06 -1 -1.265902e-05 -5.447527e-06 -1 -1.065942e-05 -1.732971e-05 -1 -8.230561e-06 -1.561073e-05 -1 2.091328e-05 -3.577186e-05 -1 -1.60541e-05 -7.694211e-06 -1 -3.073733e-05 -1.44497e-06 -1 -7.652453e-06 2.381233e-06 -0.0001024399 0.9999996 0.0009028668 -8.222815e-05 0.9999996 0.000904494 0.002947895 0.9999946 0.001451507 1 8.540908e-06 3.164468e-06 1 -2.881237e-06 -1.465914e-05 1 -8.549873e-06 1.538244e-06 1 1.408687e-05 -5.839617e-06 1 0 0 1 0 0 1 3.15102e-05 -1.006212e-05 1 -9.417747e-06 -3.397957e-06 1 6.816958e-06 2.459582e-06 1 4.810203e-07 -1.580852e-05 1 -1.104432e-05 6.092565e-06 1 -1.776652e-05 4.087526e-05 1 2.199739e-05 3.250438e-05 -0.04578328 -0.06052047 0.9971164 0.03367265 0.09092757 0.995288 -0.04166623 0.6038082 0.7960399 0.0237425 0.674031 0.7383214 -0.003983452 0.9924536 0.1225558 -0.04981839 0.9962351 0.07095002 0.0723455 0.7461249 -0.6618638 -0.04545029 0.6537246 -0.7553664 -0.001704265 -0.05454575 -0.9985098 0.02574473 -0.08453082 -0.9960882 -0.001655092 -0.715259 -0.6988575 -0.05627736 -0.7662144 -0.6401158 0.06282403 -0.9769111 -0.2042003 -0.0754171 -0.9896344 0.1222128 0.06310742 -0.9017954 0.427531 -0.0631162 -0.6728595 0.7370729 0.05116963 -0.458142 0.887405 -0.008568472 0.9573143 -0.2889223 0.007464817 0.8783788 -0.4779068 -0.003918741 0.4823095 -0.8759921 0.0008152073 0.5178632 -0.855463 -0.003318773 -0.1128207 -0.9936098 0.003941532 -0.1734154 -0.9848409 -0.0006072239 -0.8535706 -0.5209768 0.005319665 -0.8331382 -0.5530393 -0.009094656 -0.9884825 0.1510616 0.01731149 -0.9044409 0.4262474 -0.01197923 -0.6741638 0.7384847 0.00865611 -0.1692268 0.9855391 -0.002471735 -0.06058428 0.99816 0.002687923 0.5636862 0.8259846 0.0004051425 0.5799285 0.8146673 -0.003313427 0.9552846 0.2956696 0.00712986 0.9829787 0.1835813 -0.09759869 -0.03017146 0.9947684 0.08909532 0.4855578 0.8696526 -0.04461633 0.6656823 0.7449004 0.03096671 0.9483159 0.3158133 -0.01557166 0.9699877 0.2426549 0.02003947 0.9144436 -0.4042169 0.05576786 0.928733 -0.3665311 -0.07686747 0.5851683 -0.8072605 0.08706509 0.2512242 -0.9640052 -0.08705071 -0.08471146 -0.9925957 0.08887526 -0.4645391 -0.8810815 -0.07373297 -0.8308781 -0.5515478 0.03769477 -0.9179071 -0.3950009 -0.0376977 -0.9878203 0.1509633 0.05550958 -0.9533679 0.2966619 -0.06583705 -0.6727433 0.7369409 0.1032236 -0.4061577 0.9079542 0.04070306 -0.04731749 0.9980502 0.5317081 0.04892005 0.8455137 0.6411051 -0.04272026 0.7662631 0.9865168 0.05203269 0.1551685 0.9952946 -0.001700575 0.0968806 0.8331162 -0.04146106 -0.551542 0.7142331 0.07361159 -0.696026 0.3791484 -0.06284536 -0.9231993 0.09079401 0.06281875 -0.9938864 -0.3611324 -0.04935521 -0.9312076 -0.4586931 0.01557403 -0.8884584 -0.8681934 -0.0155816 -0.4959812 -0.8900592 0.01239222 -0.4556765 -0.9969144 -0.01372752 0.07728596 -0.9955361 -0.00166948 0.09436645 -0.7341906 0.02372001 0.678529 -0.6545255 -0.05522951 0.7540199 -0.1496145 0.05811893 0.9870348 0.1227365 -0.01194828 0.9923674 0.2513838 0.0678926 0.9655034 0.6310409 -0.07924014 0.7716919 0.9121474 0.07374585 0.4031731 0.9814975 -0.07372919 0.1767108 0.9342265 0.09830859 -0.3428648 0.7661469 -0.0856296 -0.6369352 0.4151971 0.06071891 -0.9077029 0.24585 -0.03367118 -0.9687229 -0.275214 0.03769282 -0.9606438 -0.3893695 -0.03769364 -0.92031 -0.8507653 0.0456063 -0.5235632 -0.881718 -0.003641443 -0.4717626 -0.9756461 -0.04411889 0.2148674 -0.938324 0.06076637 0.3403755 -0.5319642 -0.03858694 0.8458872 -0.4650653 0.01643343 0.8851238 -0.0008435622 -0.9999983 0.001622116 -0.000151687 -0.999986 -0.00530332 -0.00126082 -0.9999951 -0.002893706 -0.001173233 -0.9999992 0.0005656281 -0.001970541 -0.9999979 -0.0005860465 -0.0003478074 -0.9999369 -0.01123341 -0.006376411 -0.9999752 0.002987049 -0.004136745 -0.9999854 -0.003495349 -0.0003605638 -0.9999865 -0.00519265 0.001028299 -0.9999909 -0.004144257 0.003117025 -0.999992 -0.002537588 0.008449443 -0.9999643 5.222134e-05 0.004661078 -0.9999843 -0.003132948 0.004649511 -0.9999841 -0.00318565 -0.003177892 -0.999943 0.01019373 -0.001125063 -0.9999993 -0.0004345895 -0.0007505138 -0.9999993 -0.000909821 -0.001503824 -0.9999985 0.0009075389 -0.0005948386 -0.9999987 -0.001489562 -0.0009835726 -0.9999993 0.0006174941 0.0136945 -0.9996939 0.02060806 0.001561499 -0.999998 0.001276039 0.01996431 -0.9997987 -0.001969475 -0.004190745 -0.9999509 0.008970622 0.0005186443 -0.999998 0.001952898 0.01625176 -0.9998661 0.001922855 0.009392111 -0.999941 0.005464264 7.91085e-07 -1 7.874612e-08 7.926176e-07 -1 8.323068e-08 3.779214e-07 -1 7.63151e-07 -0.001479539 -0.9999968 -0.002024076 -0.001554298 -0.9999985 0.0006910397 -0.001216126 -0.9999993 -8.887566e-05 -0.00227812 -0.9999917 0.003384157 -0.001412281 -0.9999989 -0.0003313364 -0.09172775 -0.9883465 0.1214788 1.348342e-06 -1 -9.199729e-07 1.096621e-06 -1 -2.664294e-06 6.305421e-07 -1 -6.782374e-08 4.713257e-07 -1 8.382446e-08 -0.2053019 -0.9745145 0.09040219 0.00529438 -0.9999805 0.003315618 -0.0005903093 -0.9999971 -0.002331232 -0.002116057 -0.9999958 -0.001989484 8.72688e-07 -1 -2.067309e-07 0.003159145 -0.9999947 0.0007965536 0.002236185 -0.9999971 -0.0008915528 0.002818533 -0.9999917 0.002916044 5.849701e-07 -1 -8.704083e-07 0.004395239 -0.9997832 0.02035251 0.00287882 -0.9999788 0.00584172 0.004282887 -0.9999706 0.006369694 0.003786027 -0.9999824 0.004584346 -0.001857061 -0.999998 -0.000791181 -0.00332997 -0.9999931 -0.001602682 0.00143206 -0.9999941 -0.003129403 -0.001722825 -0.9999975 -0.001420761 0.004838338 -0.9999595 0.007582912 -0.001607368 -0.9999931 -0.003327123 -0.01264508 -0.9999197 -0.000921869 -0.006534875 -0.9999776 -0.001375371 0.01495893 -0.9998862 -0.001967374 0 -1 0 -0.006306299 -0.9999782 -0.001962442 -0.01000607 -0.9999491 -0.001327323 0.002891944 -0.9999936 -0.002110392 5.830593e-07 -1 -2.301084e-07 5.819507e-07 -1 -1.401576e-07 0.0008298554 -0.999997 -0.002328819 -0.001910711 -0.9999933 -0.003137054 8.371044e-07 -1 -8.606292e-08 9.998134e-07 -1 3.557302e-07 7.947286e-07 -1 -5.725469e-07 -0.001780566 -0.9999983 0.0003205925 0.006120996 -0.9999741 -0.003770349 -0.002720068 -0.999993 -0.002536377 0.1004954 -0.994866 -0.01193273 -0.005989936 -0.9999817 -0.0007727595 -0.03109357 -0.9995108 0.003367773 -0.0007923127 -0.9999992 0.0009698786 0.0003638965 -0.9999916 -0.004077701 -0.001090614 -0.9999884 -0.004665806 6.913743e-07 -1 3.080169e-08 -0.0002899656 -0.999998 0.001944648 -0.0004076588 -0.9999987 0.001554652 0.0006216396 -0.9998764 0.01570756 7.94677e-07 -0.9997271 0.02336011 9.682105e-07 -1 -2.513628e-07 0 -1 0 0.9179752 0.04054897 -0.3945597 0.7485412 -0.04829099 -0.6613275 0.3370533 0.04461601 -0.9404278 -0.1425882 -0.04943195 -0.988547 -0.3558747 0.01879702 -0.9343446 -0.8930379 -0.0001096879 -0.4499815 -0.8928258 9.880584e-05 -0.450402 -0.9699467 -0.01821284 0.2426354 -0.8796037 0.04859105 0.473219 -0.6434235 -0.03933838 0.764499 -0.1186485 0.04356165 0.9919803 0.1686473 -0.03627809 0.9850087 0.5546899 0.02344572 0.8317267 0.7718472 -0.01987061 0.6354975 0.9274967 0.0245445 0.3730248 0.9947486 -0.02949791 0.09800515 -0.999952 -0.00893295 -0.00402666 -0.9992409 -0.03864692 0.004888978 0.01535912 -0.02389118 0.9995966 -0.002922929 0.02201016 0.9997535 0 0 1 -0 0 1 0 0 1 -1.687482e-08 0.03538906 0.9993736 -0.009976245 0.01375941 0.9998555 0.1087986 0.1710865 0.9792305 0.3336214 -0.1049567 0.9368462 0.8228152 0.05906645 0.5652312 0.8013036 -0.007618284 0.5982095 0.9941829 0.04728872 -0.09676784 0.9784946 -0.09191515 -0.1846619 0.6294418 0.08462865 -0.7724254 0.5329182 -0.07950328 -0.8424236 0.006146232 0.06430137 -0.9979116 -0.1172839 -0.05972469 -0.9913009 -0.5314844 0.05974023 -0.8449588 -0.631706 -0.06433417 -0.7725339 -0.9342448 0.07197711 -0.3492938 -0.969638 -0.07195792 -0.2337184 -0.9559635 0.06430902 0.2863531 -0.9001381 -0.08727244 0.4267727 -0.6263153 0.1106088 0.7716832 -0.4029731 -0.1535031 0.902247 -2.152686e-06 1 1.385104e-06 -1.281699e-06 1 2.503682e-06 -0 1 0 -1.925315e-06 1 -7.045775e-07 -1.802573e-06 1 2.498792e-07 -0 1 0 0 1 0 -0 1 0 -2.629357e-06 1 -4.673984e-07 -2.742764e-06 1 1.641536e-06 0 1 0 -1.031763e-06 1 -1.288312e-06 -1.395697e-06 1 1.15467e-06 0 1 0 0 1 0 3.87418e-06 1 1.046412e-05 2.841365e-05 1 -2.765616e-06 2.535795e-06 1 -1.03903e-05 0 1 -0 0.2547358 -0.08930746 0.9628779 0.2749867 -0.0549668 0.9598755 0.7952749 0.1118803 0.595836 0.9171286 -0.1512177 0.368793 0.9919553 0.06998748 0.1054815 0.9350351 -0.05914241 -0.3495876 0.8921508 0.06506178 -0.4470279 0.5301541 -0.09233623 -0.8428586 0.334887 0.121603 -0.9343786 -0.00613731 -0.1016223 -0.9948041 -0.3804048 0.1381957 -0.9144365 -0.6043527 -0.1252131 -0.7868161 -0.9210168 0.1057311 -0.3748986 -0.969636 -0.07195693 -0.2337273 -0.9358081 0.07948949 0.3434308 -0.9150947 -0.007294307 0.4031731 -0.5295742 -0.06739135 0.8455824 -0.4135578 0.1077326 0.9040816 -2.455019e-06 1 -2.571007e-07 -2.04422e-06 1 7.634069e-07 0 1 0 -5.994156e-07 1 -8.446743e-07 -4.444691e-07 1 -1.002203e-06 0 1 -0 0 1 0 -1.457994e-06 1 -9.562258e-07 -1.339904e-06 1 2.588952e-07 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 -0 1 0 0 1 -0 -1.488836e-06 1 8.929853e-07 -1.268022e-06 1 -9.686959e-07 -2.228748e-06 1 -5.09331e-07 -2.504308e-06 1 -1.077692e-06 -5.109344e-06 1 3.490166e-07 -2.534561e-06 1 8.718096e-07 -2.810755e-06 1 1.893999e-06 0 1 0 -1.109568e-06 1 -2.364742e-06 -1.668532e-06 1 -6.362582e-07 -0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 -0 -0 1 0 -9.648752e-07 1 -7.52102e-07 -7.942714e-07 1 -9.546219e-07 0.2447032 0.1016175 0.9642584 0.5367801 -0.1036896 0.8373265 0.7437682 0.1184501 0.657859 0.944968 -0.1610707 0.2847662 0.9796501 0.1892286 -0.06691939 0.8666022 -0.1664282 -0.4704278 0.6252028 0.1431591 -0.7672203 0.353371 -0.1200635 -0.9277467 -0.05402525 0.138197 -0.9889302 -0.3077171 -0.1252162 -0.9432025 -0.7240314 0.09275866 -0.6835017 -0.8353457 -0.08728763 -0.5427509 -0.9824858 0.09752922 -0.1587756 -0.9874977 -0.1200663 0.1021391 -0.8753598 0.1200961 0.4683185 -0.7041206 -0.1200845 0.6998527 -0.3868129 0.1200533 0.9143102 -0.1081758 -0.1200787 0.9868532 7.086201e-06 -1 0 9.536743e-07 -1 0 9.851269e-07 -1 -9.435782e-08 -0.0008260825 -0.9999996 0.0002780751 -0.000378063 -0.9999999 -0.000188481 -0.08039393 -0.9959599 -0.04000949 -0.0007512611 -0.9999946 0.003216767 0 -1 0 5.238792e-07 -1 6.187248e-07 -1 2.458175e-05 1.318237e-05 -1 2.67317e-06 -5.14591e-06 -1 -1.250188e-06 -1.850471e-06 -1 -4.853021e-06 1.319476e-05 -1 -5.610882e-06 6.329576e-06 -1 0 0 -1 2.197411e-06 -6.23194e-06 -1 -1.522732e-05 -8.165902e-06 -1 2.249608e-05 -1.056544e-06 -0.9999999 5.620694e-05 -0.0002729658 -1 -3.444799e-06 1.672947e-05 -1 1.723541e-05 3.026805e-06 -1 -1.53162e-05 -2.689761e-06 -1 8.830237e-06 -7.55302e-06 -0.0001157435 -0.9999992 0.001311285 0.001505111 -0.9999982 0.001151759 -0.0001134979 -0.9999995 0.001021459 1 -5.309881e-05 1.811928e-05 1 5.817096e-05 -3.466794e-06 1 -6.182981e-06 -2.243725e-05 1 5.896111e-06 -4.255968e-06 1 4.435105e-06 -8.4531e-06 1 -3.659829e-05 2.728116e-06 1 2.179125e-05 -7.435982e-06 1 7.686222e-06 -1.464958e-05 1 1.326653e-05 1.694425e-05 1 -2.001179e-05 0 1 4.379147e-06 2.366091e-05 1 -8.547204e-06 1.561958e-05 1 -9.760174e-06 -6.249713e-06 1 5.645542e-06 -1.566958e-05 1 -3.16644e-05 -5.314502e-05 -0.06584854 -0.06045381 0.9959966 0.0727542 0.1982833 0.9774408 -0.07277791 0.6027377 0.7946135 0.09636683 0.8199889 0.5642088 -0.1011814 0.9862328 0.1307948 0.08706114 0.9526032 -0.2914921 -0.05618925 0.8372145 -0.5439803 0.05618753 0.5079476 -0.8595535 -0.04057161 0.3386793 -0.9400267 0.03508035 -0.1733069 -0.9842429 0.001645858 -0.2200365 -0.9754902 -0.02374574 -0.7662678 -0.6420823 0.02167578 -0.8052896 -0.5924853 -0.006942391 -0.9997332 0.02203221 0.001860193 -0.9999247 0.0121327 -0.02713187 -0.6949199 0.7185752 0.0690401 -0.604225 0.7938171 -0.003296647 -0.8963547 0.4433253 0.007687846 -0.8356444 0.5492171 -0.008447142 -0.4898358 0.8717738 0.007437436 -0.3019798 0.9532853 -0.003919663 0.2579727 0.9661443 -0.002687619 0.247633 0.9688501 0.002911673 0.8238077 0.5668619 0.004176457 0.8182068 0.5749089 -0.008545937 0.9993064 -0.03624507 0.01382044 0.9472944 -0.320066 -0.009315337 0.8054278 -0.5926207 0.01233385 0.3294272 -0.9441004 -0.006411595 0.1734103 -0.9848288 -0.0002473677 -0.5346063 -0.8451011 0.003738064 -0.5597802 -0.8286328 -0.0005910291 -0.9789666 -0.2040198 0.0008088619 -0.9766933 -0.2146384 0.0170219 0.2283832 0.9734225 -0.01701631 0.2753594 0.9611908 0.01704218 0.7892038 0.6138949 -0.05952007 0.8501492 0.5231671 0.08225147 0.996447 -0.01811328 -0.08798035 0.9364239 -0.3396611 0.0511654 0.7830014 -0.619912 -0.0457699 0.4658782 -0.8836643 0.0640199 0.2711528 -0.9604049 -0.0888688 -0.1921174 -0.9773399 0.08706637 -0.5576915 -0.8254694 -0.07159086 -0.7835767 -0.6171568 0.0661605 -0.9631541 -0.2606856 -0.08019489 -0.9800222 0.1820035 0.02622952 -0.945044 0.3258892 -0.001855464 -0.4609849 0.8874061 -0.02003467 -0.4426506 0.8964703 -0.1237552 0.03159275 0.9918097 -0.2515295 -0.05959825 0.966013 -0.750661 0.08902282 0.6546625 -0.9105097 -0.09477511 0.4024795 -0.9915521 0.08123115 -0.1011239 -0.9364118 -0.0707591 -0.3436947 -0.5793561 0.07764902 -0.8113675 -0.4153254 -0.05657153 -0.9079121 0.1713856 0.0340764 -0.9846146 0.3325896 -0.06778257 -0.9406326 0.7138464 0.08876278 -0.6946543 0.9412212 -0.09637449 -0.3237507 0.9959946 0.0878507 0.01664409 0.9159383 -0.07546228 0.3941604 0.6429861 0.08247723 0.7614239 0.4644167 -0.0528103 0.8840409 -0.004753887 -0.03250071 0.9994605 -0.2049413 0.05151876 0.9774175 -0.5309764 -0.06628133 0.8447905 -0.8349894 0.08122751 0.5442378 -0.9250361 -0.03393679 0.3783604 -0.978071 -0.002031041 -0.2082618 -0.9770302 0.002001701 -0.2130915 -0.6870271 0.03390747 -0.7258403 -0.5625777 -0.06302206 -0.8243388 -0.1088024 0.05617806 -0.9924747 0.168609 -0.08707403 -0.9818295 0.5608025 0.1011789 -0.821744 0.8858856 -0.1086387 -0.4510036 0.9809039 0.07253272 -0.1804617 0.9392259 -0.04864975 0.3398351 0.8630972 0.04578586 0.5029582 0.5814418 -0.05248898 0.811893 0.3791377 0.05327483 0.9238054 -0.0003115969 0.9998957 0.01443841 -7.518527e-06 1 2.193798e-06 1.409636e-06 1 -1.634431e-05 -0.0006085703 0.9999861 0.005232052 -0.001064755 0.9999984 0.001451592 -0.005901498 0.999894 0.01330743 -0.006390561 0.9999785 0.001499362 0.0005645108 0.9999996 -0.0006487391 0.0002665125 0.9999958 -0.002862771 2.408991e-05 1 1.346457e-05 -0.0004208052 0.9999982 -0.00178849 0.002402467 0.9999971 -0.0003521311 0.001405629 0.9999989 -0.0004101424 -0.0001797574 0.9999991 -0.001355366 -0.0009169233 0.9999995 -0.0004415866 -0.0008254457 0.9999984 -0.001609489 0.0005722977 0.999941 0.01084686 -0.000725275 0.9999831 -0.005760526 -2.177674e-07 1 2.297711e-06 -1.27866e-06 1 3.799693e-07 -9.976857e-07 1 -5.461844e-07 -0 1 0 0.008879405 0.9999588 0.001943089 0.007022193 0.9999704 0.003153326 0.003359665 0.9999602 0.008255816 -0.002704795 0.9999738 0.006724413 0.006410443 0.9999248 0.0104549 0.005043061 0.9999555 0.007977256 0.01057209 0.9997231 0.02102496 0.0055669 0.999939 0.009542676 -0.005497047 0.9999846 -0.0006915038 -0.00241498 0.9999966 -0.0009701569 0.002256697 0.9999909 -0.003617932 0.00202654 0.9999945 0.002638383 -0.0003581832 0.999999 -0.00137275 0.007078561 0.9999701 -0.003118677 0.006757983 0.999965 0.004935669 0.00865539 0.9999604 0.00208635 0.01400878 0.9998496 0.01022895 0.02040834 0.9997898 -0.001956199 0.0008653059 0.9999913 0.004076419 -1.2742e-06 1 -1.277759e-06 -1.062063e-06 1 -6.677222e-07 0 1 0 -2.930501e-07 1 2.912739e-07 -1.508005e-06 1 1.559763e-07 -3.991124e-06 1 0 -8.62782e-07 1 -5.605771e-07 -0.002018081 0.9999978 -0.0006071231 -0.0008423721 0.9999987 -0.001314022 -0.001176159 0.9999989 -0.0009435558 -1.106103e-06 1 -3.556176e-08 -1.211038e-06 1 -1.545201e-07 -0.002301203 0.9999791 0.00604162 -0.002197888 0.9999488 0.009874359 -0.001827594 0.9999875 0.004645908 -0.02210556 0.9997346 0.006481776 -0.03653525 0.9989387 -0.02804932 -0.003308154 0.9999929 0.00179469 -0.000444761 0.9999447 0.01050269 0.001028063 0.9999978 -0.001839876 -0.0007871019 0.9999991 -0.001067293 -0.01151636 0.9999272 -0.003615883 0.009542739 0.9999363 -0.006026057 -0.004165214 0.9999405 -0.01007834 0.002682998 0.9999956 -0.001272062 0.01224575 0.9999239 -0.001450048 0 1 0 0 1 0 0.0006186494 0.9999988 -0.001387549 0 1 -0 -1.200725e-06 1 5.317784e-07 -1.054545e-06 1 3.03108e-07 0.00160805 0.999998 -0.00112676 -8.878031e-07 1 -4.275485e-07 -1.973478e-07 1 -1.668014e-06 0 1 0 -6.357333e-07 0.9999493 0.01007552 -6.357829e-07 1 4.361812e-07 8.348011e-07 1 6.135712e-06 0 1 0 -0.0008923678 0.9999995 0.0005346263 -0.001228745 0.9999987 -0.0009970129 -0.001417048 0.9999989 -0.0003621764 -1.661524e-07 1 2.485869e-06 -0.001651205 0.9999132 -0.01307793 -1.331836e-05 1 0 1.455283e-05 1 -5.960515e-06 -0.001306569 0.9999974 -0.001857445 -8.22876e-07 1 2.136155e-06 -0.0006530492 0.9999863 0.005194981 -0.0007675752 0.9999976 0.002104125 0.02309348 0.9997333 -0.0003866171 0.02903663 0.9995784 0 0.01824255 0.9998327 -0.001367308 1 0 0 1 -1.113096e-05 4.337121e-06 0.0002504487 -0.008120229 -0.999967 -0.003788777 0.006808807 -0.9999696 0.008529034 -0.007872829 -0.9999326 0.1560505 -0.05936362 -0.9859636 -0.005592025 0.001124305 -0.9999837 -5.504073e-09 0.004032768 -0.9999919 0.001991983 0.0007910969 -0.9999977 -0.01522445 -0.002480082 -0.999881 -0.03859103 0.007938209 -0.9992236 -0.03093229 -0.007074031 -0.9994965 -0.02262611 -0.003279171 -0.9997386 0 0 -1 0 0 -1 5.631842e-09 -0.007510477 -0.9999718 0.04289297 0.007733869 -0.9990498 0.01483374 -0.004630899 -0.9998792 -0.001306798 -0.001580515 -0.999998 -0.007914795 0.01447344 -0.999864 0.004029756 4.455738e-09 -0.9999919 0 -0 -1 0 0 -1 0.002795178 1.545327e-09 -0.9999961 -0.0005376148 0.008118394 -0.9999669 0.9838493 -0.01316914 0.1785134 0.9457843 0.02157172 0.3240783 0.6961648 -0.02596681 0.7174122 0.4349534 0.03492849 0.8997753 0.2012492 -0.02128508 0.9793088 -0.3354489 0.01496303 0.9419396 -0.4338444 -0.01359249 0.9008852 -0.8075606 0.01782386 0.5895153 -0.8899848 -0.01782272 0.4556417 -0.9997423 0.01360232 -0.01817286 -0.9955126 -0.006835855 -0.09438112 -0.7476553 0.008131069 -0.6640373 -0.7344078 0.001237554 -0.6787073 -0.1750743 -0.00997056 -0.9845048 -0.08231694 0.01557614 -0.9964845 0.4095921 -0.01558172 -0.9121357 0.517808 0.01780362 -0.8553117 0.9142933 -0.0178052 -0.4046614 0.9569404 0.01566975 -0.2898611 0.9998481 0.01715008 -0.003123186 0.9999 0.009590185 0.01038831 -3.405376e-05 -0 -1 -1.440253e-10 0.0001270853 -1 -3.440357e-05 3.881723e-05 -1 -0.1700327 -0.006524948 -0.9854169 7.293348e-06 -1.205643e-05 -1 2.463319e-06 1.989968e-06 -1 7.318119e-07 1.466796e-06 -1 -1.023803e-06 -2.052043e-06 -1 1.53468e-06 -3.710151e-06 -1 3.48264e-06 -1.876737e-06 -1 1.657569e-06 -8.932365e-07 -1 3.178241e-06 3.446064e-07 -1 1.955259e-06 7.137505e-06 -1 5.210298e-06 5.519403e-06 -1 -9.647044e-07 2.21484e-06 -1 -4.715871e-07 1.082705e-06 -1 -6.981712e-06 -1.631406e-06 -1 -7.400777e-06 4.808342e-06 -1 8.931186e-07 2.504009e-06 -1 -6.143417e-06 -1.722411e-05 -1 -9.119807e-08 -2.422127e-05 -1 -5.624154e-06 2.181364e-05 -1 6.395959e-07 -2.480713e-06 -1 -1.545815e-06 -3.019259e-06 -1 9.810418e-07 1.916154e-06 -1 2.541818e-06 1.458365e-06 -1 -1.35036e-06 -7.747675e-07 -1 -2.455373e-06 5.566796e-07 -1 0 0 -1 0 0 -1 1.495895e-06 4.846601e-07 -1 1.449767e-06 2.670878e-06 -1 3.895826e-06 2.918941e-06 -1 1.957779e-06 -7.596875e-07 -1 0 0 -1 2.260523e-06 1.535375e-06 -1 1.119468e-05 -8.615842e-06 -1 1.47037e-05 -7.667103e-06 -1 -9.06016e-06 1.910634e-05 -1 -0.02099303 -0.001896694 0.9997779 0 -0 1 0 0 1 1.179498e-05 2.064544e-05 1 7.722338e-06 4.046086e-06 1 7.880653e-06 4.129035e-06 1 2.215666e-05 3.211431e-05 1 1.278589e-05 -4.188626e-06 1 0 -0 1 0 -0 1 0 0 1 5.170096e-05 -3.911936e-05 1 4.529281e-05 -4.302245e-05 1 0 0 1 5.56786e-06 7.21515e-06 1 1.714191e-05 7.252892e-06 1 1.176025e-05 3.857167e-06 1 2.20928e-05 -2.51134e-05 1 2.747561e-05 -2.281103e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 -9.702866e-06 -6.223832e-06 1 -1.504585e-06 -1.808781e-05 1 8.287354e-07 9.962885e-06 1 -1.528488e-05 1.460672e-05 1 0 0 1 0 0 1 0 -0 1 0 -0 -1 0 0 -1 -0 0 1 0 0 1 0 -0 -1 0 0 -1 0 0 1 0 -0 1 -7.564716e-08 1 7.064426e-07 -9.883117e-07 1 1.667863e-07 -7.458173e-07 1 1.258633e-07 -8.763795e-07 1 -3.768897e-07 -8.457445e-07 1 -3.63715e-07 -7.361847e-07 1 1.818397e-06 -1.368055e-06 1 3.834335e-07 0 1 0 0 1 0 0 1 0 -3.757202e-07 1 4.652196e-07 -1.837638e-06 1 -8.464153e-07 -7.141237e-07 1 -1.501958e-06 -6.311903e-07 1 -3.832514e-07 -4.226013e-07 1 -2.565986e-07 8.875489e-08 1 -8.288511e-07 -1.310992e-07 6.089609e-07 -1 1.709595e-07 -7.941134e-07 -1 4.420124e-07 7.289508e-07 -1 -0 0 -1 0 0 -1 -9.737488e-07 -1.605871e-06 -1 4.847149e-06 -2.155035e-07 -1 0 0 -1 3.270852e-07 1.84631e-07 -1 8.540957e-07 -2.101395e-09 -1 2.884865e-06 5.714788e-07 -1 5.315524e-06 3.933093e-06 -1 -4.357915e-07 2.613114e-06 -1 0 -0 1 -3.231901e-06 -6.021762e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.601539e-07 1.774324e-05 1 1.752994e-05 1.171727e-05 1 3.253151e-06 -6.971068e-06 1 0 0 1 0 0 1 -3.638802e-06 7.797466e-06 1 1.60917e-05 3.12397e-07 1 0.001325758 0.9999992 -0.0001205171 0.0009773886 0.9999937 0.003418982 0.0006959974 0.9999997 -7.733476e-05 4.115698e-07 1 -7.480564e-07 -3.355841e-07 1 6.099472e-07 -4.587148e-07 1 4.785197e-07 -4.682419e-07 1 4.884582e-07 -3.931289e-07 1 5.57861e-07 -1.303499e-06 1 1.849703e-06 -1.323317e-06 1 8.412085e-08 0 1 0 0 1 0 0 1 0 0 1 0 -1.807111e-07 1 7.165047e-07 -1.328639e-06 1 -1.76284e-07 -4.632384e-07 1 -1.656702e-06 -2.11047e-07 1 -7.547776e-07 -1.63301e-06 1 1.195056e-07 -1.647479e-06 1 2.517787e-07 0 -1 0 2.77905e-06 -1 -6.324468e-07 2.133391e-06 -1 -2.709198e-06 0 -1 -0 1.860086e-06 -1 2.429286e-06 1.761908e-06 -1 1.926626e-07 0 -1 0 -0 -1 0 0 -1 0 1.328865e-06 -1 1.391969e-07 1.518386e-06 -1 -6.754939e-07 0 -1 0 1.954805e-06 -1 3.104128e-06 2.055316e-06 -1 1.511802e-07 0 -1 0 0 -1 0 -5.610559e-07 -3.675936e-06 -1 -9.620758e-07 -8.036319e-09 -1 3.319404e-06 -1.559856e-06 -1 -5.692763e-07 3.020142e-06 -1 3.840016e-06 2.073387e-06 -1 -5.884581e-06 4.622008e-06 -1 -4.380651e-06 -1.897844e-06 -1 0 0 -1 -5.542354e-07 -1.80114e-06 -1 4.68613e-07 -5.645562e-07 -1 -6.088775e-07 -1.611639e-06 -1 1.348636e-06 9.569429e-07 -1 0 0 -1 0 0 -1 -1.566345e-09 1.888646e-06 -1 -0 0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0 1 -0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.000966851 -0.9999995 -0.0001074262 0.0009684133 -0.9999995 -8.803626e-05 0.003066501 -0.9999289 0.01152569 0 -1 0 -1.883025e-06 -1 3.128727e-06 4.77861e-07 -1 2.473147e-06 0 -1 0 1.052874e-06 -1 -1.092085e-06 -6.72441e-07 -1 -2.459255e-06 -0 -1 0 0 -1 -0 0 -1 0 5.668876e-07 -1 1.575962e-06 1.656587e-06 -1 -1.309911e-07 0 -1 0 -0 -1 0 8.380996e-07 -1 -1.031753e-06 -6.054631e-08 -1 -1.660689e-06 0 -1 0 0 -1 0 -0.05867377 -0.8647329 -0.4987929 0.001401939 -0.999999 0 -0.04094573 -0.9020426 0.4297005 6.198329e-07 -0.996868 -0.07908336 0.01366665 -0.9980137 0.06149701 6.357834e-07 -1 0 -0.05033426 0.8677955 0.4943657 0.009615645 0.9999538 0 -0.04059608 0.8644008 0.5011619 0.01705359 0.9969049 -0.07674465 -8.477109e-07 1 0 4.531626e-07 -1 -1.282928e-06 9.171617e-07 -1 1.31497e-06 2.141905e-06 -1 1.763673e-06 3.535356e-07 -1 -1.008599e-06 5.560839e-06 -1 7.972788e-06 7.128393e-07 -1 -3.793001e-07 1.898616e-06 -1 -1.134002e-05 0.9761911 0.01416269 0.2164495 0.940961 -0.01974844 0.3379384 0.6468825 0.01359929 0.7624685 0.5868994 -0.006834405 0.809631 0.02428067 0.007474846 0.9996772 -0.02428029 -0.007474729 0.9996772 -0.6316863 0.008131858 0.7751815 -0.691964 -0.01997981 0.7216554 -0.994902 0.02816612 0.09683248 -0.997795 -0.02141246 -0.06282291 -0.8181198 0.01359836 -0.574887 -0.7719563 -0.006835115 -0.6356389 -0.2753775 0.007476649 -0.9613071 -0.2579422 0.00190613 -0.9661585 0.3307739 -0.009513346 -0.9436621 0.4159302 0.01951002 -0.9091873 0.9047432 -0.02127597 -0.4254257 0.9293414 0.0006752165 -0.3692207 -7.395971e-07 1 -3.323465e-08 -8.65078e-08 1 2.924845e-07 -1.050534e-06 1 -9.663187e-07 5.436212e-07 1 2.424398e-06 -7.418075e-07 1 1.194654e-07 -6.734997e-07 1 -1.281687e-07 0.9978888 -0.03076427 -0.05719721 0.7091901 0.01305904 -0.7048964 0.6728953 0.0325448 -0.7390215 0.1089072 -0.03621167 -0.9933921 -0.2186321 0.03874473 -0.9750378 -0.5159822 -0.02249125 -0.8563039 -0.8001946 0.01702303 -0.5994988 -0.8955612 -0.0170213 -0.4446128 -0.9986662 0.02553193 -0.04487622 -0.9869409 -0.0224944 0.1595041 -0.7271018 0.01357591 0.6863953 -0.7731669 -0.01357765 0.6340572 -0.2835513 0.0224925 0.9586933 -0.05450595 -0.03201157 0.9980002 0.4118425 0.0362825 0.9105324 0.6581625 -0.04516255 0.7515201 0.9808487 0.05562925 0.1866579 0 -1 0 0 -1 0 1.182349e-07 -1 6.316639e-07 1.045089e-06 -1 -2.585926e-06 2.858029e-06 -1 1.362037e-06 -0.1961762 -0.09943269 -0.9755142 -0.3306929 0.02535751 -0.9433977 -0.8942367 -0.03139783 -0.4464919 -0.8901029 -0.04198172 -0.4538221 -0.9522415 0.08970699 0.2918713 -0.873337 -0.1197826 0.4721595 -0.3063799 0.1011799 0.9465168 -0.164744 -0.07061657 0.9838052 0.6000134 0.06583157 0.7972768 0.690575 -0.05859679 0.7208831 0.9812273 0.04845723 0.1866682 0.9967369 -0.07129676 0.03784418 0.8632747 0.09308681 -0.4960763 0.6824069 -0.1391572 -0.7176045 0.2837241 0.1138139 -0.9521276 1.254141e-06 -1 1.666459e-06 3.534635e-07 -1 -3.594381e-07 1.058785e-06 -1 -1.076682e-06 1.157217e-06 -1 -5.249599e-07 1.5424e-06 -1 -6.996943e-07 1.370916e-06 -1 -4.201991e-07 2.763636e-06 -1 3.350823e-08 1.274616e-06 -1 6.498674e-07 1.212267e-06 -1 5.327269e-07 8.744966e-07 -1 3.842948e-07 1.109255e-06 -1 -3.011002e-07 9.234692e-07 -1 -6.244331e-07 1.271029e-06 -1 -8.594466e-07 1.187022e-06 -1 -6.821161e-07 3.060546e-06 -1 1.180144e-07 1.757498e-06 -1 3.343456e-07 -0.05957652 -0.182492 -0.9814007 -0.5258318 0.1357305 -0.8396893 -0.6852238 -0.1686426 -0.7085394 -0.9064307 0.2093056 -0.3668442 -0.9704756 -0.2409123 -0.01176672 -0.8711314 0.2727105 0.4083614 -0.7291255 -0.2214518 0.6475608 -0.1991591 0.1816787 0.962979 -0.05418187 -0.1164698 0.9917153 0.5059136 0.1055062 0.8561075 0.6241215 -0.1544563 0.7659084 0.9332359 0.2180081 0.2855575 0.9555331 -0.2925729 0.03684529 0.7934502 0.2690263 -0.5459501 0.6120533 -0.2265493 -0.7576716 0.1947467 0.200986 -0.9600409 8.900063e-07 -1 -5.485526e-08 1.063464e-06 -1 -1.768179e-07 8.944111e-07 -1 1.251883e-06 1.291371e-06 -1 -6.678667e-07 0 -1 0 1.230945e-06 -1 -4.602323e-07 -0.2251398 -0.09462322 -0.9697208 -0.3043885 -0.002378345 -0.9525451 -0.8761715 0.0337079 -0.4808193 -0.9250692 -0.07661898 -0.3719901 -0.993385 0.06573045 0.09415737 -0.9335909 -0.08104225 0.349056 -0.7529782 0.06852053 0.6544684 -0.5074939 -0.06992182 0.8588136 -0.2830419 0.06363029 0.9569945 0.1446383 -0.07216619 0.9868494 0.3550117 0.07217078 0.9320719 0.7511644 -0.08091087 0.6551377 0.8752238 0.09084392 0.4751112 0.9932308 -0.09082998 -0.07240604 0.9431509 0.1042178 -0.3156024 0.6619643 -0.121494 -0.7396232 0.4132801 0.1141794 -0.9034172 3.918575e-06 -1 -1.311255e-06 2.359243e-06 -1 -1.161752e-06 1.605241e-06 -1 8.713977e-07 7.058384e-07 -1 -7.759739e-08 7.224872e-07 -1 -7.942771e-08 7.651824e-07 -1 -5.128199e-07 8.923843e-07 -1 -1.972699e-07 0 -1 -0 1.693376e-06 -1 -9.764234e-07 1.828664e-06 -1 -1.733287e-07 2.249549e-06 -1 -4.087663e-08 1.439449e-06 -1 7.899309e-07 8.407885e-07 -1 -5.894947e-08 6.407799e-07 -1 -4.492644e-08 6.441564e-07 -1 -9.076457e-08 1.684583e-06 -1 -2.373654e-07 1.98718e-06 -1 -2.838342e-06 0.05988512 0.1515583 -0.9866326 -0.2551066 -0.1485483 -0.955434 -0.5709628 0.1751246 -0.8020803 -0.7771233 -0.1750972 -0.6045002 -0.9481131 0.1751257 -0.2653536 -0.9843848 -0.1751188 0.01788729 -0.8696134 0.2265117 0.4387082 -0.7008708 -0.2690268 0.6606094 -0.1950583 0.2690312 0.9431726 0.1090155 -0.2726797 0.9559087 0.4749155 0.1743672 0.8625842 0.8274223 -0.1565225 0.5393265 0.8776445 -0.004655937 0.4792896 0.9863278 0.06660254 -0.1507372 0.9296561 -0.2289267 -0.2886729 0.6539313 0.2433586 -0.7163452 0.3518011 -0.2068986 -0.9129232 -1.277456e-06 1 7.786832e-07 -1.034482e-06 1 -6.566399e-07 -4.375694e-07 1 1.865221e-06 -9.792369e-07 1 -2.996375e-07 -7.432774e-07 1 -2.068612e-07 -1.345882e-06 1 1.545073e-07 -0.087913 -0.1322517 -0.9873099 -0.457373 0.125083 -0.880434 -0.8458288 -0.114256 -0.521075 -0.95814 0.1042141 -0.2666595 -0.9777684 -0.09684686 0.185983 -0.8498623 0.09679197 0.5180399 -0.6664042 -0.06572275 0.7426883 -0.2805717 0.06772017 0.9574411 -0.1048404 -0.0754878 0.99162 0.4811811 0.1032773 0.8705161 0.7064277 -0.1284846 0.6960255 0.9482929 0.1286187 0.290169 0.9894058 -0.1259942 -0.07212225 0.8201149 0.09464076 -0.5643179 0.6869373 -0.07129536 -0.7232111 0.2275758 0.08453482 -0.9700841 -0 1 0 -2.055974e-06 1 -3.882593e-06 -3.241795e-06 1 -6.796876e-07 -0 1 -0 0 1 0 -0 1 0 -1.500246e-06 1 -7.230476e-07 -1.821886e-06 1 8.262224e-07 0 1 0 0 1 0 -5.939032e-07 1 8.508833e-07 -4.957616e-07 1 8.999863e-07 0 1 0 0 1 -0 -7.885084e-07 1 -9.886891e-07 -1.653279e-06 1 9.702239e-07 -0.312307 0.09789166 -0.9449241 -0.2768034 -0.008473254 -0.9608892 -0.8883129 0.07612777 -0.4528849 -0.9202482 -0.1273854 -0.3700218 -0.9580393 0.1164739 0.2619054 -0.9345967 -0.06656243 0.3494257 -0.4837386 0.01123361 0.8751404 -0.5159086 -0.08669314 0.8522456 0.08136275 0.1533762 0.9848127 0.2991607 -0.2474157 0.9215684 0.7289097 0.2226987 0.6473762 0.8909882 -0.2407369 0.384949 0.9611633 0.2729082 -0.04106309 0.8609317 -0.3057003 -0.4066251 0.538338 0.2938258 -0.7898472 0.3269036 -0.1533645 -0.9325306 -4.669758e-07 1 2.272604e-06 -9.538895e-07 1 2.29946e-07 -1.212872e-06 1 -2.083127e-07 0 1 0 -1.257549e-06 1 -2.392471e-07 -9.87736e-07 1 -1.3003e-06 -1.101758e-06 1 -5.223368e-07 -0.4158866 -0.02381153 -0.9091046 -0.4339179 -0.003603498 -0.9009452 -0.9031743 0.03049495 -0.4281896 -0.9284441 -0.02784499 -0.3704271 -0.9762181 0.005566981 0.2167189 -0.9719201 0.02187208 0.2342925 -0.6677011 -0.02002431 0.7441602 -0.5576455 0.08705541 0.8255016 -0.1336298 -0.113809 0.9844748 0.2984644 0.1235301 0.9463928 0.5822746 -0.0933938 0.80761 0.8611637 0.08104296 0.5018259 0.9631842 -0.065736 0.2606817 0.9868178 0.0588193 -0.1507677 0.9321505 -0.08219403 -0.3526179 0.6927813 0.1016879 -0.7139423 0.3320729 -0.08706008 -0.9392274 0.201235 0.02001478 -0.9793385 0 1 0 0 1 0 0 1 -0 7.126189e-07 1 -2.500961e-06 -8.88014e-07 1 -8.531943e-07 -1.475312e-06 1 -1.417464e-06 -1.593642e-06 1 -4.724592e-07 -0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 -2.64873e-06 1 5.569254e-07 -1.931026e-06 1 3.03909e-06 0 1 0 -1.227602e-06 1 -4.066983e-07 -5.126656e-07 1 1.423106e-06 -0.2147331 0.1743077 -0.9609925 -0.5756288 -0.2033537 -0.7920219 -0.7385501 0.1667419 -0.6532542 -0.9910017 -0.1269789 -0.04233062 -0.9998467 -0.01579735 0.007562856 -0.8217435 0.05746629 0.5669526 -0.7387176 -0.1544729 0.6560751 -0.2755092 0.2003663 0.9401851 -0.05344236 -0.2003478 0.9782662 0.5261429 0.1910255 0.8286633 0.6298752 -0.07612133 0.7729571 0.9976401 0.00845821 0.06813752 0.9884121 0.1509803 0.0156907 0.7186751 -0.1776425 -0.6722717 0.5454642 0.2490011 -0.8002919 0.106594 -0.2081779 -0.9722652 -0.01917628 -0.02613027 0.9994746 0.02296051 -0.5512999 0.8339911 0.03239682 -0.5415636 0.8400353 -0.02507525 -0.6458679 0.7630373 0.06881286 -0.540561 0.8384859 -0.07537329 -0.01622875 0.9970233 -0.06880955 0.5405633 0.8384847 -0.0527655 0.5596883 0.8270216 -0.03047664 0.5236752 0.8513727 0.04872559 0.5890927 0.806595 -0.9993476 -0.03494696 0.009123615 -0.9998682 -0.006978672 -0.01466073 -0.999911 -0.002455189 -0.01311755 -1 5.979308e-06 5.593557e-06 -1 3.753111e-06 3.510981e-06 -1 -3.609611e-06 -4.569194e-07 -1 -1.682747e-05 7.656658e-07 -1 -3.593241e-05 -3.306177e-06 -1 3.189974e-05 2.931097e-07 -0.9996131 -0.0006341137 -0.02780884 -1 0 0 -1 1.327754e-05 -2.211615e-06 -1 -3.834208e-06 8.265412e-06 -0.9998742 0.001545095 -0.01579028 -0.999834 0.001179871 -0.01818138 -1 -4.562691e-06 -2.495068e-07 -0.9999077 0.01242859 0.005489342 -1 6.214962e-08 8.100625e-07 -0.9998605 0.01261529 -0.01094642 -0.9991865 0.03408344 -0.02155645 -0.99986 0.01661804 -0.001966442 -0.9998521 0.01424619 0.009633304 -0.9999999 -0.0001143855 0.0004014457 -1 3.12686e-05 9.338506e-05 -0.9991561 0.04102511 0.001974274 -0.9999999 0.0003936095 8.784626e-05 -0.9999976 -0.002045263 0.0007037636 -0.9998907 -0.01325735 0.006543387 -1 1.323018e-05 1.681444e-06 -0.9998085 -0.01956513 -0.0005631867 -1 -1.214343e-05 3.122145e-06 -0.9999948 -0.003064313 0.001087089 -0.9999443 -0.01046944 0.001363746 -1 1.619566e-05 2.713661e-06 -1 0 0 -0.9999257 -0.01214425 0.001059194 -1 1.614434e-05 2.201119e-06 -0.9998371 -0.01804766 -5.631036e-05 -1 3.573116e-06 -6.931269e-07 -1 -2.079338e-05 1.468016e-06 -1 -1.552204e-05 -1.021284e-05 -1 4.764718e-05 1.121157e-05 -0.9999999 -2.346344e-05 0.0002932518 -0.9999999 0.0002466991 0.0001360225 -0.9999999 0.0001053159 0.0002574705 -1 0.0001896067 0.0001599758 -1 -4.511554e-06 -3.806509e-06 -1 6.511984e-06 1.373586e-05 -1 5.429217e-06 1.869974e-06 -1 0 0 -1 6.385959e-06 1.481724e-05 -1 0 0 -1 0 0 -0.9999963 0.00243136 -0.001162719 -1 4.991444e-05 -2.544969e-06 -1 2.89252e-05 -1.180371e-06 -1 -5.41116e-05 1.570731e-05 -0.9999956 0.002798854 -0.0009399749 -0.9999989 0.0005909754 -0.001396145 -0.9988335 -0 -0.04828589 -0.9989337 3.532213e-05 -0.0461678 -1 2.190065e-05 -5.403728e-06 -1 -7.401332e-06 8.919185e-05 -1 0 -0.0001198367 -1 -5.724408e-06 5.862532e-07 -1 -3.743298e-05 -4.604686e-06 -1 2.991427e-06 -7.381002e-07 -1 6.678301e-06 6.247589e-06 -1 9.760366e-06 7.353346e-07 -1 3.753034e-06 3.510984e-06 -1 1.502603e-06 -1.160107e-06 -1 5.120382e-06 -1.735484e-07 -1 -1.668581e-05 0 -1 9.967979e-06 -1.02085e-06 -0.9999616 -0.006927102 0.005378391 -0.9994399 -0.03344078 -0.001243529 0.005232694 0.9995262 0.03033113 -0.08096562 0.6796619 -0.7290434 -0.0006705893 0.6608497 -0.7505179 0.1269448 -0.0758783 -0.9890033 -0.1998549 -0.2026684 -0.9586363 0.1270123 -0.8216776 -0.5556202 -0.184382 -0.8836437 -0.4303221 0.2086535 -0.9712136 0.1149254 -0.2096807 -0.8693785 0.4474539 0.1357311 -0.7486599 0.648911 -0.1641527 -0.3734511 0.9130105 0.1857886 -0.09519953 0.9779671 -0.1381596 0.1767587 0.9745092 0.1748739 0.5890099 0.7889781 -0.1461603 0.7306069 0.6669713 0.1307425 0.9881651 0.0802248 0.1743164 0.9776319 -0.1176842 -0.2408966 0.8612686 -0.4474206 0.2408964 0.6188289 -0.7476762 -0.1743177 0.3210195 -0.9308919 0.1262705 0.009509534 -0.9919503 -0.1262821 -0.2591456 -0.957547 0.1485466 -0.5236974 -0.8388534 -0.2010277 -0.7945856 -0.5729063 0.1824547 -0.9188224 -0.3499651 -0.1357274 -0.9817395 0.1332884 0.1278176 -0.9428892 0.3076078 -0.1801941 -0.6906853 0.7003456 0.1735639 -0.5365474 0.8258283 -0.1025229 0.1599358 0.981789 0.1025083 0.09261268 0.9904115 -0.1633562 0.7080069 0.6870524 0.180395 0.8448325 0.5037019 -0.1262826 0.9716868 0.1996934 0.2046543 0.9719504 -0.1158844 -0.1995322 0.7100805 -0.6752574 0.1995194 0.5795969 -0.7901009 -0.2214953 -0.03701191 -0.9744588 0.2726615 -0.3079566 -0.9114924 -0.2728973 -0.6947142 -0.6655068 0.2677232 -0.8895933 -0.3700648 -0.203601 -0.9700533 0.132451 0.1055007 -0.9453835 0.3084147 -0.1164762 -0.6145242 0.780252 0.1239968 -0.5164452 0.8472953 -0.1132518 0.09174075 0.9893218 0.1946085 0.2628398 0.9450094 -0.1829337 0.6249512 0.7589276 0.1685365 0.8600104 0.4816405 -0.2179372 0.9619619 0.1647199 0.2717642 -0.8657073 0.420351 -0.2424478 -0.6663241 0.7051463 0.1751231 -0.3891598 0.9043708 -0.1750775 -0.01787944 0.9843923 0.1426434 0.2401942 0.9601873 -0.1278167 0.6089509 0.782842 0.09437888 0.7229892 0.6843824 -0.1054896 0.9681344 0.227129 0.05743246 0.9889997 0.1363127 -0.01580912 0.8962042 -0.44336 -0.05971167 0.8858243 -0.460163 0.06856193 0.2884208 -0.9550459 -0.07552218 0.2379154 -0.9683453 0.06661637 -0.5705402 -0.8185635 -0.1097535 -0.6308349 -0.7681155 0.1271979 -0.9481678 -0.2912021 -0.226116 -0.9702808 -0.086179 0.2585947 -0.9113015 0.3204035 -0.2341824 -0.8052666 0.5447057 0.234246 -0.2848905 0.9294978 -0.2490122 -0.04488346 0.9674598 0.2081331 0.4190017 0.8838089 -0.2727196 0.7309194 0.6256045 0.1259961 0.8814917 0.4550795 0.05978487 0.9940727 -0.09080319 -0.1936425 0.9572983 -0.2146684 0.1563374 0.7294684 -0.6659089 -0.113467 0.5957269 -0.7951319 0.07561948 0.1779432 -0.9811309 -0.07562903 0.07504483 -0.9943081 0.1134605 -0.3761483 -0.9195864 -0.1979539 -0.5587031 -0.8053975 0.2342749 -0.8513381 -0.4694023 -0.2261375 -0.9594125 -0.168492 -0.3331077 -0.9298114 0.1564926 0.2739463 -0.7974625 0.5375937 -0.2406845 -0.487447 0.839325 0.2226906 -0.2011107 0.95392 -0.2226905 0.2812826 0.9334286 0.2801481 0.5738265 0.7695714 -0.3044405 0.8316773 0.4643585 0.2742254 0.9612838 0.02708963 -0.2096717 0.9042007 -0.3721006 0.1775509 0.778146 -0.6024653 -0.2181868 0.4447576 -0.8686686 0.1623369 0.06962823 -0.9842758 -0.07560945 -0.0940825 -0.9926892 0.1134713 -0.5261272 -0.8428016 -0.2389879 -0.7013285 -0.6715826 0.3141312 -0.9072587 -0.2796484 -0.5895485 -0.6687515 0.4529943 -0.8034152 -0.0002924096 0.595419 -0.8727263 0.00144325 0.4882077 -0.9940448 6.366462e-05 0.1089715 -0.8254283 0.4671433 0.3169308 -0.9992872 0.0377119 0.001735964 -0.7827229 0.512238 -0.3534927 -0.7858878 -0.0005319298 -0.6183688 -0.75345 0.0003453083 -0.6575052 -0.9999039 -0.009984943 -0.009618262 -0.9984471 -0.05306381 -0.0169582 -0.8362387 -0.4532074 -0.3087197 -1 1.409851e-05 1.050845e-05 -1 2.707698e-05 3.810479e-05 -1 -5.5611e-05 0.0001223119 -1 1.131528e-05 5.352213e-05 -1 -1.63073e-05 -9.173542e-06 -1 1.253121e-05 3.438998e-06 -1 -1.636992e-05 -4.492472e-06 -1 -2.426705e-05 8.326076e-06 -1 2.06742e-05 3.065575e-05 -1 2.095525e-05 2.948984e-05 -1 2.644257e-05 1.287716e-05 -1 1.310347e-05 -1.417908e-05 -1 1.344282e-05 -1.441953e-05 -1 1.076606e-05 1.196274e-06 -1 8.569532e-06 3.704038e-06 -1 -9.909708e-05 3.007368e-05 -1 -7.036744e-06 1.95934e-05 -1 -4.597088e-06 2.220105e-05 -1 -6.498077e-06 1.884312e-05 -1 -1.298922e-06 -3.972692e-06 -1 1.831582e-06 5.601809e-06 -1 3.464951e-05 1.177192e-06 -1 3.164666e-05 -5.284267e-06 -1 -1.221482e-05 -1.438198e-05 -1 -1.213803e-05 6.305586e-06 -1 -4.310625e-05 -9.66499e-05 -1 4.138852e-06 -1.037433e-05 -1 -1.799972e-05 1.314304e-06 -1 -2.560027e-05 1.722109e-05 -1 -2.573544e-05 1.718677e-05 -1 4.696484e-06 -2.268107e-05 -1 -2.123692e-05 -3.008287e-05 -1 0 0 -1 1.941435e-05 5.944912e-05 -1 -4.154013e-05 -3.482328e-05 -1 1.28564e-05 2.680475e-05 -1 1.919094e-05 -5.114146e-05 -1 7.431169e-07 1.956497e-05 -1 -9.350032e-06 4.954881e-06 -1 0 0 -1 -1.735787e-05 2.51626e-05 -1 -4.735817e-05 2.815306e-06 -1 9.109262e-05 -5.415193e-06 -1 8.253413e-05 8.412371e-05 -1 -1.115999e-05 3.176399e-05 -1 0 0 -1 -5.608254e-05 7.120714e-05 -1 -2.994822e-05 -7.53797e-06 -1 0 0 -1 1.131247e-05 -4.420929e-06 -1 -1.252379e-05 1.360411e-05 -1 -2.794312e-06 1.933461e-05 -1 -2.774206e-05 -2.959156e-05 -1 -6.760845e-05 -1.686553e-05 -1 -1.205101e-05 1.766296e-06 -1 -1.256647e-05 1.359742e-05 -1 -4.256721e-06 -7.163333e-07 -1 0 -0 -1 -4.257161e-06 -1.352587e-05 -1 -3.023446e-05 1.179808e-05 -1 4.952336e-05 6.366518e-05 -1 4.232494e-05 -8.536448e-06 -1 -1.928761e-05 -4.524966e-06 -1 -9.605369e-06 9.349144e-06 -1 -0 0 -1 0 0 -1 -4.873904e-07 -1.173538e-05 -1 -2.882601e-05 6.489152e-06 -1 6.098053e-05 -2.839698e-05 -1 -6.74726e-06 -3.567842e-05 -1 0 -0 -1 -0 0 -1 7.819736e-06 2.21321e-08 -1 -1.402551e-05 -1.200464e-05 -1 -1.440757e-05 7.202533e-06 -1 -4.023514e-05 2.011407e-05 -1 -3.317791e-05 7.013226e-05 -1 -2.938536e-05 6.756368e-05 -1 -3.497117e-05 5.528468e-05 -1 -1.958609e-05 3.096296e-05 -1 4.240194e-05 6.813162e-05 -1 2.4436e-05 1.334993e-05 -1 2.604112e-05 1.270726e-05 -1 -2.427988e-05 -1.184783e-05 -1 0 0 -1 -2.941458e-06 2.146185e-06 -1 -2.517313e-06 2.791209e-06 -1 3.538371e-06 -3.923364e-06 -1 -3.454672e-05 -4.9201e-06 -1 -1.127174e-05 3.886958e-05 -1 0 -0 -1 1.135715e-05 -6.590732e-06 -1 -4.518751e-05 -9.438016e-05 -1 -5.118212e-05 -3.170325e-05 -1 1.723657e-06 -1.548092e-05 -1 1.137267e-05 -1.947118e-06 -1 4.691086e-05 -2.710721e-05 -1 2.442282e-05 -2.965698e-05 -1 2.415417e-05 -2.450509e-05 -1 -4.394975e-06 -1.006534e-05 -0.001456717 -0.8411436 0.5408098 -0.0005914563 -0.838448 0.5449814 -0.001156498 -6.986352e-05 0.9999993 0.0003839991 0.002398593 0.9999971 0.0009407953 0.8441989 0.5360292 -0.0007698922 0.8385872 0.5447667 -0.02863012 0.8423193 -0.5382179 -9.357815e-05 0.831395 -0.5556819 -0.003848424 -0.8423744 -0.5388789 -0.02044474 -0.8354 -0.5492621 0.002133576 -0.9994578 -0.03285661 0.07226426 -0.9912848 -0.1101469 -0.08065931 -0.8223187 -0.5632816 0.09677384 -0.5954432 -0.7975476 -0.08105237 -0.3149123 -0.9456536 0.08103026 0.06646387 -0.9944931 -0.112832 0.401717 -0.9087862 0.1055225 0.6749126 -0.7303137 -0.09462111 0.9763765 -0.1942571 0.03252496 0.9958902 -0.08452816 -0.03667639 0.6799245 0.7323644 0.03667396 0.6400504 0.7674571 -0.03251953 -0.2103422 0.9770868 -0.008934657 -0.2305874 0.9730106 0.02784216 -0.7761748 0.6299027 -0.03049804 -0.8142762 0.579676 -0.1167169 -0.9892514 -0.08808365 0.0549895 -0.9598736 -0.2749888 0.004674226 -0.5749381 -0.8181836 -0.0293829 -0.5478642 -0.8360512 0.005581396 0.04860268 -0.9988026 0.07645421 0.1268697 -0.9889686 -0.1055257 0.6386595 -0.7622194 0.1322491 0.8634551 -0.4867806 -0.1038669 0.9810282 -0.163693 0.1279691 0.9150698 0.3824542 -0.08501378 0.8082243 0.5827059 0.04707049 0.1770086 0.983083 -0.0886377 0.272166 0.9581591 0.1072341 -0.3684143 0.9234564 -0.1477993 -0.6744134 0.7234098 0.1090597 -0.9039424 0.4135145 0.08453713 -0.9904866 -0.1085807 -0.1322564 -0.9016207 -0.4118109 0.1055274 -0.7009962 -0.7053143 -0.0854455 -0.1819233 -0.9795933 -0.03470403 -0.1330889 -0.9904963 0.06573325 0.4197591 -0.9052521 -0.1126364 0.6370485 -0.7625498 0.1127477 0.8925865 -0.4365516 -0.1127505 0.9921438 -0.05420441 0.09678781 0.9399279 0.3273648 -0.09676783 0.7715665 0.6287456 0.1127593 0.4740481 0.873249 -0.09737097 0.1239832 0.9874954 0.07799274 -0.2876276 0.9545615 -0.0432782 -0.4552813 0.8892952 0.0484536 -0.8408597 0.53908 -0.07130098 -0.9107445 0.4067686 -0.01941749 0.9611455 -0.2753586 0.01770472 0.9419114 -0.3353946 -0.003553625 0.5896612 -0.8076429 -0.01393621 0.5748931 -0.8181098 0.01639576 -0.0764941 -0.9969352 0.02354082 -0.06667888 -0.9974967 -0.04812229 -0.6552281 -0.7538969 0.06530739 -0.8266158 -0.5589645 -0.04054693 -0.9581392 -0.2834167 0.04599592 -0.9883817 0.1448654 -0.03320138 -0.9444026 0.3271108 0.02533083 -0.6784998 0.7341638 -0.02789019 -0.5963983 0.8022039 0.03964269 -0.09426971 0.9947571 -0.07767025 0.1820312 0.9802204 0.04811114 0.4552157 0.8890803 -0.02674848 0.9127539 0.4076333 0.004258167 0.8966338 0.4427525 -0.07657427 0.9966547 0.0285652 0.0962874 0.9695603 -0.2251258 -0.0962875 0.5703855 -0.8157138 0.03840236 0.3985443 -0.9163447 0.01741833 -0.2166716 -0.9760891 -0.07460487 -0.368215 -0.9267426 0.06177894 -0.7611119 -0.6456718 -0.06175878 -0.9395728 -0.3367323 0.05167901 -0.9983693 -0.02424879 -0.043657 -0.9440119 0.3270102 0.03699321 -0.8091184 0.5864801 -0.04514397 -0.5960279 0.8016937 0.04834191 -0.3666779 0.9290912 -0.0398237 0.09224715 0.9949394 0.02558664 0.2425706 0.9697963 -0.02904808 0.6585221 0.7520006 0.04812417 0.7641658 0.6432222 -0.07126104 0.9957123 0.05898224 0.06483974 0.9835839 -0.1683997 -0.04543466 0.724309 -0.6879769 0.01671061 0.6356096 -0.7718297 -0.00569333 0.06283361 -0.9980078 0.001514951 0.07272153 -0.9973512 -0.02363059 -0.7016426 -0.7121372 0.04803775 -0.7601821 -0.6479318 -0.04195164 -0.9899372 0.1351461 0.03735056 -0.967113 0.2515896 -0.03085338 -0.6419547 0.7661216 0.01673947 -0.5678122 0.8229879 -0.004621344 -0.00752202 0.9999611 0.002293808 -0.01815966 0.9998325 -0.02025654 0.6374774 0.7702027 0.05912563 0.7233917 0.6879015 8.956229e-08 -0.1414195 -0.9899498 -1 0 0 -1 0 0 8.991214e-08 -0.1414195 0.9899498 1 0 0 1 0 0 0.9756428 0.2014292 0.08687654 0.9212471 -0.1475285 -0.3599154 0.6709798 0.1782602 -0.7197287 0.5895446 -0.012496 -0.8076392 0.009551461 -0.09297222 -0.9956228 -0.1748201 0.1639023 -0.9708624 -0.5705085 -0.1614321 -0.80527 -0.8028173 0.2477211 -0.542327 -0.9653214 -0.2477195 -0.08239888 -0.9017777 0.2591977 0.3458518 -0.7379493 -0.2180686 0.6386524 -0.2380337 0.2180639 0.9464608 0.04149351 -0.1829404 0.982248 0.5156726 0.1829208 0.8370315 0.6814669 -0.1010228 0.724843 0.9681698 -0.04784118 0.2456796 0 0 -1 0 0 -1 -1 0 0 -1 0 -0 -0.03383369 -0.189414 0.9813142 -0 0 1 1 0 0 1 -0 0 1 0 0 6.442861e-08 -0.06651792 -0.9977853 -1 0 0 -1 0 -0 -0.03383366 -0.1894138 0.9813142 -0 0 1 1 2.543132e-06 -0 1 2.543132e-06 0 1 3.559343e-06 -2.311469e-06 1 -7.141093e-07 0 1 1.193608e-06 -2.951225e-05 1 -1.102738e-05 -2.409039e-05 1 -1.350643e-05 -2.950613e-05 -1 0 0 -1 0 0 -0.06047292 -0.02429286 -0.9978742 0.07748896 -0.04660018 -0.9959036 -0 0 1 0 0 1 1 0 1.289037e-06 0.02460199 -0.8411427 -0.5402535 0.007180747 -0.8346135 -0.5507892 0.7554097 -0.5390481 0.3725366 0.001623445 -0.4478561 0.8941041 -0.001573098 -0.3716094 0.9283879 0.8926524 0.0039234 0.4507286 0.6291784 -0.001584691 0.7772593 0.9015251 0.004935282 0.4326986 0.7492468 -0.005402938 0.6622688 -0.0001025559 0.577511 0.8163829 -0.0022649 0.5070518 0.8619125 0.001827285 0.2702001 0.9628025 0.5699871 0.6821204 0.4580682 -1.35221e-07 0.1414191 0.9899498 -1 0 0 -1 0 0 1 0 -0 1 0 0 0.9709111 0.2230633 0.08703022 0.9252499 -0.1929252 -0.3266382 0.7632576 0.1929891 -0.616598 0.4625198 -0.1967537 -0.8645018 -0.03785777 0.1849339 -0.9820216 -0.241285 -0.1462132 -0.9593765 -0.7790619 0.1927833 -0.5965712 -0.8999954 -0.2202591 -0.3761571 -0.9610884 0.20015 0.1903917 -0.9033189 -0.1230907 0.41093 -0.5180012 0.0608064 0.8532159 -0.5536253 -0.01258644 0.8326708 0.009568469 0.04601273 0.998895 0.1304659 -0.1241117 0.9836539 0.6292377 0.1614733 0.7602541 0.8066586 -0.2388058 0.5406234 0 0 -1 0 0 -1 1 2.606466e-06 0 1 2.54313e-06 1.491263e-08 0.03401763 0.1904419 0.9811089 0 0 1 -1 0 0 -1 -0 0 -1 0 0 -6.343643e-08 0.06651792 -0.9977853 1 0 0 1 0 0 0.03401886 0.1904492 0.9811075 0 0 1 -1 -0 0 -1 -0 0 -1 0 0 0.002843569 0.8444738 -0.5355893 0.0244223 0.8353194 -0.5492222 1 2.54313e-06 -8.176197e-09 1 2.575844e-06 0 -0 0 1 0 0 1 0.04351141 0.01725801 -0.9989038 -0.1202244 0.04363968 -0.9917871 -6.277659e-08 0.06651792 0.9977853 -1 -0 0 -1 0 0 -0.01819262 0.4882564 -0.8725106 -0.008864955 0.4640117 -0.8857847 -0.03066879 -0.3566085 -0.9337505 0.01247924 -0.546317 -0.8374856 -0.01680448 -0.6877841 -0.7257207 1 4.394818e-06 -2.388643e-05 1 1.068346e-05 6.762979e-05 1 -8.443633e-05 2.21178e-05 1 2.865858e-05 -1.71315e-05 1 2.937464e-05 9.656745e-07 1 3.29329e-05 2.607181e-06 1 1.507729e-05 1.032782e-05 1 1.148309e-05 -1.370082e-06 1 -3.875792e-06 -1.163866e-05 1 -9.924284e-06 -1.106267e-06 1 -6.7368e-06 1.524036e-05 1 -4.928356e-05 3.240427e-05 1 -3.170414e-05 6.307765e-06 1 -7.25748e-05 -6.194e-06 1 -2.294208e-05 -2.471151e-05 1 -2.300776e-05 -2.487671e-05 1 0 -0 1 -1.635842e-05 -1.1402e-05 1 5.380516e-06 -3.454236e-05 1 2.595724e-05 -1.96779e-06 1 -5.607622e-06 1.617757e-05 1 6.349751e-06 -6.453368e-05 1 9.64877e-05 -4.521609e-05 1 2.310875e-05 1.900264e-05 1 -1.318908e-05 -1.084556e-05 1 -1.60741e-06 -1.346853e-05 1 1.134427e-05 2.049538e-05 1 -1.020084e-05 1.968605e-05 1 -7.373384e-06 2.498996e-06 1 2.773836e-05 -9.401117e-06 1 3.078719e-05 -3.302389e-05 1 2.965274e-05 -3.28084e-05 1 1.84258e-05 7.812847e-06 1 -0 0 1 -1.544931e-05 -2.894072e-06 1 9.015946e-06 3.502284e-05 1 -9.273274e-07 3.744778e-05 1 9.953993e-06 -9.616246e-06 1 -2.703566e-06 -4.431769e-05 1 6.909473e-05 -6.136705e-05 1 -6.981288e-06 3.055589e-05 1 -3.446386e-05 8.649375e-06 1 1.473031e-05 6.728001e-06 1 8.779745e-06 -3.260216e-05 1 5.92077e-06 -3.53477e-05 1 -1.328008e-05 4.495329e-06 1 -8.671833e-06 1.038022e-05 1 -5.187447e-05 3.572645e-05 1 -6.230352e-05 -1.659507e-05 1 -1.479979e-05 -3.942048e-06 -1 1.34665e-05 -5.923089e-06 -1 4.165974e-07 6.232177e-06 -1 -3.490692e-06 1.209064e-06 -1 -1.788233e-06 2.405318e-06 -1 -1.259885e-05 -6.118552e-07 -1 -1.727601e-05 -5.110227e-06 -1 -1.203161e-05 1.222786e-05 -1 8.084026e-07 2.03463e-06 -1 -8.490005e-06 2.889632e-07 -1 -2.247283e-06 -6.440956e-08 -1 -7.527125e-07 -8.595616e-07 -1 3.50759e-06 1.257081e-06 -1 4.991698e-05 -3.437754e-05 -1 -2.528266e-06 3.489792e-07 -1 1.809591e-07 6.802228e-06 -1 -3.151003e-06 3.76047e-06 -1 -2.884527e-06 3.873216e-06 -1 9.225376e-06 5.058783e-06 -1 1.03514e-05 4.676645e-06 6.357833e-07 -1 0 6.357833e-07 -1 0 6.357833e-07 -1 0 5.143478e-07 -1 4.390422e-08 4.662795e-07 -1 4.959587e-07 5.71882e-07 -1 2.505435e-07 4.698575e-07 -1 1.192295e-07 7.668859e-07 -1 -1.088126e-06 0 -1 0 0 -1 0 0 -1 0 7.986815e-07 -1 1.310482e-07 6.325737e-07 -1 -8.503082e-08 1.267247e-06 -1 8.52646e-08 7.083537e-07 -1 1.994052e-07 1.194061e-06 -1 -1.703248e-07 7.947297e-07 -1 9.632392e-07 8.317401e-07 -1 7.164985e-07 1.409864e-06 -1 4.631256e-08 -0.04228681 -0.9990854 0.006340838 -0.01680817 -0.9997871 0.0119674 -0.006432728 -0.9996414 0.02599508 -0.004250712 -0.9993103 0.03689044 0.02874362 -0.8383231 0.5444156 9.172743e-07 -1 -1.514694e-07 1.972916e-06 -1 0 8.648988e-07 -1 -1.713036e-07 1.103972e-06 -1 1.708895e-07 -0.01049179 -0.9997996 0.01705077 8.074745e-07 -1 9.036414e-07 1.414033e-06 -1 1.092997e-07 9.536743e-07 -1 1.604637e-07 8.958983e-07 -1 5.63135e-07 -0.03654229 -0.999312 0.006342276 -0.02872354 -0.9995605 0.007340242 -0.003616353 -0.9988918 0.04692542 0.02874366 -0.8383235 0.5444147 0.1776776 -0.9745308 -0.1368228 -0.1388987 -0.6327032 -0.7618358 -0.01121111 -0.5982079 -0.8012626 0.06946179 0.09664658 -0.992892 -0.1345003 0.1837624 -0.9737253 0.1239794 0.7692257 -0.626834 -0.172842 0.8472241 -0.5023316 0.2179938 0.972415 0.08299216 -0.2385197 0.9236869 0.2998517 0.1816435 0.5438383 0.8192958 -0.1728435 0.3906452 0.9041689 0.2003519 -0.1772818 0.9635509 -0.293825 -0.4336625 0.8518237 0.2750183 -0.7941332 0.5419571 -0.3022512 -0.9473101 0.1060561 0.2265374 -0.959956 -0.1648186 -0.1260099 -0.923994 -0.3610493 -0.05978446 -0.5885795 -0.8062257 0.1359597 -0.5020719 -0.8540719 -0.07561722 -0.00956396 -0.9970911 0.07563675 0.09407886 -0.9926873 -0.1245975 0.5493851 -0.8262272 0.1956714 0.6870963 -0.6997223 -0.1776105 0.9529557 -0.2456219 0.1773318 0.9841412 -0.004421531 -0.1485359 0.9303657 0.3351966 0.2010267 0.7274386 0.656065 -0.1426248 0.5620792 0.8146933 0.08671629 0.00753658 0.9962046 0.1389365 -0.01366723 0.990207 -0.1667568 -0.6532494 0.7385507 0.2033376 -0.7920215 0.5756351 -0.1485528 -0.9585209 0.2432482 0.06944673 -0.9878978 -0.1386906 -0.1995167 -0.9473078 -0.2506013 0.2040238 -0.6092368 -0.7662929 -0.1803806 -0.392305 -0.9019754 0.09848875 -0.1051855 -0.9895636 -0.1164256 0.2152495 -0.9695941 0.1727753 0.4412563 -0.8805916 -0.1833042 0.7316918 -0.6565261 0.1418344 0.9212747 -0.3621271 -0.1084168 0.9808274 -0.1619367 0.1426429 0.9655156 0.2177905 -0.241059 0.8306368 0.5019292 0.1847711 0.6538492 0.7337171 -0.05346349 0.1593207 0.9857782 -0.2538742 0.0667311 0.9649326 0.2181755 -0.433968 0.8741117 -0.2135619 -0.7773475 0.5917112 -0.004658051 -0.8565118 0.5161066 0.02395243 -0.6571599 -0.7533705 -0.1107853 -0.6099931 -0.7846242 0.1816751 -0.9595295 -0.2151681 -0.06082973 -0.9403082 -0.3348439 0.01583373 -0.5661375 -0.8241587 -0.2446529 0.6861627 -0.6850736 0.2690223 0.9431754 -0.195057 -0.226541 0.9705113 0.0823838 0.2009768 0.8278731 0.523674 -0.1427079 0.6916705 0.7079734 0.07571185 0.2040474 0.9760289 0.1844 0.1527165 0.9709141 -0.226113 -0.4172992 0.8801898 0.3180487 -0.7016567 0.6375914 -0.2214829 -0.8903939 0.3976732 -0.2407215 -0.9688961 -0.05739033 0.2409049 -0.8612641 -0.447425 -0.2092912 -0.6442277 -0.7356412 -0.2974564 0.7266178 -0.6193109 0.1159195 0.8911554 -0.4386394 0.004812709 0.9749184 0.2225109 -0.07223618 0.9652651 0.251088 0.007884451 0.5447955 0.8385319 0.1187486 0.4986506 0.8586305 -0.1461447 -0.1018007 0.9840114 0.2705891 -0.3332261 0.9031844 -0.2750079 -0.697104 0.6621303 0.2627609 -0.9248933 0.2748259 0.02596327 0.434955 -0.9000778 -0.07276972 0.5841478 -0.8083786 -0.0170501 0.01491409 -0.9997434 0.009236984 0.6283531 -0.7778734 -0.01387362 0.5225976 -0.8524666 0.02140198 0.3622144 -0.9318491 0.02069082 -0.4831055 -0.8753176 -0.002542488 -0.5445208 -0.8387435 0.3041765 -0.9488618 0.08448593 -0.3041795 -0.8665116 -0.3957681 0.2438197 -0.703177 -0.6679027 -0.1843973 -0.1794618 -0.9663287 0.05969124 -0.0725968 -0.9955735 -0.05969894 0.6176443 -0.7841886 0.05199961 0.6564053 -0.7526142 -0.05200448 0.9850328 -0.1643349 0.1269965 0.9883499 -0.08388258 -0.1776498 0.7982485 0.5755345 0.1359205 0.7011124 0.6999764 -0.08676717 0.2334723 0.9684845 0.04374491 0.1594118 0.9862425 -0.0478403 -0.4279051 0.9025567 0.1653978 -0.5172862 0.8396776 -0.2438159 -0.8855184 0.3954882 0.5744175 -0.6796868 -0.4561474 0.999294 0.03527085 -0.01294158 0.999865 0.008223871 -0.01421859 1 -1.818287e-06 -5.844175e-06 1 -6.125871e-06 4.854453e-06 1 -1.335076e-05 -2.698196e-05 0.9997131 0.01546254 -0.01829003 1 -4.886179e-06 1.02363e-05 0.9996519 0.02612838 -0.003656175 0.9997128 0.004985223 -0.0234412 0.9998487 0.01739277 -0.0001263221 0.9996176 0.02329172 0.01490811 1 -0.0001636406 0.0001113344 0.9999954 0.001355682 0.002701883 1 -7.888794e-06 3.718953e-07 1 -1.791837e-06 1.107828e-05 1 1.057922e-05 3.209769e-07 1 1.673032e-06 -1.357121e-05 0.9998111 -0.01943241 0.0001379991 1 5.450852e-07 6.201243e-06 1 2.472192e-07 2.812526e-06 0.9999997 -9.982953e-05 0.0007561175 0.9999305 7.690003e-05 0.01179183 0.9998231 -0.0002986657 -0.01880641 0.999634 -0.02705494 -0.0001623221 1 -9.126466e-07 -3.233451e-06 0.999847 -0.01356077 -0.01105061 0.998075 -0.05323421 -0.03181712 0.9995463 -0.02549372 0.01603599 1 4.421697e-05 -5.928576e-06 0.9998918 -0.001000757 -0.01467572 0.9992764 -0.03801811 -0.001093902 1 1.245358e-05 5.078974e-06 1 1.107658e-05 2.023956e-06 1 1.250331e-05 4.036067e-06 1 1.238608e-07 -2.441714e-07 1 -1.947907e-05 -2.968823e-06 1 2.894122e-06 1.109715e-06 0.999997 0.002305769 0.0008048551 0.9998516 0.01398268 0.01005612 0.9999976 -0.0007747636 0.0020658 0.9967312 -0.08003142 -0.01104612 0.9999937 -0.002729514 0.002220379 0.9997619 -0.02180177 0.0008300864 0.9997748 -0.02000055 0.007088672 1 -6.829068e-05 -3.043031e-05 1 -6.323931e-06 -6.853731e-06 0.999901 0.01218728 -0.00704728 0.9998376 0.01744812 0.004514202 0.9989517 0.04547159 -0.00526881 0.99999 -0.002483298 0.003700152 0.9986542 0.004260323 0.05168691 1 -6.209451e-08 -2.073267e-07 0.9999524 0.009468941 -0.002380099 0.9980931 0.06105991 -0.009042798 0.9999985 0.0004848181 0.001664314 1 -6.887855e-06 -1.62131e-06 0.9999874 -0.0005576962 0.00500654 0.743126 -0.2843401 0.6057346 0.6726955 -0.3370476 0.6586955 -0.7623024 -0.2343427 0.6033064 -0.8984605 -0.211639 0.3846786 -0.004451534 0.04698908 0.9988855 0.01772631 0.01114619 0.9997807 0.04451211 0.1761782 0.9833514 -0.06304324 0.449084 0.8912627 -0.01749091 0.4828392 0.8755343 0.05025728 0.6834484 0.7282669 -0.0505438 0.8110843 0.5827413 0.03403159 0.8665581 0.4979146 -0.03858186 0.9674373 0.2501534 0.03757565 0.9864622 0.1596263 -0.04992423 0.9921356 -0.11478 0.03237787 0.9804223 -0.1942264 0.007634848 0.8669502 -0.4983363 -0.03895487 0.8435904 -0.5355724 0.03261271 0.6893159 -0.7237266 -0.04982567 0.5706209 -0.8197007 0.03108265 0.4864877 -0.8731344 0.005331929 0.1696887 -0.9854833 -0.013865 0.1553963 -0.9877549 -0.005082614 -0.2106452 -0.9775494 0.03244115 -0.2436499 -0.9693205 -0.02948317 -0.5482768 -0.8357771 0.03063433 -0.5905824 -0.8063956 0.06028936 -0.7340478 -0.6764163 -0.06750312 -0.8710195 -0.4865885 0.005823107 -0.9039669 -0.4275626 0.03401221 -0.9934134 -0.1094211 -0.02485455 -0.9992799 -0.02867274 0.04200458 -0.9948906 0.09180617 -0.03059889 -0.9424373 0.3329799 0.03217144 -0.9129084 0.4068945 -0.03806216 -0.777443 0.6278006 0.03788423 -0.7152708 0.6978197 -0.02754272 -0.5279666 0.8488184 -0.001569796 -0.2787056 0.9603753 0.02248411 -0.2467812 0.9688103 0.04686407 -0.4435107 0.895043 0.822298 0.3148155 0.4740435 0.7305819 0.4153636 0.5419624 0.7339393 0.2262818 0.6404136 -0.8438755 0.2813997 0.4568242 -0.8251545 0.2880826 0.4859305 -9.536743e-07 1 0 -9.536743e-07 1 0 -9.536743e-07 1 0 -5.49348e-07 1 -4.924229e-08 -1.000243e-06 1 6.52393e-07 -9.455896e-07 1 7.63895e-07 -9.862291e-07 1 -9.526226e-07 -0 1 0 -4.493623e-07 1 1.414527e-06 -1.849389e-06 1 2.715614e-07 -4.557217e-07 1 -1.134876e-06 -7.489193e-07 1 -5.074258e-07 0.02059554 0.9997512 0.008567501 0.007909755 0.9997799 0.01943418 -1.716321e-06 1 -2.543755e-07 0 1 0 -0 1 0 0.03923463 0.9992129 0.005859273 -6.357837e-07 1 2.826279e-07 0.003699329 0.999275 0.03789128 -4.945668e-07 1 1.347446e-06 -0.02896663 0.8383231 0.5444035 -8.095662e-07 1 2.855661e-07 -7.317098e-07 1 7.489929e-07 0.01438088 0.9998304 0.01150518 -1.598607e-06 1 -4.706115e-07 0 1 0 0 1 0 -1.986859e-06 1 2.299907e-07 0.04099615 0.9991421 0.005859022 -9.536743e-07 1 1.051881e-06 -1.119537e-06 1 -1.632884e-07 0.005776653 0.9996446 0.02602692 0.003916067 0.9993992 0.03443738 -5.119613e-07 1 1.405884e-06 -0.02896575 0.8383226 0.5444044 0.7478797 0.547438 -0.3754832 -0.1536296 0.5259194 -0.8365446 0.1538003 0.6064641 -0.7800941 -0.9998812 0.01439739 -0.005500577 -0.8382459 0.3071115 -0.4505843 -0.6401479 0.3633208 -0.6769111 -0.6655386 -0.2665735 -0.6971347 -0.8358643 -0.2824749 -0.470679 -0.7553141 -0.4255234 -0.498428 0.9825239 0.1833172 0.03227489 0.9138936 -0.1979392 -0.354427 0.8046056 0.1563899 -0.5728455 0.4393117 -0.1748355 -0.881157 0.2355882 0.195669 -0.9519516 -0.3154681 -0.1956578 -0.9285461 -0.5124474 0.1748628 -0.8407263 -0.8503203 -0.1563346 -0.5025085 -0.9406575 0.1979546 -0.2756402 -0.9677595 -0.208159 0.1418145 -0.8560406 0.2080915 0.4731728 -0.6916882 -0.1426097 0.7079759 -0.3473282 0.1278615 0.9289857 -0.2036871 -0.09432826 0.9744813 0.314191 0.1054988 0.9434798 0.4260032 -0.1055269 0.8985462 0.8213446 0.09434716 0.562576 0.899988 -0.1686764 0.4019575 0.9445317 0.222708 -0.2413732 0.8403103 -0.2010234 -0.5034561 0.5104773 0.2265117 -0.8295212 0.3111584 -0.1735634 -0.9343748 -0.3490773 0.08068833 -0.9336137 -0.3404551 0.05629497 -0.938574 -0.8599328 -0.04782964 -0.5081612 -0.8835866 0.04781773 -0.4658201 -0.9921201 -0.04377127 0.1173954 -0.9860386 0.03486923 0.1628244 -0.7736332 -0.03478187 0.6326784 -0.6945809 0.1467133 0.7042958 -0.2000516 -0.2438183 0.9489637 0.1173166 0.3041797 0.9453632 0.5337068 -0.2409098 0.8106291 0.8178626 0.2407408 0.5226324 0.944537 -0.222678 0.2413797 -0.1834237 -0.1013989 -0.9777904 -1 -2.546083e-05 2.234678e-05 -1 -2.072112e-05 2.174726e-05 -1 -1.865568e-05 7.823032e-06 -1 5.339779e-06 -2.239172e-06 -1 1.642758e-05 1.546122e-05 -1 2.254578e-05 1.073777e-05 -1 0 -0 -1 -4.100023e-06 1.353176e-05 -1 1.582366e-05 1.034852e-05 -1 0 0 -1 1.638007e-05 -3.053829e-05 -1 1.251764e-05 -2.908711e-05 -1 1.420952e-05 -2.255051e-05 -1 7.081653e-06 -1.123858e-05 -1 -2.107304e-05 -2.668327e-05 -1 -9.295411e-06 3.121401e-05 -1 4.793057e-05 1.706808e-05 -1 1.215758e-05 -1.067062e-05 -1 -1.184893e-05 -2.229199e-05 -1 -1.14091e-05 -2.146451e-05 -1 -1.162053e-05 -2.064308e-05 -1 -5.86739e-07 -1.762471e-05 -1 5.14679e-06 -4.131536e-06 -1 -6.637598e-06 5.328268e-06 -1 2.390569e-06 3.75144e-06 -1 -2.247692e-06 -3.527228e-06 -1 -2.439396e-06 -3.211522e-06 -1 0 -0 -1 -1.197248e-05 3.019216e-05 -1 1.982377e-07 3.748906e-05 -1 -7.244713e-06 2.095227e-06 -1 2.700491e-05 -7.810027e-06 -1 1.580385e-05 -1.375399e-05 -1 2.069325e-05 -1.366516e-06 -1 7.517339e-05 -6.604644e-05 0.7481154 0.4330606 -0.5027742 0.8482814 0.2908146 -0.4425445 0.4905111 0.2773506 -0.8261207 0.6338648 -2.075474e-05 -0.7734439 0.6589097 -0.0005436551 -0.7522218 0.9985716 0.0003781529 -0.05342808 0.9985391 -0.04701786 -0.02662507 0.634615 -0.3607594 -0.6834592 0.806528 -0.3230246 -0.4951442 -1 5.923902e-05 2.885903e-05 -1 3.883857e-06 -1.089871e-05 -1 -2.796266e-05 2.3464e-05 -1 -4.090939e-05 2.526379e-05 -1 -4.056943e-05 5.404511e-05 -1 -2.77975e-06 1.818961e-05 -1 7.331425e-06 3.041205e-05 -1 1.486579e-05 -2.617317e-05 -1 -4.079719e-05 -2.941464e-05 -1 -1.089649e-05 8.705319e-06 -1 -2.250333e-05 1.797814e-05 -1 -2.284269e-05 1.795082e-05 -1 -1.543931e-05 -2.989286e-06 -1 -4.428208e-06 -1.040388e-05 -1 0 0 -1 -4.658347e-07 1.896215e-05 0.1979505 -0.9706905 -0.1362921 -0.2081642 -0.8234138 -0.5278801 0.2406881 -0.5568722 -0.7949607 -0.2226883 -0.2812961 -0.9334251 0.2474032 0.2284325 -0.9415998 -0.1533598 0.4470412 -0.8812689 0.07570923 0.8734974 -0.4809057 0.0520105 0.8696338 -0.49095 -0.05202463 0.9835162 0.1731742 0.059736 0.9731879 0.222119 -0.06407247 0.5449324 0.8360284 0.06400886 0.501185 0.8629696 -0.05112159 -0.187187 0.9809932 0.1284146 -0.2861464 0.949542 -0.1385154 -0.6404121 0.7554376 0.2081716 -0.8234163 0.5278733 -0.1979251 -0.9706976 0.1362779 -0.1195755 -0.8358082 -0.5358418 0.1936354 -0.7310289 -0.6542951 -0.1748675 -0.2840688 -0.9427228 0.1461522 -0.1017763 -0.9840128 -0.09545338 0.4503442 -0.887738 0.0348639 0.5187221 -0.8542318 -0.03857002 0.8888347 -0.4566017 0.1153037 0.9163126 -0.3835052 -0.1667444 0.9535719 0.2507926 0.2033819 0.8705611 0.4480616 -0.1742313 0.6243635 0.7614551 0.2081909 0.3425656 0.9161361 -0.2490044 -0.1267704 0.9601698 0.234268 -0.3627075 0.9019766 -0.199456 -0.8281229 0.5238604 0.2808243 -0.9348916 0.2170605 -0.02133211 -0.9986634 0.04707921 -0.106949 -0.9938071 -0.03015242 0.04781123 -0.9929096 -0.108833 -0.04375599 -0.7562429 -0.6528264 0.1376498 -0.6766272 -0.7233452 -0.1743575 -0.2825144 -0.9432842 0.208041 0.03713069 -0.9774151 -0.1751079 0.3447928 -0.9222013 0.1751294 0.6682112 -0.7230654 -0.1426354 0.8378115 -0.526998 0.127822 0.9813126 -0.1438297 -0.09434573 0.9955204 0.006162355 0.09435698 0.8721017 0.480141 -0.168671 0.7640975 0.6226597 0.2092836 0.4423761 0.8720687 -0.2726646 0.0655726 0.959872 0.2333698 -0.2805694 0.9310314 -0.2234386 -0.6861032 0.6923422 0.1461318 -0.8328222 0.5339033 0.8332415 0.166915 -0.5271128 0.8446138 -0.5236972 -0.1112147 0.4523512 -0.8054579 -0.3829047 0.8605484 -0.4247081 -0.2812105 0.8642737 -0.2514524 -0.4356634 0.235502 -0.2371858 -0.942487 0.8825294 -0.05373 -0.4671777 0.1149397 0.1690781 -0.9788777 0.5383064 0.4071693 -0.7378615 0.8174099 0.3295039 -0.4725127 0.3894153 0.635945 -0.6662804 0.86554 0.4307758 -0.255485 0.8168882 0.5015924 -0.2847785 0.3654888 0.9127657 -0.1824195 0.8908944 0.4533647 -0.02770901 0.3567703 0.9221421 0.149562 0.8302341 0.5333343 0.1620678 0.4195333 0.7623396 0.492778 0.8142108 0.5032985 0.2893983 0.406195 0.6260723 0.6656119 0.8664168 0.2738868 0.4175019 0.6182176 0.3736723 0.6915027 0.7578026 0.1727862 0.6291901 0.9018466 -0.04999135 0.4291545 0.8546176 -0.2872773 0.4325511 0.2115952 -0.698971 0.6831303 0.8820731 -0.400388 0.2482669 0.3313606 -0.8620081 0.3835911 0.7661468 -0.6339955 0.1052075 0.9591982 0.06662189 -0.2747734 0.907652 -0.1728772 -0.3824674 0.5914981 0.1640845 -0.7894341 0.338561 -0.1858463 -0.9224086 0.07450417 0.1381558 -0.9876042 -0.3712106 -0.1748577 -0.9119361 -0.5768361 0.2439962 -0.7795678 -0.8900687 -0.2658699 -0.3702579 -0.9830734 0.1569196 -0.09456711 -0.9449072 -0.1100965 0.3082678 -0.8979164 0.08450737 0.4319776 -0.4878624 -0.1686853 0.8564669 -0.374152 0.1232907 0.9191353 0.3445445 0.004803662 0.9387577 0.3716649 -0.07224949 0.9255513 0.9130151 0.01123548 0.4077711 0.9093088 -0.01121531 0.4159709 0.9686086 -0.2470908 0.02726857 0.815037 0.1551513 -0.5582498 0.7963046 0.2035541 -0.569618 0.3346412 -0.2086775 -0.9189499 0.02169101 0.1756448 -0.9842146 -0.2154456 -0.1084384 -0.9704763 -0.5620939 0.142648 -0.814679 -0.7637662 -0.2080715 -0.6110381 -0.9313931 0.2408919 -0.2729063 -0.9641136 -0.2408945 0.1116018 -0.8348602 0.2407477 0.4950242 -0.6916583 -0.1426584 0.7079954 -0.1757778 0.08675336 0.9805998 -0.2150759 -0.01122775 0.9765328 0.4707089 0.06660883 0.8797706 0.5818911 -0.2289343 0.7803793 0.9019812 0.2915827 0.3184483 -1.116819e-06 -1 2.035426e-06 3.977706e-07 -1 3.251493e-07 -0 -1 0 0 -1 0 -0 -1 -0 0 -1 0 2.704682e-07 -1 -7.430995e-07 7.781366e-07 -1 -2.004091e-07 0 -1 -0 0 -1 -0 1.775707e-06 -1 1.353857e-08 2.038155e-06 -1 -5.507575e-07 2.579323e-06 -1 -3.779714e-07 1.51714e-06 -1 2.224014e-07 1.539256e-06 -1 2.559724e-07 1.13179e-06 -1 1.882124e-07 1.011663e-06 -1 1.425744e-06 9.27194e-07 -1 1.306701e-06 1.548559e-06 -1 -4.36306e-07 -0 -1 0 0 -1 -0 -0 -1 0 6.511127e-07 -1 -3.162019e-07 3.734278e-07 -1 -1.248492e-06 6.785966e-07 -1 -1.104444e-06 7.795503e-07 -1 -1.26875e-06 9.235225e-07 -1 -1.87643e-07 1.357382e-06 -1 -2.757952e-07 1.058355e-06 -1 4.281105e-07 0 -1 0 9.409366e-07 -1 -6.526681e-07 1.539502e-06 -1 2.560751e-07 8.448043e-07 -1 1.405216e-07 8.844396e-07 -1 7.586116e-07 5.433479e-07 -1 4.660466e-07 1.41901e-06 -1 -6.989931e-07 0.03699225 -0.9974788 -0.06056233 0.0257402 -0.9983801 -0.05073989 -0.02577404 -0.6977182 -0.7159085 -0.071568 -0.7243433 -0.6857148 0.0986484 -0.2415096 -0.9653713 -0.1274504 0.1541081 -0.9797994 0.06739116 0.3944004 -0.9164642 -0.04380218 0.8291056 -0.5573736 0.03978395 0.8839071 -0.4659671 -0.05214198 0.9986206 0.006180148 0.07217622 0.9786572 0.1924076 -0.06362628 0.8080325 0.5856921 0.05350871 0.6643713 0.7454848 -0.05350859 0.3665788 0.928847 0.07993563 0.1290686 0.9884086 -0.09683662 -0.2682438 0.9584717 0.1284967 -0.6336122 0.7629051 -0.08029816 -0.8120291 0.5780666 0.09156877 -0.9945534 -0.04978684 -0.08612813 -0.9288744 -0.3602422 0.06362396 -0.7966465 -0.6010876 -0.07217024 -0.4705094 -0.8794387 0.07216314 -0.2687916 -0.9604914 -0.08987215 0.242918 -0.9658746 0.05498622 0.3947007 -0.917163 0.0046675 0.8845921 -0.4663423 -0.05860986 0.9095621 -0.4114142 0.04328275 0.985717 0.1627529 -0.04021624 0.9581503 0.2834263 0.04022234 0.7436987 0.6673039 -0.0432742 0.6553954 0.7540452 0.05859248 0.1265564 0.9902275 0.02447553 0.09434654 0.9952385 -0.08563729 -0.4540294 0.8868616 0.1322494 -0.7129279 0.6886537 -0.1038612 -0.908132 0.4055974 0.115946 -0.9871818 -0.1096748 -0.09310155 -0.9282812 -0.360036 0.07996686 -0.571905 -0.8164129 -0.004846351 -0.4960248 -0.8682948 -0.04361476 0.04856366 -0.9978675 0.104229 0.234498 -0.9665128 -0.1090608 0.6600801 -0.7432361 0.1477925 0.8891867 -0.4330178 -0.1260212 0.9905499 -0.05412478 0.08216587 0.8995889 0.4289389 -0.04025969 0.8090024 0.5864249 0.04017791 0.4788681 0.876967 -0.06249129 0.3396074 0.9384891 0.08453976 -0.1505261 0.9849847 -0.09338319 -0.399066 0.9121546 0.09339458 -0.7552979 0.648693 -0.103865 -0.9081281 0.4056051 1 0 0 1 1.7361e-05 1.010742e-05 1 3.641154e-05 6.63737e-06 1 4.328346e-05 6.376535e-05 1 -1.58692e-05 3.76749e-06 1 1.87795e-05 -4.458421e-06 1 -1.091678e-05 4.317228e-05 1 -3.930778e-05 1.071373e-05 1 0 0 1 2.235941e-07 5.651575e-06 1 -1.863504e-05 -2.616498e-06 1 2.775342e-06 -1.653506e-05 1 2.188983e-05 2.81083e-05 1 -8.998758e-06 1.771161e-05 1 -7.096687e-06 1.39679e-05 1 -1.208303e-05 8.122925e-06 1 -1.767475e-06 5.600971e-06 1 1.617199e-05 7.212338e-06 1 -9.888209e-06 -4.409915e-06 1 -1.976275e-06 -1.910739e-05 1 2.26708e-05 3.236086e-05 1 1.402482e-05 3.413837e-05 1 2.935855e-05 -5.380807e-05 1 7.370873e-05 -5.341067e-05 1 1.237721e-05 -5.676147e-06 1 2.124419e-05 4.847905e-06 1 -3.579744e-05 -8.168946e-06 1 -7.156399e-06 -4.054495e-05 1 -4.526502e-06 7.480498e-07 1 4.143918e-06 -6.84824e-07 1 6.395993e-06 -1.461947e-05 1 1.213695e-05 -5.420833e-06 1 3.872269e-05 -7.447641e-06 1 1.535296e-05 5.95468e-06 1 0 0 1 4.757945e-05 6.30522e-05 1 4.830558e-05 6.296013e-05 1 4.471505e-05 2.148141e-05 1 7.263571e-06 -8.125417e-06 1 -2.368363e-05 2.649377e-05 1 -2.364018e-05 2.846343e-05 1 -2.356965e-05 2.847933e-05 1 -9.0059e-06 1.088188e-05 1 -1.566738e-06 1.681177e-05 1 3.915641e-05 8.492812e-06 1 4.91782e-05 3.795788e-05 1 -4.448164e-06 6.598008e-06 1 5.313751e-06 -7.881941e-06 1 7.697396e-06 1.748964e-06 1 -4.193692e-05 2.382121e-05 1 -3.57151e-05 9.999514e-06 1 -1.606362e-05 1.372952e-05 0.9993755 -0.03431891 0.008415371 0.8864148 -0.4026982 -0.2282609 0.9940673 -0.1087234 0.003066169 1 3.482165e-05 0.0001369789 0.9999737 0.005549777 0.00467142 1 4.753866e-05 6.561349e-05 1 4.169513e-05 0.0001150451 1 1.600764e-05 4.80878e-06 1 2.283593e-05 -3.241273e-05 1 6.156168e-05 2.708455e-05 1 7.140101e-05 7.689307e-06 0.9999807 0.002572386 0.005644154 0.9997769 -0.008582713 0.01929948 0.9365771 -0.03875452 0.348312 0.9998572 -0.01570285 0.006257223 0.99463 0.03270013 0.09819283 0.9976875 -0.003064526 0.06789989 1 -0.0003015231 -7.000189e-05 1 4.929968e-06 -1.848172e-05 0.9999999 -0.0001867895 -8.724602e-05 0.9999999 -8.400152e-05 -0.0003232292 1 -1.695226e-05 1.943343e-05 1 1.660306e-05 -3.549936e-05 0.9999999 -5.324847e-05 -0.0002252731 1 -3.211694e-05 1.240848e-05 1 8.22498e-05 -3.177748e-05 0.9999999 -0.0001018277 0.0002382361 1 -1.557301e-05 -3.10702e-05 0.9999985 -0.001730559 -0.0001269561 0.999998 -0.001918777 -0.0005088071 0.9936202 -0.1125835 0.006629365 1 -0.0002369894 0.0001103915 1 -5.320188e-05 -8.484904e-06 1 5.613331e-05 5.354151e-05 1 0.0001786597 7.179733e-05 1 0 -0 1 -4.438062e-05 -2.992508e-05 1 -0.0001657102 0.0001580015 0.9999999 -5.896948e-05 0.0002571399 1 -0.0001637401 5.875247e-05 1 -8.170463e-05 1.943466e-05 0.9999998 -2.690474e-06 0.000515965 0.9999978 -0.001256732 0.001677444 0.9999985 -0.0001203896 0.001782311 0.9999851 0.0004658042 0.005446159 1 1.986035e-05 2.242816e-05 0.9999468 -0.009653812 -0.003635549 0.999899 -0.002746995 -0.01394524 1 -1.251308e-05 1.03635e-05 1 2.782056e-06 -6.343997e-06 0.9999055 -0.01150287 -0.007528524 0.999976 0.003111717 -0.006181445 1 1.358996e-06 9.205403e-07 1 1.483148e-06 -2.512222e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.0001572191 -1.471019e-05 1 0 0 1 0 -0 1 0 0 1 0.0001449159 -0.0001388164 1 -4.955724e-07 1.642627e-05 1 6.245341e-06 1.042728e-05 0.9999999 4.222305e-05 -0.0003227203 0.9999999 4.060991e-05 -0.0003332681 1 1.398899e-05 -3.523945e-06 1 2.248181e-06 9.311304e-07 1 0 0 1 2.151507e-05 2.06916e-05 1 0 0 1 1.529564e-06 -1.87086e-06 1 -9.721123e-05 9.300124e-06 1 0 -0 1 0.000130052 1.324985e-05 1 0 0 1 0 0 1 6.541269e-05 6.604181e-07 1 1.363161e-06 2.200345e-06 1 7.158106e-07 -2.083487e-06 1 1.987886e-07 1.501014e-05 1 9.91772e-06 -0.0001438051 1 -1.516582e-05 5.756863e-06 1 2.337863e-07 1.765275e-05 1 -3.044199e-05 -1.599794e-06 1 -0 0 1 0 0 1 -1.044112e-05 1.188215e-05 1 4.933214e-05 -5.461396e-07 1 5.028907e-07 4.661946e-06 1 9.773947e-07 -8.468947e-06 1 3.705736e-06 -3.210953e-05 1 -4.183763e-06 -6.308541e-06 1 1.745147e-06 2.631443e-06 1 -2.839361e-05 -9.354267e-05 0.999999 -0.000160162 0.001347788 1 0 0 1 -1.982095e-05 9.109387e-06 1 -0 0 1 5.212974e-06 -1.475378e-05 1 3.199877e-06 -5.757981e-06 1 -5.437812e-06 -5.137932e-05 1 -1.995665e-05 7.481453e-05 1 -7.621352e-05 -4.201376e-05 1 -7.640251e-06 2.720946e-07 1.620651e-06 1 3.698811e-06 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 -2.507829e-07 1 -2.04195e-06 -1.000087e-06 1 -1.019051e-06 0 1 0 0 1 0 -2.008384e-06 1 7.031674e-07 -2.104377e-07 1 1.005735e-06 0 1 0 -3.357668e-06 1 -3.689164e-08 -3.012666e-06 1 1.866796e-06 0 1 0 0 1 -0 -1.467252e-06 1 3.063924e-06 -0 1 0 0 1 -0 -0 1 0 -0 1 -0 0 1 0 -0 1 0 0 1 0 -3.755042e-07 1 -2.954239e-06 -1.43065e-06 1 -1.259667e-06 0 1 0 0 1 0 -2.770555e-06 1 -2.657351e-08 -2.944113e-06 1 -1.474189e-07 -4.140999e-06 1 2.038256e-06 0 1 0 -1.362996e-06 1 -8.586013e-07 -1.015933e-06 1 5.388124e-07 0.9933738 -0.07266276 -0.08904283 0.956149 0.09962635 -0.2754155 0.6565984 -0.08226395 -0.7497408 0.4801083 0.0621076 -0.8750078 0.1206585 -0.05347849 -0.9912525 -0.09415653 0.06363972 -0.9935213 -0.4783308 -0.06362516 -0.8758719 -0.6770349 0.06992248 -0.7326217 -0.8987156 -0.09307016 -0.4285421 -0.983901 0.1055265 -0.1442325 -0.9086698 -0.07642571 0.4104609 -0.8441116 0.04912517 0.5339124 -0.3943603 -0.0673888 0.9164817 -0.2442307 0.05731076 0.9680221 0.2693042 -0.03979566 0.9622326 0.3421021 0.0200202 0.9394495 0.8144786 -0.02189244 0.5797804 0.8567893 0.04910699 0.5133231 0.9932836 0.09964032 0.05881707 0.8214306 -0.1086036 -0.5598724 0.7453707 0.02555434 -0.6661603 0.1826956 0.06026738 -0.9813206 0.01368173 -0.1198106 -0.9927025 -0.6324477 0.08414986 -0.7700186 -0.7760185 -0.1069081 -0.6215834 -0.9794564 0.1016452 -0.1741653 -0.9641217 -0.08705048 0.2507823 -0.924081 0.02003801 0.3816711 -0.5678186 -0.02005955 0.8229092 -0.5030794 0.03978608 0.8633239 -0.03617662 -0.05213772 0.9979844 0.1207478 0.05214917 0.9913124 0.5744857 -0.03980742 0.8175461 0.6581962 0.04378231 0.7515723 0.966296 -0.07266767 0.2469648 -0.02242554 -0.8761532 -0.4815109 0.007007637 -0.8157592 -0.5783491 -0.008403009 0.09584136 -0.9953611 0.0001102579 0.1219623 -0.9925347 0.008857583 0.9716644 -0.2361987 -0.05134961 0.9981727 -0.03185198 0.0524864 0.6969394 0.7152067 -0.05248097 0.1927281 0.9798477 0.03098695 -0.3624631 0.9314828 -0.03343978 -0.7697264 0.6374975 0.02661388 -0.9414499 0.336101 -0.03195853 0.1903563 -0.9811948 0.03352563 0.7481103 -0.662727 -0.03573009 0.9400706 -0.3391026 0.03907585 0.9663863 0.2541075 -0.03907607 0.7230623 0.6896768 0.04195843 0.1527534 0.9873732 -0.04194492 -0.2233292 0.9738402 0.04890315 -0.8950812 0.4432136 -0.03950413 -0.9969895 0.06671757 0.02323288 -0.8469051 -0.5312364 -0.02186083 -0.6106292 -0.7916148 0.02470569 -0.1958667 -0.9803193 -0.06049923 -0.7636507 -0.6427888 0.05297814 -0.4344739 -0.899125 -0.0519348 0.5000717 -0.8644252 0.02755691 0.7348172 -0.6777052 -0.01139046 0.9584967 0.2848758 0.01137999 0.9757064 0.2187866 -0.02661003 0.3406157 0.939826 0.05323865 0.01496792 0.9984696 -0.05935951 -0.7489391 0.6599748 0.05698146 -0.9693815 0.2388568 -0.03334183 -0.9735518 -0.2260208 0.02313618 -0.8468711 -0.5312948 -0.01950591 -0.2889999 -0.9571304 0.007019483 -0.179895 -0.9836608 -0.00740792 0.7202885 -0.693635 0.006251952 0.75597 -0.6545765 -0.005481653 0.9896199 0.1436052 0.02527643 0.9582498 0.2848129 -0.04155122 0.4668534 0.883358 0.05479271 0.04661937 0.9974089 -0.04550375 -0.6566811 0.7527944 0.03646731 -0.9090124 0.4151705 0.1514519 0.5626701 -0.8126898 0.1857885 -0.9472143 -0.2612808 -0.1998067 -0.8917333 -0.4060653 0.207956 -0.6277707 -0.7501056 -0.1505773 -0.5117069 -0.8458621 0.07013648 -0.09155562 -0.993327 0.09046636 -0.08522531 -0.9922462 -0.07968776 0.5164008 -0.8526314 -0.116191 0.9382181 -0.3259548 0.1462644 0.9588794 -0.2432224 -0.15808 0.9661376 0.2039336 0.2285431 0.9097785 0.3465129 -0.2167617 0.6491184 0.7291499 0.1128774 0.564406 0.8177435 0.06630197 0.1925999 0.979035 -0.1458419 0.1180241 0.9822426 -0.04352017 -0.3717876 0.9272971 0.2417371 -0.4430272 0.8633019 -0.244745 -0.9633746 0.1095866 -0.18432 -0.7978487 0.5739891 0.1606955 0.8204962 0.5486009 -0.1994343 0.5273505 0.82591 0.2080718 0.2103568 0.9552257 -0.1426362 -0.0744854 0.9869685 0.1278145 -0.4678886 0.8744963 -0.09433184 -0.5969139 0.7967405 0.1057207 -0.9159972 0.3870043 -0.1192183 -0.9567606 0.2653227 0.1681933 -0.9554363 -0.2425952 -0.1955116 -0.8456259 -0.4966811 0.1380948 -0.6784281 -0.7215713 -0.1749056 -0.2840737 -0.9427143 0.1461287 -0.1017817 -0.9840157 -0.1069685 0.4743302 -0.8738241 0.1654192 0.5866323 -0.7927793 -0.2355411 0.9133805 -0.3320488 0.2117213 0.9753167 -0.06270193 -0.1201914 0.9270732 0.3550908 -0.09762929 0.6826019 -0.7242396 0.2690604 0.7820456 -0.5621486 -0.2418336 0.9670227 -0.07989715 0.209685 0.9324934 0.294089 -0.09437591 0.8660961 0.4908877 0.1259612 0.4498561 0.8841738 0.06967126 0.4299702 0.9001508 -0.1931922 -0.1257046 0.973075 0.2819011 -0.4274739 0.8589516 -0.1824681 -0.6931131 0.6973519 0.1357268 -0.9494891 0.2829288 -0.1278044 -0.9858931 0.1080773 0.1426643 -0.9435555 -0.2989143 -0.1425511 -0.8477845 -0.5108235 0.1278239 -0.5702261 -0.8114822 -0.09434481 -0.4427059 -0.8916897 0.1177428 0.09959405 -0.9880373 -0.01301286 0.1645156 -0.9862887 -0.2465894 -0.8487051 -0.4678604 0.1690705 -0.4552785 -0.8741491 -0.105497 -0.3141765 -0.9434848 0.1273824 0.2906708 -0.948306 -0.1477974 0.40188 -0.9036859 0.1525899 0.9145929 -0.3744811 -0.2715416 0.9450786 -0.1819113 0.2521568 0.9070058 0.3372794 -0.2706275 0.6756509 0.6857526 0.2439625 0.4363839 0.8660551 -0.3141293 -0.1242605 0.9412131 0.2616135 -0.404873 0.8761485 -0.2032983 -0.8809847 0.427242 -0.08031397 -0.9179857 0.3883966 0.1664887 -0.9446055 -0.2828461 0.02771402 0.3878837 -0.9212915 -0.191228 0.4664367 -0.8636369 0.1824926 0.8697391 -0.4585307 -0.2407322 0.9520911 -0.1886017 0.2081943 0.9597217 0.1886513 -0.1727928 0.8146566 0.5536037 0.1163753 0.6607745 0.7415079 -0.1354139 0.3363695 0.9319435 0.1810488 0.1255748 0.9754242 -0.1840031 -0.3967867 0.8992792 0.2259901 -0.5969558 0.7697871 -0.2081963 -0.8812096 0.4244102 0.2080519 -0.974212 0.08732285 -0.2080604 -0.9454405 -0.2507049 0.2081767 -0.7968092 -0.5672368 -0.2477063 -0.4341216 -0.8661294 0.09039762 -0.2844261 -0.9544265 0.9285288 -0.09080064 -0.3599855 0.8283121 0.08100093 -0.5543807 0.4949842 -0.0636219 -0.8665696 0.2982655 0.05351384 -0.9529815 -0.04854519 -0.05350611 -0.9973868 -0.2895155 0.07991903 -0.9538311 -0.6600701 -0.1090722 -0.7432435 -0.8656175 0.1090705 -0.4886818 -0.9934162 -0.07992724 -0.08207182 -0.9852342 0.05348594 0.1626435 -0.8376725 -0.07090476 0.5415508 -0.6985931 0.1008821 0.7083717 -0.1264763 -0.1094919 0.9859083 0.09271962 0.08986335 0.9916288 0.5508874 -0.06361683 0.8321514 0.7166075 0.05351084 0.6954209 0.9232553 -0.06209718 0.3791354 0.9818599 0.08223094 0.1708486 0.9720393 0.08930985 -0.2171712 0.7375811 -0.07226591 -0.6713805 0.6623011 0.02534305 -0.748809 0.03994975 -0.02536224 -0.9988798 -0.007521036 0.01760172 -0.9998168 -0.529502 -0.01594652 -0.8481588 -0.5920696 0.04378284 -0.8046967 -0.9418657 -0.07267346 -0.328036 -0.9822458 0.0726517 -0.172959 -0.9093183 -0.04379847 0.4137898 -0.875935 0.01586083 0.4821683 -0.5189756 -0.01595178 0.8546402 -0.4791932 0.02003051 0.8774809 0.1314461 -0.02379932 0.9910376 0.1808694 0.02732702 0.9831274 0.7793564 -0.02534743 0.6260681 0.8404488 0.07223398 0.5370551 0.9947553 -0.08933508 0.04980984 1.669102e-06 -1 -7.784662e-07 5.204807e-07 -1 1.233951e-06 6.606231e-07 -1 3.150105e-07 6.448833e-07 -1 1.382792e-06 1.361452e-06 -1 -3.554044e-07 -6.573827e-07 -1 1.527738e-06 8.796976e-07 -1 -5.782085e-08 1.026175e-06 -1 -2.286225e-07 2.702759e-06 -1 -6.021501e-07 3.201935e-07 -1 4.556649e-07 3.837665e-07 -1 3.073933e-07 8.107272e-07 -1 -8.143284e-08 -4.873611e-07 -1 7.063065e-07 1 0 0 1 0 0 1 0 0 1 2.506996e-05 7.159984e-06 1 -2.279942e-05 -3.426327e-05 1 0 -0 1 0 0 1 9.549346e-06 -2.332612e-06 1 -0 0 1 0 0 1 -0 0 1 0 0 1 0 -0 1 1.54333e-05 7.486475e-06 1 -6.282885e-06 1.165177e-05 0.9570481 -0.2714594 -0.1018278 0.970554 -0.2368212 0.04405234 0.9540704 0.02668114 0.2983919 0.9678218 0.2386096 0.07991523 0.9626573 -0.1438422 0.2293477 0.9828107 -0.1630969 0.08650152 0.9669793 -0.1644936 -0.1946608 0.9986854 -0.04854567 0.01645678 0.9815392 -0.0367922 -0.1876889 0.9778049 -0.01384147 -0.2090599 0.969757 0.1527677 0.1903508 0.9776884 0.1595314 0.136657 0.9535335 0.271936 -0.1297105 0.9615927 0.122596 -0.2455804 1 -4.633293e-05 -1.489974e-05 1 3.067856e-05 9.865607e-06 1 1.440641e-05 5.609999e-05 1 -4.184389e-06 2.18534e-05 1 -1.49611e-05 2.796269e-05 1 -9.932732e-06 4.239851e-07 1 -0 0 1 0 -0 1 4.062105e-05 2.632197e-05 1 3.284107e-05 3.492953e-05 1 8.231375e-06 2.153392e-05 1 5.13545e-06 2.777085e-05 1 5.528557e-07 1.733444e-05 1 5.752038e-07 1.732505e-05 1 1.456458e-05 -1.54292e-05 1 2.936962e-05 6.001999e-06 1 -4.508259e-05 -9.213115e-06 1 4.273236e-06 1.718462e-05 1 -3.957329e-06 -1.591422e-05 1 1.738722e-05 -1.856669e-05 1 -1.667205e-05 1.780301e-05 1 -2.33614e-05 -6.845501e-06 1 4.994843e-06 1.008627e-05 1 1.263486e-05 3.954038e-06 1 1.386298e-05 9.354188e-06 1 -6.174673e-06 -4.166424e-06 1 2.635769e-05 -4.930245e-05 1 1.785314e-05 8.944491e-07 1 -0 0 1 7.331855e-06 -9.057003e-06 1 4.199418e-05 2.135749e-05 1 3.105005e-05 2.45357e-05 1 3.298471e-05 3.127907e-05 1 3.428443e-06 1.890094e-05 1 -1.342471e-05 -1.374018e-05 1 -1.662992e-05 -3.699237e-05 1 8.830018e-06 -8.858658e-06 1 -1.111324e-05 1.114929e-05 1 -1.133571e-05 1.215901e-05 1 -3.069038e-05 1.298499e-05 1 -1.061495e-05 -8.403828e-06 1 1.309807e-05 1.036971e-05 1 1.411727e-05 1.027662e-05 1 1.474257e-05 1.571923e-05 1 -6.314736e-06 -6.733073e-06 1 1.445005e-05 -3.183301e-05 1 1.517503e-05 -4.280752e-05 1 7.505807e-05 -2.061575e-05 1 4.221039e-06 -1.072949e-05 1 -3.61743e-06 9.195172e-06 1 -2.871348e-05 -1.06774e-05 1 -7.30835e-07 -1.71058e-05 1 -7.10965e-06 -1.111279e-05 1 -6.2777e-06 -3.330037e-05 1 6.292001e-05 -2.553761e-05 1 1.656762e-05 2.501482e-05 1 5.240288e-06 7.912113e-06 1 2.46695e-06 8.233196e-06 1 -7.010766e-06 -2.339772e-05 1 4.22963e-06 -1.846756e-05 1 0 0 1 1.237496e-05 1.451268e-05 1 -5.278895e-05 5.925992e-05 1 -2.906166e-05 3.419427e-06 1 -2.024412e-05 7.851319e-06 1 -2.282383e-05 8.851812e-06 1 -1.854225e-05 -2.387734e-05 1 -1.439517e-05 -1.853703e-05 1 -8.754204e-06 -2.93758e-05 -5.187165e-07 1 -5.033805e-07 -1.034235e-06 1 1.048712e-06 -7.408026e-07 1 2.366922e-06 -7.914626e-07 1 -4.468179e-07 -5.594444e-07 1 9.235367e-08 -5.570645e-07 1 1.320277e-06 -1.222153e-06 1 -6.893803e-07 -9.49255e-07 1 1.738241e-06 -5.648629e-07 1 6.386437e-07 -5.468261e-07 1 -9.628803e-08 -6.965712e-07 1 -4.451159e-07 -5.134708e-07 1 1.147187e-07 -1.428052e-06 1 -1.940901e-06 -4.223891e-07 1 2.325089e-07 0.003073727 -0.9994559 0.03284025 -0.05097472 -0.996953 -0.05904566 0.04835586 -0.8309644 -0.55422 -0.06497888 -0.6138367 -0.7867543 0.05243782 -0.3746449 -0.9256843 -0.05242942 0.1292973 -0.9902189 0.07765759 0.4231528 -0.9027243 -0.06051062 0.6851803 -0.7258557 0.05365853 0.9778649 -0.2022398 -0.0509893 0.998368 -0.02571882 0.04835721 0.8749903 0.4817193 -0.05490807 0.6995803 0.7124413 0.04055551 0.4789244 0.8769188 -0.05159931 0.03789057 0.9979488 0.05794827 -0.1806413 0.9818405 -0.06359001 -0.7024809 0.708856 0.02884876 -0.8081352 0.5882902 -0.04835079 -0.9946895 -0.0908568 0.03982702 -0.8468397 -0.5303547 -0.0374496 -0.7380183 -0.6737406 0.04187225 -0.4027807 -0.9143382 -0.04188805 -0.178321 -0.9830804 0.0374567 0.2341543 -0.9714776 -0.02756348 0.3784097 -0.9252277 0.03408729 0.8106748 -0.5845036 -0.03632914 0.8746109 -0.4834625 0.03632748 0.9857128 0.1644703 -0.03408225 0.9590911 0.2810387 0.03735263 0.594025 0.8035789 -0.002984283 0.5447925 0.8385656 -0.03719296 -0.1606818 0.9863052 0.0813297 -0.317068 0.9449092 -0.06439657 -0.8571479 0.511029 0.07528075 -0.9640001 0.2550227 -0.0509525 -0.9986981 -0.002441335 0.04457526 -0.9603705 -0.2751394 -0.05142055 -0.8074073 -0.5877494 0.0617947 -0.5738509 -0.8166251 -0.05864644 -0.1806191 -0.9818031 0.0331963 0.03621117 -0.9987926 -0.0253325 0.503315 -0.8637316 0.0127277 0.5678208 -0.8230538 -0.01274019 0.924198 -0.3817011 0.025339 0.9503876 -0.3100345 -0.03320979 0.9840124 0.1749761 0.04598246 0.9335374 0.3555187 -0.0405474 0.6982731 0.7146822 0.0653283 0.4490328 0.8911239 -0.07319313 0.1468181 0.9864519 0.08099835 -0.4181018 0.9047819 -0.08216942 -0.679604 0.7289628 0.06179877 -0.9192024 0.3889058 -0.04054654 -0.9986376 -0.03284701 0.05491452 -0.9511083 -0.3039364 -0.06873805 -0.7888377 -0.6107456 0.08292232 -0.45264 -0.8878293 -0.0713198 -0.04257675 -0.9965444 0.0713243 0.29231 -0.9536601 -0.06295159 0.6194931 -0.782474 0.04563633 0.9439386 -0.3269513 -0.0056822 0.919444 -0.3931798 0.01772614 0.9681987 0.2495535 -0.05365473 0.9296262 0.3645768 0.0548333 0.5787285 0.8136747 -0.04829495 0.3192452 0.9464408 0.02968585 0.1032503 0.9942123 -0.05143162 -0.2983305 0.9530759 0.05142381 -0.5654613 0.8231702 -0.04456029 -0.8138574 0.5793534 0.040549 -0.9306449 0.36367 1 1.601644e-05 2.630744e-06 1 2.598179e-05 -6.51868e-06 1 8.694219e-06 7.335311e-07 1 -0 0 1 -1.040501e-05 1.516809e-05 1 -2.168003e-05 1.578219e-05 1 -3.896624e-05 1.088272e-05 1 3.709002e-05 -3.45282e-06 1 3.503209e-06 -2.525844e-06 1 -7.667662e-06 -1.279382e-06 1 -4.082711e-06 -5.522968e-06 1 -1.654106e-05 2.594168e-05 1 -1.740973e-06 -6.622198e-06 1 -1.613671e-05 -5.097847e-07 1 2.698518e-05 5.951679e-06 1 3.142548e-05 5.567133e-06 1 1.52578e-05 3.701169e-07 1 -4.222163e-05 -1.024192e-06 1 1.401867e-06 -3.033671e-06 1 -2.062377e-05 8.725723e-06 1 0 0 1 -0 0 1 0 0 1 -0 0 1 5.318308e-05 1.69952e-05 1 0 0 1 -4.855436e-05 1.576122e-05 -0.01788842 -0.99984 0 -0.01788843 -0.99984 0 -0.01788842 -0.99984 0 0.02038188 -0.9997923 0 0.02038188 -0.9997922 0 0.02182681 -0.9997618 -0.0002113874 -0.01788842 -0.99984 0 -0.02263007 -0.9997437 0.0006934418 -0.02455064 -0.9996986 0 6.35513e-07 -0.9989809 0.04513644 -0.0005450767 -0.999113 0.04210518 6.347867e-07 -0.9993128 0.03706894 7.944439e-07 -0.9993128 0.03706806 0 -1 0 0 -1 -0 6.66891e-07 -1 5.93836e-08 8.833017e-07 -1 0 7.483642e-07 -1 -5.268275e-08 0 -1 -0 2.131818e-07 -1 2.535607e-07 7.947297e-07 -1 -9.536806e-08 6.357829e-07 -1 9.536794e-08 7.947296e-07 -1 0 7.947296e-07 -1 0 1.192271e-06 -1 -1.185727e-07 7.083708e-07 -1 0 6.876368e-07 -1 4.697137e-08 6.357829e-07 -1 -2.36828e-07 9.62703e-07 -1 -1.015113e-06 1 2.762002e-06 -0 1 3.960088e-07 2.344446e-05 1 -1.178004e-05 2.741509e-05 1 1.788901e-05 -2.992933e-05 -1 -7.14101e-07 -0 -1 3.675475e-06 -8.029485e-06 -1 0 0 1 1.114951e-06 -1.815599e-06 1 -1.328607e-05 -1.302403e-05 1 2.708491e-06 -4.410536e-06 -1 -0 0 -1 0 0 1 1.220666e-05 2.990601e-05 1 1.208471e-06 4.095628e-08 1 -2.244415e-05 -7.606542e-07 1 -2.520651e-05 3.136968e-05 -0.0235069 0.9997231 -0.001096747 -0.02654003 0.9996477 0 -0.02654003 0.9996477 0 -0.02654003 0.9996477 0 0.02247792 0.9997474 0 0.02307679 0.9997337 0 0.02290486 0.9997377 6.262782e-05 0 1 0 -6.357829e-07 1 0 -6.357833e-07 1 0 -0.01598569 0.9998722 0 0.02247792 0.9997473 -0 0.02247792 0.9997473 0 0.02247792 0.9997473 0 -6.357832e-07 1 0 -6.357831e-07 1 0 -6.352159e-07 0.9991077 0.04223672 -6.346551e-07 0.9991077 0.04223672 0.0009115969 0.9994285 0.03379201 -9.534612e-07 0.9995859 0.02877515 -0.01598569 0.9998722 0 -1.234897e-06 1 2.164978e-07 -7.324504e-07 1 5.80005e-08 -4.534524e-07 1 7.468956e-07 0 1 0 -0 1 0 -1.631402e-06 1 4.268453e-07 -1.159225e-06 1 -8.155376e-07 0 1 0 -1.956309e-06 1 -6.440027e-07 0 1 -0 -2.067352e-07 1 -8.220024e-07 -6.357829e-07 1 1.313003e-07 0.01752035 -0.0175203 -0.999693 -0.159644 0.1596435 -0.9741806 0.1154492 0.0608028 -0.9914507 0.09688749 0.04120598 -0.994442 0.2141799 0.09080344 -0.9725645 0.09049947 0.02934205 -0.9954642 0.03318658 0.0193978 -0.9992609 -0.05065369 0.5311168 -0.8457832 0.04104524 0.5585563 -0.8284504 -0.03085305 -0.03482176 -0.9989172 0.09052897 -0.01355894 -0.9958015 -0.07065992 -0.5576211 -0.8270827 0.05015354 -0.5282814 -0.8475868 -1 -5.892342e-07 5.28703e-07 -1 4.572736e-06 3.239189e-06 -1 -1.069078e-05 2.681928e-07 -1 3.306526e-06 -2.516903e-06 -1 -1.534158e-06 -4.006394e-07 -1 0 -0 1 -5.836284e-07 -5.429284e-06 1 2.752983e-06 2.748522e-06 1 2.454002e-06 -2.082741e-07 1 1.314264e-06 8.131036e-06 1 3.860351e-08 -4.941177e-06 1 1.140601e-05 1.912674e-05 -9.692685e-07 1 -1.761892e-08 -1.133851e-06 1 2.418651e-07 9.619031e-07 1 -2.701021e-06 -1.020011e-06 1 -3.495125e-07 -1.032628e-06 1 3.127871e-07 -1.198799e-06 1 -7.488966e-07 1.493552e-07 1 1.808013e-06 -1.346617e-07 1 4.811354e-07 -4.0687e-07 1 2.723494e-07 -8.071365e-07 1 -1.101656e-06 -6.476898e-07 1 -1.31382e-07 -1.338183e-06 1 8.39481e-08 0 1 0 0.9973004 -0.0657168 -0.03275991 0.7898936 0.04494159 -0.6115949 0.8302775 -0.04195927 -0.5557687 0.2686548 0.08032003 -0.959882 0.01370086 -0.128475 -0.9916181 -0.4202134 0.1127484 -0.9003935 -0.7552916 -0.1284901 -0.6426703 -0.9357557 0.1090539 -0.3353634 -0.9891582 -0.09193568 0.1145159 -0.9054317 0.1116335 0.4095501 -0.6517622 -0.1296711 0.747256 -0.2123969 0.1391598 0.9672239 0.1007393 -0.1159303 0.9881355 0.5878133 0.1038558 0.8023027 0.7932338 -0.09338791 0.6017133 0.9757562 0.09340119 0.1979292 -0 1 0 -0 1 -0 0 1 0 -0 1 0 0 1 0 -0 1 0 -1.095895e-06 1 3.536238e-07 -8.590226e-07 1 8.491944e-07 0 1 0 -3.617371e-06 1 -1.255495e-06 -3.671686e-06 1 1.206097e-07 -4.902159e-06 1 6.882602e-07 -2.327087e-06 1 1.801805e-06 -2.272322e-06 1 1.673532e-06 -1.033586e-06 1 7.612209e-07 -4.588614e-07 1 1.929621e-06 0.9611225 0.2409036 -0.134941 0.8107499 -0.2725768 -0.5180603 0.5520211 0.2727018 -0.7879762 0.1467526 -0.2726549 -0.9508538 -0.226837 0.2726606 -0.9349872 -0.6005133 -0.240922 -0.7624567 -0.8592483 0.2407241 -0.4513804 -0.9559953 -0.2627452 -0.1305296 -0.9079725 0.2749897 0.3161748 -0.725141 -0.2069081 0.6567798 -0.4976426 0.1515764 0.8540354 -0.1737475 -0.1743302 0.9692372 0.1756118 0.240899 0.9545303 0.5336923 -0.240881 0.8106472 0.8078996 0.2080702 0.5513665 0.9476524 -0.2080715 0.2422006 5.324553e-07 -1 -2.133262e-07 5.663213e-07 -1 9.138229e-07 1.42909e-06 -1 1.407975e-07 1.228063e-06 -1 4.896834e-07 3.019958e-07 -1 -1.724133e-06 5.944853e-07 -1 8.317417e-07 4.971857e-07 -1 4.498897e-07 4.890759e-07 -1 -5.660478e-08 8.091189e-07 -1 6.961536e-07 1.821755e-06 -1 -2.200386e-06 1.276859e-06 -1 3.490159e-07 7.213886e-07 -1 -8.270816e-07 0.9990391 -0.04376003 -0.002435485 0.993254 0.03986116 -0.1088925 0.8071148 -0.05728013 -0.5876092 0.7255101 0.04363643 -0.6868267 0.2426766 0.00485032 -0.9700952 0.1224186 -0.1068938 -0.9867053 -0.4195518 0.1260221 -0.8989409 -0.733351 -0.1478028 -0.6635892 -0.9269674 0.08931815 -0.3643537 -0.9913698 -0.06340881 0.1147394 -0.9753031 0.01998748 0.2199642 -0.6571252 -0.02389453 0.7534028 -0.593366 0.05844176 0.8028083 0.07247423 -0.08223054 0.9939747 0.2589897 0.08988638 0.9616885 0.7226698 -0.08093196 0.6864389 0.8399516 0.06738622 0.5384611 5.44315e-07 -1 6.000645e-07 3.842833e-07 -1 4.236421e-07 1.763653e-06 -1 -4.975939e-07 2.024373e-06 -1 3.632371e-07 -2.437749e-05 -1 -4.374099e-06 -2.097865e-05 -1 -9.00517e-06 -1.070818e-05 -1 2.141427e-06 6.298832e-07 -1 -1.259643e-07 6.427111e-07 -1 1.121174e-07 7.899907e-07 -1 1.378095e-07 1.41901e-06 -1 -6.990682e-07 1.576162e-06 -1 -3.805717e-07 -0 -1 0 -3.503448e-07 -1 7.46023e-07 -2.50564e-06 -1 -2.747035e-07 -5.829923e-07 -1 -1.209356e-06 -7.472923e-07 -1 -1.550179e-06 8.492166e-07 -1 -1.181824e-06 -0.879621 0.121337 -0.4599394 -0.8614072 0.00803277 -0.5078516 -0.3494467 -0.06663584 -0.9345837 -0.2618919 0.1164763 -0.9580427 0.3141699 -0.1055137 -0.9434851 0.4487706 0.1545353 -0.880184 0.8277351 -0.1824758 -0.5306196 0.9331157 0.2009877 -0.2981594 0.9786826 -0.1751219 0.107297 0.9067277 0.1751187 0.3836382 0.6940556 -0.1751221 0.6982974 0.4909681 0.1426111 0.8594256 0.07193772 -0.1468679 0.9865367 -0.04851325 0.06368129 0.9967905 -0.620677 -0.004615681 0.7840528 -0.6540895 -0.09826646 0.7500071 -0.947591 0.1263653 0.2934332 -0.9802047 -0.1340425 0.1457098 5.217935e-07 -1 4.329881e-07 5.058937e-07 -1 -1.371223e-06 -9.159282e-08 -1 -6.936818e-07 6.3339e-07 -1 6.255186e-07 4.996528e-07 -1 2.216153e-07 0.9513001 -0.1229588 -0.2826821 0.8407056 0.1229545 -0.5273483 0.3448634 -0.08549941 -0.9347508 0.2694777 -0.003597046 -0.9629999 -0.4501648 0.03309425 -0.8923321 -0.5018877 -0.03600791 -0.8641829 -0.9862542 0.005408914 -0.1651467 -0.984933 -0.005387805 -0.1728528 -0.7803719 0.03486212 0.6243431 -0.6990852 -0.08861776 0.7095258 -0.1862216 0.08455405 0.9788627 0.1297527 -0.1322482 0.9826875 0.4691165 0.1055183 0.87681 0.8703458 -0.07644444 0.4864714 0.9401987 0.07644921 0.3319369 5.286023e-07 -1 1.883129e-06 0 -1 0 9.837997e-07 -1 1.503067e-08 0.0001387432 -1 -7.129961e-05 0.0001713208 -1 -1.199404e-05 9.544652e-05 -1 1.675058e-05 0.0001124936 -1 3.879746e-05 1.713011e-07 -1 -9.056069e-07 3.217743e-07 -1 -1.701105e-06 8.46358e-07 -1 -4.141471e-07 -0 -1 0 0 -1 0 -0 -1 0 0 -1 -0 -0 -1 -0 1.047841e-06 -1 4.673436e-07 -0.8034505 -0.1659355 -0.5717803 -0.7201627 0.1292242 -0.6816646 -0.1761757 0.05572176 -0.9827804 -0.0753818 -0.1687469 -0.9827726 0.5696652 0.1187717 -0.8132496 0.63647 -0.05971241 -0.7689866 0.9918407 0.06410273 -0.1101954 0.996199 -0.06407984 -0.05900418 0.7572712 0.05969302 0.6503668 0.7240804 -0.05200614 0.6877521 0.09295902 0.0563001 0.9940769 0.04209383 -0.07100966 0.9965871 -0.7168978 0.07030855 0.693624 -0.7529228 -0.05900795 0.6554582 -0.9982937 0.05395584 0.02232331 -0.9985326 0.05010117 0.02055515 -1.06442e-06 1 -2.596856e-07 -7.51516e-07 1 6.777618e-07 -1.258306e-06 1 -2.054995e-06 -5.326019e-07 1 9.362892e-07 0 1 0 -1.217006e-06 1 -3.970518e-07 0.9584417 -0.1296526 -0.2541251 0.6948384 0.1546938 -0.7023314 0.4700929 -0.1115726 -0.8755366 -0.1765642 0.08413918 -0.9806863 -0.3212095 -0.05354298 -0.9454933 -0.792123 0.04845707 -0.608435 -0.8729725 -0.07130001 -0.4825301 -0.9961262 0.08453973 0.02419565 -0.9450881 -0.1126495 0.3067875 -0.7378713 0.1127559 0.6654562 -0.3933312 -0.1284655 0.9103775 -0.0769688 0.089329 0.9930237 0.4000304 -0.0634143 0.9143053 0.5216972 0.04377808 0.8520068 0.8989191 -0.06736825 0.432904 0.9723796 0.1274495 0.1955365 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 0 -1.8733e-06 1 1.496572e-06 -7.309393e-07 1 3.712662e-06 0 1 0 -2.278825e-06 1 -5.412946e-07 -8.952052e-07 1 1.130508e-06 0 1 0 -4.059273e-06 1 -2.196603e-07 -1.95447e-06 1 3.640153e-06 -9.027193e-07 1 -2.292313e-07 -1.233238e-06 1 -3.131613e-07 -1.259259e-06 1 1.734264e-07 0.9599624 0.2265205 -0.1648046 0.9069537 -0.173665 -0.3837648 0.4443236 0.0914347 -0.8911881 0.4803363 -0.0146347 -0.8769624 -0.233833 0.06661678 -0.9699919 -0.2946592 -0.06086449 -0.9536622 -0.7993865 0.01585352 -0.600608 -0.8096992 0.0596857 -0.5838022 -0.9946527 -0.05541591 0.08714972 -0.9688545 0.1564825 0.1919221 -0.7622533 -0.1743602 0.6233525 -0.5452156 0.1742697 0.8199818 -0.2030152 -0.1773483 0.962981 0.06883756 0.2192737 0.973232 0.530102 -0.2658849 0.805169 0.7850656 0.2410866 0.5705693 0.9464824 -0.1750892 0.2711362 -0 0 1 0 0 1 -0 0 1 -2.921263e-06 7.669846e-06 1 6.623349e-06 -4.654121e-06 1 0 0 1 1.471894e-05 2.791882e-05 1 -0.4878905 0.8729048 -0.000185671 -0.4874909 0.8731281 0.0001920337 -0.9568459 0.2883427 -0.03611382 -0.9857678 0.1605864 0.04973755 -0.8914661 -0.4522287 -0.02788281 -0.8547105 -0.5190058 0.01015121 -0.4822569 -0.875971 -0.01015184 -0.4415702 -0.8971363 0.01273782 0.1174888 -0.9929925 -0.01274012 0.2518192 -0.9661799 0.05552899 0.6316898 -0.7724998 -0.06490058 0.9006928 -0.4312843 0.05240583 0.9649565 -0.261158 -0.02560029 0.9836272 0.1783876 0.02560296 0.9446157 0.3257537 -0.03982211 0.6955909 0.7168091 0.04835317 0.4071682 0.9102461 -0.0752719 0.2011912 0.9789643 0.03392723 0 0 1 0 0 1 -6.357933e-06 3.802847e-06 1 -6.345123e-06 1.010649e-06 1 1.077886e-05 -1.716854e-06 1 5.875829e-06 4.116663e-06 1 2.423711e-05 1.698076e-05 1 5.240825e-05 1.171227e-05 1 0.000101294 0.00017273 1 6.9936e-05 0.0001588327 1 1.033671e-05 0.0002609866 1 -1.442008e-05 0.0001831351 1 -0.0001358235 0.0001660999 1 7.928038e-06 7.254388e-05 1 -1.834281e-05 -2.492703e-06 1 0 0 1 0 0 1 0 0 1 0.08758852 -0.9935077 -0.07259908 0.6401085 -0.7623809 0.0950597 0.7179729 -0.6870314 -0.1118156 0.9768975 -0.1858398 0.1055214 0.9872847 -0.03748788 -0.1544784 0.8669268 0.4638274 0.1824883 0.6894059 0.683207 -0.2407236 0.3811165 0.9007843 0.2081775 -0.02972116 0.9797638 -0.1979383 -0.2720277 0.9495038 0.1563445 -0.6659222 0.7294597 -0.1563211 -0.8187113 0.5390147 0.197927 -0.9672772 0.175423 -0.183307 -0.9743593 -0.1746641 0.1418322 -0.9201068 -0.3763614 -0.1084232 -0.6867943 -0.7090726 0.1597793 -0.514009 -0.8421661 -0.162945 -0.02003069 -0.9922535 0.1226047 -3.506499e-05 8.327041e-07 -1 2.110676e-06 2.091698e-06 -1 2.484563e-05 -1.766338e-05 -1 7.892809e-06 -2.996955e-07 -1 0 0 -1 0 0 -1 0 0 -1</float_array> + <technique_common> + <accessor count="6717" source="#cubenormals-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <source id="cubeverts-array0"> + <float_array count="10248" id="cubeverts-array0-array">-0.04000078 -0.01062947 0.023 -0.04000078 -0.01062947 0.025 -0.04000078 -0.01212947 0.023 -0.04000078 -0.01212947 0.025 -0.04600078 -0.01132948 0.0233 -0.04600077 -0.01212948 0.023 -0.04600078 -0.01132948 0.025 -0.04600077 -0.01212948 0.025 -0.04000079 0.01187052 0.023 -0.04000079 0.01187052 0.025 -0.04000079 0.01037052 0.023 -0.04000079 0.01037052 0.025 -0.04600079 0.01107052 0.025 -0.04600079 0.01187052 0.025 -0.04600079 0.01107052 0.0233 -0.04600079 0.01187052 0.023 -0.03747742 0.01187053 0.01747454 -0.03720599 0.01187053 0.01799231 -0.03831713 0.01187053 0.01844833 -0.03907294 0.01187052 0.01852499 -0.03899973 0.01187052 0.0196197 -0.03953963 0.01187052 0.02015411 -0.03872322 0.01187053 0.02112271 -0.03887923 0.01187052 0.02171484 -0.03746553 0.01187053 0.02198102 -0.03717591 0.01187053 0.02256407 -0.03611794 0.01187053 0.02183329 -0.0355444 0.01187053 0.02205997 -0.03525991 0.01187053 0.02102115 -0.03453119 0.01187053 0.02071142 -0.03496881 0.01187053 0.01968643 -0.03468023 0.01187053 0.01901031 -0.03589368 0.01187053 0.01826747 -0.03561507 0.01187053 0.01786716 -0.03609504 -0.01212947 0.0175604 -0.03820066 -0.01212947 0.0177573 -0.03779253 -0.01212947 0.01814354 -0.03870707 -0.01212947 0.01889139 -0.03944524 -0.01212947 0.01920646 -0.03900686 -0.01212947 0.0205565 -0.03921145 -0.01212947 0.02131079 -0.03802259 -0.01212947 0.02174045 -0.0374774 -0.01212947 0.02252546 -0.0368775 -0.01212947 0.02203106 -0.03581694 -0.01212947 0.0222278 -0.03562893 -0.01212947 0.02150281 -0.03459512 -0.01212941 0.02093698 -0.03498932 -0.01212947 0.02030739 -0.03463692 -0.01212947 0.01906744 -0.0353168 -0.01212947 0.0188204 -0.03662309 -0.01212947 0.0179989 -0.04970066 -0.01212948 0.01809738 -0.04958508 -0.01212948 0.01754578 -0.05087922 -0.01212948 0.01828509 -0.05081224 -0.01212948 0.0190274 -0.0515396 -0.01212948 0.01984589 -0.05096029 -0.01212948 0.0205484 -0.0509582 -0.01212948 0.02166543 -0.05030207 -0.01212948 0.02154266 -0.0490537 -0.01212948 0.02205535 -0.04926249 -0.01212948 0.02253 -0.04741988 -0.01212948 0.0220263 -0.04762895 -0.01212948 0.02150282 -0.04703738 -0.01212948 0.02046731 -0.04644188 -0.01212952 0.0201559 -0.04714169 -0.01212948 0.01912192 -0.04694141 -0.01212948 0.01854272 -0.04838383 -0.01212948 0.01804368 -0.04811009 -0.01212948 0.01761757 -0.03680077 -0.003880135 0.01543121 -0.03680078 -0.003579474 0.011 -0.03625078 -0.003573055 0.015581 -0.03580078 -0.003579474 0.011 -0.03580078 -0.003792094 0.01552284 -0.03680077 -0.004335324 0.01304008 -0.03680077 -0.005336584 0.01212603 -0.03680077 -0.005066204 0.01578986 -0.03680077 -0.004130514 0.01438027 -0.03680078 -0.00814415 0.0139604 -0.03680077 -0.008671429 0.01095866 -0.03680074 -0.007794315 0.01283011 -0.03680078 -0.008679472 0.0165 -0.03680077 -0.007750496 0.01526473 -0.03680077 -0.006596073 0.01596357 -0.03680079 -0.005526034 0.01645706 -0.03680077 -0.006689854 0.01204389 -0.04975078 -0.003561684 0.01559305 -0.05020078 -0.003737884 0.01554232 -0.05020078 -0.003579484 0.011 -0.04920078 -0.003579483 0.0155 -0.04920078 -0.003579483 0.011 -0.04920078 -0.008679482 0.0165 -0.04920077 -0.008131016 0.01437166 -0.04920078 -0.008669842 0.01096534 -0.04920078 -0.007851927 0.01287729 -0.04920076 -0.004918263 0.01230677 -0.04920078 -0.004052593 0.01414361 -0.04920078 -0.006594235 0.01201899 -0.04920076 -0.007556959 0.01542676 -0.04920076 -0.004120303 0.01550948 -0.04920078 -0.005288193 0.01641744 -0.04920077 -0.006522024 0.01599658 -0.04920077 -0.005022383 0.01573252 -0.04975078 -0.008679482 0.01653333 -0.0502008 -0.008669662 0.01095956 -0.05020078 -0.008679482 0.0166 -0.04947742 0.01187052 0.01747454 -0.04954721 0.01187052 0.01801342 -0.05107289 0.01187052 0.01852492 -0.0508599 0.01187052 0.01912192 -0.0515442 0.01187051 0.02036902 -0.0508882 0.01187052 0.02081549 -0.05040425 0.01187052 0.02215301 -0.0499471 0.01187052 0.02178259 -0.04860129 0.01187052 0.02201685 -0.04831177 0.01187052 0.02247596 -0.04722286 0.01187052 0.02103258 -0.04681105 0.01187052 0.02129399 -0.04652495 0.01187052 0.01919859 -0.04705102 0.01187052 0.01934759 -0.04805184 0.01187052 0.01820001 -0.04781685 0.01187052 0.01777222 -0.03625079 0.003314398 0.01556367 -0.03580079 0.003532717 0.01551795 -0.03580079 0.003320528 0.011 -0.03680079 0.003320526 0.0155 -0.03680079 0.003320526 0.011 -0.03680077 0.003953846 0.01463219 -0.03680079 0.003840197 0.01553187 -0.03680079 0.003911026 0.0134516 -0.03680078 0.007880917 0.01369443 -0.03680078 0.007356666 0.01263445 -0.03680079 0.008413264 0.01096175 -0.03680079 0.006165685 0.01196526 -0.03680078 0.004690455 0.01234232 -0.03680079 0.005182905 0.01643715 -0.03680078 0.006263046 0.01599659 -0.03680079 0.008420527 0.0165 -0.03680078 0.007554535 0.0151796 -0.03680078 0.004763465 0.01573254 -0.04920079 0.003621176 0.01543121 -0.04920079 0.003320517 0.011 -0.04975079 0.003311876 0.01556646 -0.05020079 0.003320517 0.011 -0.05020079 0.003320517 0.0156 -0.04920081 0.004410146 0.01544726 -0.04920079 0.003813295 0.01368077 -0.04920079 0.004772356 0.01228699 -0.04920079 0.005913796 0.01198221 -0.04920079 0.008412498 0.01095865 -0.0492008 0.007050587 0.01234232 -0.04920079 0.007576816 0.01510861 -0.04920079 0.006167706 0.01606053 -0.04920079 0.008420518 0.0165 -0.04920079 0.005233645 0.01644494 -0.04920079 0.007887836 0.01361621 -0.04975079 0.008420518 0.01656667 -0.05020079 0.008420518 0.0166 -0.05020081 0.008412516 0.01096396 -0.03400078 -0.005066233 0.01578987 -0.03400078 -0.004481732 0.01597232 -0.03400078 -0.006521418 0.01653998 -0.03400078 -0.006760575 0.01593447 -0.03400074 -0.00798784 0.01570618 -0.03400079 -0.007726045 0.01523462 -0.03400078 -0.008646082 0.01436886 -0.03400078 -0.008159741 0.0141357 -0.03400078 -0.008221025 0.0125065 -0.03400083 -0.007870363 0.01297894 -0.03400078 -0.0068641 0.01207969 -0.03400078 -0.006390135 0.01144321 -0.03400078 -0.005336593 0.01212602 -0.03400079 -0.004203502 0.01224996 -0.03400077 -0.004335342 0.01304005 -0.03400079 -0.003601123 0.0142772 -0.03400078 -0.004130523 0.01438027 -0.0340008 0.006905727 0.01575179 -0.03400079 0.005575418 0.01601329 -0.03400079 0.003803108 0.01558044 -0.03400079 0.004376147 0.01538102 -0.03400079 0.003799247 0.01379054 -0.03400079 0.003374798 0.0135094 -0.03400079 0.004395967 0.01189504 -0.03400079 0.004690457 0.01234232 -0.03400079 0.005993806 0.01196894 -0.0340008 0.006698387 0.01153289 -0.0340008 0.007510828 0.012718 -0.0340008 0.008405396 0.01341142 -0.0340008 0.007851288 0.01455125 -0.03400079 0.007942637 0.01547507 -0.0340008 0.01187053 0.0166 -0.0340008 0.01037053 0.0166 -0.0340008 0.01187053 0.011 -0.0340008 0.01037053 0.01484966 -0.0340008 0.008234278 0.01160061 -0.03398054 0.008528637 0.01097452 -0.0340008 0.007325888 0.01104373 -0.05200078 -0.00811024 0.01455125 -0.0520008 -0.00822103 0.0154935 -0.05200079 -0.006874963 0.01594379 -0.05200078 -0.00681636 0.01642751 -0.05200077 -0.005325866 0.01641321 -0.05200079 -0.005180556 0.0158 -0.05200067 -0.004133166 0.01554248 -0.0520008 -0.004347227 0.01494711 -0.05200078 -0.003590656 0.01415413 -0.05200078 -0.004105486 0.01379061 -0.05200077 -0.003953916 0.01272271 -0.05200082 -0.004686256 0.01256559 -0.05200079 -0.005232946 0.0115914 -0.05200078 -0.005745847 0.01201855 -0.0520008 -0.006922394 0.01212604 -0.05200077 -0.006919755 0.01160416 -0.05200076 -0.008146637 0.01245062 -0.05200079 -0.00792363 0.01304009 -0.05200078 -0.008647212 0.01384 -0.05200082 0.004310874 0.01530687 -0.05200081 0.004395984 0.01610497 -0.0520008 0.005478023 0.01599659 -0.05200079 0.006476454 0.0164976 -0.0520008 0.006977605 0.01573254 -0.05200079 0.008269474 0.0150085 -0.05200077 0.007787194 0.01463217 -0.0520008 0.007753704 0.01311249 -0.05200079 0.007987065 0.01248598 -0.05200078 0.006270004 0.01198315 -0.05200079 0.005913485 0.01143032 -0.05200079 0.004772324 0.01228697 -0.05200079 0.003969913 0.01227004 -0.05200079 0.003813293 0.01368077 -0.05200079 0.003316194 0.01428381 -0.05200598 0.007273495 0.01102789 -0.05200083 0.008108444 0.01146522 -0.05200079 0.01187051 0.011 -0.05200079 0.01037051 0.0166 -0.05200079 0.01187051 0.0166 -0.05200079 0.01037051 0.01484966 -0.05200078 0.004845973 0.01646747 -0.05020078 0.005203826 0.01655045 -0.03400079 -0.004057483 0.01560793 -0.05200078 -0.003493876 0.01564919 -0.05200079 -0.004079607 0.01565874 -0.0502008 0.003820615 0.01565871 -0.05200079 0.003821135 0.0156 -0.05200077 0.003259204 0.0156465 -0.05020078 -0.005104914 0.01646746 -0.05200078 -0.005462767 0.01655045 -0.05200077 -0.01062948 0.0166 -0.02248526 0.003855506 -0.00675 -0.02238806 0.003276268 -0.00675 -0.02246891 0.003840208 -0.006199996 -0.0225008 0.003320538 -0.006199995 -0.02257594 0.003577186 0.006200002 -0.0223671 0.003275976 0.006750001 -0.02244179 0.003869137 0.006750001 -0.02241979 -0.003573044 -0.006749999 -0.02246891 -0.004099144 -0.006750001 -0.02256956 -0.003880134 -0.006199995 -0.02092631 0.01185148 -0.008999998 -0.02146747 0.00842054 -0.00675 -0.0215896 0.00505081 -0.00675 -0.02155052 0.005215799 -0.006199995 -0.0210555 0.005028579 0.006750001 -0.0214508 0.00842054 0.006750001 -0.02156367 0.005182899 0.006750001 -0.02092631 0.01185149 0.009000001 -0.02092023 -0.01211876 0.009000001 -0.02145079 -0.008679461 0.006750001 -0.02236871 -0.003543764 0.006750001 -0.02245212 -0.004097873 0.006750001 -0.02154372 -0.005526023 0.006750001 -0.02155051 -0.005474714 -0.00675 -0.02155585 -0.005492624 -0.006199996 -0.02116899 -0.004799154 -0.006749999 -0.02143412 -0.008679461 -0.006749999 -0.02092628 -0.0121104 -0.008999998 -0.0215008 0.00842054 0.006200002 -0.02161236 0.004899679 0.006200002 -0.02239286 -0.004057454 -0.008999998 -0.02109565 -0.005016263 -0.008999998 -0.02140079 -0.01062946 -0.008999998 -0.02097579 -0.01062946 -0.008999998 -0.02148929 -0.005294652 -0.009 -0.02150079 -0.008679461 0.006200002 -0.02156364 -0.005441884 0.006200002 -0.02097579 -0.01062946 0.009000001 -0.02140079 -0.01062946 0.009000001 -0.02105549 -0.005287503 0.009000001 -0.02145034 -0.005462733 0.009000001 -0.003200801 0.01037055 0.009000001 -0.02311228 0.01031435 0.01193763 0.005121404 0.01030597 0.01194318 -0.02315113 0.01037054 0.009000001 -0.003000801 0.01037055 -0.008999998 0.003499205 0.01037056 -0.008999998 0.005111274 0.01030947 -0.01194378 -0.0130008 0.01037054 0.003000001 -0.0031008 0.01037055 0.003000001 -0.003000801 0.01037055 -0.003 -0.02315113 0.01037054 -0.008999998 -0.0214008 0.01037054 -0.008999998 -0.02312396 0.01030815 -0.01193906 -0.0209758 0.01037054 -0.008999998 -0.0150008 0.01037054 -0.008999998 -0.0150008 0.01037054 -0.003 -0.0130008 0.01037054 -0.003 0.003499205 0.01037056 -0.003 0.003499205 0.01037056 0.003000001 0.003499205 0.01037056 0.009000001 -0.0007354422 0.01037055 0.00192031 -0.001839441 0.01037055 0.0008716611 -0.00110786 0.01037055 -0.001732539 0.0002134675 0.01037055 -0.002006839 0.001315577 0.01037055 -0.001551629 -0.001978931 0.01037055 -0.0004768586 0.002044634 0.01037055 -0.0002085585 0.001605318 0.01037055 0.001249331 0.0006306246 0.01037055 0.001916942 -0.02315112 -0.01062946 -0.008999998 -0.02311987 -0.01056668 -0.01193988 -0.003300785 -0.01062945 0.003000001 -0.01300079 -0.01062945 0.003000001 -0.01300079 -0.01062945 -0.003 -0.02315112 -0.01062946 0.009000001 -0.02311633 -0.01057366 0.0119368 -0.01480079 -0.01062945 0.009000001 0.001777163 -0.01062944 0.001032571 0.001948983 -0.01062944 -0.0006524687 0.003499221 -0.01062944 0.003000001 -0.003000785 -0.01062945 -0.003 -0.003100785 -0.01062945 0.009000001 -0.003000785 -0.01062945 -0.008999998 0.003499221 -0.01062944 -0.008999998 0.005118552 -0.01056726 -0.01194237 0.003499221 -0.01062944 -0.003 0.005113961 -0.01056616 0.01194445 -0.01500078 -0.01062945 -0.003 -0.01500078 -0.01062945 -0.008999998 0.003499221 -0.01062944 0.009000001 0.0006403728 -0.01062944 -0.001980649 -0.001195555 -0.01062945 -0.001673259 -0.001999735 -0.01062945 -0.0003802786 -0.003000785 -0.01062945 0.003000001 -0.001856934 -0.01062945 0.0007925006 0.0003987728 -0.01062944 0.002016841 -0.001098924 -0.01062944 0.00171304 -0.02653862 -0.005959839 0.012 -0.02677123 0.007187383 0.01199475 -0.02680253 -0.007365596 0.01198999 -0.02657047 0.005827595 0.012 -0.02586878 0.001596835 0.012 -0.02592992 0.004244784 0.012 -0.02657048 -0.0001724167 0.012 -0.0242903 -0.008715611 0.012 -0.02643014 -0.008248822 0.01198268 -0.02608187 -0.007591823 0.012 -0.02270682 0.008060297 0.01200001 -0.0243696 0.008387156 0.012 -0.02586831 0.007597575 0.01200254 -0.007259149 -0.005329662 0.012 -0.02150321 0.005264558 0.012 -0.004547956 -0.007874451 0.01200002 -0.02280557 0.003595335 0.012 -0.008882735 0.001202058 0.012 -0.007532395 0.004666489 0.012 -0.02586874 -0.004403165 0.012 -0.02566633 -0.002086786 0.012 0.0007539746 0.008738496 0.012 0.003873211 0.007973299 0.01199999 -0.02195037 -0.007731918 0.012 -0.02436964 0.002387155 0.012 -0.02470126 0.003425395 0.012 0.008699211 0.001746731 0.012 0.008782971 0.007225781 0.01198733 0.008203972 0.00335175 0.012 -0.005504408 0.006901661 0.012 -0.00214953 0.008585133 0.01199979 -0.02415273 -0.003563905 0.012 -0.02363183 -0.002672885 0.012 0.004886758 -0.007601884 0.012 0.002118189 -0.008803293 0.012 -0.02172429 0.006957767 0.012 -0.008576901 -0.002614622 0.012 -0.02161838 0.0007613487 0.012 -0.02170907 -0.001362363 0.012 -0.02235533 -0.004189904 0.01199999 -0.02150209 -0.005654153 0.012 0.006790297 0.005667658 0.01200001 0.008292096 0.00809136 0.01198627 -0.0008924315 -0.009013741 0.012 -0.02270681 0.002060296 0.01200001 0.008699327 -0.0020052 0.012 0.007544142 -0.005001371 0.012 0.008778161 -0.007606283 0.01198438 0.008187571 -0.008461514 0.01197859 0.0009481953 0.004070595 -0.012 -0.0005699312 0.003894864 -0.012 0.0009068335 0.007744135 -0.012 -0.000956974 0.007690742 -0.012 -0.001758876 0.004846083 -0.012 -0.001998858 0.006355314 -0.012 0.001958708 0.006418984 -0.012 0.001868301 0.005066266 -0.012 0.004241126 -0.001153903 -0.012 0.003985084 -5.736947e-07 -0.012 0.00805496 -9.50899e-05 -0.012 0.006220975 0.001893248 -0.012 0.007442416 0.00130499 -0.012 0.004599153 0.001411317 -0.012 0.007263562 -0.00178338 -0.012 0.005430085 -0.002105133 -0.012 0.001238717 -0.007743154 -0.012 -0.001641089 -0.004847468 -0.012 -0.0001240885 -0.004098386 -0.012 0.0001272205 -0.008143626 -0.012 0.00102101 -0.004388966 -0.012 0.001977355 -0.006606297 -0.012 0.001837845 -0.005257745 -0.012 -0.001035987 -0.007881234 -0.012 -0.001981538 -0.00668071 -0.012 -0.004162144 0.0007422007 -0.012 -0.004090383 -0.0009567393 -0.012 -0.007859912 -0.001007493 -0.012 -0.006956974 0.001690729 -0.012 -0.005266154 0.00179087 -0.012 -0.007931365 0.000513427 -0.012 -0.006725041 -0.002030992 -0.012 -0.005369712 -0.00206391 -0.012 0.0006340146 0.007826146 -0.0142 0.001694734 0.006965326 -0.0142 0.002044636 0.005661996 -0.0142 0.001315566 0.004318915 -0.0142 0.0002134312 0.003863713 -0.0142 -0.0009497684 0.004070593 -0.0142 -0.001783046 0.004923513 -0.0142 -0.002021168 0.006251843 -0.0142 -0.001049399 0.007639104 -0.0142 0.005599687 0.001887407 -0.0142 0.007097383 0.001583578 -0.0142 0.007855358 0.0006630588 -0.0142 0.007998167 -0.0005096905 -0.0142 0.007194012 -0.00180268 -0.0142 0.005358075 -0.002110102 -0.0142 0.004130118 -0.0009337338 -0.0142 0.004116024 0.0007580761 -0.0142 -5.372614e-05 -0.004074097 -0.0142 0.001507158 -0.004731805 -0.0142 0.002033682 -0.006166416 -0.0142 0.001647233 -0.007294485 -0.0142 0.0005683405 -0.00810514 -0.0142 -0.001265126 -0.007783385 -0.0142 -0.002031058 -0.006265144 -0.0142 -0.00157865 -0.004811258 -0.0142 -0.006400295 0.001887398 -0.0142 -0.004902574 0.00158355 -0.0142 -0.004144644 0.0006630495 -0.0142 -0.004001832 -0.0005097296 -0.0142 -0.004805982 -0.001802679 -0.0142 -0.006295862 -0.00214274 -0.0142 -0.007621823 -0.001394182 -0.0142 -0.008018593 -8.703209e-05 -0.0142 -0.007665634 0.001040436 -0.0142 0.001179216 0.009670555 0.0076577 0.00195871 0.009670555 0.006548411 0.0007909043 0.009670555 0.004143522 -0.0005699257 0.009670554 0.004024311 -0.0004716665 0.009670554 0.008027903 -0.00175888 0.009670554 0.004975521 -0.00197448 0.009670554 0.006662301 0.001810653 0.009670555 0.005027422 0.0002209628 0.009670554 -0.003977319 0.001442418 0.009670555 -0.004565589 0.001620231 0.009670555 -0.00726474 -0.0009470274 0.009670554 -0.004217319 0.0004657684 0.009670555 -0.007963576 -0.0007250738 0.009670554 -0.007901536 -0.00195246 0.009670554 -0.006724616 -0.00179494 0.009670554 -0.005040099 0.002023207 0.009670555 -0.005790625 -0.001294815 0.003680833 -0.0142 -0.002383216 0.004979791 -0.0142 -0.002409209 0.006675471 -0.0142 -0.001373509 0.008011835 -0.0142 5.328096e-05 0.008392783 -0.0142 0.001474255 0.007942677 -0.0142 0.002355153 0.006765386 -0.0142 0.002471879 0.005274486 -0.0142 0.001705428 0.004012216 -0.0142 0.0003680689 0.003353944 -0.0142 0.003501623 0.0004765168 -0.0142 0.004626512 0.002011856 -0.0142 0.006269764 0.002397688 -0.0142 0.007971551 0.001518291 -0.0142 0.00853705 -0.0002990496 -0.0142 0.007577958 -0.002199131 -0.0142 0.005508606 -0.002625172 -0.0142 0.003894253 -0.001603993 -0.0142 -0.0009061042 -0.008506372 -0.0142 -0.002193437 -0.007414687 -0.0142 -0.002518438 -0.005968388 -0.0142 -0.002008439 -0.004567788 -0.0142 -0.0007900186 -0.003733276 -0.0142 0.000699739 -0.003684307 -0.0142 0.002221646 -0.004838735 -0.0142 0.002503187 -0.006273765 -0.0142 0.002130876 -0.007516386 -0.0142 0.0007880824 -0.008547517 -0.0142 -0.007715635 0.001749027 -0.0142 -0.006153285 0.002409119 -0.0142 -0.004150844 0.001700781 -0.0142 -0.003460812 -0.0005214093 -0.0142 -0.004616911 -0.00229509 -0.0142 -0.00648466 -0.002624542 -0.0142 -0.0077851 -0.001912924 -0.0142 -0.008602764 -0.0001707422 -0.0142 0.0005524662 0.0009782333 -0.01497961 -0.001346405 0.002403652 -0.01451521 0.0007172134 0.002607264 -0.01450419 -0.002711792 -0.0009012492 -0.01450203 -0.002684254 0.0008401517 -0.01450333 -0.001309503 -0.0001223478 -0.0149376 -0.001658321 -0.002471099 -0.01450171 -2.068374e-05 -0.001338476 -0.01495656 0.0003396021 -0.002958946 -0.01450017 0.001910058 -0.002199055 -0.01450793 0.00224265 0.001640845 -0.01450224 0.002851744 -0.0004989049 -0.01451929 0.003452378 0.004378127 -0.012 0.004913614 0.004672207 -0.012 0.004870571 0.003528466 -0.012 0.003732614 0.003402967 -0.012 0.003987907 0.004895426 -0.012 0.005086591 -0.004359112 -0.012 0.003370073 -0.004310834 -0.012 0.004054576 -0.003562753 -0.012 0.004684706 -0.005065073 -0.012 0.004699053 -0.003695642 -0.012 0.003943667 -0.005149604 -0.012 -0.003800595 0.003420202 -0.012 -0.004471086 0.00332292 -0.012 -0.003391827 0.004197741 -0.012 -0.005087417 0.003955409 -0.012 -0.004691217 0.00481529 -0.012 -0.003949567 0.004881322 -0.012 -0.00462654 -0.00364462 -0.012 -0.003947901 -0.00360603 -0.012 -0.003655769 -0.004985189 -0.012 -0.00344278 -0.004150609 -0.012 -0.004541629 -0.005149611 -0.012 -0.00510194 -0.00438497 -0.012 -0.0006318958 -0.009929444 0.004065552 0.0006340193 -0.009929443 0.007955591 -0.0007137805 -0.009929444 0.007888123 0.0007234896 -0.009929442 0.004098472 -0.001883956 -0.009929446 0.00688753 0.001647212 -0.009929442 0.004834932 -0.001812235 -0.009929445 0.005027422 0.002050476 -0.009929442 0.006140103 0.001594264 -0.009929443 0.007217302 0.001950888 -0.009929442 -0.006724615 0.001721663 -0.009929442 -0.004877299 0.0005683545 -0.009929444 -0.007975697 0.0006306479 -0.009929443 -0.004083069 -0.0007354142 -0.009929444 -0.00407969 -0.002006875 -0.009929445 -0.005443533 -0.001707065 -0.009929446 -0.007108601 -0.0007924838 -0.009929444 -0.007856481 -0.0002324432 0.01107055 0.008068922 0.001639515 0.01107055 0.007281982 0.001998159 0.01107055 0.005619741 0.00119401 0.01107055 0.004326773 -0.0002958635 0.01107055 0.003986712 -0.001365731 0.01107055 0.004513293 -0.001978932 0.01107055 0.005523131 -0.001778741 0.01107055 0.007032561 -0.0002324404 0.01107055 -0.003931079 0.001371086 0.01107055 -0.004497219 0.002080787 0.01107055 -0.006033027 0.00106246 0.01107055 -0.00778985 -0.00079918 0.01107055 -0.007894695 -0.001950561 0.01107055 -0.006652468 -0.001778752 0.01107055 -0.004967449 0.002438798 0.004964795 -0.015 0.000507026 0.003318285 -0.015 -0.001550136 0.003853403 -0.015 -0.002581247 0.005614402 -0.015 -0.002144688 0.007190661 -0.015 -0.001104449 0.008162133 -0.015 0.0007927278 0.008315025 -0.015 0.002239995 0.007072674 -0.015 0.007884126 0.001617622 -0.015 0.008555998 -0.0003901497 -0.015 0.007783467 -0.001912951 -0.015 0.006073319 -0.002732111 -0.015 0.004131245 -0.001855743 -0.015 0.003504284 -0.0005034534 -0.015 0.003776784 0.001161277 -0.015 0.005731382 0.002464669 -0.015 0.002471322 -0.006803632 -0.015 0.001456414 -0.00818884 -0.015 -0.002167057 -0.007560084 -0.015 -0.002450158 -0.005443908 -0.015 -0.00131152 -0.003918757 -0.015 0.0007927604 -0.003684976 -0.015 0.002241896 -0.004929535 -0.015 -0.008027061 -0.001710382 -0.015 -0.007196335 0.002105268 -0.015 -0.006000795 0.002388259 -0.015 -0.004628104 0.002011839 -0.015 -0.003587584 0.0006741918 -0.015 -0.003573272 -0.0008162791 -0.015 -0.004355331 -0.00206903 -0.015 -0.006162821 -0.002696671 -0.015 0.002565589 -0.001435474 -0.015 0.001122292 0.002482554 -0.015 0.00222661 0.001577664 -0.015 0.002745493 0.000512125 -0.015 0.001176777 -0.002699316 -0.015 -0.000288506 -0.002950118 -0.015 -0.001979161 -0.002193628 -0.015 -0.002893813 -0.0001399489 -0.015 -0.002015535 0.001880994 -0.015 -0.0005206149 0.002640514 -0.015 0.004070364 0.004970137 -0.015 0.00509074 0.004320888 -0.015 0.004667145 0.003397258 -0.015 0.003787907 0.003400687 -0.015 0.003413338 0.004196987 -0.015 0.004284225 -0.003541923 -0.015 0.005090747 -0.004164383 -0.015 0.004667171 -0.005088014 -0.015 0.003654843 -0.005019514 -0.015 0.003510714 -0.003948783 -0.015 -0.003428887 0.004194772 -0.015 -0.003707036 0.003448902 -0.015 -0.004495885 0.003339412 -0.015 -0.005007606 0.003782291 -0.015 -0.004978896 0.00446186 -0.015 -0.004474636 0.004913192 -0.015 -0.003743446 0.004766172 -0.015 -0.00393739 -0.00356751 -0.015 -0.00340043 -0.004593629 -0.015 -0.004365269 -0.005222011 -0.015 -0.005023339 -0.00463306 -0.015 -0.00489253 -0.00383134 -0.015 -0.000299138 -0.01132944 0.007996072 0.0008821208 -0.01132944 0.007833272 0.001837851 -0.01132944 0.006871701 0.001909626 -0.01132944 0.005172702 0.0006303126 -0.01132944 0.004065552 -0.0005510766 -0.01132944 0.004058243 -0.001684744 -0.01132944 0.00482037 -0.002012234 -0.01132944 0.006307393 -0.001372624 -0.01132944 0.00750281 0.0003987634 -0.01132944 -0.00398316 0.001664093 -0.01132944 -0.004830129 0.002017023 -0.01132944 -0.005957597 0.001705494 -0.01132944 -0.007108619 0.000465896 -0.01132944 -0.008002369 -0.0008713547 -0.01132944 -0.00782083 -0.001758864 -0.01132944 -0.00702447 -0.001998854 -0.01132944 -0.00551525 -0.001098915 -0.01132944 -0.004286959 0.00252467 0.01107055 0.006476603 0.002025492 0.01107055 0.0044191 0.0003680652 0.01107055 0.003483391 -0.001494291 0.01107055 0.003908451 -0.002499482 0.01107055 0.005524672 -0.002320951 0.01107055 0.006990652 -0.001373521 0.01107055 0.00814128 5.330518e-05 0.01107055 0.008522232 0.001474222 0.01107055 0.008072111 0.002506819 0.01107055 -0.005304392 0.002025488 0.01107055 -0.007580913 0.0003680745 0.01107055 -0.008516611 -0.001494291 0.01107055 -0.008091549 -0.002499491 0.01107055 -0.006475325 -0.002320982 0.01107055 -0.005009399 -0.00119603 0.01107055 -0.003724799 0.0009174757 0.01107055 -0.003599609 -0.003602457 -0.00810015 -0.01500008 0.003153044 -0.008328697 -0.01500029 0.006125106 -0.006521272 -0.01493083 0.008073183 -0.003576681 -0.01500028 0.002884875 -0.003190104 -0.015 0.007712089 0.00408628 -0.01500028 0.008851524 -0.0002191393 -0.01494228 0.004512711 0.007410915 -0.0150002 0.00276704 0.002697294 -0.015 0.001919101 0.008494696 -0.01494955 -0.002334529 0.008298092 -0.01500019 -0.006062968 0.00619567 -0.01500052 -0.008446606 0.002360796 -0.01498552 -0.003061456 0.002756212 -0.015 -0.008686801 -0.001756012 -0.01494428 -0.00787236 -0.004098172 -0.01498185 -0.006536638 -0.006069619 -0.01494883 -0.003061451 -0.003190109 -0.015 -0.02276684 -0.004532394 -0.0112 -0.02248678 -0.004012913 -0.0112 -0.02200272 -0.005644683 -0.0112 -0.02147079 -0.005867729 -0.0112 -0.02217956 -0.006999229 -0.0112 -0.02197448 -0.007710351 -0.0112 -0.02296559 -0.007881258 -0.0112 -0.02363192 -0.008646073 -0.0112 -0.0246419 -0.008110128 -0.0112 -0.02508897 -0.008405513 -0.0112 -0.02632467 -0.007227061 -0.0112 -0.02595056 -0.0067819 -0.0112 -0.0262925 -0.004896547 -0.0112 -0.0257069 -0.004936476 -0.0112 -0.02458174 -0.003653205 -0.0112 -0.02405372 -0.004074115 -0.0112 -0.02504937 0.001639094 -0.0112 -0.02571566 0.001748994 -0.0112 -0.02371124 0.002456687 -0.0112 -0.023194 0.001789696 -0.0112 -0.02191968 0.001332838 -0.0112 -0.02200272 0.0003552958 -0.0112 -0.02147853 -7.645227e-05 -0.0112 -0.02231681 -0.001309074 -0.0112 -0.02186792 -0.001515223 -0.0112 -0.02301118 -0.002450094 -0.0112 -0.02377375 -0.002172925 -0.0112 -0.02449139 -0.002625194 -0.0112 -0.02509484 -0.001825446 -0.0112 -0.02595037 -0.001763025 -0.0112 -0.0258699 -0.000933745 -0.0112 -0.02656484 4.572421e-05 -0.0112 -0.02596029 0.0004189852 -0.0112 -0.02200185 0.005490256 -0.0112 -0.02155142 0.006556058 -0.0112 -0.02173648 0.004654797 -0.0112 -0.02268441 0.004318915 -0.0112 -0.02362933 0.003294878 -0.0112 -0.02412236 0.003818108 -0.0112 -0.02564626 0.003930995 -0.0112 -0.02536573 0.004383843 -0.0112 -0.02603278 0.005557004 -0.0112 -0.02649947 0.005395195 -0.0112 -0.02615386 0.007273935 -0.0112 -0.02566564 0.007040445 -0.0112 -0.02423241 0.007939464 -0.0112 -0.02479012 0.008266685 -0.0112 -0.02286627 0.008212516 -0.0112 -0.02236048 0.007152496 -0.0112 -0.02495693 0.001690716 -0.009800002 -0.0234404 0.001826655 -0.0098 -0.02233594 0.001040457 -0.009800002 -0.02197052 -0.000265142 -0.0098 -0.02250642 -0.001510494 -0.009800002 -0.0237057 -0.002142754 -0.0098 -0.0251956 -0.001802695 -0.0098 -0.02599974 -0.0005097268 -0.009800002 -0.02585695 0.0006630328 -0.009799996 -0.0241241 -0.004098405 -0.0098 -0.02297904 -0.004388955 -0.0098 -0.02199471 -0.005572953 -0.0098 -0.02247511 -0.00754593 -0.0098 -0.02405018 -0.008163663 -0.0098 -0.02531715 -0.007681109 -0.009800002 -0.02599973 -0.006509753 -0.0098 -0.02564109 -0.004847486 -0.009799998 -0.02463216 0.007787485 -0.0098 -0.02344042 0.007826667 -0.0098 -0.02222285 0.006903097 -0.009799996 -0.02200487 0.005571317 -0.0098 -0.0225064 0.004489476 -0.009800002 -0.02405611 0.003789436 -0.0098 -0.02542822 0.004443735 -0.009800002 -0.02599974 0.005490273 -0.0098 -0.02572321 0.006993245 -0.009800002 -0.02177834 0.001161216 -0.009 -0.02150586 -0.0005034823 -0.008999998 -0.02537349 0.002011834 -0.009000001 -0.02406994 -0.002730855 -0.009 -0.02578507 -0.001912955 -0.008999996 -0.02632098 0.000861153 -0.009 -0.02649947 -0.0006047869 -0.008999998 -0.02213275 -0.001855703 -0.009 -0.02350137 0.002391597 -0.009 0.002319398 -0.01132944 0.006990622 0.001194446 -0.01132944 0.008275201 -0.0009190496 -0.01132944 0.008400402 -0.002299075 -0.01132944 0.007089622 -0.002437984 -0.01132944 0.00518443 -0.000802191 -0.01132944 0.00352417 0.001492718 -0.01132944 0.003908451 0.002497909 -0.01132944 0.005524672 -0.002526245 -0.01132944 -0.005523409 -0.002027074 -0.01132944 -0.007580911 -0.000369654 -0.01132944 -0.008516609 0.001687279 -0.01132944 -0.007980524 0.00250789 -0.01132944 -0.006266713 0.00224191 -0.01132944 -0.004800109 0.001182087 -0.01132944 -0.003771699 -0.0005001463 -0.01132944 -0.003478939 -0.001763404 -0.01132944 -0.004215608 -0.02597316 0.001518246 0.009000001 -0.02167692 -0.001227093 0.009000001 -0.02154658 0.0004548076 0.009000001 -0.02654076 -0.0005214363 0.009000001 -0.02520907 -0.002434256 0.009000001 -0.02309544 -0.002506384 0.009000001 -0.02260141 0.002064558 0.009000001 -0.02448039 0.002347345 0.009000001 0.000792725 0.01187056 0.00844447 0.00235846 0.01187056 0.007019342 0.002381619 0.01187056 0.005109231 0.001293221 0.01187056 0.003810261 -0.000369682 0.01187055 0.003483401 -0.002179693 0.01187055 0.004577192 -0.002409382 0.01187055 0.006896571 -0.001104452 0.01187055 0.008291592 0.000580133 0.01187056 -0.003523739 0.001856811 0.01187056 -0.004292999 0.002513514 0.01187056 -0.005615762 0.002196801 0.01187056 -0.007280593 0.00108742 0.01187056 -0.008276042 -0.0008022068 0.01187055 -0.008475831 -0.002529222 0.01187055 -0.006615687 -0.002081902 0.01187055 -0.004537669 -0.0008920049 0.01187055 -0.003639849 -0.002267457 -0.008779641 -0.0148028 -0.005183837 -0.007397598 -0.01479171 -0.008908484 0.0002489667 -0.01478861 -0.007561067 0.004596447 -0.01479887 -0.005618538 0.00682802 -0.0147992 -0.002756999 0.008361353 -0.01478766 -3.993511e-06 0.008802833 -0.01479205 0.004399986 0.007624568 -0.01479897 0.006550207 0.005934708 -0.01479177 0.007946245 0.003877431 -0.01479999 0.008693905 0.0017992 -0.01480861 0.008602406 -0.00251368 -0.01480109 0.00757783 -0.00479582 -0.01480004 0.003669873 -0.008283566 -0.01480281 0.0007553175 -0.009013054 -0.0147886 -0.02406694 -0.003560275 -0.012 -0.02211586 -0.004382413 -0.012 -0.02145771 -0.006175667 -0.012 -0.02205119 -0.007763009 -0.012 -0.02393161 -0.008730849 -0.012 -0.02602706 -0.007710399 -0.012 -0.02652302 -0.00607643 -0.012 -0.02597312 -0.004481747 -0.012 -0.02406694 0.002439726 -0.012 -0.02228598 0.001749046 -0.012 -0.02148648 0.0002547894 -0.012 -0.02189579 -0.001603954 -0.012 -0.02351017 -0.002625193 -0.012 -0.02499038 -0.002450076 -0.012 -0.02626509 -0.001345216 -0.012 -0.02645018 0.0005560852 -0.012 -0.0256274 0.001798956 -0.012 -0.02472323 0.008370556 -0.012 -0.02243829 0.007911047 -0.012 -0.02154659 0.006454848 -0.012 -0.02161839 0.004979759 -0.012 -0.02306894 0.003440797 -0.012 -0.02499038 0.003549915 -0.012 -0.0263888 0.004836405 -0.012 -0.02629906 0.006960215 -0.012 -0.02478964 -0.002547545 -0.009799998 -0.02267171 -0.002366784 -0.0098 -0.02157329 -0.0008163033 -0.0098 -0.02170908 0.001103437 -0.009799998 -0.02341982 0.002346797 -0.0098 -0.02489204 0.002230683 -0.0098 -0.02622319 0.001161275 -0.009800002 -0.02638878 -0.001163607 -0.0098 -0.02672441 -0.008035801 -0.0118519 -0.02697365 -0.007344868 -0.01181601 -0.02676712 -0.007516146 -0.01199517 -0.02636542 -0.008460101 -0.0119182 -0.02695861 0.007243263 -0.01181265 -0.02682087 0.007095912 -0.01198256 -0.02647205 0.008154156 -0.01182732 -0.02624718 0.008137865 -0.01198898 -0.0215032 -0.005523493 -0.0098 -0.02245834 -0.004133114 -0.0098 -0.02384667 -0.003590634 -0.0098 -0.02585075 -0.004299246 -0.0098 -0.02652303 -0.006076454 -0.0098 -0.02613365 -0.007515209 -0.009800002 -0.0249904 -0.008450065 -0.0098 -0.02351763 -0.008627606 -0.009799985 -0.02189585 -0.007604011 -0.009799998 -0.0215337 0.006698439 -0.0098 -0.02300972 0.008213016 -0.0098 -0.0247013 0.008315675 -0.0098 -0.02608188 0.007332925 -0.0098 -0.02653863 0.005700925 -0.0098 -0.02586874 0.004144235 -0.009800002 -0.0243689 0.003354443 -0.009799953 -0.02291262 0.003594486 -0.009799998 -0.02180318 0.004589947 -0.009799998 -0.0224418 -0.004128085 0.006200002 -0.02250079 -0.003579464 0.006200002 -0.0009918399 -0.01212945 0.008342472 0.0009175074 -0.01212944 0.008400402 0.002297512 -0.01212944 0.00708961 0.002471889 -0.01212944 0.005403931 0.00154858 -0.01212944 0.003982862 -0.000508599 -0.01212945 0.003447731 -0.002440364 -0.01212945 0.005094242 -0.002243454 -0.01212945 0.007199911 6.537419e-05 -0.01212944 -0.003430809 0.001625831 -0.01212944 -0.00407161 0.0024486 -0.01212944 -0.005314471 0.002395051 -0.01212944 -0.006790282 0.001383091 -0.01212944 -0.008165646 -0.0004913919 -0.01212945 -0.008495733 -0.002105733 -0.01212945 -0.007474547 -0.002515084 -0.01212945 -0.005615762 -0.001715633 -0.01212945 -0.004121509 -0.02695632 -0.007498443 0.01182178 -0.02649203 -0.008397278 0.01183232 -0.02645871 0.007948306 0.01197992 -0.02634162 0.008263124 0.01182777 -0.02694374 0.007352743 0.01182208 0.003499204 0.01144231 0.009000001 0.003215122 0.01183411 0.003000001 0.002839744 0.01187056 0.009000001 -0.003000802 0.01187055 0.009000001 -0.003000802 0.01187055 0.003000001 0.003499204 0.01144231 -0.003 0.003215125 0.0118341 -0.008999998 0.002839744 0.01187056 -0.003 -0.003000802 0.01187055 -0.003 -0.003000802 0.01187055 -0.008999998 -0.00116653 0.009570554 -0.001647528 0.00117921 0.009570556 0.00165771 -5.021691e-05 0.009570554 -0.002034199 0.001383174 0.009570556 -0.0015205 0.002070486 0.009570556 0.0002094507 -0.0004716581 0.009570554 0.002027902 -0.00198155 0.009570554 -0.0005512787 -0.00179494 0.009570554 0.0009599114 -0.0147008 0.01107054 0.003000001 -0.0147008 0.01107054 0.009000001 -0.0130008 0.01107054 0.003000001 -0.003300802 0.01107055 0.009000001 -0.003300802 0.01107055 0.003000001 0.008955057 0.007225221 0.01183274 0.00846711 0.008162592 0.01181346 0.008789749 0.00716557 -0.01199118 0.008364236 0.008047121 -0.01198015 0.008954856 0.007242132 -0.01182098 0.008455057 0.00817772 -0.01180186 0.008763982 -0.00181938 -0.01199849 0.008846873 0.0009738207 -0.01196773 0.007974699 0.003891911 -0.012 0.006179658 0.006319009 -0.012 0.003678231 0.008009577 -0.012 0.00072648 0.008772865 -0.01200001 -0.00225141 0.008514302 -0.012 -0.005645388 0.0068613 -0.012 -0.008338016 0.003220677 -0.012 -0.008924682 -0.0005085338 -0.012 -0.008288622 -0.003459803 -0.012 -0.006705718 -0.00603058 -0.012 -0.004356867 -0.007927149 -0.012 -0.001510296 -0.008932911 -0.012 0.001508706 -0.008932909 -0.012 0.005030678 -0.007573695 -0.012 0.007605055 -0.00481251 -0.012 0.008467216 -0.008426244 0.01179264 0.00895995 -0.007485302 0.01181154 0.00871601 -0.00776095 -0.01199794 0.008956861 -0.00748267 -0.01182704 0.008451982 -0.008419193 -0.01186189 -0.02696903 -0.007555296 -0.009000001 -0.02641634 -0.008474561 -0.008999998 -0.02684405 0.007785432 -0.008999971 -0.02105549 0.005028589 -0.008999998 -0.02235163 0.003234915 -0.009 -0.02367099 -0.008619647 -0.00900001 -0.02245143 -0.008146599 -0.008999996 -0.02152814 -0.006725579 -0.008999998 -0.02164029 -0.005239193 -0.008999998 -0.02252581 -0.004057314 -0.008999998 -0.02394669 -0.003607235 -0.009 -0.02537347 -0.003988166 -0.009 -0.02649837 -0.005523517 -0.008999998 -0.02627731 -0.007216671 -0.009 -0.02514083 -0.008430263 -0.008999998 -0.02384404 0.003353437 -0.008999983 -0.02245144 0.003853366 -0.009 -0.02152814 0.005274469 -0.009 -0.02170252 0.006960166 -0.008999998 -0.02289719 0.008162147 -0.008999994 -0.02500927 0.008269485 -0.009000001 -0.02622304 0.007033424 -0.009000003 -0.02655757 0.005609825 -0.008999998 -0.02549427 0.003778974 -0.009 -0.02350138 0.002391597 0.009800001 -0.02191966 0.001332838 0.009799982 -0.02147237 -0.0007451521 0.009800001 -0.02263319 -0.002249413 0.009799982 -0.02406255 -0.002672214 0.009800001 -0.02545795 -0.002188876 0.009800013 -0.02647673 -0.0008185366 0.009800001 -0.0262435 0.001070473 0.009800001 -0.02518361 0.002098884 0.009799992 -0.02458175 -0.003653205 0.009800001 -0.02470128 -0.003684325 0.009000001 -0.02321151 -0.003733293 0.009000001 -0.02310953 -0.003769324 0.009800001 -0.02177835 -0.004838743 0.009800001 -0.021444 -0.006390171 0.009000001 -0.02152813 -0.006725532 0.009800001 -0.02250729 -0.008221017 0.009000011 -0.02279248 -0.008434239 0.009800001 -0.02436963 -0.008646074 0.009000001 -0.02468865 -0.008556683 0.009799992 -0.02602706 -0.007710383 0.009000001 -0.02595033 -0.007763072 0.009800001 -0.02656484 -0.005954314 0.009800001 -0.02652303 -0.006076446 0.009000001 -0.02608189 -0.004667137 0.009000021 -0.02585847 -0.004422606 0.009799982 -0.02393463 0.008439727 0.009800001 -0.02470127 0.008315675 0.009000001 -0.02321151 0.008266706 0.009000001 -0.02237423 0.007798966 0.009800001 -0.02199314 0.007432176 0.008999982 -0.02147534 0.006347179 0.009800001 -0.02177297 0.004686806 0.009800013 -0.0228146 0.003620567 0.009799992 -0.02415276 0.003304994 0.009000001 -0.02449138 0.003374806 0.009800001 -0.02602711 0.004289635 0.009000011 -0.02595036 0.004236955 0.009799992 -0.02656485 0.006045705 0.009800001 -0.02653079 0.006132264 0.009000001 -0.02592995 0.007496314 0.009000032 -0.02571566 0.007748995 0.009799982 0.003499222 -0.01170118 0.003000001 0.003217317 -0.01208998 0.009000001 0.002839762 -0.01212944 0.003000001 -0.003000784 -0.01212945 0.003000001 -0.003000784 -0.01212945 0.009000001 0.003499222 -0.01170118 -0.008999998 0.003217317 -0.01208998 -0.003 0.002839762 -0.01212944 -0.008999998 -0.003000784 -0.01212945 -0.003 -0.003000784 -0.01212945 -0.008999998 0.0002975641 -0.009829445 0.001996071 -0.0006318996 -0.009829445 -0.001934458 0.001371077 -0.009829443 0.001502802 0.000549525 -0.009829443 -0.001941779 0.001558885 -0.009829443 -0.001306849 0.002050475 -0.009829442 0.0001401007 -0.001049366 -0.009829445 0.001768562 -0.001812235 -0.009829445 -0.0009725792 -0.001960276 -0.009829445 0.0005484316 -0.003300785 -0.01132944 0.003000001 -0.003300785 -0.01132944 0.009000001 -0.01300078 -0.01132945 0.003000001 -0.01470079 -0.01132945 0.009000001 -0.01470079 -0.01132945 0.003000001 -0.02260075 -0.004588684 0.009800001 -0.02196632 -0.006166401 0.009800001 -0.02235276 -0.007294549 0.009800013 -0.02343167 -0.008105162 0.009799992 -0.0249497 -0.007929454 0.009799992 -0.02602353 -0.006621994 0.009800001 -0.02566563 -0.004959555 0.009800013 -0.02440031 -0.004112614 0.009800001 -0.02521202 0.001563763 0.009800001 -0.023536 0.001851546 0.009800001 -0.02239466 0.001119846 0.009800001 -0.02196632 -0.0001663929 0.009800001 -0.02265034 -0.001713864 0.009799992 -0.02429585 -0.002142754 0.009799992 -0.02574388 -0.001267726 0.009800001 -0.02598238 0.0002533756 0.009800001 -0.02195537 0.005661977 0.009800001 -0.02268444 0.004318887 0.009799992 -0.02378659 0.003863696 0.009800001 -0.02494975 0.004070574 0.009800001 -0.02578304 0.004923524 0.009800001 -0.0260248 0.006079916 0.009800001 -0.02544402 0.007304935 0.009799992 -0.02405373 0.007925898 0.009800001 -0.02249286 0.007268187 0.009800001 -0.02694497 -0.007643423 0.008995571 -0.02640021 -0.008493084 0.009000021 -0.02665049 0.007993253 0.009000001 -0.02694926 0.007563044 0.008992911 -0.0150008 0.01187054 0.009000001 -0.0150008 0.01187054 0.003000001 -0.0215008 0.00842054 -0.006199995 -0.0150008 0.01187054 -0.003 -0.0150008 0.01187054 -0.008999998 -0.02145034 0.005203867 -0.009 -0.02234209 0.003820658 -0.008999998 -0.01500078 -0.01212945 -0.008999998 -0.01500078 -0.01212945 -0.003 -0.02150079 -0.008679461 -0.006199995 -0.01500078 -0.01212945 0.003000001 -0.01500078 -0.01212945 0.009000001 -0.02479362 -0.004255486 0.01119999 -0.02309316 -0.004255884 0.01119999 -0.02204127 -0.005581063 0.0112 -0.02208413 -0.00676168 0.0112 -0.02276129 -0.007743172 0.01120002 -0.02405018 -0.008163663 0.0112 -0.02531715 -0.007681094 0.0112 -0.02594282 -0.006678889 0.01120001 -0.02588819 -0.005313995 0.0112 -0.02479362 0.001744526 0.0112 -0.02344041 0.001826655 0.01120001 -0.02233594 0.001040425 0.01120001 -0.02197805 -0.0006220024 0.0112 -0.02320241 -0.002024164 0.01120001 -0.02472504 -0.002031005 0.0112 -0.02585989 -0.001007516 0.0112 -0.0258882 0.0006859637 0.01120001 -0.02429915 0.007866615 0.0112 -0.02311789 0.007703816 0.0112 -0.02225997 0.006891718 0.01120003 -0.02197053 0.005734848 0.0112 -0.0224042 0.004635906 0.01119999 -0.02336968 0.003936086 0.0112 -0.02489563 0.004019445 0.0112 -0.02604685 0.005486205 0.0112 -0.02550875 0.007268176 0.0112 -0.0270008 0.003320534 -0.007199999 -0.02704308 0.008414632 -0.00720001 -0.02702625 0.008523883 -0.008973422 -0.02704215 -0.008671494 -0.006199996 -0.027039 -0.008672118 0.006200002 -0.02700079 -0.003579467 -0.006199995 -0.02700079 -0.003579467 0.006200002 -0.0270008 0.003320534 -0.006199995 -0.02700079 -0.003579467 -0.007199999 -0.02701983 -0.008686193 -0.008975924 -0.02703942 -0.008671139 -0.007200034 -0.02703594 0.008415092 0.007199991 -0.0270008 0.003320534 0.007200002 -0.02700079 -0.003579467 0.007200002 -0.02704201 -0.008675534 0.007200002 -0.0270008 0.003320534 0.006200002 -0.02703336 0.008403573 0.006200002 -0.02704336 0.008415943 -0.006199995 -0.02500925 -0.008528413 0.0112 -0.02649837 -0.006735425 0.0112 -0.02599928 -0.004462717 0.0112 -0.02384884 -0.003563905 0.0112 -0.02229464 -0.004271064 0.01120004 -0.02152813 -0.005533382 0.0112 -0.02289715 -0.008421044 0.01119999 -0.02170248 -0.007219062 0.01119999 -0.02384077 0.002388267 0.0112 -0.02245142 0.001887666 0.0112 -0.02160496 0.0006608181 0.0112 -0.02159219 -0.001026023 0.0112 -0.02308251 -0.002529845 0.0112 -0.02499186 -0.002471926 0.0112 -0.02624349 -0.001329326 0.0112 -0.02647673 0.0005595945 0.0112 -0.02529475 0.002060294 0.0112 -0.02300283 0.008238915 0.0112 -0.02532987 0.008107844 0.0112 -0.02660277 0.005911823 0.01120001 -0.02571563 0.003992043 0.01119999 -0.02177296 0.007054357 0.0112 -0.0214708 0.005608819 0.0112 -0.02415488 0.003331704 0.0112 -0.02233529 0.003913168 0.01120001 0.004334344 -0.001299324 0.01379999 0.003967228 0.0001841169 0.0138 0.003734903 -0.001345183 0.0138 0.00637217 0.002365649 0.0138 0.006376912 0.001871649 0.0138 0.007714059 0.001749048 0.0138 0.007426652 0.001297358 0.01380001 0.008563281 4.572049e-05 0.0138 0.003549834 0.0005560871 0.0138 0.008044643 7.911958e-05 0.01379999 0.007694714 -0.001224241 0.0138 0.007824704 -0.001938511 0.0138 0.004892114 0.001603078 0.0138 0.004688478 0.002081236 0.01379999 0.006792103 -0.002003402 0.0138 0.005627748 -0.002705092 0.0138 0.005438832 -0.002085552 0.0138 0.006478792 0.002347369 0.015 0.005008088 0.002213018 0.015 0.003639956 0.0008898973 0.015 0.003675334 -0.001227033 0.015 0.005093884 -0.002506371 0.015 0.006788084 -0.002547521 0.015 0.007994915 -0.001672731 0.01500001 0.00853705 -0.0002990496 0.015 0.007971548 0.001518281 0.015 -0.0003722617 0.003294904 0.0138 -0.0008837218 0.004037302 0.0138 -0.002133626 0.004484771 0.0138 -0.0004803808 0.008347355 0.0138 -0.0009497255 0.007670542 0.01379999 0.0005455846 0.007857134 0.0138 0.000990306 0.008213016 0.01379999 0.001950876 0.006595176 0.0138 0.002358467 0.006889885 0.01379999 0.002381629 0.004979776 0.0138 0.001793365 0.004910655 0.01379999 0.0006340016 0.003914975 0.0138 0.001456435 0.003811136 0.01379997 -0.002530788 0.006132251 0.0138 -0.001869888 0.006674843 0.01379999 -0.001804829 0.007663583 0.0138 -0.001927667 0.005153332 0.01380001 0.0009175074 0.008270946 0.015 -0.0009918874 0.008213023 0.01500002 -0.002120199 0.007239072 0.015 -0.002543868 0.00582432 0.015 -0.001950377 0.004236992 0.015 -0.0004914217 0.003374824 0.015 0.001579635 0.003803136 0.015 0.002537047 0.005700946 0.015 0.002175309 0.007146936 0.01500002 -0.001311529 -0.003918757 0.01379999 -0.0004605278 -0.004124968 0.0138 0.0005801907 -0.003653176 0.0138 0.0008697864 -0.004308616 0.0138 0.002152268 -0.004726056 0.0138 0.001757308 -0.005104976 0.0138 0.002013344 -0.006258305 0.0138 0.002507887 -0.006396159 0.0138 0.00160534 -0.007378751 0.01379999 0.001687277 -0.008109968 0.0138 0.0006306311 -0.008046377 0.0138 -0.0003696475 -0.008646057 0.0138 -0.0005611591 -0.008085562 0.01379999 -0.002179677 -0.007552269 0.0138 -0.001665628 -0.007299352 0.01379998 -0.002018589 -0.006171844 0.0138 -0.002450149 -0.005443898 0.01379999 -0.00170708 -0.005020847 0.0138 5.330052e-05 -0.003607216 0.015 -0.001563319 -0.004088948 0.015 -0.002564848 -0.005954319 0.015 -0.001826267 -0.007938507 0.015 0.0001511797 -0.00869499 0.015 0.001867181 -0.007855742 0.01500002 0.00258832 -0.005867635 0.015 0.001474248 -0.004057324 0.015 -0.008032775 0.0001841281 0.0138 -0.007240264 0.001484258 0.01379999 -0.007850735 0.001700768 0.01380001 -0.007665632 -0.001299363 0.0138 -0.008538624 -0.0002990728 0.0138 -0.005948995 0.00189914 0.0138 -0.005846665 0.002409378 0.0138 -0.004094853 0.00058317 0.01380001 -0.003587584 0.0006741918 0.0138 -0.004458334 0.001866912 0.01380004 -0.004835054 0.001518078 0.01379998 -0.004037413 -0.0005968604 0.01379999 -0.003618372 -0.001020219 0.0138 -0.004881242 -0.00188464 0.0138 -0.004543591 -0.00218884 0.01379999 -0.005939021 -0.0026722 0.0138 -0.006561161 -0.002085571 0.01379999 -0.007730751 -0.002030062 0.01379999 -0.005501365 0.00239161 0.015 -0.007183604 0.002098897 0.015 -0.008243464 0.001070468 0.015 -0.008440383 -0.001035222 0.015 -0.006712191 -0.002599072 0.015 -0.004616911 -0.00229509 0.015 -0.003404682 -0.0003089588 0.015 -0.004071664 0.0014963 0.015 0.008407372 -0.003290679 0.015 0.008919731 -3.567897e-05 0.012 0.008877704 0.00120366 0.01499986 0.007530776 0.0046665 0.01500001 0.004867765 0.007417688 0.015 0.001173328 0.008735616 0.01499996 -0.001788749 0.008610552 0.015 -0.004472739 0.007598992 0.01500003 -0.006791947 0.00566759 0.01500003 -0.008335227 0.003074147 0.015 -0.008926384 0.0001145564 0.015 -0.008497821 -0.002872832 0.015 -0.007098539 -0.005546792 0.01500004 -0.004888318 -0.007601912 0.01499998 -0.002119756 -0.008803297 0.01499999 0.000890879 -0.009013739 0.015 0.003799661 -0.008209187 0.01500002 0.006274253 -0.006481538 0.01499998 -0.005541055 0.00187503 0.012 -0.004404223 0.001105182 0.01200001 -0.003970513 6.241724e-06 0.012 -0.004259932 -0.00115058 0.01199999 -0.005117842 -0.001962711 0.012 -0.006465522 -0.002110472 0.012 -0.007606901 -0.001378782 0.012 -0.008046854 0.0002549067 0.012 -0.007035985 0.001622338 0.012 -0.0004138062 -0.004094137 0.012 0.001238702 -0.004515726 0.012 0.001977352 -0.005652586 0.01200001 0.001837848 -0.007001119 0.01200001 0.000882118 -0.00796271 0.012 -0.0006355941 -0.008085027 0.012 -0.001974467 -0.00679174 0.012 -0.001758869 -0.005104979 0.01199999 0.0001250198 0.007883062 0.012 0.001383184 0.007391045 0.012 0.002054958 0.005836205 0.012 0.001210426 0.004177324 0.01199999 -0.0006355978 0.003914973 0.012 -0.001794947 0.004910654 0.012 -0.001981548 0.006421823 0.012 -0.001035999 0.007622372 0.01200001 0.005621507 0.001871649 0.01200001 0.006948129 0.001670549 0.012 0.007948976 0.0005230308 0.012 0.007887626 -0.0008416213 0.01200001 0.00704781 -0.001897972 0.012 0.005700894 -0.002125513 0.012 0.004491299 -0.001527114 0.012 0.003964747 -9.247288e-05 0.012 0.004439538 0.001177397 0.012 0.0001533031 0.003331723 0.012 -0.001475866 0.003798462 0.012 -0.002450157 0.005185002 0.01200001 -0.002396628 0.006660821 0.012 -0.001384649 0.008036215 0.01199999 0.0006878786 0.008351336 0.01199999 0.002196815 0.007151136 0.012 0.002513519 0.005486324 0.012 0.00171405 0.003992064 0.01199999 -0.002299067 -0.007219067 0.012 -0.002495719 -0.005755432 0.012 -0.001581229 -0.004062028 0.012 0.000687886 -0.003648666 0.01199999 0.002438806 -0.005223684 0.012 0.002241898 -0.007329344 0.01200001 0.001182077 -0.008357764 0.01199998 -0.0007232065 -0.008629464 0.012 0.002023208 0.005661177 0.009000001 0.001781469 0.006817596 0.008999991 4.24739e-05 0.003852773 0.009000001 0.0009481311 0.007670535 0.009000001 -0.0007462576 0.007814353 0.009000001 -0.001906738 0.006583173 0.009000001 -0.001931367 0.005227674 0.009000001 -0.001098976 0.004157543 0.009000001 0.001331603 0.004304676 0.009000001 -0.0002225284 0.003847873 0.0112 0.001249236 0.004238175 0.0112 0.002080792 0.005903596 0.0112 0.001194019 0.007543786 0.0112 -0.0004674792 0.007872933 0.0112 -0.001812258 0.006843153 0.0112 -0.001960287 0.005322123 0.01119999 -0.001302076 0.004327834 0.01120001 -0.0006573442 0.008310584 0.01119994 -0.001950399 0.007504083 0.01120001 -0.002543868 0.005916811 0.0112 -0.002008416 0.004308883 0.01120002 -0.0005816966 0.003394272 0.0112 0.001102844 0.003578974 0.0112 0.0022975 0.004780956 0.0112 0.002387216 0.006904675 0.0112 0.0008067237 0.008280486 0.01119992 -0.0002959743 -0.008164179 0.009000001 0.000127214 -0.004115255 0.009000001 -0.00103597 -0.004377647 0.009000001 -0.001821989 -0.005259639 0.008999991 -0.001486897 -0.007495008 0.008999982 -0.002012228 -0.006436832 0.009000001 0.002076103 -0.005985831 0.009000001 0.001238693 -0.004515726 0.009000001 0.001331605 -0.007695326 0.009000001 0.0006340332 -0.008085022 0.01120001 0.001793358 -0.007089368 0.0112 0.001979975 -0.005578195 0.0112 0.000744679 -0.004185647 0.0112 -0.001107869 -0.004396927 0.01120001 -0.002032768 -0.005815875 0.0112 -0.001741657 -0.007150551 0.01119999 -0.000883692 -0.007962717 0.01120001 -0.001826289 -0.004320377 0.0112 -0.002564848 -0.006304569 0.0112 -0.001715637 -0.008007928 0.0112 0.0002887463 -0.008715594 0.0112 0.002221638 -0.007420152 0.0112 0.002387224 -0.005095325 0.01120001 0.0003748853 -0.003558156 0.0112001 -0.0214008 0.00842054 -0.007199999 -0.02148929 0.005035728 -0.007199999 -0.0214008 0.01187054 -0.008999998 -0.02248284 0.003532717 -0.007199999 -0.02148302 -0.005272902 -0.007199999 -0.02140079 -0.008679461 -0.007199999 -0.02140079 -0.01212946 -0.008999998 -0.02247825 -0.003784754 -0.007199998 -0.02145034 0.005203849 0.007200002 -0.02145565 -0.005480954 0.007200002 -0.02235231 -0.004048844 0.007199991 -0.05296072 0.01428294 0.01143018 -0.05197029 0.0144391 0.0111572 -0.05228172 0.01402617 0.01107225 -0.05185208 0.01485786 0.01176953 -0.05321292 0.01475723 0.0121264 -0.05442471 0.01469343 0.01363086 -0.05466549 0.01422507 0.01331006 -0.05492002 0.0143255 0.01442987 -0.05399257 0.0148616 0.01351062 -0.05393271 0.01425828 0.01220166 -0.05174393 0.01487516 0.0123147 -0.05444797 0.01480003 0.02145398 -0.05494719 0.0141772 0.02150659 -0.05186001 0.01483455 0.01173047 -0.04842471 0.01463375 0.01077188 -0.05192297 0.01467705 0.01140765 -0.04819107 0.01410482 0.01041301 -0.02769143 0.01426926 -0.006914061 -0.02688684 0.01437558 -0.008966025 -0.02665529 0.01418106 -0.009852661 -0.02745999 0.01482614 -0.005998045 -0.02619031 0.01485668 -0.008763694 -0.02606253 0.0148707 -0.008726562 -0.02866506 0.01411026 -0.00473633 -0.02932376 0.01460368 -0.002809569 -0.02919924 0.01485742 -0.002175779 -0.03077199 0.01417836 -0.001008789 -0.0330928 0.01485792 0.003121092 -0.03312698 0.01466531 0.002482421 -0.03172464 0.01457599 0.0006904314 -0.03278958 0.0140752 0.00161719 -0.03631887 0.01427176 0.005039062 -0.03467679 0.01406769 0.003580571 -0.03770632 0.01481814 0.006812991 -0.03884279 0.01429632 0.006795171 -0.04149539 0.01425232 0.008186522 -0.04338527 0.0146868 0.009386961 -0.04062698 0.01485695 0.008629401 -0.04420241 0.0142486 0.009283602 -0.05381399 0.01485881 0.02272156 -0.05360329 0.01440774 0.02394922 -0.05255838 0.01466604 0.02430493 -0.05181888 0.0148557 0.02417557 -0.05456203 0.01437191 0.0226759 -0.05139834 0.01435806 0.02491191 -0.05406008 0.01428958 0.02350024 -0.05250442 0.01413481 0.02469598 -0.02407315 0.01486342 -0.01108713 -0.02601613 0.01479992 -0.009864746 -0.02670461 0.01462619 -0.008914124 -0.02700179 0.01187137 -0.008999807 -0.02548587 0.01469983 -0.01073975 -0.02587454 0.01417817 -0.01089001 -0.02478215 0.01423378 -0.01162172 -0.02374222 0.01461509 -0.01167062 -0.02363218 0.01406073 -0.01196194 -0.03414894 0.01486202 0.02411963 -0.03439664 0.01459583 0.02468887 -0.0345245 0.01405179 0.02496799 -0.0151581 0.01486803 -0.01060388 -0.0158929 0.01477793 -0.01133496 -0.01656441 0.01436666 -0.01190127 -0.03209331 0.01481757 0.02284851 -0.03196609 0.01425977 0.02355177 -0.03141373 0.01421405 0.02268835 -0.03296316 0.01466773 0.02402997 -0.03314041 0.0141377 0.02455278 -0.0139241 0.01484725 -0.009333344 -0.01438445 0.0146149 -0.01064423 -0.01342525 0.01468606 -0.008400131 -0.01335521 0.0142858 -0.009541748 -0.01305219 0.01419926 -0.008460158 -0.01547145 0.01418607 -0.01167569 -0.01418261 0.01414976 -0.01085118 -0.03061415 0.01421003 0.02050635 -0.0304324 0.01483853 0.0185249 -0.02946081 0.01426922 0.01809607 -0.02752936 0.01419058 0.01535836 -0.02775638 0.01463518 0.01515259 -0.02758864 0.01483955 0.01442407 -0.01376875 0.01485069 0.008841162 -0.0133014 0.01453024 0.008816341 -0.01304072 0.01413442 0.008434483 -0.02597928 0.01446893 0.01375256 -0.02580617 0.01402048 0.0138439 -0.02495608 0.01485428 0.0123999 -0.02386325 0.01414305 0.0127352 -0.02403787 0.01468122 0.01242468 -0.02228811 0.01428488 0.01221283 -0.02142605 0.01484259 0.01135407 -0.02083981 0.01413375 0.01200591 -0.02085501 0.0146414 0.0116889 -0.01561893 0.01484196 0.01110535 -0.01422735 0.01468756 0.01036414 -0.01662465 0.01462681 0.01165952 -0.01620734 0.01417048 0.01191924 -0.01490054 0.01420975 0.01137637 -0.01395991 0.01420977 0.01056204 -0.01332983 0.01418377 0.009544271 -0.05313565 -0.01511751 0.01237811 -0.05182031 -0.01512895 0.0119375 -0.0534535 -0.01442114 0.01172092 -0.05200253 -0.01432335 0.010995 -0.05415745 -0.01493797 0.01301086 -0.05437036 -0.01436328 0.01272192 -0.05429461 -0.01510917 0.0142175 -0.05475599 -0.01445558 0.01358203 -0.05493751 -0.01451148 0.01441657 -0.04720094 -0.01510089 0.01078381 -0.05184023 -0.01511417 0.01183068 -0.02597241 -0.01511708 -0.008700545 -0.02844604 -0.0148636 -0.004551759 -0.02991235 -0.01511585 -0.001013669 -0.03031299 -0.01465909 -0.001551759 -0.03343594 -0.01511169 0.00371069 -0.03317761 -0.0150137 0.002830812 -0.03450879 -0.01477433 0.00376233 -0.02674219 -0.01480911 -0.008923828 -0.03248682 -0.01446066 0.001300291 -0.02699563 -0.01435282 -0.008996969 -0.03466578 -0.01437999 0.00357861 -0.03678687 -0.01443473 0.005368902 -0.02836816 -0.01435147 -0.005416991 -0.03091602 -0.01434048 -0.0008129888 -0.03768335 -0.01487091 0.006328252 -0.0396629 -0.01445843 0.007251862 -0.04041138 -0.01510629 0.008370611 -0.04188168 -0.01498449 0.008829002 -0.04205047 -0.0144559 0.008414031 -0.04470105 -0.01432711 0.009436831 -0.04407971 -0.01483281 0.009472902 -0.0484624 -0.01428985 0.01042743 -0.05200018 -0.01429811 0.01100708 -0.05491653 -0.01448497 0.0217121 -0.0543392 -0.01508218 0.02181586 -0.0256799 -0.01510026 -0.01020767 -0.0262207 -0.01511526 -0.008772949 -0.02678326 -0.0148273 -0.008936417 -0.026475 -0.01501769 -0.008846292 -0.02387502 -0.01511469 -0.0111862 -0.02467351 -0.01479077 -0.01145317 -0.02367002 -0.01460441 -0.01190785 -0.02513238 -0.01437124 -0.01148332 -0.02590759 -0.01486039 -0.01049143 -0.02629823 -0.01440262 -0.01041907 -0.05272041 -0.01512598 0.02376367 -0.0518121 -0.01501833 0.02441818 -0.05323413 -0.01490837 0.02391736 -0.05422083 -0.01477313 0.02304785 -0.05147278 -0.01453952 0.02492715 -0.05254639 -0.01446874 0.02466315 -0.0537057 -0.01444148 0.02393432 -0.05462727 -0.01409697 0.02275525 -0.01656191 -0.01436812 -0.01196478 -0.01609439 -0.01485656 -0.01164288 -0.01572537 -0.01511659 -0.01106109 -0.03456886 -0.01431259 0.02497237 -0.03423676 -0.01476398 0.02473602 -0.03414847 -0.01510701 0.02423613 -0.01445462 -0.01491899 -0.01067136 -0.01381498 -0.01511511 -0.008735657 -0.01345731 -0.01490231 -0.009056885 -0.01548309 -0.0144449 -0.01168054 -0.01358563 -0.01439393 -0.01006342 -0.01306628 -0.01443559 -0.008696471 -0.01438361 -0.0143199 -0.01102505 -0.03347852 -0.0143203 0.02469941 -0.03301547 -0.01485486 0.02416368 -0.0323756 -0.01444263 0.02399521 -0.03202396 -0.01511138 0.02244116 -0.03196248 -0.01496932 0.02296557 -0.03151622 -0.01444134 0.0229454 -0.01304221 -0.01438679 0.008472233 -0.01338879 -0.01487315 0.008958792 -0.01374627 -0.01509531 0.008810322 -0.01400078 -0.01512945 0.003000001 -0.01600162 -0.01513989 -0.001656389 -0.02842114 -0.014521 0.01646472 -0.02923096 -0.01490173 0.01718335 -0.02730807 -0.01492139 0.01462701 -0.03007413 -0.0151176 0.01745264 -0.03023493 -0.01435763 0.01964722 -0.03050311 -0.01486972 0.01955054 -0.01499571 -0.01512384 0.01062765 -0.01430759 -0.01481869 0.01063568 -0.01548969 -0.01459356 0.01164291 -0.01641626 -0.01499552 0.01149452 -0.01655689 -0.01447384 0.01194241 -0.01343954 -0.01439645 0.009842682 -0.01441049 -0.01444494 0.01102322 -0.0208602 -0.01451858 0.01198154 -0.02278113 -0.01435873 0.01236536 -0.02321551 -0.01492856 0.01214179 -0.0215468 -0.01508901 0.01145014 -0.02496808 -0.01438469 0.01328294 -0.02517056 -0.01488253 0.01306268 -0.02634019 -0.01511962 0.01315056 -0.0268 -0.01442857 0.01462698 -0.02695712 -0.01212936 0.01473219 -0.02373722 -0.0121295 0.01269385 -0.02113458 -0.01212954 0.01205336 -0.02695715 0.01187044 0.0147322 -0.02373726 0.01187058 0.01269385 -0.02103042 0.01187065 0.01203648 -0.02977258 -0.01212971 0.0187633 -0.03159335 -0.01212952 0.02317833 -0.03177077 0.01187064 0.02351402 -0.02984517 0.01187049 0.0188739 -0.02742574 -0.009768959 0.009121411 -0.0277226 -0.01013492 -0.006976561 -0.0291336 -0.01103621 -0.003839228 -0.02859336 -0.01077661 0.009468283 -0.02949586 -0.01110134 0.008508633 -0.02730955 0.009236922 0.009088191 -0.02783718 0.009979043 -0.006695677 -0.02847214 0.01049695 0.009429553 -0.02932119 0.01083003 -0.00344482 -0.0294779 0.01083219 0.008548203 -0.03580077 -0.008674379 0.01096056 -0.03297675 -0.009469148 0.01070738 -0.03401091 -0.007644261 0.01104538 -0.05004652 -0.00942436 0.01072939 -0.05200584 -0.007630313 0.01103753 -0.04619776 -0.01049501 0.009872441 -0.04224739 -0.0111097 0.008497501 -0.04297963 0.01077248 0.008774231 -0.03943172 0.01088135 0.007108482 -0.04599636 0.01028521 0.009817383 -0.03151979 0.009831389 0.01029126 -0.05034951 0.009078147 0.01077841 -0.03580078 0.008414767 0.01095989 -0.02643303 0.0118705 -0.01031281 -0.02451766 0.01187049 -0.01183537 -0.01305195 0.01187054 -0.008747498 -0.01385546 0.01187054 -0.01056667 -0.01593595 0.01187054 -0.01191777 -0.01305881 0.01187054 0.008813951 -0.01397372 0.01187054 0.01070514 -0.01596518 0.01187054 0.01190898 -0.03395462 0.01187053 0.0249071 -0.05181479 0.01187051 0.02494199 -0.05343434 0.01187051 0.0242138 -0.05485394 0.01187051 0.02233307 -0.05489565 0.01187213 0.01382016 -0.05361578 0.0118705 0.01176119 -0.05489879 -0.01212948 0.01379965 -0.05361575 -0.01212947 0.0117612 -0.05200077 -0.01212948 0.011 -0.05486424 -0.01212949 0.02236816 -0.05330518 -0.01212948 0.02430768 -0.0517483 -0.01212948 0.02494886 -0.03356233 -0.01212947 0.02483041 -0.0159359 -0.01212946 0.01191777 -0.01385547 -0.01212945 0.01056671 -0.01305193 -0.01212945 0.008747512 -0.01625327 -0.01212946 -0.01194885 -0.01443413 -0.01212945 -0.01114534 -0.01310469 -0.01212945 -0.009118102 -0.02700079 -0.01212946 -0.008999998 -0.02624693 -0.01212943 -0.01060776 -0.02418683 -0.01213007 -0.01190135 -0.03402529 0.01087077 0.003064272 -0.03142163 -0.01112961 -0.0001076683 -0.03495619 -0.01112957 0.003865113 -0.03847262 -0.01112947 0.006481341 -0.02700079 -0.01212946 0.009000001 -0.03400079 -0.01212947 0.011 -0.0270008 0.01187053 0.009000001 -0.01300078 -0.01212945 0.003000001 -0.01300078 -0.01212945 -0.003 -0.01806079 -0.01392946 -0.00256986 -0.01708286 -0.01512946 -0.002387919 -0.01658725 -0.01392946 -0.002175479 -0.01563374 -0.01392946 -0.001009429 -0.01544205 -0.01512946 -0.0002731094 -0.01545512 -0.01392946 0.000500421 -0.0157058 -0.01512946 0.001209891 -0.01618157 -0.01392946 0.001819941 -0.01708527 -0.01512946 0.002446321 -0.01773106 -0.01392946 0.002602511 -0.01875829 -0.01512946 0.002473601 -0.01959369 -0.01392946 0.002047791 -0.01996774 -0.01512946 0.00165915 -0.02065062 -0.01392946 0.0001547113 -0.0205797 -0.01512946 0.0002827207 -0.02018487 -0.01512946 -0.00140019 -0.01968148 -0.01392946 -0.00201177 -0.01860953 -0.01512946 -0.002552189 -0.02001395 -0.01392946 0.0001259306 -0.01950871 -0.01392946 0.001397631 -0.01812409 -0.01392946 0.002031061 -0.01682077 -0.01392946 0.00165771 -0.01604128 -0.01392946 0.0005484214 -0.01618932 -0.01392946 -0.0009725792 -0.0173697 -0.01392946 -0.001934458 -0.01872505 -0.01392946 -0.001901539 -0.01975888 -0.01392946 -0.00102443 -0.01703043 -0.01392946 -0.008414794 -0.01649675 -0.01512946 -0.008147057 -0.01583839 -0.01392946 -0.007394866 -0.01552503 -0.01512946 -0.006701674 -0.01540717 -0.01392946 -0.005937022 -0.01553434 -0.01512946 -0.005195342 -0.0163007 -0.01392946 -0.00396154 -0.01687761 -0.01512946 -0.00360531 -0.017936 -0.01392946 -0.003445059 -0.01854181 -0.01512946 -0.003489569 -0.01943227 -0.01392946 -0.003803889 -0.01982968 -0.01512946 -0.004159898 -0.02052658 -0.01392946 -0.005407469 -0.02057971 -0.01512946 -0.005717307 -0.02025566 -0.01392946 -0.007336945 -0.01996523 -0.01512946 -0.007785079 -0.01870001 -0.01392946 -0.008498363 -0.0181782 -0.01512946 -0.008564038 -0.0183 -0.01392946 -0.007995939 -0.01938182 -0.01392946 -0.007494361 -0.01604467 -0.01392946 -0.006560379 -0.0169682 -0.01392946 -0.007777938 -0.02007046 -0.01392946 -0.005941927 -0.01930762 -0.01392946 -0.004440339 -0.01624556 -0.01392946 -0.004880478 -0.01786067 -0.01392946 -0.003948749 -0.02025566 -0.01392946 0.004663051 -0.01926551 -0.01392946 0.00437897 -0.02004506 -0.01392946 0.005873591 -0.02052658 -0.01392946 0.006592582 -0.01870002 -0.01392946 0.003501632 -0.01795838 -0.01392946 0.003982202 -0.01746112 -0.01392946 0.00349577 -0.0168309 -0.01392946 0.00433511 -0.01606212 -0.01392946 0.004235472 -0.01604465 -0.01392946 0.00543962 -0.01539536 -0.01392946 0.006289491 -0.0161268 -0.01392946 0.00679284 -0.01649674 -0.01392946 0.008147053 -0.01704085 -0.01392946 0.00779415 -0.01839428 -0.01392946 0.008563981 -0.01821417 -0.01392946 0.008006943 -0.01944803 -0.01392946 0.007460402 -0.01974191 -0.01392946 0.007894841 -0.01649674 -0.01512946 0.003852962 -0.01545512 -0.01512946 0.005499582 -0.01563376 -0.01512946 0.007009421 -0.01658727 -0.01512946 0.008175491 -0.01806556 -0.01512946 0.008567602 -0.01949237 -0.01512946 0.008122701 -0.02063866 -0.01512946 0.006295291 -0.01978278 -0.01512946 0.004077393 -0.01817815 -0.01512946 0.003435963 -0.02385717 -0.004052585 -0.007199999 -0.02556667 -0.004797066 -0.007199998 -0.02226828 -0.005022343 -0.007199995 -0.0220042 -0.00652192 -0.007199999 -0.02528275 -0.007769767 -0.007200001 -0.02603185 -0.006252754 -0.0072 -0.02257395 -0.007556908 -0.007199998 -0.02362052 -0.008128414 -0.007199999 -0.02362052 -0.004130505 0.007200002 -0.02240078 -0.003579464 0.007200002 -0.02496069 -0.004335295 0.007200002 -0.02595636 -0.005494626 0.007200002 -0.02502187 -0.007870349 0.007200002 -0.02386509 -0.008159733 0.007200002 -0.02140079 -0.008679461 0.007200002 -0.02261976 -0.007623849 0.007200002 -0.02194835 -0.006251026 0.007200011 -0.02583405 -0.0070124 0.007200002 -0.02244915 -0.004813074 0.007199991 -0.02591995 -0.006936244 0.009000001 -0.02479329 -0.007985603 0.009000001 -0.02362052 -0.008128416 0.009000011 -0.02221094 -0.007192718 0.009000001 -0.0220372 -0.005662883 0.009000001 -0.02273605 -0.004508444 0.009000001 -0.02455728 -0.004123375 0.009000001 -0.02583405 -0.005246575 0.009000001 -0.02455465 -0.008135978 -0.006199996 -0.02447772 -0.008130331 0.006200002 -0.02297631 -0.007887544 0.006200002 -0.02289221 -0.007835748 -0.006199995 -0.02209925 -0.006853737 0.006200011 -0.02199841 -0.006596116 -0.006199998 -0.02203721 -0.005662883 0.006200002 -0.02232754 -0.004934643 -0.006199998 -0.02261974 -0.004635085 0.006200011 -0.0237922 -0.004084035 -0.006199995 -0.02386507 -0.004099195 0.006200002 -0.02502186 -0.004388556 0.006200002 -0.02525012 -0.004523355 -0.006199995 -0.02583405 -0.005246546 0.006200002 -0.02591775 -0.005498136 -0.006199995 -0.02591995 -0.006936259 0.006200002 -0.02592111 -0.006864086 -0.006199995 -0.02602347 -0.00635123 -0.008999998 -0.02531898 -0.007707324 -0.009 -0.02404319 -0.008147262 -0.008999998 -0.02258431 -0.007655122 -0.009000002 -0.02196658 -0.006080066 -0.008999998 -0.02244917 -0.004813044 -0.009 -0.02379221 -0.004084035 -0.009 -0.02554152 -0.004729396 -0.009 -0.02000527 -0.01212946 0.006459742 -0.01910938 -0.01212946 0.007706273 -0.01779139 -0.01212946 0.008023992 -0.0164349 -0.01212946 0.0073324 -0.01597288 -0.01212946 0.00552916 -0.01704088 -0.01212946 0.004205832 -0.01872536 -0.01212946 0.004048322 -0.01982161 -0.01212946 0.005129441 -0.02000847 -0.01212946 -0.006205177 -0.01965474 -0.01212946 -0.00473569 -0.01796643 -0.01212946 -0.003944249 -0.01643489 -0.01212946 -0.004667599 -0.015983 -0.01212946 -0.005956718 -0.01636839 -0.01212946 -0.00725003 -0.01786066 -0.01212946 -0.008051253 -0.01944804 -0.01212946 -0.007460372 -0.0130008 0.01187054 -0.003 -0.0130008 0.01187054 0.003000001 -0.02062139 0.01367054 6.748084e-05 -0.02059509 0.01487054 0.0003763512 -0.0198297 0.01367054 0.00184013 -0.01959372 0.01487054 0.00204778 -0.01804458 0.01367054 0.002621091 -0.01816512 0.01487054 0.002568021 -0.01669464 0.01487054 0.002241581 -0.01589201 0.01367054 0.001612022 -0.01557633 0.01487054 0.0009234203 -0.01545515 0.01367054 -0.0005004387 -0.01558508 0.01487053 -0.001017929 -0.01633458 0.01367054 -0.001988589 -0.01697532 0.01487054 -0.002383078 -0.01795366 0.01367054 -0.002593939 -0.01870008 0.01487054 -0.002498358 -0.0197828 0.01367054 -0.001922609 -0.02011436 0.01487054 -0.001504549 -0.01983945 0.01367054 0.00087173 -0.01993489 0.01367054 -0.0007933583 -0.01863194 0.01367054 -0.001934449 -0.017106 0.01367054 -0.00185111 -0.0161796 0.01367054 -0.0008697789 -0.01598935 0.01367054 0.0003074007 -0.01651471 0.01367054 0.00136559 -0.01753604 0.01367054 0.001981012 -0.01888374 0.01367054 0.001833261 -0.02065064 0.01367054 -0.006154706 -0.02057973 0.01487054 -0.006282691 -0.0201849 0.01487054 -0.004599849 -0.01982968 0.01367054 -0.004159879 -0.01861886 0.01487054 -0.003452459 -0.01826776 0.01367054 -0.003419399 -0.0164968 0.01487053 -0.003852929 -0.01679332 0.01367054 -0.003727629 -0.01570582 0.01367054 -0.004790099 -0.01545515 0.01487054 -0.00549958 -0.01545515 0.01367054 -0.006500411 -0.01570582 0.01487054 -0.007209868 -0.01649678 0.01367054 -0.008147063 -0.01716892 0.01487054 -0.008485949 -0.0181651 0.01367054 -0.008568013 -0.01952191 0.01487054 -0.008175288 -0.01959372 0.01367054 -0.008047782 -0.02000189 0.01367054 -0.006377676 -0.01942763 0.01367054 -0.007427444 -0.01604522 0.01367054 -0.006634825 -0.01838107 0.01367054 -0.007998953 -0.01704085 0.01367054 -0.007794144 -0.01616751 0.01367054 -0.00511714 -0.01712907 0.01367054 -0.004161379 -0.01865323 0.01367054 -0.004050239 -0.01980079 0.01367054 -0.005051039 -0.02057973 0.01367054 0.006282722 -0.01996412 0.01367054 0.005284921 -0.02008209 0.01367054 0.004406202 -0.01855202 0.01367054 0.004019241 -0.01839269 0.01367054 0.0034354 -0.01543271 0.01367054 0.006163181 -0.01601979 0.01367054 0.00553522 -0.01611267 0.01367054 0.006712972 -0.01594331 0.01367054 0.007580361 -0.01696822 0.01367054 0.007777941 -0.017601 0.01367054 0.008590781 -0.01687809 0.01367054 0.004277551 -0.01689184 0.01367054 0.003677982 -0.01576727 0.01367054 0.004680081 -0.01847768 0.01367054 0.007978131 -0.01968149 0.01367054 0.008011772 -0.01973332 0.01367054 0.0071071 -0.02057973 0.01487054 0.005717291 -0.01996527 0.01487054 0.007785081 -0.01795365 0.01487054 0.008593942 -0.01615554 0.01487054 0.007861982 -0.01544206 0.01487054 0.006273121 -0.01570582 0.01487054 0.004790151 -0.01697531 0.01487054 0.003616911 -0.0184889 0.01487054 0.00347346 -0.01982972 0.01487054 0.00415993 -0.0340008 0.01185148 0.01707449 -0.0214008 0.01187054 0.009000001 -0.0340008 0.01187053 0.023 -0.02269393 0.004310876 -0.0072 -0.02396382 0.003836077 -0.007199999 -0.02576934 0.006919114 -0.007199998 -0.024713 0.007758945 -0.007200001 -0.02352395 0.007848676 -0.0072 -0.02226828 0.006977648 -0.007199997 -0.02554155 0.004470484 -0.007199997 -0.0260024 0.005730545 -0.007199998 -0.02200421 0.005478097 -0.007199999 -0.02319651 0.004001435 0.007200002 -0.02488829 0.003987344 0.007200002 -0.0214008 0.00842054 0.007200002 -0.02224903 0.006905798 0.007200011 -0.02601764 0.005470995 0.007200002 -0.02313103 0.007691747 0.007200011 -0.02571382 0.006968666 0.007200002 -0.02202014 0.005229397 0.007200011 -0.02448555 0.007868605 0.007200002 -0.02603186 0.005747246 0.009000001 -0.02550357 0.004498655 0.009000001 -0.02446827 0.003907174 0.009000001 -0.02328821 0.003964597 0.008999991 -0.02224904 0.004835278 0.009000001 -0.02198661 0.005998537 0.009000001 -0.02238706 0.007110028 0.009000001 -0.02336859 0.007787217 0.009000001 -0.02454923 0.007830033 0.009000001 -0.02565848 0.007050605 0.009000001 -0.02414688 0.007913394 -0.006199996 -0.02421817 0.007931005 0.006200002 -0.02550356 0.007242465 -0.006199994 -0.02554354 0.007171856 0.006200002 -0.02602348 0.006092306 0.006200002 -0.02603186 0.005993835 -0.006199996 -0.02554155 0.004470496 0.006200002 -0.0255667 0.004538166 -0.006199992 -0.0242102 0.003846543 -0.006199995 -0.02379221 0.003825117 0.006200002 -0.02289223 0.004164256 -0.006199997 -0.02232757 0.004675746 0.006200002 -0.02214429 0.005078835 -0.006199992 -0.0219875 0.006165626 0.006200002 -0.0220042 0.006262995 -0.006199995 -0.02261975 0.007364897 0.006200002 -0.02269392 0.007430186 -0.006199995 -0.02587477 0.006663395 -0.009000001 -0.02595691 0.005310144 -0.008999998 -0.0248883 0.003987344 -0.008999998 -0.02302821 0.004059087 -0.009 -0.02206634 0.005239446 -0.008999996 -0.02214971 0.006765386 -0.008999998 -0.02313103 0.007691747 -0.008999998 -0.0246631 0.007844215 -0.009 -0.02003721 0.01187054 0.006234271 -0.01961453 0.01187054 0.004760533 -0.01831436 0.01187054 0.00396802 -0.01683095 0.01187054 0.004335142 -0.01611269 0.01187054 0.005287052 -0.01601979 0.01187054 0.006464782 -0.01663527 0.01187054 0.007486162 -0.01786069 0.01187054 0.008051262 -0.0193077 0.01187054 0.00755963 -0.01998738 0.01187054 -0.005453604 -0.01980078 0.01187054 -0.006948973 -0.01880509 0.01187054 -0.007869095 -0.01745236 0.01187054 -0.0079595 -0.01612722 0.01187054 -0.006907614 -0.01612681 0.01187054 -0.005207152 -0.01733848 0.01187054 -0.00402632 -0.0190253 0.01187054 -0.00424193 -0.02140079 -0.01212946 0.009000001 -0.04600078 -0.01062948 0.025 -0.04359337 -0.01392948 0.01747422 -0.04306825 -0.01512948 0.01737942 -0.041875 -0.01392948 0.0176626 -0.04142749 -0.01512947 0.01796368 -0.040544 -0.01392947 0.01908552 -0.0405393 -0.01512947 0.01918036 -0.04057071 -0.01512947 0.02090858 -0.0406177 -0.01392947 0.0210255 -0.04185986 -0.01512947 0.02236015 -0.04179086 -0.01392948 0.02229495 -0.04372639 -0.01392948 0.02251903 -0.04380539 -0.01512948 0.02246646 -0.04503638 -0.01512948 0.02157416 -0.04537109 -0.01392948 0.02111954 -0.04558938 -0.01512948 0.02017296 -0.04553314 -0.01392948 0.01963669 -0.04501254 -0.01512948 0.0183193 -0.04504855 -0.01392948 0.0184071 -0.04168437 -0.01392948 0.02155162 -0.04295135 -0.01392948 0.02203419 -0.04438477 -0.01392948 0.02152045 -0.04505318 -0.01392947 0.01996532 -0.04454405 -0.01392948 0.0186994 -0.04356113 -0.01392948 0.01804388 -0.04188124 -0.01392948 0.01824481 -0.04091919 -0.01392947 0.02003304 -0.03780586 -0.01392947 0.01755591 -0.03684361 -0.01512947 0.0174104 -0.0362863 -0.01392947 0.01750595 -0.03507815 -0.01512947 0.01821799 -0.03487808 -0.01392947 0.01850833 -0.03443275 -0.01512947 0.0198357 -0.03441219 -0.01392947 0.020173 -0.03485371 -0.01512947 0.02150402 -0.03496513 -0.01392947 0.02157414 -0.03619619 -0.01392947 0.02246644 -0.03629913 -0.01512947 0.02247575 -0.03801872 -0.01512947 0.02241574 -0.03792416 -0.01392947 0.02242445 -0.03948916 -0.01392947 0.02092386 -0.03948672 -0.01512947 0.02083188 -0.03934505 -0.01512947 0.01888862 -0.03919689 -0.01392947 0.01856855 -0.03830361 -0.01512947 0.01778092 -0.03550641 -0.01392947 0.01861905 -0.03492949 -0.01392947 0.02020946 -0.03582073 -0.01392947 0.02165768 -0.03712402 -0.01392947 0.02203106 -0.03850874 -0.01392947 0.02139767 -0.03903524 -0.01392947 0.01996308 -0.03835123 -0.01392947 0.01841558 -0.03670796 -0.01392947 0.01798773 -0.03400079 -0.01212947 0.0166 -0.03400079 -0.01212947 0.023 -0.03400078 -0.01211983 0.01708132 -0.04805188 -0.01392948 0.01819998 -0.04766377 -0.01392948 0.01774513 -0.04713168 -0.01392948 0.01919568 -0.04650242 -0.01392948 0.01930081 -0.04701915 -0.01392948 0.02038275 -0.04655708 -0.01392948 0.02080615 -0.04755756 -0.01392948 0.02143441 -0.04742044 -0.01392948 0.02205749 -0.04861716 -0.01392948 0.02198146 -0.04860662 -0.01392948 0.02252774 -0.05014173 -0.01392948 0.02236015 -0.04979367 -0.01392948 0.02187399 -0.05097445 -0.01392948 0.02066232 -0.05132291 -0.01392948 0.02110883 -0.05156539 -0.01392948 0.01960805 -0.05068473 -0.01392948 0.01882037 -0.05089557 -0.01392948 0.01825891 -0.04959336 -0.01392948 0.01747421 -0.04937845 -0.01392948 0.0179989 -0.04993744 -0.01512948 0.0175516 -0.04757339 -0.01512948 0.0177621 -0.04643618 -0.01512948 0.01960806 -0.04661276 -0.01512948 0.02091772 -0.0473224 -0.01512948 0.02197834 -0.04872764 -0.01512948 0.02255874 -0.05001025 -0.01512948 0.022367 -0.0511763 -0.01512948 0.02141345 -0.05155854 -0.01512948 0.01929049 -0.05200077 -0.01211043 0.01707449 -0.05200077 -0.01212948 0.023 -0.03580077 -0.004551624 0.0126818 -0.03580078 -0.006250831 0.01192169 -0.03580078 -0.005462744 0.01655045 -0.03580079 -0.0074799 0.01558444 -0.03580078 -0.008679471 0.0166 -0.03580077 -0.008163939 0.01403697 -0.03580077 -0.007735568 0.01275067 -0.03580077 -0.004099204 0.01413572 -0.03580077 -0.004635074 0.01538098 -0.03580077 -0.005834347 0.01601328 -0.03625078 -0.008679472 0.01655 -0.05020078 -0.004335345 0.01304007 -0.05020077 -0.005336605 0.01212604 -0.05020078 -0.006689893 0.0120439 -0.05020076 -0.005234664 0.01585111 -0.05020078 -0.004148725 0.01455125 -0.0502008 -0.007907432 0.01296742 -0.05020078 -0.008039888 0.01482731 -0.05020079 -0.006760587 0.01593447 -0.04000077 -0.01512947 0.023275 -0.04600077 -0.01512948 0.023275 -0.04498805 -0.009829478 0.02053822 -0.04374622 -0.009829476 0.02194382 -0.04173643 -0.009829475 0.02165393 -0.04097051 -0.009829476 0.02013566 -0.04125993 -0.009829474 0.0189787 -0.04242281 -0.009829476 0.01799999 -0.04409892 -0.009829477 0.01828696 -0.04485696 -0.009829478 0.01920764 -0.04600079 0.01037052 0.025 -0.04219137 0.01367052 0.01750664 -0.04293333 0.01487052 0.01737942 -0.04433778 0.01367052 0.01774512 -0.04457408 0.01487052 0.01796371 -0.04554835 0.01487052 0.01938197 -0.04549917 0.01367052 0.01930081 -0.04531042 0.01367052 0.02124002 -0.04514789 0.01487052 0.02150394 -0.04380538 0.01367052 0.02246646 -0.04350117 0.01487052 0.02254566 -0.04229912 0.01367052 0.02247574 -0.04199142 0.01487052 0.02236703 -0.04101222 0.01367052 0.02166627 -0.04082524 0.01487052 0.02141345 -0.04040686 0.01367052 0.02004712 -0.04042021 0.01487052 0.01973305 -0.04083908 0.01367052 0.01860419 -0.04116076 0.01487052 0.01817111 -0.04446115 0.01367052 0.02144729 -0.04321509 0.01367052 0.02200683 -0.04205182 0.01367052 0.02179996 -0.04113171 0.01367052 0.02080434 -0.04101917 0.01367052 0.01961728 -0.04155761 0.01367052 0.01856555 -0.04277908 0.01367052 0.01797732 -0.0439471 0.01367052 0.01821735 -0.04479494 0.01367052 0.01904008 -0.04500766 0.01367051 0.02021249 -0.03684363 0.01367053 0.0174104 -0.03649142 0.01487051 0.01742852 -0.03878585 0.01487053 0.01803553 -0.03850534 0.01367053 0.01788645 -0.0394085 0.01367052 0.01909192 -0.03959474 0.01487052 0.0200471 -0.03954563 0.01367052 0.02038147 -0.03898938 0.01487052 0.02166626 -0.0387654 0.01367053 0.0219386 -0.03770242 0.01487053 0.02247575 -0.03693781 0.01367053 0.02259362 -0.0361962 0.01487053 0.02246646 -0.03513877 0.01367053 0.02184522 -0.03482526 0.01487053 0.02141345 -0.03440687 0.01367053 0.02004714 -0.03442021 0.01487053 0.01973304 -0.03507814 0.01367053 0.01821799 -0.03503316 0.01487053 0.0183418 -0.03859739 0.01367053 0.01876541 -0.03905654 0.01367052 0.02003439 -0.03821205 0.01367053 0.02169319 -0.03653603 0.01367053 0.02198101 -0.03527838 0.01367053 0.02112271 -0.03499388 0.01367053 0.0197866 -0.03544113 0.01367053 0.01869314 -0.03759701 0.01367053 0.01804898 -0.03645736 0.01367053 0.0180544 -0.05049515 0.01367052 0.01861893 -0.05030364 0.01367052 0.01778092 -0.05145758 0.01367052 0.01908555 -0.05103107 0.01367052 0.0198643 -0.05131041 0.01367052 0.02124002 -0.05048076 0.01367052 0.02146419 -0.04980541 0.01367052 0.02246643 -0.04887754 0.01367052 0.02203106 -0.0478599 0.01367052 0.02236015 -0.04749287 0.01367052 0.02139764 -0.04667877 0.01367052 0.02110898 -0.04696632 0.01367052 0.01996305 -0.04643622 0.01367052 0.01960811 -0.04765036 0.01367052 0.0184156 -0.04725168 0.01367052 0.01808389 -0.04929362 0.01367052 0.01798773 -0.04884361 0.01367052 0.0174104 -0.04959342 0.01487052 0.01747422 -0.05104858 0.01487052 0.01840707 -0.05160874 0.01487051 0.02026591 -0.05067916 0.01487052 0.02197833 -0.0490638 0.01487052 0.02259361 -0.04742042 0.01487052 0.02205746 -0.04647869 0.01487052 0.02060806 -0.04665655 0.01487052 0.01888855 -0.04787509 0.01487052 0.01766258 -0.05200079 0.01185145 0.01707449 -0.05200079 0.01187051 0.023 -0.03580076 0.004704727 0.01564748 -0.03580079 0.003964588 0.01471262 -0.03580079 0.006092247 0.01197732 -0.03580079 0.007448386 0.0126818 -0.03580079 0.007576807 0.01510855 -0.03580079 0.006167728 0.01606053 -0.03580079 0.008420528 0.0166 -0.03580078 0.005035747 0.01651151 -0.03580078 0.003939947 0.01335712 -0.03580079 0.004772367 0.01228699 -0.03580078 0.007888327 0.01395758 -0.03625079 0.008420528 0.01655 -0.05020079 0.007776467 0.0147126 -0.05020077 0.007757926 0.01318454 -0.0502008 0.006663386 0.01212603 -0.05020079 0.005310126 0.01204389 -0.05020077 0.004092565 0.01296745 -0.05020078 0.003892385 0.01447686 -0.05020077 0.006905686 0.0157518 -0.05020079 0.004631085 0.01561376 -0.05020079 0.005742476 0.01601418 -0.0460008 0.01487052 0.023275 -0.0147258 0.01487054 -0.003 -0.0147258 0.01487054 0.003000001 -0.0400008 0.01487052 0.023275 -0.0460008 0.01487052 0.013 -0.03400079 -0.01062947 0.01484966 -0.03400075 -0.008474642 0.01158444 -0.05483303 0.007249612 0.01104367 -0.05482965 -0.007373266 0.01103211 -0.03122481 0.007096801 0.01101844 -0.03119715 -0.007516724 0.0110415 -0.04501683 0.00957052 0.01996057 -0.04457866 0.00957052 0.01868181 -0.04305372 0.009570522 0.01794465 -0.0417668 0.009570522 0.01840295 -0.04107022 0.009570524 0.01935718 -0.04109486 0.009570524 0.02071265 -0.042106 0.009570522 0.02185112 -0.04346737 0.009570522 0.02196358 -0.04462181 0.00957052 0.02126468 -0.05200077 -0.01062948 0.01484966 -0.05200083 -0.00849321 0.0116005 -0.02057231 -0.01212946 0.006399022 -0.01995037 -0.01212946 0.004366451 -0.01849139 -0.01212946 0.003504272 -0.01642036 -0.01212946 0.003932592 -0.01543109 -0.01212946 0.006042942 -0.01607168 -0.01212946 0.00762575 -0.01750136 -0.01212946 0.008521051 -0.01937352 -0.01212946 0.00814128 -0.02049947 -0.01212946 -0.006475317 -0.01978508 -0.01212946 -0.007783463 -0.01849139 -0.01212946 -0.008495733 -0.01642035 -0.01212946 -0.00806742 -0.01546294 -0.01212946 -0.006169631 -0.01591969 -0.01212946 -0.004537659 -0.01730032 -0.01212946 -0.003554859 -0.01899184 -0.01212946 -0.003657529 -0.02024345 -0.01212946 -0.004800089 -0.02057048 0.01187054 -0.005957073 -0.01966628 0.01187054 -0.00404265 -0.01805489 0.01187054 -0.003477769 -0.01625071 0.01187054 -0.004074069 -0.01545772 0.01187054 -0.006046242 -0.01605118 0.01187054 -0.007633544 -0.01771698 0.01187054 -0.008554325 -0.01973078 0.01187054 -0.007900603 -0.02040937 0.01187054 0.00689659 -0.01910445 0.01187054 0.008291581 -0.01741985 0.01187054 0.008476272 -0.01570908 0.01187054 0.007232911 -0.01561837 0.01187054 0.005109241 -0.01688227 0.01187054 0.003686131 -0.01878966 0.01187054 0.003581931 -0.0202651 0.01187054 0.004784252 -0.01727653 -0.009829457 -0.001901539 -0.01604912 -0.009829458 -0.0007246295 -0.01959735 -0.009829459 -0.001234599 -0.01933317 -0.009829458 0.001565921 -0.01614464 -0.009829456 0.000792482 -0.01690265 -0.009829456 0.001713051 -0.01804406 -0.009829458 0.002017782 -0.0200532 -0.009829474 3.465079e-05 -0.0186319 -0.009829458 -0.001934458 -0.01611236 0.009570542 0.0007121311 -0.01605104 0.009570542 -0.0006524995 -0.0199782 0.009570539 0.0006561717 -0.01690679 0.00957054 -0.001695999 -0.01805022 0.00957054 -0.002034189 -0.01847168 0.00957054 0.002027891 -0.01682078 0.00957054 0.00165771 -0.01959958 0.009570539 -0.001333399 -0.01680596 -0.009929458 0.004326782 -0.01591921 -0.009929458 0.005966971 -0.01992765 -0.009929458 0.006717271 -0.01864191 -0.009929458 0.004019341 -0.01675076 -0.009929457 0.007632402 -0.01857874 -0.00992946 0.008000011 -0.01986987 -0.00992946 0.005195682 -0.01795751 -0.01132946 0.008017781 -0.0166684 -0.01132946 0.007565902 -0.01597678 -0.01132946 0.006209412 -0.01647514 -0.01132946 0.004583522 -0.01840704 -0.01132946 0.003958181 -0.01975886 -0.01132946 0.004975532 -0.02001223 -0.01132946 0.006307381 -0.01925082 -0.01132946 0.00763239 -0.0202651 -0.01132946 0.004784242 -0.01878965 -0.01132946 0.003581931 -0.01688222 -0.01132946 0.003686142 -0.01561837 -0.01132945 0.005109192 -0.01564153 -0.01132945 0.007019342 -0.01700964 -0.01132946 0.008342441 -0.01870126 -0.01132946 0.008445131 -0.02035476 -0.01132946 0.007109421 -0.01660076 -0.009929457 -0.004459219 -0.01995055 -0.00992946 -0.006652472 -0.01894974 -0.009929459 -0.007799977 -0.01596632 -0.009929456 -0.00603695 -0.01644113 -0.009929456 -0.007306884 -0.01760829 -0.009929458 -0.007996587 -0.01857874 -0.00992946 -0.00399999 -0.01983944 -0.00992946 -0.00512831 -0.01812408 -0.01132946 -0.003968939 -0.0166684 -0.01132946 -0.004434109 -0.01601916 -0.01132946 -0.005617171 -0.01613168 -0.01132946 -0.006804289 -0.01690675 -0.01132946 -0.007696013 -0.01805019 -0.01132946 -0.008034199 -0.01931712 -0.01132946 -0.007551642 -0.02004621 -0.01132946 -0.006208553 -0.01950874 -0.01132946 -0.00460237 -0.01985075 -0.01132946 -0.004169819 -0.02054075 -0.01132946 -0.006391955 -0.01938463 -0.01132946 -0.00816566 -0.01706894 -0.01132946 -0.008429749 -0.01561837 -0.01132945 -0.006890762 -0.01558758 -0.01132945 -0.005196342 -0.01662806 -0.01132946 -0.003858739 -0.01805488 -0.01132946 -0.003477769 -0.01956045 0.009670539 -0.007306853 -0.01596881 0.009670543 -0.006313551 -0.01676133 0.009670543 -0.007613708 -0.02005802 0.009670539 -0.005680758 -0.01909896 0.009670541 -0.004286969 -0.01777902 0.009670541 -0.003977319 -0.01642295 0.009670543 -0.004681779 -0.01822784 0.009670541 -0.008043459 -0.01873543 0.01107054 -0.00407969 -0.01688127 0.01107054 -0.00424479 -0.01598936 0.01107054 -0.005692572 -0.0162427 0.01107054 -0.007024459 -0.01713024 0.01107054 -0.007820838 -0.01864193 0.01107054 -0.007980663 -0.01995057 0.01107054 -0.006652464 -0.01983947 0.01107054 -0.005128355 -0.01836976 0.01107054 -0.003456579 -0.01633529 0.01107054 -0.00404265 -0.0154708 0.01107054 -0.005738306 -0.01597452 0.01107054 -0.007580902 -0.01741759 0.01107054 -0.008454467 -0.01911932 0.01107054 -0.008313874 -0.02038322 0.01107054 -0.006890791 -0.02029249 0.01107054 -0.004767059 -0.01777902 0.009670541 0.008022682 -0.01655755 0.009670543 0.007434391 -0.01894707 0.009670541 0.00778267 -0.01597679 0.009670543 0.006209403 -0.01629452 0.009670543 0.004891361 -0.01979497 0.009670539 0.006959901 -0.01770362 0.009670541 0.003939481 -0.01931715 0.009670539 0.00444834 -0.01999973 0.009670539 0.005619691 -0.01787749 0.01107054 0.00803106 -0.01649285 0.01107054 0.007397632 -0.01598667 0.01107054 0.006128931 -0.01624273 0.01107054 0.004975501 -0.01713027 0.01107054 0.004179151 -0.01846748 0.01107054 0.003997642 -0.01970706 0.01107054 0.004891361 -0.02001859 0.01107054 0.00604242 -0.01948075 0.01107054 0.007464212 -0.02025222 0.01107054 0.004694971 -0.02029251 0.01107054 0.007232911 -0.01836976 0.01107054 0.008543422 -0.01672348 0.01107054 0.008175562 -0.01559221 0.01107054 0.006896581 -0.01560497 0.01107054 0.005209751 -0.01645144 0.01107054 0.003982871 -0.01828462 0.01107054 0.003445682 -0.03400079 0.005203808 0.01655044 -0.03400079 0.003820626 0.01565871 -0.03400079 0.003234906 0.01564918 -0.03400078 -0.005294662 0.0165115 -0.05500077 -0.008404686 0.01519523 -0.05500921 -0.008604335 0.01350582 -0.05492769 -0.01057712 0.01487896 -0.05499506 -0.00829912 0.01171729 -0.05500325 -0.007777865 0.012028 -0.05499358 -0.007509142 0.01124057 -0.05500081 -0.005737568 0.01146002 -0.05500079 -0.003129489 0.0114 -0.05500079 -0.004112339 0.01245063 -0.05500079 -0.003586728 0.01406178 -0.05500081 -0.004320438 0.01582552 -0.0550008 -0.006528505 0.01657154 -0.05500082 -0.004743758 0.03586716 -0.05500079 0.002870511 0.026 -0.05500079 0.003471572 0.0150085 -0.05500079 0.002870511 0.0114 -0.05500079 0.003659863 0.01268922 -0.0550008 0.005185023 0.01155062 -0.05500079 0.007086253 0.01173569 -0.0549924 0.007309122 0.01122632 -0.0550008 0.005066883 0.01641321 -0.05496957 0.01029169 0.01488423 -0.0550008 0.007175552 0.01625143 -0.0550008 0.008191113 0.01301039 -0.0550008 0.008366262 0.01449055 -0.05499844 0.007314892 0.04671423 -0.0550008 0.006350942 0.04055758 -0.05500082 0.004123392 0.03988487 -0.05500021 0.008034372 0.04628468 -0.05500085 0.007930003 0.03945697 -0.0550008 0.008426422 0.03784063 -0.05500079 0.003375422 0.03837293 -0.05500079 -0.005086528 0.0467 -0.05500079 -0.004189958 0.03964548 -0.05500081 -0.005442678 0.0404275 -0.0549635 -0.01055672 0.04311037 -0.05500081 -0.008525661 0.03878924 -0.05500079 -0.008471454 0.03686546 -0.05500079 -0.007362413 0.0402917 -0.05499369 -0.00738225 0.04676617 -0.05498144 -0.008439013 0.04621338 -0.05500078 -0.002606298 0.03752045 -0.05500079 -0.003564528 0.03761641 -0.05500078 -0.00660605 0.03547453 -0.05500079 -0.001329399 0.04024267 -0.05500076 -0.002471968 0.03899105 -0.05500079 0.002415731 0.03829614 -0.05500079 0.001504073 0.03994958 -0.05500079 0.0001372509 0.04050867 -0.05500079 -0.001922508 0.03619595 -0.05500079 -0.0003912179 0.03546999 -0.05500079 0.001641093 0.03609289 -0.05500083 0.007596774 0.036132 -0.05500079 0.003578931 0.03689639 -0.05500073 0.004594192 0.03582385 -0.05500082 0.006040132 0.03546216 -0.05500076 -0.001620718 0.01186736 -0.05500079 -0.002606298 0.01352043 -0.05500081 0.0004665628 0.01152733 -0.05500079 0.001810072 0.01564545 -0.05500079 0.0005573816 0.01642751 -0.05500081 -0.002404688 0.01519523 -0.05500079 0.001887651 0.01245062 -0.05500079 -0.0009331079 0.01641322 -0.05500079 0.002413273 0.01406177 -0.05420079 0.003528062 0.01300891 -0.05420079 0.003470121 0.0149183 -0.05420079 0.005174901 0.01650761 -0.05420079 0.007451434 0.01602632 -0.05420079 0.008471903 0.01393084 -0.05420081 0.007504093 0.01205043 -0.0542008 0.006137203 0.01149133 -0.05420082 0.004670612 0.01175734 -0.05420079 -0.002657847 0.01427717 -0.05420079 -0.001777238 0.01597231 -0.05420079 -0.000182528 0.01652225 -0.05420081 0.001256242 0.01613287 -0.05420079 0.002373481 0.01458332 -0.05420081 0.002146542 0.01291177 -0.05420079 0.0007762834 0.01156042 -0.05420076 -0.001329347 0.01175731 -0.0542008 -0.002357788 0.01281711 -0.05420078 -0.008629504 0.01472243 -0.05420078 -0.007026033 0.01640859 -0.05420078 -0.005124059 0.01633635 -0.05420079 -0.003653648 0.01480141 -0.05420079 -0.003939758 0.01270598 -0.05420079 -0.005440438 0.01152405 -0.05420079 -0.007120134 0.01167981 -0.0542008 -0.008270754 0.0126273 -0.0542008 0.008307652 0.03707881 -0.05420079 0.006761242 0.03561754 -0.05420079 0.005066883 0.03558677 -0.05420079 0.003729234 0.03662729 -0.05420079 0.003342163 0.03827717 -0.05420079 0.004222741 0.03997231 -0.05420079 0.006486192 0.04052842 -0.05420082 0.008120481 0.03918622 -0.05420081 0.002365602 0.0375079 -0.05420079 0.001175543 0.03574859 -0.05420079 -0.001148808 0.03564075 -0.05420079 -0.002664368 0.03741145 -0.05420076 -0.002201618 0.03947503 -0.05420074 -0.001019757 0.04036049 -0.05420079 0.0004665628 0.04047268 -0.05420079 0.002036143 0.03938386 -0.05420079 -0.003652078 0.03879909 -0.05420079 -0.004037939 0.03650649 -0.05420079 -0.005868769 0.03544321 -0.05420076 -0.007691118 0.03599237 -0.05420079 -0.008727366 0.0378483 -0.0542008 -0.007922565 0.03980397 -0.05420079 -0.006608019 0.04047701 -0.05420079 -0.005124167 0.04033638 -0.05485548 -0.008298357 0.04658496 -0.05484657 -0.007349719 0.04696469 -0.05487799 0.007326612 0.0469295 -0.05491931 0.01032385 0.04312079 -0.05486528 0.008173171 0.04643152 -0.05485583 0.008171492 0.01156003 -0.05498375 0.008112503 0.01175781 -0.05485689 -0.008567522 0.01173706 -0.0542008 0.007639052 0.01504858 -0.05420081 0.006418932 0.01595951 -0.0542008 0.005486183 0.01195394 -0.05420075 0.006965272 0.01230446 -0.05420079 0.005066233 0.01586911 -0.05420079 0.004070541 0.01494895 -0.05420079 0.003926722 0.01325451 -0.0542008 0.007826103 0.01336519 -0.0542008 -0.001267748 0.01574312 -0.05420081 0.0004189722 0.0159595 -0.05420079 -0.002181918 0.01412156 -0.05420077 -0.001462909 0.01240123 -0.05420079 -6.482005e-07 0.01198587 -0.05420079 0.001268173 0.01249207 -0.05420079 0.001901582 0.0138767 -0.05420079 0.001528192 0.01518005 -0.05420079 -0.004296218 0.01488292 -0.05420076 -0.005257797 0.01583862 -0.05420076 -0.004880208 0.01239386 -0.05420079 -0.006338068 0.01195458 -0.05420079 -0.006428729 0.01599595 -0.05420078 -0.00751053 0.01549433 -0.0542008 -0.008181924 0.01412157 -0.05420075 -0.007681124 0.01268366 -0.05420079 -0.004148478 0.01353522 -0.05420079 0.005227582 0.03993057 -0.05420081 0.006914552 0.03980113 -0.05420079 0.007867102 0.03839247 -0.05420079 0.007670492 0.03705105 -0.05420079 0.006674852 0.0361309 -0.05420079 0.005487652 0.03601839 -0.05420076 0.004436051 0.03655682 -0.05420079 0.003815163 0.03794708 -0.05420079 0.004273372 0.0392339 -0.05420079 0.001804972 0.03736891 -0.05420081 0.001105143 0.03640342 -0.05420079 6.241724e-06 0.03596972 -0.05420079 -0.001150558 0.03625906 -0.05420079 -0.002129508 0.03742208 -0.05420079 -0.001670238 0.03940005 -0.05420079 -0.000258348 0.04001412 -0.05420082 0.0008950326 0.03975809 -0.05420081 0.001772052 0.03872427 -0.05420079 -0.005404869 0.03995166 -0.05420079 -0.004087658 0.03840625 -0.05420077 -0.004515798 0.03676048 -0.05420079 -0.005497328 0.03608328 -0.0542008 -0.006846758 0.03607313 -0.05420078 -0.008129493 0.03742204 -0.05420078 -0.007842532 0.03909811 -0.05420078 -0.006922046 0.03985614 -0.0311749 -0.008399627 0.04649124 -0.03105908 -0.0105695 0.04311666 -0.03112976 0.007068209 0.04695695 -0.03116508 -0.007471953 0.04695589 -0.03104726 0.01030235 0.04311275 -0.03119173 0.008209811 0.04640857 -0.05280078 0.007826645 0.01343961 -0.05280078 0.007787464 0.01463144 -0.05280078 0.007119823 0.01560611 -0.05280078 0.005833525 0.01603446 -0.05280078 0.004286096 0.01535044 -0.05280078 0.003889855 0.01335885 -0.05280078 0.005378014 0.01197725 -0.05280082 0.007040363 0.01233511 -0.05280077 0.001790835 0.01326537 -0.05280079 0.001625743 0.0151195 -0.0528008 0.0003379639 0.01596338 -0.05280077 -0.0008420758 0.01590596 -0.05280082 -0.001881236 0.01503526 -0.05280078 -0.002131846 0.01353331 -0.0528008 -0.001238146 0.01229373 -0.05280077 0.0004270039 0.01199391 -0.05280078 -0.004074137 0.01394707 -0.05280078 -0.004847517 0.01564031 -0.05280076 -0.006680733 0.01598076 -0.05280076 -0.007980571 0.01489485 -0.05280079 -0.008063943 0.0133689 -0.05280078 -0.007102081 0.01218855 -0.05280077 -0.005746706 0.01201838 -0.05280074 -0.004695097 0.01255676 -0.05200079 0.003839454 0.03787673 -0.05200077 0.004212834 0.03918002 -0.05200078 0.005322084 0.0399595 -0.05200078 0.006674795 0.03986908 -0.05200079 0.007566454 0.03909412 -0.05200079 0.007904714 0.03795057 -0.05200079 0.007518064 0.03683427 -0.05200079 0.006421784 0.03601925 -0.05200077 0.004588563 0.03635968 -0.05200078 -0.001949636 0.03704379 -0.05200078 -0.002003056 0.03890764 -0.05200079 -0.0003389362 0.04007127 -0.05200079 0.001391035 0.03938391 -0.05200079 0.001904724 0.03795058 -0.05200077 0.001518024 0.03683426 -0.05200079 0.000421783 0.03601925 -0.05200078 -0.0009219255 0.03614383 -0.05200079 -0.007949639 0.03704382 -0.05200078 -0.008049795 0.03873462 -0.05200076 -0.007001175 0.03983861 -0.05200077 -0.005477016 0.03994975 -0.05200077 -0.004148826 0.03864113 -0.05200078 -0.004377676 0.03696481 -0.05200078 -0.005416856 0.03609406 -0.05200078 -0.006772384 0.03606944 -0.05200077 -0.01062948 0.0232 -0.05200077 -0.01132948 0.0233 -0.05200077 -0.01062948 0.0349 -0.05200077 -0.01132948 0.0347 -0.04600078 -0.01132948 0.0347 -0.04600078 -0.01062948 0.0348 -0.04475601 -0.01062948 0.03688051 -0.04503184 -0.009829476 0.03812328 -0.04492111 -0.01062948 0.03873462 -0.04459785 -0.009829476 0.03923413 -0.04355725 -0.01062948 0.0400061 -0.04364378 -0.009829476 0.03993056 -0.04245127 -0.009829476 0.03994201 -0.04189216 -0.01062947 0.03970627 -0.04121095 -0.009829474 0.03906328 -0.04094026 -0.01062947 0.03829715 -0.04106632 -0.009829474 0.0373689 -0.04166739 -0.01062947 0.03640121 -0.04217347 -0.009829475 0.03608961 -0.04330819 -0.01062948 0.03598855 -0.04387252 -0.009829476 0.03616139 -0.04474125 -0.009829476 0.03697813 -0.04000078 -0.01212947 0.035 -0.04000078 -0.01062947 0.035 -0.03400079 -0.01212947 0.035 -0.03400079 -0.01062947 0.035 -0.04000078 -0.01209001 0.04121809 -0.04000078 -0.01062947 0.0415 -0.03400079 -0.01170121 0.0415 -0.03400079 -0.01062947 0.0415 -0.03400079 -0.01212947 0.04084055 -0.04600077 -0.01212948 0.035 -0.05200077 -0.01212948 0.035 -0.05200077 -0.01209002 0.04121809 -0.05200077 -0.01062948 0.0415 -0.04600077 -0.01170122 0.0415 -0.04600078 -0.01062948 0.0415 -0.04600077 -0.01212948 0.04084055 -0.05200077 -0.01062948 0.017025 -0.05200077 -0.005287587 0.01694531 -0.04975078 -0.005123335 0.01636693 -0.03400079 -0.01062947 0.023 -0.03105507 -0.01056344 0.014881 -0.03117306 -0.00842218 0.01154181 -0.03101065 -0.008222869 0.04641394 -0.03099332 0.001863981 0.04673203 -0.03100599 0.00736789 0.04670921 -0.03104369 -0.00108768 0.04687065 -0.03101206 -0.007440277 0.04678304 -0.03116834 0.007675393 0.04678662 -0.03102043 0.008234391 0.04615881 -0.04600079 0.01037052 0.0349 -0.04600079 0.01107052 0.0347 -0.05200079 0.01037051 0.0348 -0.05200079 0.01107051 0.0347 -0.05200079 0.01037051 0.0231 -0.05200079 0.01107051 0.0233 -0.04482097 0.00957052 0.03704384 -0.04506971 0.01037052 0.03776836 -0.04495691 0.00957052 0.03856039 -0.04450362 0.01037052 0.03937189 -0.04388831 0.00957052 0.03988316 -0.0433082 0.01037052 0.04001146 -0.0420282 0.009570522 0.03981145 -0.04166738 0.01037052 0.03959879 -0.04099842 0.009570524 0.03846667 -0.04094835 0.01037052 0.03787843 -0.04132756 0.009570522 0.03680521 -0.041514 0.01037052 0.03663501 -0.04252394 0.01037052 0.03602186 -0.04245137 0.009570522 0.03605801 -0.04364368 0.009570522 0.03606944 -0.04403338 0.01037052 0.03622206 -0.04000079 0.01037052 0.035 -0.04000079 0.01187052 0.035 -0.0340008 0.01037053 0.035 -0.0340008 0.01187053 0.035 -0.0340008 0.01183408 0.04121592 -0.0340008 0.01037053 0.0415 -0.04000079 0.01144227 0.0415 -0.04000079 0.01037052 0.0415 -0.04000079 0.01187052 0.04084055 -0.04600079 0.01187052 0.035 -0.05200079 0.01187051 0.035 -0.04600079 0.01183407 0.0412159 -0.04600079 0.01037052 0.0415 -0.05200079 0.01144226 0.0415 -0.05200079 0.01037051 0.0415 -0.05200079 0.01187051 0.04084055 -0.03117317 0.008258421 0.01165369 -0.03105086 0.0103042 0.01487996 -0.0340008 0.01037053 0.023 -0.0340008 0.01037053 0.017025 -0.04975079 0.005029257 0.01641745 -0.05200079 0.01037051 0.017025 -0.05482926 -0.008128818 0.01132065 -0.05280079 0.005395213 0.01150131 -0.05280079 0.007273923 0.01184697 -0.05280079 0.008346776 0.01341903 -0.05280079 0.008081184 0.01531073 -0.05280077 0.006556034 0.01644938 -0.05280079 0.004654763 0.01626431 -0.0528008 0.003452435 0.01478886 -0.0528008 0.003633194 0.01267092 -0.05280079 0.002081202 0.0153107 -0.05280079 0.0007607248 0.01636054 -0.05280077 -0.0005035056 0.01649492 -0.05280077 -0.002030117 0.01572995 -0.05280078 -0.002647206 0.01416003 -0.05280079 -0.002319216 0.01270598 -0.05280079 -0.001216725 0.0117235 -0.05280077 0.000254754 0.01148568 -0.0528008 0.001577524 0.0121424 -0.05280079 0.002346775 0.01341902 -0.0528008 -0.008506406 0.01309467 -0.05280076 -0.007227051 0.01167612 -0.05280078 -0.004896576 0.01170829 -0.05280076 -0.003653226 0.01341902 -0.05280079 -0.004012936 0.01551404 -0.05280075 -0.005651007 0.016477 -0.05280077 -0.007134858 0.01633637 -0.05280079 -0.008497856 0.01499796 -0.03444646 -0.01212947 0.03771617 -0.0353672 -0.01212947 0.03605041 -0.03695459 -0.01212947 0.03545692 -0.03856244 -0.01212947 0.03599236 -0.03939697 -0.01212947 0.03721075 -0.03660883 -0.01212947 0.04053998 -0.03498364 -0.01212947 0.03954939 -0.03944591 -0.01212947 0.03870056 -0.03846302 -0.01212947 0.04008111 -0.04672476 -0.01212948 0.0369118 -0.04648416 -0.01212948 0.03836886 -0.04809507 -0.01212948 0.0355604 -0.05040416 -0.01212948 0.03584695 -0.05154417 -0.01212948 0.03763094 -0.05107292 -0.01212948 0.03947504 -0.04926257 -0.01212948 0.04058911 -0.04727447 -0.01212948 0.03986795 -0.05200079 0.005004283 0.01695293 -0.05200079 0.002391564 0.01350057 -0.05200079 0.001796484 0.01575006 -0.05200077 3.16333e-05 0.01651766 -0.05200078 -0.001410097 0.0161976 -0.05200078 -0.002405536 0.01508819 -0.05200078 -0.002646097 0.01363115 -0.05200078 -0.001552356 0.01182113 -0.05200079 0.0009798855 0.01164601 -0.04975078 -0.004129484 0.0155 -0.03320079 0.00843972 0.01393383 -0.03320079 0.00786688 0.01554248 -0.03320079 0.00647646 0.0164976 -0.03320081 0.004783338 0.01627654 -0.03320079 0.00344079 0.01493185 -0.03320081 0.003620578 0.01281383 -0.03320081 0.004686769 0.01177219 -0.03320079 0.006132249 0.01147 -0.03320081 0.007663559 0.01219599 -0.03320079 -0.003729071 0.01308172 -0.03320078 -0.003854262 0.01519522 -0.0332008 -0.005138851 0.01632019 -0.03320078 -0.007035263 0.01643959 -0.03320078 -0.008681746 0.01450782 -0.03320075 -0.008146624 0.01245064 -0.03320078 -0.006725495 0.01152733 -0.03320078 -0.005039842 0.01170172 -0.03625079 0.005249089 0.01698697 -0.03400079 0.005028568 0.01694531 -0.03625082 0.003911287 0.01634049 -0.03115738 0.00782327 0.01130237 -0.03625078 -0.004799184 0.0168318 -0.0340008 0.002064548 0.01260061 -0.03320079 0.002439719 0.01393384 -0.03400079 0.002270916 0.01491829 -0.03320079 0.001473019 0.01605037 -0.0340008 0.000960147 0.01629828 -0.03320079 -0.0008185413 0.01647595 -0.03400079 -0.0009450521 0.01643721 -0.03320076 -0.002319231 0.01529397 -0.03400079 -0.002379453 0.01518617 -0.03320079 -0.002632431 0.01341664 -0.03400079 -0.002559212 0.01306815 -0.03320079 -0.001515262 0.01186716 -0.03400079 -0.001216772 0.01172353 -0.03320079 0.0001322385 0.01147 -0.03400079 0.0002547559 0.01148568 -0.03320081 0.001663579 0.01219601 -0.03103922 -0.008481232 0.01179834 -0.03100077 0.00808122 0.01268927 -0.03101413 0.008124121 0.01177466 -0.03101515 0.00723779 0.01119026 -0.03100077 -0.00372907 0.01308172 -0.03100078 -0.00523293 0.01159141 -0.03100077 -0.0009450502 0.0115628 -0.03100077 -0.003787001 0.01499107 -0.03100076 -0.001912991 0.01578427 -0.03100078 -0.004761021 0.01611939 -0.03100076 -0.00224945 0.01263236 -0.03100082 0.00696573 0.01174362 -0.0310008 0.00143213 0.01600768 -0.03100079 0.002346801 0.01458097 -0.03100079 0.004087061 0.01578433 -0.03100079 0.008346802 0.01458096 -0.03100006 0.005478792 0.01145993 -0.03100076 0.007432191 0.0160076 -0.03100077 0.001361791 0.01186737 -0.03100079 0.002287891 0.01333135 -0.03100077 0.003704851 0.01261615 -0.03100078 -0.00268379 0.01428381 -0.03100079 -0.007763047 0.01594959 -0.03100079 0.003374802 0.01449061 -0.0310087 -0.007497925 0.01120656 -0.03100078 -0.008547543 0.01321113 -0.03100079 -0.008556684 0.01468788 -0.03100075 -0.00345975 0.02971203 -0.03100075 -0.006616241 0.03178271 -0.03100078 -0.007345229 0.01173571 -0.03100079 0.005609842 0.01655679 -0.0310008 0.008342411 0.03500673 -0.03100073 0.006319061 0.0318197 -0.03100078 -0.008824661 0.03573591 -0.03100077 -0.008932939 0.03950949 -0.03100079 -0.0003901702 0.01655679 -0.03100079 -0.0005086204 0.02907611 -0.0310008 0.00322067 0.02966281 -0.03100081 0.005806921 0.04474475 -0.03100078 0.008009611 0.04167896 -0.03100078 -0.006175671 0.01654308 -0.03100087 -0.006030426 0.04470495 -0.03100083 -0.007927186 0.04235608 -0.03100077 0.00877284 0.03872726 -0.03100042 -0.00356461 0.04623871 -0.02805658 0.0007587615 0.0467971 -0.02818095 -0.001271638 0.04682195 -0.02822892 0.002851533 0.04642996 -0.02820085 0.005163063 0.04515576 -0.02820718 0.006766572 0.04365137 -0.02820648 0.008302022 0.04097906 -0.02820312 0.008810503 0.03783595 -0.02821744 0.008215044 0.03482779 -0.02820706 0.006847573 0.03244897 -0.02820076 0.005162813 0.0308446 -0.02821742 0.003002413 0.02964029 -0.02820086 -0.0004422469 0.02904725 -0.02820567 -0.003934597 0.02992493 -0.02802617 -0.006185085 0.03157995 -0.02821663 -0.007516263 0.03300757 -0.02820575 -0.008705381 0.03552179 -0.02805338 -0.008959343 0.03787482 -0.02820713 -0.008741232 0.0403088 -0.0282016 -0.00753819 0.04300751 -0.02821661 -0.005431178 0.04516803 -0.02802134 -0.003203948 0.04626144 -0.03879383 0.01187053 0.036196 -0.03956999 0.01187052 0.03793385 -0.03682125 0.01187053 0.03540389 -0.03498366 0.01187053 0.03645062 -0.03445804 0.01187053 0.03806176 -0.03519174 0.01187053 0.03982551 -0.03695459 0.01187053 0.04054309 -0.03874786 0.01187053 0.0398849 -0.05134277 0.01187051 0.03686546 -0.04947739 0.01187052 0.03547453 -0.04781711 0.01187052 0.03577215 -0.04675081 0.01187052 0.03681384 -0.04653116 0.01187052 0.03871137 -0.0477202 0.01187052 0.04019761 -0.05056246 0.01187052 0.04000763 -0.05139693 0.01187051 0.03878931 -0.04916188 0.01187052 0.04051766 -0.04975079 0.003861336 0.01550948 -0.03956998 -0.01132947 0.03793385 -0.03887928 -0.01132947 0.03971484 -0.03717591 -0.01132947 0.04056408 -0.03536723 -0.01132947 0.03994958 -0.03450504 -0.01132947 0.03849063 -0.03475076 -0.01132947 0.03681381 -0.03581696 -0.01132947 0.03577215 -0.03726249 -0.01132947 0.03547 -0.03879382 -0.01132947 0.03619601 -0.05154419 -0.01132948 0.03836902 -0.05056245 -0.01132948 0.04000763 -0.04895455 -0.01132948 0.04054308 -0.0473672 -0.01132948 0.03994957 -0.04650505 -0.01132948 0.03849061 -0.04668021 -0.01132948 0.03701025 -0.04761506 -0.01132948 0.03586713 -0.0494774 -0.01132948 0.03547453 -0.05107295 -0.01132948 0.03652502 -0.03320079 0.0077897 0.01319323 -0.03320079 0.006355308 0.01200193 -0.0332008 0.0050007 0.01217882 -0.03320081 0.00411878 0.01296478 -0.03320079 0.003857238 0.01429507 -0.03320079 0.004489448 0.01549433 -0.03320079 0.005734809 0.01603027 -0.03320078 0.006891569 0.01574088 -0.03320081 0.007703828 0.01488287 -0.03320076 -0.00751053 0.01549434 -0.03320078 -0.006265191 0.01603027 -0.03320079 -0.004959592 0.0156649 -0.03320078 -0.004241361 0.014713 -0.03320079 -0.004173891 0.01336518 -0.03320078 -0.005467172 0.01202631 -0.03320076 -0.0071539 0.01224188 -0.03320075 -0.007950304 0.01312946 -0.03320077 -0.00814276 0.01429508 -0.03320081 0.001639079 0.01504858 -0.03320079 0.001826108 0.01336516 -0.03320078 0.0008304287 0.01220585 -0.03320078 -0.0005097017 0.01200105 -0.03320081 -0.001556341 0.01257257 -0.03320079 -0.002210582 0.01394467 -0.03320078 -0.001394241 0.015621 -0.03320079 0.0002518184 0.01602037 -0.0318008 0.0083468 0.01341904 -0.0318008 0.00808119 0.01531075 -0.0318008 0.006347138 0.01652546 -0.03180081 0.004289619 0.0160263 -0.0318008 0.00335392 0.01436887 -0.03180079 0.003778979 0.01250652 -0.0318008 0.005609849 0.01144321 -0.0318008 0.0074322 0.01199238 -0.03180081 0.002370559 0.01472244 -0.03180079 0.0009601098 0.01629831 -0.03180079 -0.0007255804 0.01647266 -0.03180075 -0.001987821 0.01570618 -0.03180079 -0.00273085 0.01393084 -0.0318008 -0.001763061 0.01205048 -0.03180079 -0.0001756595 0.01145691 -0.0318008 0.001796508 0.01224997 -0.03180078 -0.003653211 0.01341902 -0.03180081 -0.00383786 0.01510361 -0.03180079 -0.005232961 0.01640861 -0.03180078 -0.007134857 0.01633636 -0.03180081 -0.00837944 0.01518619 -0.03180079 -0.008625206 0.01350941 -0.03180074 -0.007912934 0.01221567 -0.03180079 -0.006390137 0.01144321 -0.03180076 -0.0045678 0.01199237 -0.02800064 0.003787082 0.03023144 -0.02800016 0.000793552 0.02928427 -0.0280006 -0.008200405 0.0347019 -0.02800073 -0.002842928 0.02970141 -0.02800036 0.006055571 0.03181384 -0.02800058 0.008272894 0.03555173 -0.02799981 0.008498805 0.03927279 -0.02800073 0.007798044 0.04158356 -0.02800026 0.006195653 0.0440621 -0.02800066 0.003118133 0.04608182 -0.0280007 -0.006433021 0.04407608 -0.02800054 -0.008390347 0.04091885 -0.03953962 0.01107052 0.03784589 -0.03907293 0.01107052 0.03947504 -0.03789113 0.01107053 0.04036053 -0.03640473 0.01107053 0.04047266 -0.03469603 0.01107053 0.03920832 -0.03453543 0.01107053 0.03753882 -0.03519179 0.01107053 0.0361745 -0.03695459 0.01107053 0.03545692 -0.03874785 0.01107053 0.03611509 -0.05158694 0.01107051 0.03828956 -0.0501102 0.01107052 0.04035399 -0.04821056 0.01107052 0.04039586 -0.04698359 0.01107052 0.0395493 -0.04644647 0.01107052 0.03771618 -0.04752629 0.01107052 0.03589505 -0.04938502 0.01107052 0.03548568 -0.05087928 0.01107052 0.03628516 -0.03738358 -0.01132947 0.03998159 -0.03856668 -0.01132947 0.03933244 -0.03903552 -0.01132947 0.0377048 -0.03825013 -0.01132947 0.0363939 -0.03712963 -0.01132947 0.03598587 -0.0358211 -0.01132947 0.03631601 -0.03500419 -0.01132947 0.03760754 -0.03520084 -0.01132947 0.038949 -0.03619647 -0.01132947 0.03986909 -0.05002173 -0.01132948 0.03974097 -0.05092111 -0.01132948 0.03873465 -0.05082099 -0.01132948 0.03704385 -0.04979335 -0.01132948 0.03614389 -0.0486205 -0.01132948 0.03600103 -0.04744917 -0.01132948 0.03668359 -0.04699393 -0.01132948 0.0377858 -0.04720074 -0.01132948 0.03894884 -0.04850824 -0.01132948 0.04002274 -0.0318008 0.00782666 0.01343962 -0.03180081 0.007744499 0.01479283 -0.03180079 0.006532859 0.01597368 -0.0318008 0.004690898 0.01568397 -0.0318008 0.003928758 0.01455027 -0.0318008 0.003936069 0.01336894 -0.03180082 0.004635899 0.01240344 -0.0318008 0.00573485 0.01196973 -0.03180082 0.007040378 0.0123351 -0.03180079 -0.004074121 0.01394706 -0.03180078 -0.00462672 0.01537192 -0.03180079 -0.005822074 0.01601145 -0.03180078 -0.007462852 0.01559879 -0.03180079 -0.008163671 0.01404941 -0.03180079 -0.007825408 0.01290588 -0.03180078 -0.006933792 0.01213091 -0.03180079 -0.00574672 0.01201838 -0.03180078 -0.004695061 0.01255678 -0.03180079 0.001925889 0.01394707 -0.03180079 0.001373258 0.01537192 -0.0318008 0.0003379192 0.01596337 -0.03180077 -0.0008420907 0.01590594 -0.03180079 -0.001980551 0.01489486 -0.0318008 -0.00206393 0.01336893 -0.03180079 -0.001364071 0.01240344 -0.03180079 -9.512156e-05 0.01194425 -0.03180079 0.001304928 0.01255677 -0.02800081 -0.007855771 0.03613205 -0.02800078 -0.008583936 0.03741679 -0.02800078 -0.008443334 0.03911855 -0.02800077 -0.006547176 0.03550698 -0.02800078 -0.004239708 0.04309098 -0.02800078 -0.003505697 0.04221896 -0.02800078 -0.003087467 0.04082674 -0.02800077 -0.004216578 0.04141225 -0.02800077 -0.004980288 0.04168904 -0.02800078 -0.005173517 0.04255077 -0.02800078 -0.002128717 0.04567457 -0.02800078 -0.0001757173 0.04654309 -0.02800079 0.001432193 0.04600766 -0.02800079 0.004729495 0.04280267 -0.02800079 0.004913183 0.04201146 -0.02800079 0.002756193 0.04100349 -0.02800079 0.004198823 0.04138831 -0.02800078 0.003420183 0.04179982 -0.02800078 0.003887743 0.04305684 -0.02800079 0.003322892 0.04247028 -0.0280008 0.007663533 0.03619597 -0.02800079 0.005923481 0.03542822 -0.02800079 0.005834142 0.04060349 -0.02800079 0.007911043 0.0395625 -0.02800079 0.008398883 0.03772279 -0.02800078 0.004841253 0.03413984 -0.02800079 0.004777674 0.03318973 -0.02800079 0.003852163 0.03297749 -0.02800079 0.003290143 0.03356671 -0.02800079 0.002697272 0.035042 -0.02800079 0.003596922 0.03441718 -0.02800079 0.004303903 0.03455433 -0.02800079 0.002434973 0.03230027 -0.02800079 0.001942653 0.03052495 -0.02800079 0.0007607713 0.02963949 -0.02800077 -0.0007255673 0.02952732 -0.02800076 -0.002102777 0.03040668 -0.02800078 -0.004085237 0.03298659 -0.02800079 -0.005019538 0.03317036 -0.02800078 -0.003523167 0.03366525 -0.02800078 -0.004980617 0.03439005 -0.02800079 0.003778992 0.03949353 -0.02800079 0.004327303 0.03600433 -0.02800079 0.003367573 0.03741662 -0.02800079 0.002462922 0.04413791 -0.02800079 0.001361793 0.04186735 -0.02800078 -0.0009450372 0.0415628 -0.02800078 -0.002605298 0.0431986 -0.0280008 -0.007224149 0.04026764 -0.02800078 -0.005745267 0.04051432 -0.02800077 -0.004422388 0.03985754 -0.02800078 -0.002984797 0.03483667 -0.02800078 -0.005039858 0.0357017 -0.02800078 -0.003653198 0.03858096 -0.02800078 -0.003837868 0.03689638 -0.02800078 -0.002689538 0.03193859 -0.02800079 0.001432132 0.03400766 -0.02800078 -0.0003901869 0.03455679 -0.02800078 -0.002069017 0.03364548 -0.02800079 0.002663393 0.03839771 -0.02800078 0.002502702 0.0369851 -0.02800078 -0.0006578472 0.04079456 -0.02800082 0.0007414334 0.04066559 -0.02800079 0.001968782 0.0399231 -0.02800076 -0.002403658 0.0397372 -0.02800078 -0.002947887 0.03817072 -0.02800077 -0.001256098 0.03539259 -0.0280008 -0.002617258 0.03660434 -0.02800078 0.0002568737 0.03521079 -0.02800079 0.001619173 0.03575699 -0.02800078 -0.003974727 0.0344869 -0.03628821 0.01107053 0.03990594 -0.03514969 0.01107053 0.03889483 -0.03503722 0.01107053 0.03753349 -0.03586254 0.01107053 0.03625688 -0.03754924 0.01107053 0.0360405 -0.03854351 0.01107053 0.03669872 -0.03905614 0.01107052 0.03794705 -0.03850374 0.01107053 0.03937189 -0.03746822 0.01107053 0.03996338 -0.04845128 0.01107052 0.03994198 -0.04744918 0.01107052 0.03931637 -0.04694836 0.01107052 0.03787843 -0.04751419 0.01107052 0.03663501 -0.04852391 0.01107052 0.03602186 -0.0500334 0.01107052 0.03622207 -0.05088889 0.01107052 0.03728702 -0.05095638 0.01107052 0.03863486 -0.04981627 0.01107052 0.03988739 -0.03895688 -0.009929474 0.03743962 -0.03882095 -0.009929475 0.03895615 -0.03779322 -0.009929473 0.0398562 -0.03662048 -0.009929472 0.03999895 -0.03557395 -0.009929471 0.03942742 -0.03491967 -0.009929471 0.03805531 -0.0356197 -0.009929473 0.03650562 -0.03686508 -0.009929473 0.03596973 -0.03817066 -0.009929475 0.03633513 -0.05103553 -0.009929483 0.03829521 -0.04998713 -0.009929482 0.03983339 -0.04812271 -0.00992948 0.03985909 -0.04695896 -0.00992948 0.0384062 -0.047387 -0.009929481 0.03676062 -0.0483686 -0.009929481 0.0360833 -0.04954922 -0.009929482 0.0360405 -0.05065849 -0.009929482 0.03681998 -0.03100078 -0.00354434 0.03384349 -0.03100078 -0.00401566 0.03450829 -0.03100078 -0.004952511 0.03439317 -0.03100077 -0.0051624 0.03352973 -0.03100078 -0.004529881 0.03291337 -0.03100078 -0.00377097 0.03320868 -0.03100079 0.003863789 0.03456666 -0.03100079 0.00331223 0.03394404 -0.03100079 0.003519321 0.03315646 -0.03100079 0.004520591 0.03300156 -0.03100079 0.004940732 0.03385004 -0.03100078 0.004581122 0.03442334 -0.03100078 -0.00358829 0.04259944 -0.03100078 -0.00457596 0.0430767 -0.03100078 -0.00517306 0.04242928 -0.03100078 -0.004921471 0.04158278 -0.03100078 -0.00384278 0.04156661 -0.03100079 0.004940741 0.04233531 -0.03100079 0.004581062 0.04290863 -0.03100079 0.00384398 0.04304343 -0.03100079 0.003312221 0.0424293 -0.03100077 0.003563821 0.04158279 -0.03100079 0.00457545 0.04153551 -0.02847464 -0.002521329 0.03956742 -0.02850036 -0.0007912284 0.04076047 -0.0284706 0.002720993 0.03785482 -0.02849419 0.002248053 0.03955259 -0.02850227 0.0009845626 0.04060777 -0.02850229 -0.002957929 0.03782954 -0.02849982 -0.002342098 0.03621103 -0.02846488 -0.001189969 0.03541101 -0.028502 0.0001592021 0.03514811 -0.028496 0.001958683 0.03606989 -0.02880079 -0.002555738 0.03131848 -0.02880077 -0.001603989 0.02989502 -0.02880077 0.0002547838 0.02948569 -0.02880077 0.001749013 0.03028516 -0.02880077 0.002409102 0.03184752 -0.0288008 0.002046052 0.03327734 -0.0288008 0.0009601526 0.03429831 -0.02880079 -0.000725558 0.03447268 -0.02880077 -0.002434249 0.0332083 -0.02880077 -0.007349562 0.04025728 -0.02880078 -0.008705124 0.03837145 -0.02880076 -0.008069029 0.03635452 -0.02880078 -0.006183407 0.03539514 -0.02880078 -0.004088968 0.03643748 -0.02880078 -0.003607248 0.0380541 -0.02880079 -0.004057399 0.03947504 -0.02880078 -0.005443938 0.04044936 -0.02880079 0.001877893 0.0456208 -0.02880077 0.0001321919 0.04653001 -0.02880076 -0.001900039 0.0459071 -0.02880078 -0.002680899 0.044 -0.02880078 -0.002068998 0.04235449 -0.02880079 -0.0001707682 0.04139802 -0.02880077 0.001749022 0.04228516 -0.02880077 0.002409361 0.04384589 -0.02880078 0.005762232 0.04054914 -0.0288008 0.004144242 0.03986794 -0.02880079 0.003353933 0.03836889 -0.02880077 0.003680803 0.03670599 -0.02880079 0.004783362 0.03572348 -0.02880079 0.006471192 0.03550619 -0.02880078 0.008145753 0.03680478 -0.02880079 0.008315673 0.03870051 -0.02880078 0.007332863 0.04008109 -0.03901763 0.009670524 0.03839953 -0.03817073 0.009670526 0.03966489 -0.03704317 0.009670526 0.0400178 -0.03573608 0.009670527 0.03962106 -0.0349875 0.009670527 0.03829507 -0.03517992 0.009670527 0.03712946 -0.03627617 0.009670527 0.03604834 -0.03796067 0.009670526 0.03620584 -0.03878344 0.009670526 0.03705368 -0.05103554 0.009670516 0.03770481 -0.05074129 0.009670516 0.03902185 -0.04971807 0.009670516 0.03992686 -0.04836864 0.009670518 0.03991671 -0.04726826 0.009670518 0.03910709 -0.04700421 0.009670518 0.03760751 -0.04757387 0.009670518 0.03657264 -0.04862053 0.009670518 0.03600105 -0.05012351 0.009670516 0.03627756 -0.0280888 -0.001341848 0.03740753 -0.02806377 -0.0001819767 0.03931006 -0.02798386 0.0008570813 0.03752532 -0.02880077 -0.002024158 0.0312016 -0.02880079 -0.0009337785 0.0301309 -0.02880079 0.0005878024 0.03007313 -0.02880077 0.001790853 0.03126536 -0.02880077 0.001690714 0.03295617 -0.02880079 0.0003553014 0.03399807 -0.02880078 -0.0009992086 0.03382121 -0.02880078 -0.001980538 0.03289487 -0.02880077 -0.006342802 0.04000693 -0.02880078 -0.007436246 0.03955972 -0.02880077 -0.00817293 0.03822702 -0.02880077 -0.007743193 0.03676047 -0.02880078 -0.006606291 0.03602186 -0.02880077 -0.004936459 0.0362939 -0.02880078 -0.004148029 0.03761633 -0.02880077 -0.004255499 0.03879289 -0.02880077 -0.005169518 0.03979411 -0.02880077 -0.001929458 0.04305105 -0.02880077 -0.001076508 0.04221768 -0.02880079 0.0004270431 0.0419939 -0.02880079 0.001790853 0.04326537 -0.02880077 0.001787513 0.04463136 -0.02880077 0.000993263 0.04572244 -0.02880078 -0.0005097482 0.04599894 -0.02880079 -0.001681119 0.04531636 -0.02880078 -0.002136298 0.04421425 -0.02880079 0.006856872 0.03983336 -0.02880079 0.005157935 0.03990594 -0.02880082 0.004223013 0.03916576 -0.02880079 0.003836334 0.03804939 -0.02880077 0.004454043 0.0364743 -0.02880079 0.005912963 0.03598219 -0.02880081 0.007040392 0.0363351 -0.02880079 0.007826663 0.03743963 -0.0288008 0.007787464 0.03863141 -0.03100077 0.00178748 0.03136861 -0.03100079 0.00182664 0.03256041 -0.03100082 0.001171112 0.03354327 -0.03100079 -9.51197e-05 0.03405574 -0.03100077 -0.001783401 0.03326436 -0.03100077 -0.00212606 0.03160754 -0.03100077 -0.0015563 0.03057263 -0.03100079 -0.0005097203 0.03000105 -0.03100077 0.0009932425 0.03027757 -0.03100078 -0.004112631 0.03839956 -0.03100075 -0.00482895 0.03954333 -0.03100078 -0.005920082 0.04002399 -0.03100078 -0.007238036 0.03970633 -0.03100078 -0.008131838 0.03846667 -0.03100078 -0.007881241 0.03696478 -0.03100078 -0.006513831 0.03595396 -0.03100077 -0.004588711 0.03659994 -0.03100079 0.0019016 0.04387671 -0.0310008 0.001528202 0.04518005 -0.03100077 0.0004190114 0.0459595 -0.03100079 -0.00076163 0.04591669 -0.03100076 -0.00174318 0.04523952 -0.03100078 -0.00216366 0.04395057 -0.03100076 -0.001681181 0.04268365 -0.03100079 -0.0001625204 0.04191841 -0.03100079 0.001373339 0.04262814 -0.03100079 0.007901611 0.03787672 -0.03100079 0.007436432 0.03933241 -0.03100079 0.006079901 0.040024 -0.03100079 0.00445403 0.03952565 -0.03100079 0.003856352 0.03812799 -0.03100079 0.00419731 0.03680516 -0.03100079 0.005150732 0.03612704 -0.03100079 0.00635533 0.03600194 -0.03100075 0.00746756 0.03676596 -0.03625078 -0.005441854 0.01643714 -0.03625079 -0.004099144 0.01553188 -0.0362508 0.003881816 0.01558718 -0.03625079 0.005267048 0.01645705 -0.05017067 0.009670516 0.02166485 -0.04886509 0.009670516 0.02203026 -0.04766742 0.009670518 0.0184012 -0.05101763 0.009670516 0.02039955 -0.04948558 0.009670516 0.01800194 -0.05071382 0.009670516 0.01890182 -0.0474803 0.009670518 0.02138398 -0.04696659 0.009670518 0.01995059 -0.05095691 0.01107052 0.01943957 -0.05091776 0.01107052 0.02063141 -0.04998711 0.01107052 0.02183337 -0.04812277 0.01107052 0.02185913 -0.04702511 0.01107052 0.02056911 -0.04720085 0.01107052 0.01905109 -0.04834833 0.01107052 0.01805025 -0.05003334 0.01107052 0.01822204 -0.04741986 0.01107052 0.02202628 -0.04643525 0.01107052 0.02015197 -0.04706115 0.01107052 0.01835455 -0.04852546 0.01107052 0.0175013 -0.05040415 0.01107052 0.01784694 -0.05147706 0.01107051 0.01941904 -0.05121148 0.01107051 0.02131064 -0.0494774 0.01107052 0.02252546 -0.04702509 -0.00992948 0.02056908 -0.04827615 -0.00992948 0.02195166 -0.05091778 -0.009929482 0.02063141 -0.04720078 -0.00992948 0.01905109 -0.05092111 -0.009929482 0.01926536 -0.05012345 -0.009929482 0.02172247 -0.04987245 -0.009929482 0.01816135 -0.04834829 -0.00992948 0.01805022 -0.05098177 -0.01132948 0.0195352 -0.05083402 -0.01132948 0.02088293 -0.0500218 -0.01132948 0.0217409 -0.04886508 -0.01132948 0.02203026 -0.04748028 -0.01132948 0.02138395 -0.0469866 -0.01132948 0.02012796 -0.04724896 -0.01132948 0.01896466 -0.04861643 -0.01132948 0.01795395 -0.05025014 -0.01132948 0.01839392 -0.05009044 -0.01132948 0.01770173 -0.04818522 -0.01132948 0.0175628 -0.04675079 -0.01132948 0.01881378 -0.04650264 -0.01132949 0.02048315 -0.04736717 -0.01132948 0.02194955 -0.04895454 -0.01132948 0.02254308 -0.05056245 -0.01132948 0.02200766 -0.05147704 -0.01132948 0.02058096 -0.05129234 -0.01132948 0.01889633 -0.03502011 -0.009929472 0.0193589 -0.03854154 -0.009929473 0.02140002 -0.03902346 -0.009929474 0.01977824 -0.03532753 -0.009929471 0.0211948 -0.03679219 -0.009929473 0.02204542 -0.03819379 -0.009929473 0.01829389 -0.03634834 -0.009929473 0.01805022 -0.03906969 -0.01132947 0.02023162 -0.03817062 -0.01132947 0.02166492 -0.03686506 -0.01132947 0.02203026 -0.03534686 -0.01132947 0.02126436 -0.03502509 -0.01132947 0.01943086 -0.0359763 -0.01132947 0.01824193 -0.03730819 -0.01132947 0.01798855 -0.03850357 -0.01132947 0.01862811 -0.03809037 -0.01132947 0.01770168 -0.03596667 -0.01132947 0.01761198 -0.03459089 -0.01132939 0.01919235 -0.03456075 -0.0113294 0.02065652 -0.03569577 -0.01132947 0.02225144 -0.03780448 -0.01132947 0.02241318 -0.03927599 -0.01132947 0.02119525 -0.03940117 -0.01132947 0.01908172 -0.03755729 0.009670526 0.0220061 -0.03509925 0.009670527 0.01927573 -0.03900079 0.009670524 0.020578 -0.0361227 0.009670527 0.01814091 -0.03746819 0.009670526 0.01803662 -0.03863319 0.009670526 0.01874997 -0.03589224 0.009670527 0.02170632 -0.03506633 0.009670527 0.02063107 -0.03902346 0.01107052 0.01977823 -0.03863323 0.01107053 0.02125 -0.03714092 0.01107053 0.02205125 -0.03569396 0.01107053 0.02155968 -0.03495733 0.01107053 0.020227 -0.03548027 0.01107053 0.01861603 -0.03703513 0.01107053 0.01794425 -0.03843526 0.01107053 0.01855684 -0.03561502 0.01107053 0.02213285 -0.03449783 0.01107053 0.02058337 -0.03490924 0.01107053 0.0185065 -0.03631395 0.01107053 0.01757249 -0.0382337 0.01107053 0.01770828 -0.03947705 0.01107052 0.01941905 -0.03911739 0.01107052 0.02151402 -0.03726249 0.01107053 0.02253 -0.002007724 8.397177e-05 0.009000001 -0.001794932 -0.001089358 0.009000001 -0.001351244 0.001454962 0.009000001 0.0002209209 -0.002152125 0.009000001 0.001705318 -0.001322455 0.009000001 0.001977348 0.000347415 0.009000001 0.001364137 0.001357265 0.008999991 0.0002942886 0.001883844 0.009000001 -0.0009471178 -0.001912077 0.009000011 0.0001205709 -0.002207746 0.0112 0.001605312 -0.001378775 0.01120001 0.002044643 7.911399e-05 0.0112 0.001426646 0.001297355 0.01120002 0.0003916854 0.001867142 0.0112 -0.0007924959 0.001727032 0.01120001 -0.001707084 0.0009791535 0.01120001 -0.002018593 -0.0001718476 0.0112 -0.001578622 -0.001447668 0.0112 -0.001715621 -0.002007938 0.0112 -0.0001548845 -0.002668276 0.0112 0.001474263 -0.002201536 0.01120001 0.002524678 -0.0006060535 0.0112 0.00222703 0.001054354 0.01119998 0.00101338 0.002229855 0.0111999 -0.0008683819 0.002267843 0.01119991 -0.002198384 0.001151161 0.0112 -0.002515092 -0.0005136682 0.0112 0.0005835732 0.002337387 0.01199995 -0.001078945 0.002190814 0.01200001 -0.002337154 0.0008759406 0.012 -0.002409373 -0.001026018 0.012 -0.0009190748 -0.002529837 0.012 0.0009902921 -0.002471916 0.012 0.002241901 -0.001329325 0.012 0.00250788 0.0001372751 0.012 0.001948778 0.001504136 0.012</float_array> + <technique_common> + <accessor count="3416" source="#cubeverts-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <vertices id="cubeverts-array0-vertices"> + <input source="#cubeverts-array0" semantic="POSITION"/> + </vertices> + <triangles count="6717" material="ref_Mesh001"> + <input source="#cubenormals-array0" semantic="NORMAL" offset="1"/> + <input source="#cubeverts-array0-vertices" semantic="VERTEX" offset="0"/> + <p>0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 6 2 6 3 5 3 7 3 8 4 9 4 10 4 10 5 9 5 11 5 12 6 13 6 14 6 14 7 13 7 15 7 16 8 17 8 18 8 16 9 18 9 19 9 19 10 18 10 20 10 19 11 20 11 21 11 21 12 20 12 22 12 21 13 22 13 23 13 23 14 22 14 24 14 23 15 24 15 25 15 25 16 24 16 26 16 25 17 26 17 27 17 27 18 26 18 28 18 27 19 28 19 29 19 29 20 28 20 30 20 29 21 30 21 31 21 31 22 30 22 32 22 31 23 32 23 33 23 33 24 32 24 16 24 16 25 32 25 17 25 34 26 35 26 36 26 36 27 35 27 37 27 37 28 35 28 38 28 37 29 38 29 39 29 39 30 38 30 40 30 39 31 40 31 41 31 41 32 40 32 42 32 41 33 42 33 43 33 43 34 42 34 44 34 43 35 44 35 45 35 45 36 44 36 46 36 45 37 46 37 47 37 47 38 46 38 48 38 47 39 48 39 49 39 49 40 48 40 34 40 49 41 34 41 50 41 50 42 34 42 36 42 51 43 52 43 53 43 51 44 53 44 54 44 54 45 53 45 55 45 54 46 55 46 56 46 56 47 55 47 57 47 56 48 57 48 58 48 58 49 57 49 59 49 59 50 57 50 60 50 59 51 60 51 61 51 59 52 61 52 62 52 62 53 61 53 63 53 63 54 61 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 52 59 67 60 52 60 51 60 69 61 70 61 71 61 71 62 70 62 72 62 71 63 72 63 73 63 70 64 74 64 75 64 69 65 76 65 77 65 78 66 79 66 80 66 69 67 77 67 70 67 70 68 77 68 74 68 81 69 82 69 83 69 81 70 83 70 84 70 70 71 75 71 79 71 79 72 75 72 85 72 79 73 78 73 81 73 81 74 78 74 82 74 79 75 85 75 80 75 84 76 83 76 76 76 84 77 76 77 69 77 86 78 87 78 88 78 86 79 88 79 89 79 89 80 88 80 90 80 91 81 92 81 93 81 93 82 92 82 94 82 90 83 95 83 96 83 93 84 97 84 90 84 90 85 97 85 95 85 91 86 98 86 92 86 93 87 94 87 97 87 90 88 96 88 89 88 89 89 96 89 99 89 100 90 101 90 91 90 91 91 101 91 98 91 99 92 96 92 102 92 99 93 102 93 100 93 100 94 102 94 101 94 91 95 93 95 103 95 103 96 93 96 104 96 103 97 104 97 105 97 106 98 107 98 108 98 108 99 107 99 109 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 112 105 114 105 115 105 115 106 114 106 116 106 115 107 116 107 117 107 117 108 116 108 118 108 118 109 116 109 119 109 118 110 119 110 120 110 118 111 120 111 121 111 121 112 120 112 106 112 106 113 120 113 107 113 122 114 123 114 124 114 122 115 124 115 125 115 125 116 124 116 126 116 127 117 128 117 129 117 130 118 131 118 132 118 132 119 131 119 133 119 126 120 134 120 129 120 126 121 129 121 125 121 125 122 129 122 128 122 135 123 136 123 137 123 137 124 136 124 138 124 128 125 127 125 139 125 128 126 139 126 135 126 135 127 139 127 136 127 138 128 130 128 137 128 137 129 130 129 132 129 132 130 133 130 126 130 126 131 133 131 134 131 140 132 141 132 142 132 142 133 141 133 143 133 145 134 146 134 140 134 140 135 146 135 141 135 146 136 147 136 141 136 141 137 147 137 148 137 141 138 148 138 149 138 150 139 149 139 148 139 151 140 152 140 153 140 153 141 152 141 154 141 150 142 155 142 149 142 145 143 140 143 152 143 154 144 152 144 140 144 149 145 155 145 153 145 153 146 155 146 151 146 156 147 157 147 158 147 156 148 158 148 153 148 153 149 158 149 149 149 159 150 160 150 161 150 159 151 161 151 162 151 162 152 161 152 163 152 162 153 163 153 164 153 164 154 163 154 165 154 164 155 165 155 166 155 166 156 165 156 167 156 166 157 167 157 168 157 168 158 167 158 169 158 169 159 167 159 170 159 169 160 170 160 171 160 171 161 170 161 172 161 171 162 172 162 173 162 173 163 172 163 174 163 173 164 174 164 175 164 175 165 174 165 160 165 175 166 160 166 159 166 177 167 178 167 179 167 179 168 178 168 180 168 180 169 178 169 181 169 180 170 181 170 182 170 180 171 182 171 183 171 183 172 182 172 184 172 184 173 182 173 185 173 184 174 185 174 186 174 186 175 185 175 187 175 186 176 187 176 188 176 188 177 187 177 189 177 188 178 189 178 176 178 190 179 191 179 192 179 192 180 191 180 193 180 192 181 193 181 194 181 192 182 194 182 195 182 195 183 194 183 196 183 197 184 198 184 199 184 199 185 198 185 200 185 199 186 200 186 201 186 199 187 201 187 202 187 202 188 201 188 203 188 202 189 203 189 204 189 204 190 203 190 205 190 204 191 205 191 206 191 206 192 205 192 207 192 206 193 207 193 208 193 208 194 207 194 209 194 208 195 209 195 210 195 210 196 209 196 211 196 211 197 209 197 212 197 211 198 212 198 213 198 211 199 213 199 214 199 214 200 213 200 215 200 214 201 215 201 197 201 197 202 215 202 198 202 216 203 217 203 218 203 218 204 217 204 219 204 218 205 219 205 220 205 220 206 219 206 221 206 220 207 221 207 222 207 222 208 221 208 223 208 223 209 221 209 224 209 223 210 224 210 225 210 225 211 224 211 226 211 225 212 226 212 227 212 227 213 226 213 228 213 227 214 228 214 229 214 229 215 228 215 230 215 229 216 230 216 216 216 216 217 230 217 217 217 231 218 232 218 233 218 234 219 235 219 236 219 236 220 235 220 233 220 236 221 233 221 232 221 237 222 238 222 234 222 234 223 238 223 157 223 157 224 156 224 234 224 87 225 240 225 241 225 242 226 243 226 144 226 144 227 243 227 244 227 245 228 246 228 105 228 105 229 246 229 247 229 248 230 249 230 250 230 250 231 249 231 251 231 252 232 253 232 254 232 255 233 256 233 257 233 261 234 260 234 250 234 250 235 260 235 248 235 254 236 253 236 262 236 262 237 263 237 264 237 262 238 264 238 254 238 257 239 256 239 271 239 257 240 271 240 272 240 256 241 255 241 273 241 273 242 274 242 271 242 273 243 271 243 256 243 276 244 277 244 263 244 263 245 277 245 264 245 280 246 281 246 282 246 282 247 281 247 279 247 282 248 279 248 278 248 267 249 270 249 283 249 283 250 270 250 284 250 285 251 286 251 287 251 287 252 286 252 288 252 289 253 290 253 291 253 293 254 294 254 295 254 296 255 297 255 298 255 299 256 300 256 301 256 301 257 300 257 302 257 301 258 302 258 303 258 303 259 304 259 305 259 296 260 298 260 305 260 305 261 298 261 293 261 305 262 293 262 303 262 303 263 293 263 295 263 303 264 295 264 301 264 294 265 306 265 295 265 295 266 306 266 307 266 295 267 307 267 291 267 291 268 307 268 308 268 291 269 308 269 289 269 309 270 310 270 297 270 311 271 312 271 298 271 298 272 312 272 306 272 306 273 312 273 313 273 297 274 310 274 314 274 297 275 314 275 298 275 314 276 311 276 298 276 306 277 313 277 315 277 315 278 316 278 307 278 306 279 315 279 307 279 316 280 317 280 307 280 307 281 317 281 297 281 297 282 317 282 309 282 280 283 318 283 319 283 320 284 321 284 322 284 323 285 286 285 324 285 324 286 286 286 285 286 324 287 285 287 325 287 326 288 327 288 328 288 329 289 330 289 331 289 331 290 330 290 320 290 332 291 333 291 334 291 334 292 333 292 335 292 324 293 325 293 330 293 320 294 322 294 331 294 331 295 322 295 336 295 331 296 336 296 337 296 332 297 331 297 333 297 333 298 331 298 337 298 333 299 337 299 319 299 319 300 337 300 281 300 319 301 281 301 280 301 330 302 338 302 335 302 335 303 338 303 328 303 335 304 328 304 334 304 334 305 328 305 327 305 327 306 339 306 334 306 340 307 341 307 329 307 335 308 324 308 330 308 342 309 330 309 329 309 342 310 329 310 341 310 341 311 343 311 342 311 328 312 344 312 326 312 334 313 339 313 329 313 329 314 339 314 340 314 343 315 345 315 342 315 342 316 344 316 328 316 342 317 345 317 344 317 346 318 347 318 348 318 349 319 350 319 351 319 349 320 352 320 350 320 324 321 353 321 354 321 354 322 353 322 355 322 355 323 346 323 348 323 346 324 352 324 347 324 347 325 352 325 349 325 355 326 348 326 354 326 356 327 290 327 357 327 347 328 349 328 358 328 358 329 357 329 290 329 359 330 360 330 361 330 361 331 360 331 362 331 363 332 364 332 360 332 346 333 365 333 352 333 352 334 365 334 366 334 367 335 368 335 291 335 335 336 369 336 324 336 324 337 369 337 353 337 370 338 371 338 351 338 370 339 351 339 350 339 372 340 373 340 374 340 360 341 375 341 376 341 365 342 377 342 366 342 366 343 377 343 378 343 379 344 380 344 335 344 290 345 356 345 291 345 291 346 356 346 381 346 367 347 291 347 376 347 360 348 359 348 382 348 360 349 364 349 375 349 362 350 383 350 361 350 383 351 384 351 361 351 361 352 385 352 386 352 387 353 388 353 368 353 368 354 388 354 291 354 382 355 363 355 360 355 361 356 384 356 385 356 373 357 387 357 374 357 361 358 386 358 389 358 291 359 381 359 376 359 376 360 381 360 360 360 387 361 373 361 388 361 335 362 380 362 389 362 383 363 362 363 390 363 385 364 384 364 378 364 391 365 392 365 393 365 394 366 393 366 392 366 389 367 386 367 369 367 389 368 369 368 335 368 378 369 377 369 385 369 379 370 335 370 394 370 379 371 394 371 392 371 371 372 370 372 362 372 362 373 370 373 390 373 395 374 396 374 397 374 397 375 396 375 398 375 398 376 396 376 399 376 398 377 399 377 400 377 397 378 401 378 402 378 402 379 395 379 397 379 403 380 404 380 405 380 406 381 407 381 408 381 405 382 409 382 403 382 403 383 409 383 410 383 405 384 404 384 408 384 405 385 408 385 407 385 411 386 412 386 413 386 411 387 414 387 412 387 415 388 416 388 411 388 416 389 415 389 417 389 415 390 411 390 413 390 414 391 418 391 412 391 412 392 418 392 419 392 420 393 421 393 422 393 423 394 424 394 420 394 420 395 422 395 425 395 425 396 423 396 420 396 422 397 421 397 426 397 421 398 427 398 426 398 398 399 428 399 397 399 397 400 428 400 429 400 397 401 429 401 401 401 401 402 429 402 430 402 401 403 430 403 402 403 402 404 430 404 431 404 402 405 431 405 395 405 395 406 431 406 432 406 395 407 432 407 396 407 396 408 432 408 433 408 396 409 433 409 399 409 399 410 433 410 434 410 399 411 434 411 435 411 399 412 435 412 400 412 400 413 435 413 436 413 400 414 436 414 398 414 398 415 436 415 428 415 406 416 437 416 438 416 406 417 438 417 407 417 407 418 438 418 439 418 407 419 439 419 405 419 405 420 439 420 440 420 405 421 440 421 409 421 409 422 440 422 441 422 409 423 441 423 442 423 409 424 442 424 410 424 410 425 442 425 403 425 403 426 442 426 443 426 403 427 443 427 404 427 404 428 443 428 444 428 404 429 444 429 408 429 408 430 444 430 437 430 408 431 437 431 406 431 413 432 445 432 415 432 415 433 445 433 446 433 415 434 446 434 417 434 417 435 446 435 447 435 417 436 447 436 416 436 416 437 447 437 448 437 416 438 448 438 411 438 411 439 448 439 449 439 411 440 449 440 414 440 414 441 449 441 450 441 414 442 450 442 418 442 418 443 450 443 419 443 419 444 450 444 451 444 419 445 451 445 412 445 412 446 451 446 452 446 412 447 452 447 445 447 412 448 445 448 413 448 423 449 453 449 424 449 424 450 453 450 454 450 424 451 454 451 420 451 420 452 454 452 455 452 420 453 455 453 456 453 420 454 456 454 421 454 421 455 456 455 457 455 421 456 457 456 427 456 427 457 457 457 458 457 427 458 458 458 426 458 426 459 458 459 459 459 426 460 459 460 422 460 422 461 459 461 460 461 422 462 460 462 425 462 425 463 460 463 461 463 425 464 461 464 423 464 423 465 461 465 453 465 462 466 463 466 464 466 462 467 465 467 466 467 465 468 462 468 464 468 466 469 465 469 467 469 467 470 468 470 466 470 463 471 469 471 464 471 470 472 471 472 472 472 473 473 474 473 475 473 473 474 475 474 476 474 474 475 473 475 472 475 472 476 473 476 470 476 476 477 477 477 473 477 472 478 471 478 478 478 433 479 479 479 434 479 434 480 479 480 480 480 434 481 480 481 435 481 435 482 480 482 481 482 435 483 481 483 436 483 436 484 481 484 482 484 436 485 482 485 483 485 436 486 483 486 428 486 428 487 483 487 484 487 428 488 484 488 429 488 429 489 484 489 485 489 429 490 485 490 430 490 430 491 485 491 486 491 430 492 486 492 431 492 431 493 486 493 487 493 431 494 487 494 488 494 431 495 488 495 432 495 432 496 488 496 433 496 433 497 488 497 479 497 444 498 489 498 490 498 444 499 490 499 437 499 437 500 490 500 491 500 437 501 491 501 438 501 438 502 491 502 492 502 438 503 492 503 439 503 439 504 492 504 493 504 439 505 493 505 440 505 440 506 493 506 494 506 440 507 494 507 441 507 441 508 494 508 442 508 442 509 494 509 495 509 442 510 495 510 496 510 442 511 496 511 443 511 443 512 496 512 489 512 443 513 489 513 444 513 449 514 497 514 450 514 450 515 497 515 498 515 450 516 498 516 451 516 451 517 498 517 499 517 451 518 499 518 452 518 452 519 499 519 500 519 452 520 500 520 501 520 452 521 501 521 445 521 445 522 501 522 502 522 445 523 502 523 446 523 446 524 502 524 503 524 446 525 503 525 447 525 447 526 503 526 504 526 447 527 504 527 505 527 447 528 505 528 448 528 448 529 505 529 449 529 449 530 505 530 506 530 449 531 506 531 497 531 461 532 507 532 453 532 453 533 507 533 508 533 453 534 508 534 454 534 454 535 508 535 509 535 454 536 509 536 455 536 455 537 509 537 510 537 455 538 510 538 456 538 456 539 510 539 457 539 457 540 510 540 511 540 457 541 511 541 458 541 458 542 511 542 512 542 458 543 512 543 459 543 459 544 512 544 513 544 459 545 513 545 514 545 459 546 514 546 460 546 460 547 514 547 461 547 461 548 514 548 507 548 515 549 516 549 517 549 518 550 519 550 520 550 521 551 518 551 520 551 522 552 523 552 521 552 522 553 524 553 523 553 515 554 525 554 526 554 515 555 517 555 525 555 526 556 524 556 522 556 520 557 522 557 521 557 515 558 526 558 522 558 515 559 522 559 520 559 515 560 520 560 516 560 516 561 520 561 519 561 527 562 528 562 529 562 530 563 527 563 529 563 527 564 531 564 528 564 532 565 533 565 534 565 533 566 532 566 535 566 536 567 532 567 534 567 535 568 537 568 533 568 538 569 539 569 540 569 540 570 541 570 542 570 543 571 540 571 542 571 540 572 539 572 541 572 544 573 545 573 546 573 546 574 545 574 547 574 546 575 548 575 544 575 548 576 549 576 544 576 550 577 551 577 552 577 550 578 553 578 551 578 550 579 552 579 554 579 551 580 553 580 555 580 554 581 556 581 550 581 551 582 555 582 557 582 551 583 557 583 558 583 559 584 560 584 561 584 561 585 560 585 562 585 563 586 564 586 565 586 565 587 566 587 563 587 561 588 562 588 563 588 566 589 561 589 563 589 466 590 567 590 462 590 462 591 567 591 568 591 462 592 568 592 463 592 463 593 568 593 569 593 463 594 569 594 469 594 469 595 569 595 570 595 469 596 570 596 464 596 464 597 570 597 571 597 464 598 571 598 465 598 465 599 571 599 572 599 465 600 572 600 467 600 467 601 572 601 573 601 467 602 573 602 468 602 468 603 573 603 574 603 468 604 574 604 466 604 466 605 574 605 567 605 470 606 575 606 576 606 470 607 576 607 471 607 471 608 576 608 577 608 471 609 577 609 478 609 478 610 577 610 472 610 472 611 577 611 578 611 472 612 578 612 474 612 474 613 578 613 579 613 474 614 579 614 475 614 475 615 579 615 476 615 476 616 579 616 580 616 476 617 580 617 581 617 476 618 581 618 477 618 477 619 581 619 473 619 473 620 581 620 575 620 473 621 575 621 470 621 485 622 582 622 486 622 486 623 582 623 487 623 487 624 582 624 583 624 487 625 583 625 488 625 488 626 583 626 479 626 479 627 583 627 584 627 479 628 584 628 480 628 480 629 584 629 585 629 480 630 585 630 481 630 585 631 586 631 481 631 481 632 586 632 482 632 482 633 586 633 587 633 482 634 587 634 483 634 483 635 587 635 588 635 483 636 588 636 484 636 484 637 588 637 589 637 484 638 589 638 485 638 485 639 589 639 582 639 491 640 590 640 492 640 492 641 590 641 591 641 492 642 591 642 493 642 493 643 591 643 494 643 494 644 591 644 592 644 494 645 592 645 593 645 494 646 593 646 495 646 495 647 593 647 594 647 495 648 594 648 496 648 496 649 594 649 595 649 496 650 595 650 489 650 489 651 595 651 596 651 489 652 596 652 490 652 490 653 596 653 597 653 490 654 597 654 491 654 491 655 597 655 590 655 505 656 598 656 599 656 505 657 599 657 506 657 497 658 600 658 498 658 498 659 600 659 499 659 499 660 600 660 601 660 499 661 601 661 500 661 500 662 601 662 602 662 500 663 602 663 501 663 501 664 602 664 603 664 501 665 603 665 502 665 502 666 603 666 503 666 503 667 603 667 604 667 503 668 604 668 598 668 503 669 598 669 504 669 504 670 598 670 505 670 512 671 605 671 513 671 513 672 605 672 514 672 507 673 606 673 508 673 606 674 607 674 508 674 508 675 607 675 608 675 508 676 608 676 509 676 509 677 608 677 609 677 509 678 609 678 510 678 510 679 609 679 610 679 510 680 610 680 611 680 510 681 611 681 511 681 511 682 611 682 612 682 511 683 612 683 512 683 512 684 612 684 605 684 517 685 614 685 525 685 525 686 614 686 615 686 525 687 615 687 616 687 524 688 613 688 617 688 524 689 617 689 523 689 523 690 617 690 618 690 614 691 517 691 622 691 531 692 623 692 528 692 528 693 623 693 624 693 528 694 624 694 529 694 529 695 624 695 625 695 529 696 625 696 530 696 530 697 625 697 626 697 530 698 626 698 627 698 530 699 627 699 527 699 527 700 627 700 623 700 527 701 623 701 531 701 534 702 628 702 536 702 536 703 628 703 629 703 536 704 629 704 532 704 532 705 629 705 630 705 532 706 630 706 535 706 535 707 630 707 537 707 537 708 630 708 631 708 537 709 631 709 533 709 533 710 631 710 632 710 533 711 632 711 534 711 534 712 632 712 628 712 633 713 634 713 540 713 540 714 634 714 538 714 538 715 634 715 539 715 539 716 634 716 635 716 539 717 635 717 636 717 539 718 636 718 541 718 541 719 636 719 637 719 541 720 637 720 542 720 542 721 637 721 638 721 542 722 638 722 543 722 543 723 638 723 639 723 543 724 639 724 540 724 540 725 639 725 633 725 544 726 640 726 545 726 545 727 640 727 547 727 547 728 640 728 641 728 547 729 641 729 546 729 546 730 641 730 642 730 546 731 642 731 548 731 548 732 642 732 643 732 548 733 643 733 549 733 549 734 643 734 644 734 549 735 644 735 544 735 544 736 644 736 640 736 645 737 551 737 646 737 646 738 551 738 558 738 646 739 558 739 647 739 647 740 558 740 557 740 647 741 557 741 648 741 648 742 557 742 555 742 648 743 555 743 553 743 648 744 553 744 649 744 649 745 553 745 550 745 649 746 550 746 650 746 650 747 550 747 651 747 651 748 550 748 556 748 651 749 556 749 652 749 652 750 556 750 554 750 652 751 554 751 653 751 653 752 554 752 552 752 653 753 552 753 645 753 645 754 552 754 551 754 654 755 563 755 562 755 654 756 562 756 560 756 654 757 560 757 655 757 655 758 560 758 656 758 656 759 560 759 559 759 656 760 559 760 657 760 657 761 559 761 561 761 657 762 561 762 658 762 658 763 561 763 566 763 658 764 566 764 659 764 659 765 566 765 565 765 659 766 565 766 660 766 660 767 565 767 564 767 660 768 564 768 661 768 661 769 564 769 662 769 662 770 564 770 563 770 662 771 563 771 654 771 568 772 663 772 569 772 569 773 663 773 664 773 569 774 664 774 570 774 570 775 664 775 665 775 570 776 665 776 571 776 571 777 665 777 666 777 571 778 666 778 572 778 572 779 666 779 573 779 573 780 666 780 667 780 573 781 667 781 574 781 574 782 667 782 668 782 574 783 668 783 669 783 574 784 669 784 567 784 567 785 669 785 670 785 567 786 670 786 671 786 567 787 671 787 568 787 568 788 671 788 663 788 576 789 672 789 577 789 577 790 672 790 673 790 577 791 673 791 578 791 578 792 673 792 674 792 578 793 674 793 579 793 579 794 674 794 675 794 579 795 675 795 580 795 580 796 675 796 676 796 580 797 676 797 581 797 581 798 676 798 677 798 581 799 677 799 678 799 581 800 678 800 575 800 575 801 678 801 679 801 575 802 679 802 576 802 576 803 679 803 672 803 682 804 630 804 683 804 683 805 630 805 629 805 683 806 629 806 628 806 630 807 681 807 631 807 681 808 630 808 682 808 628 809 632 809 684 809 684 810 632 810 631 810 684 811 631 811 681 811 597 812 685 812 590 812 686 813 591 813 590 813 686 814 590 814 685 814 592 815 591 815 683 815 683 816 591 816 686 816 685 817 625 817 624 817 685 818 624 818 687 818 687 819 624 819 623 819 688 820 627 820 626 820 688 821 626 821 625 821 688 822 625 822 685 822 623 823 627 823 687 823 687 824 589 824 689 824 587 825 690 825 588 825 588 826 690 826 689 826 589 827 588 827 689 827 587 828 586 828 690 828 690 829 586 829 585 829 690 830 633 830 639 830 639 831 638 831 690 831 690 832 638 832 691 832 691 833 637 833 636 833 691 834 636 834 692 834 691 835 638 835 637 835 692 836 636 836 635 836 692 837 635 837 693 837 693 838 635 838 634 838 694 839 605 839 695 839 644 840 643 840 695 840 695 841 640 841 644 841 695 842 643 842 696 842 680 843 642 843 641 843 696 844 643 844 642 844 696 845 642 845 680 845 693 846 585 846 584 846 687 847 582 847 589 847 584 848 583 848 693 848 693 849 583 849 688 849 688 850 583 850 582 850 683 851 593 851 592 851 595 852 594 852 684 852 593 853 683 853 684 853 684 854 594 854 593 854 685 855 597 855 688 855 688 856 595 856 684 856 597 857 596 857 688 857 688 858 596 858 595 858 599 859 598 859 681 859 601 860 680 860 697 860 601 861 600 861 680 861 681 862 598 862 684 862 684 863 598 863 604 863 604 864 603 864 684 864 697 865 602 865 601 865 684 866 603 866 697 866 697 867 603 867 602 867 695 868 605 868 612 868 695 869 612 869 697 869 608 870 693 870 609 870 612 871 611 871 697 871 697 872 611 872 610 872 697 873 610 873 609 873 697 874 609 874 693 874 608 875 607 875 693 875 693 876 607 876 692 876 692 877 607 877 606 877 688 878 614 878 622 878 688 879 622 879 693 879 616 880 615 880 688 880 688 881 615 881 614 881 684 882 613 882 616 882 684 883 616 883 688 883 617 884 613 884 684 884 697 885 618 885 684 885 684 886 618 886 617 886 620 887 619 887 697 887 697 888 619 888 618 888 620 889 697 889 693 889 622 890 621 890 693 890 693 891 621 891 620 891 683 892 628 892 684 892 585 893 693 893 690 893 690 894 693 894 633 894 693 895 634 895 633 895 640 896 695 896 697 896 697 897 641 897 640 897 697 898 680 898 641 898 582 899 687 899 688 899 688 900 687 900 627 900 698 901 699 901 700 901 700 902 699 902 701 902 700 903 701 903 702 903 702 904 701 904 703 904 702 905 703 905 704 905 704 906 703 906 705 906 704 907 705 907 706 907 706 908 705 908 707 908 706 909 707 909 708 909 706 910 708 910 709 910 709 911 708 911 710 911 709 912 710 912 711 912 711 913 710 913 712 913 711 914 712 914 713 914 713 915 712 915 699 915 713 916 699 916 698 916 714 917 715 917 716 917 714 918 716 918 717 918 717 919 716 919 718 919 717 920 718 920 719 920 719 921 718 921 720 921 719 922 720 922 721 922 721 923 720 923 722 923 721 924 722 924 723 924 721 925 723 925 724 925 724 926 723 926 725 926 724 927 725 927 726 927 726 928 725 928 727 928 726 929 727 929 728 929 728 930 727 930 729 930 728 931 729 931 730 931 730 932 729 932 715 932 730 933 715 933 714 933 731 934 732 934 733 934 731 935 733 935 734 935 734 936 733 936 735 936 734 937 735 937 736 937 736 938 735 938 737 938 736 939 737 939 738 939 738 940 737 940 739 940 739 941 737 941 740 941 739 942 740 942 741 942 739 943 741 943 742 943 742 944 741 944 743 944 743 945 741 945 744 945 743 946 744 946 745 946 743 947 745 947 746 947 746 948 745 948 732 948 746 949 732 949 731 949 747 950 717 950 748 950 748 951 717 951 749 951 749 952 717 952 719 952 749 953 719 953 750 953 750 954 719 954 721 954 750 955 721 955 751 955 751 956 721 956 724 956 751 957 724 957 752 957 752 958 724 958 753 958 753 959 724 959 726 959 753 960 726 960 728 960 753 961 728 961 754 961 754 962 728 962 730 962 754 963 730 963 755 963 755 964 730 964 714 964 755 965 714 965 747 965 747 966 714 966 717 966 756 967 713 967 757 967 757 968 713 968 698 968 757 969 698 969 758 969 758 970 698 970 700 970 758 971 700 971 702 971 758 972 702 972 759 972 759 973 702 973 704 973 759 974 704 974 760 974 760 975 704 975 706 975 760 976 706 976 761 976 761 977 706 977 709 977 761 978 709 978 762 978 762 979 709 979 711 979 762 980 711 980 763 980 763 981 711 981 713 981 763 982 713 982 756 982 764 983 743 983 765 983 765 984 743 984 746 984 765 985 746 985 766 985 766 986 746 986 731 986 766 987 731 987 767 987 767 988 731 988 768 988 768 989 731 989 734 989 768 990 734 990 769 990 769 991 734 991 736 991 769 992 736 992 738 992 769 993 738 993 770 993 770 994 738 994 739 994 770 995 739 995 771 995 771 996 739 996 772 996 772 997 739 997 742 997 772 998 742 998 743 998 772 999 743 999 764 999 773 1000 774 1000 775 1000 776 1001 777 1001 774 1001 775 1002 774 1002 778 1002 774 1003 777 1003 779 1003 779 1004 778 1004 774 1004 780 1005 776 1005 774 1005 773 1006 775 1006 781 1006 647 1007 782 1007 783 1007 647 1008 783 1008 646 1008 646 1009 783 1009 645 1009 645 1010 783 1010 784 1010 645 1011 784 1011 653 1011 653 1012 784 1012 785 1012 653 1013 785 1013 652 1013 652 1014 785 1014 786 1014 652 1015 786 1015 651 1015 651 1016 786 1016 787 1016 651 1017 787 1017 650 1017 650 1018 787 1018 649 1018 649 1019 787 1019 788 1019 649 1020 788 1020 648 1020 648 1021 788 1021 789 1021 648 1022 789 1022 647 1022 647 1023 789 1023 782 1023 661 1024 790 1024 660 1024 660 1025 790 1025 791 1025 660 1026 791 1026 659 1026 659 1027 791 1027 792 1027 659 1028 792 1028 658 1028 658 1029 792 1029 793 1029 658 1030 793 1030 657 1030 657 1031 793 1031 794 1031 657 1032 794 1032 656 1032 656 1033 794 1033 795 1033 656 1034 795 1034 655 1034 655 1035 795 1035 796 1035 655 1036 796 1036 654 1036 654 1037 796 1037 797 1037 654 1038 797 1038 662 1038 662 1039 797 1039 798 1039 662 1040 798 1040 661 1040 661 1041 798 1041 790 1041 799 1042 800 1042 801 1042 799 1043 802 1043 800 1043 800 1044 802 1044 803 1044 800 1045 803 1045 804 1045 799 1046 801 1046 805 1046 805 1047 806 1047 799 1047 670 1048 807 1048 671 1048 671 1049 807 1049 808 1049 671 1050 808 1050 663 1050 663 1051 808 1051 809 1051 663 1052 809 1052 664 1052 664 1053 809 1053 810 1053 664 1054 810 1054 665 1054 665 1055 810 1055 811 1055 665 1056 811 1056 666 1056 666 1057 811 1057 812 1057 666 1058 812 1058 667 1058 667 1059 812 1059 813 1059 667 1060 813 1060 668 1060 668 1061 813 1061 669 1061 669 1062 813 1062 814 1062 669 1063 814 1063 670 1063 670 1064 814 1064 807 1064 678 1065 815 1065 679 1065 679 1066 815 1066 816 1066 679 1067 816 1067 672 1067 672 1068 816 1068 817 1068 672 1069 817 1069 818 1069 672 1070 818 1070 673 1070 673 1071 818 1071 819 1071 673 1072 819 1072 674 1072 674 1073 819 1073 820 1073 674 1074 820 1074 675 1074 675 1075 820 1075 821 1075 675 1076 821 1076 676 1076 676 1077 821 1077 677 1077 677 1078 821 1078 822 1078 677 1079 822 1079 678 1079 678 1080 822 1080 823 1080 678 1081 823 1081 815 1081 680 1082 824 1082 825 1082 680 1083 825 1083 696 1083 694 1084 826 1084 692 1084 692 1085 827 1085 691 1085 691 1086 827 1086 828 1086 691 1087 828 1087 690 1087 690 1088 828 1088 829 1088 690 1089 829 1089 830 1089 690 1090 830 1090 689 1090 689 1091 831 1091 687 1091 687 1092 831 1092 832 1092 687 1093 832 1093 685 1093 685 1094 832 1094 833 1094 685 1095 833 1095 834 1095 685 1096 834 1096 686 1096 686 1097 835 1097 683 1097 683 1098 835 1098 836 1098 683 1099 836 1099 682 1099 681 1100 682 1100 837 1100 837 1101 838 1101 681 1101 712 1102 839 1102 699 1102 699 1103 839 1103 840 1103 699 1104 840 1104 701 1104 701 1105 840 1105 841 1105 701 1106 841 1106 703 1106 703 1107 841 1107 842 1107 703 1108 842 1108 843 1108 703 1109 843 1109 705 1109 705 1110 843 1110 707 1110 707 1111 843 1111 844 1111 707 1112 844 1112 708 1112 708 1113 844 1113 845 1113 708 1114 845 1114 710 1114 710 1115 845 1115 846 1115 710 1116 846 1116 712 1116 712 1117 846 1117 839 1117 716 1118 847 1118 848 1118 716 1119 848 1119 718 1119 718 1120 848 1120 849 1120 718 1121 849 1121 720 1121 720 1122 849 1122 850 1122 720 1123 850 1123 722 1123 722 1124 850 1124 723 1124 723 1125 850 1125 851 1125 723 1126 851 1126 725 1126 725 1127 851 1127 852 1127 725 1128 852 1128 727 1128 727 1129 852 1129 853 1129 727 1130 853 1130 729 1130 729 1131 853 1131 854 1131 729 1132 854 1132 715 1132 715 1133 854 1133 855 1133 715 1134 855 1134 847 1134 715 1135 847 1135 716 1135 744 1136 856 1136 745 1136 745 1137 856 1137 857 1137 745 1138 857 1138 732 1138 732 1139 857 1139 858 1139 732 1140 858 1140 859 1140 732 1141 859 1141 733 1141 733 1142 859 1142 860 1142 733 1143 860 1143 735 1143 735 1144 860 1144 861 1144 735 1145 861 1145 737 1145 737 1146 861 1146 862 1146 737 1147 862 1147 740 1147 740 1148 862 1148 863 1148 740 1149 863 1149 741 1149 741 1150 863 1150 856 1150 741 1151 856 1151 744 1151 753 1152 864 1152 752 1152 752 1153 864 1153 865 1153 752 1154 865 1154 751 1154 751 1155 865 1155 866 1155 751 1156 866 1156 750 1156 750 1157 866 1157 867 1157 750 1158 867 1158 749 1158 749 1159 867 1159 748 1159 748 1160 867 1160 868 1160 748 1161 868 1161 747 1161 747 1162 868 1162 869 1162 747 1163 869 1163 870 1163 747 1164 870 1164 755 1164 755 1165 870 1165 754 1165 754 1166 870 1166 871 1166 754 1167 871 1167 753 1167 753 1168 871 1168 864 1168 872 1169 873 1169 874 1169 872 1170 874 1170 875 1170 873 1171 876 1171 877 1171 877 1172 874 1172 873 1172 876 1173 878 1173 877 1173 877 1174 878 1174 879 1174 758 1175 880 1175 881 1175 758 1176 881 1176 757 1176 757 1177 881 1177 882 1177 757 1178 882 1178 756 1178 756 1179 882 1179 883 1179 756 1180 883 1180 763 1180 763 1181 883 1181 884 1181 763 1182 884 1182 762 1182 762 1183 884 1183 885 1183 762 1184 885 1184 761 1184 761 1185 885 1185 886 1185 761 1186 886 1186 760 1186 760 1187 886 1187 887 1187 760 1188 887 1188 759 1188 759 1189 887 1189 888 1189 759 1190 888 1190 758 1190 758 1191 888 1191 880 1191 767 1192 889 1192 766 1192 766 1193 889 1193 890 1193 766 1194 890 1194 765 1194 765 1195 890 1195 891 1195 765 1196 891 1196 764 1196 764 1197 891 1197 772 1197 772 1198 891 1198 892 1198 772 1199 892 1199 893 1199 772 1200 893 1200 771 1200 771 1201 893 1201 894 1201 771 1202 894 1202 770 1202 770 1203 894 1203 769 1203 769 1204 894 1204 895 1204 769 1205 895 1205 896 1205 769 1206 896 1206 768 1206 768 1207 896 1207 897 1207 768 1208 897 1208 767 1208 767 1209 897 1209 889 1209 898 1210 269 1210 899 1210 899 1211 269 1211 268 1211 900 1212 784 1212 901 1212 901 1213 784 1213 783 1213 901 1214 783 1214 902 1214 902 1215 783 1215 782 1215 902 1216 782 1216 789 1216 902 1217 789 1217 903 1217 903 1218 789 1218 788 1218 903 1219 788 1219 904 1219 904 1220 788 1220 905 1220 905 1221 788 1221 787 1221 905 1222 787 1222 906 1222 906 1223 787 1223 786 1223 906 1224 786 1224 785 1224 906 1225 785 1225 907 1225 907 1226 785 1226 784 1226 907 1227 784 1227 900 1227 908 1228 797 1228 796 1228 908 1229 796 1229 909 1229 909 1230 796 1230 795 1230 909 1231 795 1231 910 1231 910 1232 795 1232 794 1232 910 1233 794 1233 911 1233 911 1234 794 1234 793 1234 911 1235 793 1235 912 1235 912 1236 793 1236 792 1236 912 1237 792 1237 913 1237 913 1238 792 1238 791 1238 913 1239 791 1239 914 1239 914 1240 791 1240 790 1240 914 1241 790 1241 915 1241 915 1242 790 1242 916 1242 916 1243 790 1243 798 1243 916 1244 798 1244 797 1244 916 1245 797 1245 908 1245 354 1246 348 1246 917 1246 354 1247 917 1247 918 1247 358 1248 919 1248 347 1248 919 1249 920 1249 921 1249 347 1250 919 1250 921 1250 264 1251 277 1251 254 1251 254 1252 277 1252 252 1252 301 1253 879 1253 878 1253 922 1254 923 1254 924 1254 925 1255 813 1255 926 1255 926 1256 813 1256 812 1256 925 1257 814 1257 813 1257 808 1258 924 1258 923 1258 808 1259 923 1259 809 1259 811 1260 926 1260 812 1260 808 1261 807 1261 924 1261 924 1262 807 1262 925 1262 925 1263 807 1263 814 1263 923 1264 810 1264 809 1264 926 1265 811 1265 923 1265 923 1266 811 1266 810 1266 927 1267 928 1267 929 1267 822 1268 821 1268 930 1268 930 1269 821 1269 931 1269 929 1270 816 1270 815 1270 930 1271 823 1271 822 1271 929 1272 817 1272 816 1272 929 1273 815 1273 930 1273 930 1274 815 1274 823 1274 931 1275 821 1275 820 1275 928 1276 819 1276 818 1276 817 1277 929 1277 928 1277 931 1278 820 1278 928 1278 928 1279 820 1279 819 1279 928 1280 818 1280 817 1280 932 1281 933 1281 934 1281 935 1282 934 1282 933 1282 935 1283 933 1283 936 1283 932 1284 937 1284 933 1284 932 1285 938 1285 937 1285 937 1286 938 1286 939 1286 940 1287 941 1287 942 1287 942 1288 941 1288 943 1288 942 1289 943 1289 944 1289 945 1290 946 1290 373 1290 373 1291 946 1291 388 1291 947 1292 948 1292 949 1292 949 1293 948 1293 950 1293 951 1294 686 1294 952 1294 686 1295 951 1295 835 1295 834 1296 952 1296 686 1296 952 1297 834 1297 953 1297 834 1298 833 1298 953 1298 953 1299 833 1299 832 1299 953 1300 832 1300 954 1300 954 1301 832 1301 831 1301 954 1302 831 1302 955 1302 831 1303 689 1303 955 1303 955 1304 689 1304 956 1304 956 1305 689 1305 830 1305 956 1306 830 1306 957 1306 830 1307 829 1307 957 1307 957 1308 829 1308 958 1308 829 1309 828 1309 958 1309 958 1310 828 1310 827 1310 958 1311 827 1311 959 1311 827 1312 692 1312 959 1312 959 1313 692 1313 826 1313 959 1314 826 1314 960 1314 826 1315 694 1315 960 1315 960 1316 694 1316 961 1316 961 1317 694 1317 695 1317 961 1318 695 1318 962 1318 695 1319 696 1319 962 1319 696 1320 825 1320 962 1320 962 1321 825 1321 963 1321 825 1322 824 1322 963 1322 963 1323 824 1323 964 1323 964 1324 824 1324 838 1324 964 1325 838 1325 965 1325 838 1326 837 1326 965 1326 965 1327 837 1327 966 1327 966 1328 837 1328 682 1328 966 1329 682 1329 967 1329 682 1330 836 1330 967 1330 835 1331 951 1331 967 1331 835 1332 967 1332 836 1332 968 1333 969 1333 393 1333 968 1334 393 1334 394 1334 970 1335 971 1335 972 1335 965 1336 333 1336 964 1336 844 1337 843 1337 874 1337 319 1338 843 1338 842 1338 319 1339 842 1339 333 1339 960 1340 961 1340 849 1340 849 1341 961 1341 850 1341 850 1342 961 1342 962 1342 850 1343 962 1343 963 1343 859 1344 957 1344 958 1344 874 1345 843 1345 319 1345 333 1346 842 1346 841 1346 333 1347 841 1347 964 1347 964 1348 841 1348 963 1348 965 1349 966 1349 333 1349 333 1350 966 1350 970 1350 963 1351 841 1351 840 1351 958 1352 959 1352 859 1352 859 1353 959 1353 960 1353 857 1354 856 1354 301 1354 854 1355 853 1355 874 1355 970 1356 967 1356 951 1356 850 1357 963 1357 840 1357 850 1358 840 1358 851 1358 848 1359 847 1359 860 1359 846 1360 845 1360 853 1360 853 1361 845 1361 874 1361 874 1362 845 1362 844 1362 859 1363 960 1363 860 1363 860 1364 960 1364 849 1364 860 1365 849 1365 848 1365 295 1366 857 1366 301 1366 863 1367 877 1367 879 1367 863 1368 862 1368 877 1368 877 1369 862 1369 874 1369 874 1370 862 1370 854 1370 862 1371 861 1371 854 1371 854 1372 861 1372 855 1372 840 1373 839 1373 851 1373 301 1374 856 1374 879 1374 879 1375 856 1375 863 1375 860 1376 847 1376 861 1376 861 1377 847 1377 855 1377 846 1378 853 1378 852 1378 952 1379 953 1379 947 1379 947 1380 953 1380 954 1380 851 1381 839 1381 852 1381 852 1382 839 1382 846 1382 967 1383 970 1383 966 1383 954 1384 948 1384 947 1384 948 1385 954 1385 295 1385 295 1386 954 1386 955 1386 955 1387 956 1387 295 1387 295 1388 956 1388 957 1388 859 1389 858 1389 957 1389 957 1390 858 1390 295 1390 295 1391 858 1391 857 1391 874 1392 319 1392 875 1392 781 1393 868 1393 867 1393 781 1394 867 1394 773 1394 773 1395 867 1395 774 1395 774 1396 867 1396 866 1396 774 1397 866 1397 780 1397 780 1398 866 1398 865 1398 780 1399 865 1399 776 1399 776 1400 865 1400 864 1400 776 1401 864 1401 777 1401 777 1402 864 1402 871 1402 777 1403 871 1403 779 1403 779 1404 871 1404 870 1404 779 1405 870 1405 778 1405 778 1406 870 1406 775 1406 775 1407 870 1407 869 1407 775 1408 869 1408 781 1408 781 1409 869 1409 868 1409 873 1410 872 1410 973 1410 973 1411 872 1411 974 1411 872 1412 875 1412 974 1412 975 1413 878 1413 876 1413 887 1414 978 1414 979 1414 887 1415 979 1415 888 1415 888 1416 979 1416 980 1416 888 1417 980 1417 880 1417 880 1418 980 1418 981 1418 880 1419 981 1419 982 1419 880 1420 982 1420 881 1420 881 1421 982 1421 882 1421 882 1422 982 1422 983 1422 882 1423 983 1423 984 1423 882 1424 984 1424 883 1424 883 1425 984 1425 985 1425 883 1426 985 1426 884 1426 884 1427 985 1427 986 1427 884 1428 986 1428 885 1428 885 1429 986 1429 987 1429 885 1430 987 1430 886 1430 886 1431 987 1431 887 1431 887 1432 987 1432 978 1432 895 1433 988 1433 896 1433 896 1434 988 1434 989 1434 896 1435 989 1435 897 1435 897 1436 989 1436 990 1436 897 1437 990 1437 889 1437 889 1438 990 1438 991 1438 889 1439 991 1439 992 1439 889 1440 992 1440 890 1440 890 1441 992 1441 993 1441 890 1442 993 1442 891 1442 891 1443 993 1443 892 1443 892 1444 993 1444 994 1444 892 1445 994 1445 995 1445 892 1446 995 1446 893 1446 893 1447 995 1447 894 1447 894 1448 995 1448 996 1448 894 1449 996 1449 895 1449 895 1450 996 1450 988 1450 269 1451 898 1451 284 1451 269 1452 284 1452 270 1452 997 1453 806 1453 805 1453 997 1454 805 1454 998 1454 998 1455 805 1455 801 1455 998 1456 801 1456 999 1456 999 1457 801 1457 800 1457 999 1458 800 1458 1000 1458 1000 1459 800 1459 804 1459 1000 1460 804 1460 1001 1460 1001 1461 804 1461 803 1461 1001 1462 803 1462 1002 1462 1002 1463 803 1463 1003 1463 1003 1464 803 1464 802 1464 1003 1465 802 1465 1004 1465 1004 1466 802 1466 799 1466 1004 1467 799 1467 1005 1467 1005 1468 799 1468 806 1468 1005 1469 806 1469 997 1469 1006 1470 1007 1470 1008 1470 1006 1471 1008 1471 1009 1471 1010 1472 1011 1472 1012 1472 1012 1473 1011 1473 1013 1473 1012 1474 1013 1474 1014 1474 1014 1475 1013 1475 1015 1475 1014 1476 1015 1476 1016 1476 1016 1477 1015 1477 1017 1477 1016 1478 1017 1478 1018 1478 1018 1479 1017 1479 1019 1479 1019 1480 1017 1480 1020 1480 1019 1481 1020 1481 1021 1481 1019 1482 1021 1482 1022 1482 1022 1483 1021 1483 1007 1483 1022 1484 1007 1484 1006 1484 1023 1485 1024 1485 1025 1485 1023 1486 1025 1486 1026 1486 1026 1487 1025 1487 1027 1487 1026 1488 1027 1488 1028 1488 1030 1489 1031 1489 1032 1489 1032 1490 1031 1490 1033 1490 1032 1491 1033 1491 1034 1491 1034 1492 1033 1492 1035 1492 1035 1493 1033 1493 1036 1493 1035 1494 1036 1494 1037 1494 1035 1495 1037 1495 1038 1495 1038 1496 1037 1496 1024 1496 1038 1497 1024 1497 1023 1497 1039 1498 1040 1498 1041 1498 1040 1499 903 1499 1041 1499 906 1500 1042 1500 905 1500 1043 1501 907 1501 900 1501 1040 1502 902 1502 903 1502 1041 1503 903 1503 904 1503 1041 1504 904 1504 905 1504 1043 1505 900 1505 901 1505 1043 1506 901 1506 1040 1506 1040 1507 901 1507 902 1507 1042 1508 906 1508 1043 1508 1043 1509 906 1509 907 1509 1041 1510 905 1510 1042 1510 1044 1511 1045 1511 1046 1511 909 1512 1045 1512 908 1512 1047 1513 908 1513 1045 1513 1045 1514 909 1514 910 1514 914 1515 1048 1515 913 1515 1045 1516 910 1516 1046 1516 1046 1517 910 1517 911 1517 911 1518 912 1518 1046 1518 912 1519 913 1519 1046 1519 1046 1520 913 1520 1048 1520 914 1521 915 1521 1048 1521 1048 1522 915 1522 1047 1522 1047 1523 915 1523 916 1523 1047 1524 916 1524 908 1524 1049 1525 1050 1525 1051 1525 1050 1526 1052 1526 1051 1526 1051 1527 1053 1527 1054 1527 1050 1528 1049 1528 1055 1528 1050 1529 1055 1529 1056 1529 1052 1530 1053 1530 1051 1530 1056 1531 1055 1531 1057 1531 1058 1532 1059 1532 1060 1532 1060 1533 1059 1533 1061 1533 1060 1534 1061 1534 1062 1534 1063 1535 1009 1535 1010 1535 1063 1536 1010 1536 1064 1536 1064 1537 1010 1537 1012 1537 1064 1538 1012 1538 1065 1538 1065 1539 1012 1539 1014 1539 1065 1540 1014 1540 1066 1540 1066 1541 1014 1541 1016 1541 1066 1542 1016 1542 1067 1542 1067 1543 1016 1543 1018 1543 1067 1544 1018 1544 1068 1544 1068 1545 1018 1545 1019 1545 1068 1546 1019 1546 1069 1546 1069 1547 1019 1547 1022 1547 1069 1548 1022 1548 1070 1548 1070 1549 1022 1549 1006 1549 1070 1550 1006 1550 1009 1550 1070 1551 1009 1551 1063 1551 1071 1552 1005 1552 997 1552 1071 1553 997 1553 1072 1553 1072 1554 997 1554 1073 1554 1073 1555 997 1555 998 1555 1073 1556 998 1556 1074 1556 1074 1557 998 1557 999 1557 1074 1558 999 1558 1075 1558 1075 1559 999 1559 1000 1559 1075 1560 1000 1560 1001 1560 1075 1561 1001 1561 1076 1561 1076 1562 1001 1562 1002 1562 1076 1563 1002 1563 1077 1563 1077 1564 1002 1564 1003 1564 1077 1565 1003 1565 1078 1565 1078 1566 1003 1566 1004 1566 1078 1567 1004 1567 1071 1567 1071 1568 1004 1568 1005 1568 1079 1569 1028 1569 1029 1569 1079 1570 1029 1570 1080 1570 1080 1571 1029 1571 1030 1571 1080 1572 1030 1572 1081 1572 1081 1573 1030 1573 1032 1573 1081 1574 1032 1574 1082 1574 1082 1575 1032 1575 1034 1575 1082 1576 1034 1576 1083 1576 1083 1577 1034 1577 1035 1577 1083 1578 1035 1578 1084 1578 1084 1579 1035 1579 1085 1579 1085 1580 1035 1580 1038 1580 1085 1581 1038 1581 1086 1581 1086 1582 1038 1582 1023 1582 1086 1583 1023 1583 1087 1583 1087 1584 1023 1584 1026 1584 1087 1585 1026 1585 1028 1585 1087 1586 1028 1586 1079 1586 917 1587 1088 1587 918 1587 918 1588 1088 1588 1089 1588 920 1589 1090 1589 921 1589 921 1590 1090 1590 1091 1590 260 1591 261 1591 259 1591 259 1592 261 1592 1094 1592 1095 1593 304 1593 1096 1593 1096 1594 304 1594 303 1594 1096 1595 303 1595 258 1595 258 1596 303 1596 302 1596 878 1597 975 1597 301 1597 301 1598 975 1598 299 1598 925 1599 289 1599 924 1599 924 1600 289 1600 308 1600 924 1601 308 1601 922 1601 923 1602 922 1602 307 1602 307 1603 922 1603 308 1603 923 1604 307 1604 297 1604 923 1605 297 1605 926 1605 926 1606 297 1606 925 1606 930 1607 298 1607 929 1607 929 1608 298 1608 306 1608 929 1609 306 1609 927 1609 928 1610 927 1610 294 1610 294 1611 927 1611 306 1611 928 1612 294 1612 293 1612 928 1613 293 1613 931 1613 298 1614 930 1614 293 1614 293 1615 930 1615 931 1615 937 1616 309 1616 317 1616 937 1617 317 1617 933 1617 933 1618 317 1618 316 1618 933 1619 316 1619 936 1619 936 1620 316 1620 315 1620 936 1621 315 1621 935 1621 935 1622 315 1622 313 1622 935 1623 313 1623 312 1623 935 1624 312 1624 934 1624 934 1625 312 1625 311 1625 934 1626 311 1626 932 1626 932 1627 311 1627 938 1627 938 1628 311 1628 314 1628 938 1629 314 1629 310 1629 938 1630 310 1630 939 1630 939 1631 310 1631 309 1631 939 1632 309 1632 937 1632 944 1633 297 1633 942 1633 942 1634 297 1634 296 1634 295 1635 950 1635 948 1635 950 1636 946 1636 949 1636 949 1637 946 1637 945 1637 971 1638 951 1638 952 1638 949 1639 971 1639 947 1639 947 1640 971 1640 952 1640 951 1641 971 1641 970 1641 971 1642 969 1642 972 1642 972 1643 969 1643 968 1643 333 1644 970 1644 972 1644 319 1645 318 1645 875 1645 875 1646 318 1646 974 1646 302 1647 300 1647 976 1647 976 1648 300 1648 1097 1648 976 1649 1097 1649 977 1649 1097 1650 1098 1650 977 1650 275 1651 281 1651 337 1651 275 1652 337 1652 1099 1652 336 1653 1100 1653 337 1653 337 1654 1100 1654 1099 1654 272 1655 271 1655 1101 1655 1101 1656 271 1656 274 1656 1103 1657 325 1657 266 1657 266 1658 325 1658 285 1658 1042 1659 342 1659 1041 1659 1041 1660 342 1660 328 1660 1041 1661 328 1661 1039 1661 1040 1662 1039 1662 338 1662 338 1663 1039 1663 328 1663 1040 1664 338 1664 330 1664 1040 1665 330 1665 1043 1665 342 1666 1042 1666 330 1666 330 1667 1042 1667 1043 1667 1048 1668 331 1668 1046 1668 1046 1669 331 1669 332 1669 1046 1670 332 1670 1044 1670 1045 1671 1044 1671 334 1671 334 1672 1044 1672 332 1672 1045 1673 334 1673 329 1673 1045 1674 329 1674 1047 1674 1047 1675 329 1675 1048 1675 1048 1676 329 1676 331 1676 344 1677 1049 1677 1051 1677 344 1678 1051 1678 326 1678 326 1679 1051 1679 1054 1679 326 1680 1054 1680 327 1680 327 1681 1054 1681 1053 1681 327 1682 1053 1682 339 1682 339 1683 1053 1683 1052 1683 339 1684 1052 1684 1050 1684 339 1685 1050 1685 340 1685 340 1686 1050 1686 1056 1686 340 1687 1056 1687 341 1687 341 1688 1056 1688 1057 1688 341 1689 1057 1689 343 1689 343 1690 1057 1690 1055 1690 343 1691 1055 1691 345 1691 345 1692 1055 1692 344 1692 344 1693 1055 1693 1049 1693 321 1694 320 1694 1060 1694 1060 1695 320 1695 1058 1695 1058 1696 320 1696 1059 1696 1059 1697 320 1697 330 1697 325 1698 1061 1698 330 1698 330 1699 1061 1699 1059 1699 325 1700 1062 1700 1061 1700 1104 1701 1070 1701 1105 1701 1105 1702 1070 1702 1063 1702 1105 1703 1063 1703 1106 1703 1106 1704 1063 1704 1064 1704 1106 1705 1064 1705 1107 1705 1107 1706 1064 1706 1065 1706 1107 1707 1065 1707 1108 1707 1108 1708 1065 1708 1066 1708 1108 1709 1066 1709 1109 1709 1109 1710 1066 1710 1067 1710 1109 1711 1067 1711 1110 1711 1110 1712 1067 1712 1068 1712 1110 1713 1068 1713 1111 1713 1111 1714 1068 1714 1112 1714 1112 1715 1068 1715 1069 1715 1112 1716 1069 1716 1104 1716 1104 1717 1069 1717 1070 1717 1113 1718 1072 1718 1114 1718 1114 1719 1072 1719 1073 1719 1114 1720 1073 1720 1115 1720 1115 1721 1073 1721 1074 1721 1115 1722 1074 1722 1116 1722 1116 1723 1074 1723 1075 1723 1116 1724 1075 1724 1117 1724 1117 1725 1075 1725 1076 1725 1117 1726 1076 1726 1118 1726 1118 1727 1076 1727 1077 1727 1118 1728 1077 1728 1119 1728 1119 1729 1077 1729 1078 1729 1119 1730 1078 1730 1120 1730 1120 1731 1078 1731 1071 1731 1120 1732 1071 1732 1113 1732 1113 1733 1071 1733 1072 1733 1121 1734 1086 1734 1122 1734 1122 1735 1086 1735 1087 1735 1122 1736 1087 1736 1123 1736 1123 1737 1087 1737 1079 1737 1123 1738 1079 1738 1124 1738 1124 1739 1079 1739 1125 1739 1125 1740 1079 1740 1080 1740 1125 1741 1080 1741 1126 1741 1126 1742 1080 1742 1081 1742 1126 1743 1081 1743 1127 1743 1127 1744 1081 1744 1082 1744 1127 1745 1082 1745 1083 1745 1127 1746 1083 1746 1128 1746 1128 1747 1083 1747 1084 1747 1128 1748 1084 1748 1129 1748 1129 1749 1084 1749 1085 1749 1129 1750 1085 1750 1086 1750 1129 1751 1086 1751 1121 1751 918 1752 1089 1752 324 1752 324 1753 1089 1753 323 1753 876 1754 873 1754 973 1754 1133 1755 1134 1755 1135 1755 1135 1756 1134 1756 1136 1756 1135 1757 1137 1757 1138 1757 1138 1758 1137 1758 1130 1758 1139 1759 1140 1759 973 1759 973 1760 1140 1760 1138 1760 973 1761 1138 1761 876 1761 876 1762 1138 1762 1130 1762 876 1763 1130 1763 975 1763 975 1764 1130 1764 1132 1764 1091 1765 1141 1765 1142 1765 917 1766 921 1766 1088 1766 1088 1767 921 1767 1143 1767 1088 1768 1143 1768 1144 1768 921 1769 1091 1769 1143 1769 1143 1770 1091 1770 1142 1770 1143 1771 1142 1771 1136 1771 1136 1772 1142 1772 1145 1772 1136 1773 1145 1773 1135 1773 1135 1774 1145 1774 1146 1774 1135 1775 1146 1775 1137 1775 1137 1776 1146 1776 1147 1776 290 1777 292 1777 920 1777 920 1778 292 1778 1090 1778 295 1779 291 1779 950 1779 950 1780 291 1780 946 1780 949 1781 945 1781 971 1781 971 1782 945 1782 969 1782 972 1783 968 1783 333 1783 333 1784 968 1784 335 1784 1148 1785 1109 1785 1110 1785 1148 1786 1110 1786 1149 1786 1149 1787 1110 1787 1111 1787 1149 1788 1111 1788 1112 1788 1149 1789 1112 1789 1150 1789 1150 1790 1112 1790 1104 1790 1150 1791 1104 1791 1151 1791 1151 1792 1104 1792 1105 1792 1151 1793 1105 1793 1152 1793 1152 1794 1105 1794 1106 1794 1152 1795 1106 1795 1153 1795 1108 1796 1154 1796 1155 1796 1108 1797 1155 1797 1107 1797 1109 1798 1148 1798 1154 1798 1109 1799 1154 1799 1108 1799 1153 1800 1106 1800 1107 1800 1153 1801 1107 1801 1155 1801 1156 1802 1114 1802 1157 1802 1157 1803 1114 1803 1115 1803 1157 1804 1115 1804 1158 1804 1115 1805 1116 1805 1158 1805 1158 1806 1116 1806 1159 1806 1159 1807 1116 1807 1117 1807 1159 1808 1117 1808 1160 1808 1161 1809 1118 1809 1119 1809 1161 1810 1119 1810 1162 1810 1162 1811 1119 1811 1163 1811 1163 1812 1119 1812 1120 1812 1163 1813 1120 1813 1164 1813 1164 1814 1120 1814 1113 1814 1164 1815 1113 1815 1156 1815 1156 1816 1113 1816 1114 1816 1160 1817 1117 1817 1118 1817 1160 1818 1118 1818 1161 1818 1121 1819 1122 1819 1165 1819 1121 1820 1165 1820 1166 1820 1121 1821 1166 1821 1129 1821 1129 1822 1166 1822 1167 1822 1129 1823 1167 1823 1128 1823 1128 1824 1167 1824 1168 1824 1128 1825 1168 1825 1127 1825 1165 1826 1122 1826 1123 1826 1165 1827 1123 1827 1169 1827 1169 1828 1123 1828 1170 1828 1127 1829 1168 1829 1171 1829 1127 1830 1171 1830 1126 1830 1126 1831 1171 1831 1172 1831 1126 1832 1172 1832 1125 1832 1125 1833 1172 1833 1170 1833 1125 1834 1170 1834 1124 1834 1123 1835 1124 1835 1170 1835 324 1836 354 1836 918 1836 917 1837 348 1837 921 1837 348 1838 347 1838 921 1838 290 1839 920 1839 919 1839 358 1840 290 1840 919 1840 291 1841 388 1841 946 1841 969 1842 945 1842 393 1842 393 1843 945 1843 373 1843 372 1844 393 1844 373 1844 335 1845 968 1845 394 1845 1148 1846 353 1846 1154 1846 1154 1847 353 1847 369 1847 1154 1848 369 1848 1155 1848 1155 1849 369 1849 386 1849 1155 1850 386 1850 1153 1850 1153 1851 386 1851 385 1851 1153 1852 385 1852 1152 1852 1152 1853 385 1853 1151 1853 1151 1854 385 1854 377 1854 1151 1855 377 1855 1150 1855 1150 1856 377 1856 365 1856 1150 1857 365 1857 346 1857 1150 1858 346 1858 1149 1858 1149 1859 346 1859 355 1859 1149 1860 355 1860 1148 1860 1148 1861 355 1861 353 1861 1161 1862 378 1862 1160 1862 1160 1863 378 1863 384 1863 1160 1864 384 1864 1159 1864 1159 1865 384 1865 383 1865 1159 1866 383 1866 1158 1866 1158 1867 383 1867 1157 1867 1157 1868 383 1868 390 1868 1157 1869 390 1869 1156 1869 1156 1870 390 1870 370 1870 1156 1871 370 1871 1164 1871 1164 1872 370 1872 350 1872 1164 1873 350 1873 1163 1873 1163 1874 350 1874 352 1874 1163 1875 352 1875 1162 1875 1162 1876 352 1876 366 1876 1162 1877 366 1877 1161 1877 1161 1878 366 1878 378 1878 1171 1879 371 1879 362 1879 1171 1880 362 1880 1172 1880 1172 1881 362 1881 360 1881 1172 1882 360 1882 1170 1882 1170 1883 360 1883 381 1883 1170 1884 381 1884 1169 1884 1169 1885 381 1885 356 1885 1169 1886 356 1886 1165 1886 1165 1887 356 1887 357 1887 1165 1888 357 1888 1166 1888 1166 1889 357 1889 358 1889 1166 1890 358 1890 1167 1890 1167 1891 358 1891 349 1891 1167 1892 349 1892 351 1892 1167 1893 351 1893 1168 1893 1168 1894 351 1894 371 1894 1168 1895 371 1895 1171 1895 1173 1896 1174 1896 1175 1896 1176 1897 1177 1897 1178 1897 1178 1898 1177 1898 1179 1898 1178 1899 1179 1899 1180 1899 1175 1900 1174 1900 1181 1900 1179 1901 1182 1901 1180 1901 1180 1902 1182 1902 1183 1902 1180 1903 1183 1903 1184 1903 1181 1904 1174 1904 1185 1904 1181 1905 1185 1905 1186 1905 1186 1906 1185 1906 1177 1906 1186 1907 1177 1907 1176 1907 1184 1908 1183 1908 1187 1908 1184 1909 1187 1909 1188 1909 1188 1910 1187 1910 1189 1910 1188 1911 1189 1911 1173 1911 1188 1912 1173 1912 1175 1912 1176 1913 1190 1913 1191 1913 1176 1914 1191 1914 1186 1914 1186 1915 1191 1915 1192 1915 1186 1916 1192 1916 1181 1916 1181 1917 1192 1917 1193 1917 1181 1918 1193 1918 1175 1918 1175 1919 1193 1919 1194 1919 1175 1920 1194 1920 1188 1920 1188 1921 1194 1921 1195 1921 1188 1922 1195 1922 1184 1922 1184 1923 1195 1923 1196 1923 1184 1924 1196 1924 1197 1924 1184 1925 1197 1925 1180 1925 1180 1926 1197 1926 1198 1926 1180 1927 1198 1927 1178 1927 1178 1928 1198 1928 1190 1928 1178 1929 1190 1929 1176 1929 1199 1930 1200 1930 1201 1930 1202 1931 1203 1931 1204 1931 1202 1932 1204 1932 1205 1932 1205 1933 1204 1933 1206 1933 1205 1934 1206 1934 1207 1934 1207 1935 1206 1935 1208 1935 1208 1936 1206 1936 1209 1936 1200 1937 1199 1937 1210 1937 1210 1938 1199 1938 1211 1938 1210 1939 1211 1939 1209 1939 1209 1940 1211 1940 1208 1940 1212 1941 1213 1941 1214 1941 1200 1942 1215 1942 1201 1942 1201 1943 1215 1943 1212 1943 1212 1944 1215 1944 1213 1944 1213 1945 1203 1945 1214 1945 1214 1946 1203 1946 1202 1946 1205 1947 1216 1947 1202 1947 1202 1948 1216 1948 1217 1948 1202 1949 1217 1949 1214 1949 1214 1950 1217 1950 1218 1950 1214 1951 1218 1951 1212 1951 1212 1952 1218 1952 1219 1952 1212 1953 1219 1953 1201 1953 1201 1954 1219 1954 1220 1954 1201 1955 1220 1955 1199 1955 1199 1956 1220 1956 1221 1956 1199 1957 1221 1957 1222 1957 1199 1958 1222 1958 1211 1958 1211 1959 1222 1959 1208 1959 1208 1960 1222 1960 1223 1960 1208 1961 1223 1961 1207 1961 1207 1962 1223 1962 1224 1962 1207 1963 1224 1963 1216 1963 1207 1964 1216 1964 1205 1964 1225 1965 1226 1965 1227 1965 1227 1966 1226 1966 1228 1966 1227 1967 1228 1967 1229 1967 1229 1968 1228 1968 1230 1968 1229 1969 1230 1969 1231 1969 1229 1970 1231 1970 1232 1970 1232 1971 1231 1971 1233 1971 1232 1972 1233 1972 1234 1972 1234 1973 1233 1973 1235 1973 1234 1974 1235 1974 1236 1974 1236 1975 1235 1975 1237 1975 1236 1976 1237 1976 1238 1976 1238 1977 1237 1977 1239 1977 1238 1978 1239 1978 1240 1978 1238 1979 1240 1979 1241 1979 1241 1980 1240 1980 1242 1980 1241 1981 1242 1981 1225 1981 1225 1982 1242 1982 1226 1982 1227 1983 1243 1983 1225 1983 1225 1984 1243 1984 1244 1984 1225 1985 1244 1985 1241 1985 1241 1986 1244 1986 1245 1986 1241 1987 1245 1987 1238 1987 1238 1988 1245 1988 1246 1988 1238 1989 1246 1989 1236 1989 1236 1990 1246 1990 1247 1990 1236 1991 1247 1991 1234 1991 1234 1992 1247 1992 1248 1992 1234 1993 1248 1993 1249 1993 1234 1994 1249 1994 1232 1994 1232 1995 1249 1995 1229 1995 1229 1996 1249 1996 1250 1996 1229 1997 1250 1997 1227 1997 1227 1998 1250 1998 1243 1998 1251 1999 1252 1999 1253 1999 1254 2000 1251 2000 1255 2000 1255 2001 1251 2001 1253 2001 1253 2002 1252 2002 1256 2002 1253 2003 1256 2003 1257 2003 1258 2004 1259 2004 1260 2004 1258 2005 1260 2005 1261 2005 1261 2006 1260 2006 1257 2006 1261 2007 1257 2007 1256 2007 1259 2008 1258 2008 1262 2008 1259 2009 1262 2009 1263 2009 1263 2010 1262 2010 1264 2010 1263 2011 1264 2011 1265 2011 1265 2012 1264 2012 1266 2012 1266 2013 1264 2013 1267 2013 1266 2014 1267 2014 1268 2014 1268 2015 1267 2015 1254 2015 1268 2016 1254 2016 1255 2016 1257 2017 1269 2017 1270 2017 1257 2018 1270 2018 1253 2018 1253 2019 1270 2019 1271 2019 1253 2020 1271 2020 1255 2020 1255 2021 1271 2021 1272 2021 1255 2022 1272 2022 1268 2022 1268 2023 1272 2023 1273 2023 1268 2024 1273 2024 1266 2024 1266 2025 1273 2025 1274 2025 1266 2026 1274 2026 1265 2026 1265 2027 1274 2027 1263 2027 1263 2028 1274 2028 1275 2028 1263 2029 1275 2029 1259 2029 1259 2030 1275 2030 1276 2030 1259 2031 1276 2031 1260 2031 1260 2032 1276 2032 1269 2032 1260 2033 1269 2033 1257 2033 1277 2034 1278 2034 1279 2034 1279 2035 1278 2035 372 2035 372 2036 374 2036 1279 2036 1279 2037 374 2037 1280 2037 1280 2038 374 2038 387 2038 1280 2039 387 2039 1281 2039 1281 2040 387 2040 368 2040 1281 2041 368 2041 1282 2041 1282 2042 368 2042 367 2042 1282 2043 367 2043 376 2043 1282 2044 376 2044 1283 2044 1283 2045 376 2045 1284 2045 1284 2046 376 2046 375 2046 1284 2047 375 2047 1285 2047 1285 2048 375 2048 364 2048 1285 2049 364 2049 1286 2049 1286 2050 364 2050 363 2050 1286 2051 363 2051 1287 2051 1287 2052 363 2052 382 2052 1287 2053 382 2053 1288 2053 1288 2054 382 2054 359 2054 1288 2055 359 2055 1289 2055 1289 2056 359 2056 361 2056 1289 2057 361 2057 1290 2057 1290 2058 361 2058 1291 2058 1291 2059 361 2059 389 2059 1291 2060 389 2060 1292 2060 1292 2061 389 2061 380 2061 1292 2062 380 2062 1293 2062 1293 2063 380 2063 379 2063 1293 2064 379 2064 1294 2064 1294 2065 379 2065 392 2065 1294 2066 392 2066 1277 2066 1277 2067 392 2067 391 2067 1277 2068 391 2068 1278 2068 391 2069 372 2069 1278 2069 1198 2070 1279 2070 1280 2070 1198 2071 1280 2071 1190 2071 1279 2072 1198 2072 1197 2072 1282 2073 1216 2073 1281 2073 1281 2074 1216 2074 1224 2074 1247 2075 1291 2075 1292 2075 1271 2076 1286 2076 1287 2076 1271 2077 1287 2077 1272 2077 1286 2078 1271 2078 1270 2078 1286 2079 1270 2079 1285 2079 1281 2080 1224 2080 1223 2080 1288 2081 1272 2081 1287 2081 1243 2082 1223 2082 1222 2082 1284 2083 1218 2083 1283 2083 1283 2084 1218 2084 1217 2084 1283 2085 1217 2085 1282 2085 1282 2086 1217 2086 1216 2086 1243 2087 1250 2087 1223 2087 1223 2088 1250 2088 1281 2088 1279 2089 1197 2089 1277 2089 1290 2090 1291 2090 1246 2090 1289 2091 1273 2091 1288 2091 1288 2092 1273 2092 1272 2092 1285 2093 1270 2093 1269 2093 1285 2094 1269 2094 1284 2094 1220 2095 1244 2095 1221 2095 1197 2096 1196 2096 1277 2096 1277 2097 1196 2097 1195 2097 1194 2098 1293 2098 1294 2098 1194 2099 1294 2099 1195 2099 1195 2100 1294 2100 1277 2100 1281 2101 1192 2101 1191 2101 1284 2102 1269 2102 1276 2102 1244 2103 1220 2103 1284 2103 1284 2104 1220 2104 1219 2104 1284 2105 1219 2105 1218 2105 1293 2106 1248 2106 1292 2106 1292 2107 1248 2107 1247 2107 1193 2108 1192 2108 1250 2108 1250 2109 1192 2109 1281 2109 1281 2110 1191 2110 1190 2110 1281 2111 1190 2111 1280 2111 1247 2112 1246 2112 1291 2112 1284 2113 1276 2113 1275 2113 1284 2114 1275 2114 1244 2114 1244 2115 1275 2115 1274 2115 1293 2116 1249 2116 1248 2116 1290 2117 1246 2117 1245 2117 1290 2118 1245 2118 1289 2118 1289 2119 1245 2119 1273 2119 1273 2120 1245 2120 1244 2120 1273 2121 1244 2121 1274 2121 1243 2122 1222 2122 1221 2122 1243 2123 1221 2123 1244 2123 1249 2124 1194 2124 1250 2124 1250 2125 1194 2125 1193 2125 1194 2126 1249 2126 1293 2126 1256 2127 1295 2127 1261 2127 1261 2128 1295 2128 1296 2128 1261 2129 1296 2129 1258 2129 1258 2130 1296 2130 1297 2130 1258 2131 1297 2131 1262 2131 1262 2132 1297 2132 1298 2132 1262 2133 1298 2133 1264 2133 1264 2134 1298 2134 1299 2134 1264 2135 1299 2135 1300 2135 1264 2136 1300 2136 1267 2136 1267 2137 1300 2137 1301 2137 1267 2138 1301 2138 1254 2138 1254 2139 1301 2139 1302 2139 1254 2140 1302 2140 1251 2140 1251 2141 1302 2141 1252 2141 1252 2142 1302 2142 1303 2142 1252 2143 1303 2143 1256 2143 1256 2144 1303 2144 1295 2144 1226 2145 1304 2145 1228 2145 1228 2146 1304 2146 1305 2146 1228 2147 1305 2147 1230 2147 1230 2148 1305 2148 1306 2148 1230 2149 1306 2149 1231 2149 1231 2150 1306 2150 1307 2150 1231 2151 1307 2151 1233 2151 1233 2152 1307 2152 1308 2152 1233 2153 1308 2153 1235 2153 1235 2154 1308 2154 1309 2154 1235 2155 1309 2155 1237 2155 1237 2156 1309 2156 1239 2156 1239 2157 1309 2157 1310 2157 1239 2158 1310 2158 1240 2158 1240 2159 1310 2159 1311 2159 1240 2160 1311 2160 1242 2160 1242 2161 1311 2161 1304 2161 1242 2162 1304 2162 1226 2162 1204 2163 1312 2163 1313 2163 1204 2164 1313 2164 1206 2164 1206 2165 1313 2165 1314 2165 1206 2166 1314 2166 1209 2166 1209 2167 1314 2167 1315 2167 1209 2168 1315 2168 1210 2168 1210 2169 1315 2169 1316 2169 1210 2170 1316 2170 1200 2170 1200 2171 1316 2171 1317 2171 1200 2172 1317 2172 1215 2172 1215 2173 1317 2173 1318 2173 1215 2174 1318 2174 1213 2174 1213 2175 1318 2175 1319 2175 1213 2176 1319 2176 1203 2176 1203 2177 1319 2177 1312 2177 1203 2178 1312 2178 1204 2178 1177 2179 1320 2179 1321 2179 1177 2180 1321 2180 1179 2180 1179 2181 1321 2181 1322 2181 1179 2182 1322 2182 1182 2182 1182 2183 1322 2183 1323 2183 1182 2184 1323 2184 1183 2184 1183 2185 1323 2185 1324 2185 1183 2186 1324 2186 1187 2186 1187 2187 1324 2187 1325 2187 1187 2188 1325 2188 1189 2188 1189 2189 1325 2189 1326 2189 1189 2190 1326 2190 1173 2190 1173 2191 1326 2191 1327 2191 1173 2192 1327 2192 1174 2192 1174 2193 1327 2193 1328 2193 1174 2194 1328 2194 1185 2194 1185 2195 1328 2195 1320 2195 1185 2196 1320 2196 1177 2196 1316 2197 1329 2197 1330 2197 1316 2198 1330 2198 1317 2198 1317 2199 1330 2199 1331 2199 1317 2200 1331 2200 1318 2200 1318 2201 1331 2201 1332 2201 1318 2202 1332 2202 1333 2202 1318 2203 1333 2203 1319 2203 1319 2204 1333 2204 1312 2204 1312 2205 1333 2205 1334 2205 1312 2206 1334 2206 1313 2206 1313 2207 1334 2207 1335 2207 1313 2208 1335 2208 1314 2208 1314 2209 1335 2209 1336 2209 1314 2210 1336 2210 1315 2210 1315 2211 1336 2211 1337 2211 1315 2212 1337 2212 1329 2212 1315 2213 1329 2213 1316 2213 1310 2214 1338 2214 1339 2214 1310 2215 1339 2215 1311 2215 1311 2216 1339 2216 1340 2216 1311 2217 1340 2217 1304 2217 1304 2218 1340 2218 1341 2218 1304 2219 1341 2219 1305 2219 1305 2220 1341 2220 1342 2220 1305 2221 1342 2221 1306 2221 1306 2222 1342 2222 1307 2222 1307 2223 1342 2223 1343 2223 1307 2224 1343 2224 1308 2224 1308 2225 1343 2225 1344 2225 1308 2226 1344 2226 1345 2226 1308 2227 1345 2227 1309 2227 1309 2228 1345 2228 1310 2228 1310 2229 1345 2229 1338 2229 1298 2230 1297 2230 1300 2230 1300 2231 1297 2231 1296 2231 1295 2232 1303 2232 1300 2232 1298 2233 1300 2233 1299 2233 1300 2234 1296 2234 1295 2234 1300 2235 1303 2235 1302 2235 1302 2236 1301 2236 1300 2236 1325 2237 1323 2237 1322 2237 1327 2238 1326 2238 1325 2238 1323 2239 1325 2239 1324 2239 1322 2240 1321 2240 1325 2240 1325 2241 1321 2241 1320 2241 1320 2242 1328 2242 1325 2242 1325 2243 1328 2243 1327 2243 1346 2244 1347 2244 1348 2244 1348 2245 1347 2245 1349 2245 1348 2246 1349 2246 1350 2246 1351 2247 1352 2247 1350 2247 1350 2248 1352 2248 1353 2248 1346 2249 1348 2249 1354 2249 1350 2250 1353 2250 1348 2250 1348 2251 1355 2251 1356 2251 1348 2252 1356 2252 1354 2252 1354 2253 1356 2253 1357 2253 1354 2254 1357 2254 1346 2254 1346 2255 1357 2255 1347 2255 1347 2256 1357 2256 1358 2256 1347 2257 1358 2257 1349 2257 1349 2258 1358 2258 1359 2258 1349 2259 1359 2259 1350 2259 1350 2260 1359 2260 1360 2260 1350 2261 1360 2261 1351 2261 1351 2262 1360 2262 1361 2262 1351 2263 1361 2263 1352 2263 1352 2264 1361 2264 1362 2264 1352 2265 1362 2265 1353 2265 1353 2266 1362 2266 1355 2266 1353 2267 1355 2267 1348 2267 1359 2268 1363 2268 1364 2268 1359 2269 1364 2269 1360 2269 1360 2270 1364 2270 1365 2270 1360 2271 1365 2271 1361 2271 1361 2272 1365 2272 1366 2272 1361 2273 1366 2273 1362 2273 1362 2274 1366 2274 1367 2274 1362 2275 1367 2275 1355 2275 1355 2276 1367 2276 1368 2276 1355 2277 1368 2277 1356 2277 1356 2278 1368 2278 1369 2278 1356 2279 1369 2279 1357 2279 1357 2280 1369 2280 1370 2280 1357 2281 1370 2281 1358 2281 1358 2282 1370 2282 1371 2282 1358 2283 1371 2283 1359 2283 1359 2284 1371 2284 1363 2284 1363 2285 1334 2285 1333 2285 1363 2286 1333 2286 1364 2286 1364 2287 1333 2287 1332 2287 1364 2288 1332 2288 1365 2288 1365 2289 1332 2289 1331 2289 1365 2290 1331 2290 1366 2290 1366 2291 1331 2291 1330 2291 1366 2292 1330 2292 1367 2292 1367 2293 1330 2293 1329 2293 1367 2294 1329 2294 1368 2294 1368 2295 1329 2295 1337 2295 1368 2296 1337 2296 1369 2296 1369 2297 1337 2297 1336 2297 1369 2298 1336 2298 1370 2298 1370 2299 1336 2299 1335 2299 1370 2300 1335 2300 1334 2300 1370 2301 1334 2301 1371 2301 1371 2302 1334 2302 1363 2302 1372 2303 1373 2303 1374 2303 1375 2304 1376 2304 1374 2304 1376 2305 1375 2305 1377 2305 1376 2306 1372 2306 1374 2306 1378 2307 1379 2307 1380 2307 1373 2308 1372 2308 1380 2308 1373 2309 1380 2309 1379 2309 1372 2310 1381 2310 1380 2310 1380 2311 1381 2311 1382 2311 1380 2312 1382 2312 1378 2312 1378 2313 1382 2313 1383 2313 1378 2314 1383 2314 1379 2314 1379 2315 1383 2315 1384 2315 1379 2316 1384 2316 1373 2316 1373 2317 1384 2317 1385 2317 1373 2318 1385 2318 1374 2318 1374 2319 1385 2319 1375 2319 1375 2320 1385 2320 1386 2320 1375 2321 1386 2321 1377 2321 1377 2322 1386 2322 1387 2322 1377 2323 1387 2323 1376 2323 1376 2324 1387 2324 1388 2324 1376 2325 1388 2325 1372 2325 1372 2326 1388 2326 1381 2326 1385 2327 1389 2327 1386 2327 1386 2328 1389 2328 1390 2328 1386 2329 1390 2329 1387 2329 1387 2330 1390 2330 1391 2330 1387 2331 1391 2331 1388 2331 1388 2332 1391 2332 1392 2332 1388 2333 1392 2333 1381 2333 1381 2334 1392 2334 1393 2334 1381 2335 1393 2335 1382 2335 1382 2336 1393 2336 1383 2336 1383 2337 1393 2337 1394 2337 1383 2338 1394 2338 1384 2338 1384 2339 1394 2339 1395 2339 1384 2340 1395 2340 1385 2340 1385 2341 1395 2341 1389 2341 1395 2342 1341 2342 1340 2342 1395 2343 1340 2343 1389 2343 1389 2344 1340 2344 1339 2344 1389 2345 1339 2345 1390 2345 1390 2346 1339 2346 1338 2346 1390 2347 1338 2347 1391 2347 1391 2348 1338 2348 1345 2348 1391 2349 1345 2349 1392 2349 1392 2350 1345 2350 1344 2350 1392 2351 1344 2351 1393 2351 1393 2352 1344 2352 1343 2352 1393 2353 1343 2353 1342 2353 1393 2354 1342 2354 1394 2354 1394 2355 1342 2355 1341 2355 1394 2356 1341 2356 1395 2356 1397 2357 1097 2357 1396 2357 1396 2358 1097 2358 300 2358 1399 2359 977 2359 1098 2359 282 2360 1400 2360 280 2360 280 2361 1400 2361 1401 2361 1401 2362 274 2362 280 2362 1399 2363 1098 2363 1397 2363 1397 2364 1098 2364 1097 2364 1400 2365 282 2365 278 2365 1400 2366 278 2366 1403 2366 288 2367 1405 2367 1406 2367 1407 2368 1408 2368 1409 2368 1412 2369 1413 2369 1414 2369 1415 2370 1411 2370 1412 2370 1412 2371 1411 2371 1416 2371 1412 2372 1416 2372 1413 2372 1417 2373 1410 2373 1415 2373 1415 2374 1410 2374 1411 2374 1411 2375 1407 2375 1416 2375 1418 2376 1415 2376 1412 2376 1418 2377 1412 2377 1414 2377 1418 2378 1414 2378 1419 2378 1421 2379 1408 2379 1422 2379 1408 2380 1421 2380 1423 2380 1408 2381 1423 2381 1409 2381 1424 2382 1425 2382 1426 2382 1428 2383 1427 2383 1429 2383 1424 2384 1430 2384 1431 2384 1424 2385 1431 2385 1427 2385 1432 2386 1427 2386 1431 2386 1433 2387 1431 2387 1430 2387 1434 2388 1432 2388 1435 2388 1435 2389 1432 2389 1436 2389 1436 2390 1432 2390 1431 2390 1436 2391 1431 2391 1433 2391 1437 2392 1436 2392 1433 2392 1436 2393 1437 2393 1435 2393 1434 2394 1435 2394 1438 2394 1438 2395 1435 2395 1439 2395 1440 2396 1434 2396 1438 2396 1441 2397 1440 2397 1438 2397 1437 2398 1439 2398 1435 2398 1442 2399 1440 2399 1441 2399 1443 2400 1444 2400 1440 2400 1443 2401 1440 2401 1442 2401 1443 2402 1442 2402 1445 2402 1417 2403 1444 2403 1443 2403 1421 2404 1417 2404 1443 2404 1421 2405 1443 2405 1445 2405 1421 2406 1445 2406 1423 2406 1420 2407 1417 2407 1421 2407 1446 2408 1447 2408 1448 2408 1446 2409 1448 2409 1449 2409 1446 2410 1418 2410 1450 2410 1446 2411 1450 2411 1447 2411 1449 2412 1448 2412 1451 2412 1450 2413 1452 2413 1447 2413 1418 2414 1419 2414 1450 2414 1448 2415 1447 2415 1453 2415 1448 2416 1453 2416 1451 2416 1429 2417 1454 2417 1455 2417 1424 2418 1426 2418 1457 2418 1456 2419 1455 2419 1426 2419 1456 2420 1426 2420 1425 2420 1455 2421 1458 2421 1426 2421 1426 2422 1458 2422 1459 2422 1455 2423 1454 2423 1458 2423 1458 2424 1460 2424 1459 2424 1454 2425 1461 2425 1458 2425 1458 2426 1461 2426 1460 2426 1460 2427 1461 2427 1462 2427 1463 2428 1449 2428 1464 2428 1464 2429 1449 2429 1451 2429 1464 2430 1451 2430 1465 2430 1454 2431 1466 2431 1467 2431 1454 2432 1467 2432 1461 2432 1461 2433 1467 2433 1468 2433 1461 2434 1468 2434 1462 2434 1469 2435 1470 2435 1471 2435 1469 2436 1472 2436 1470 2436 1470 2437 1472 2437 1473 2437 1469 2438 1463 2438 1472 2438 1472 2439 1463 2439 1464 2439 1472 2440 1464 2440 1473 2440 1473 2441 1464 2441 1465 2441 1466 2442 1474 2442 1475 2442 1466 2443 1475 2443 1467 2443 1474 2444 1476 2444 1477 2444 1474 2445 1477 2445 1475 2445 1476 2446 1478 2446 1477 2446 1467 2447 1475 2447 1479 2447 1475 2448 1477 2448 1480 2448 1475 2449 1480 2449 1479 2449 1467 2450 1479 2450 1468 2450 1471 2451 1481 2451 1482 2451 1471 2452 1482 2452 1469 2452 1481 2453 1483 2453 1482 2453 1483 2454 1484 2454 1485 2454 1483 2455 1485 2455 1482 2455 1482 2456 1485 2456 1486 2456 1474 2457 1487 2457 1476 2457 1476 2458 1487 2458 1488 2458 1476 2459 1488 2459 1478 2459 1478 2460 1488 2460 1489 2460 1486 2461 1485 2461 1490 2461 1490 2462 1485 2462 1484 2462 1490 2463 1484 2463 1491 2463 1486 2464 1490 2464 1492 2464 1491 2465 1493 2465 1490 2465 1490 2466 1493 2466 1494 2466 1490 2467 1494 2467 1492 2467 1493 2468 1495 2468 1494 2468 1494 2469 1495 2469 1496 2469 1494 2470 1496 2470 1492 2470 1495 2471 1497 2471 1498 2471 1495 2472 1498 2472 1496 2472 1487 2473 1499 2473 1500 2473 1487 2474 1500 2474 1488 2474 1499 2475 1501 2475 1502 2475 1499 2476 1502 2476 1503 2476 1499 2477 1503 2477 1500 2477 1500 2478 1503 2478 1504 2478 1500 2479 1504 2479 1505 2479 1500 2480 1505 2480 1488 2480 1488 2481 1505 2481 1489 2481 1499 2482 1496 2482 1498 2482 1499 2483 1498 2483 1501 2483 1501 2484 1498 2484 1497 2484 1501 2485 1497 2485 1502 2485 1508 2486 1510 2486 1511 2486 1512 2487 1510 2487 1506 2487 1510 2488 1513 2488 1511 2488 1510 2489 1512 2489 1514 2489 1510 2490 1514 2490 1513 2490 1506 2491 1507 2491 1515 2491 1515 2492 1507 2492 1516 2492 1518 2493 1517 2493 1519 2493 1520 2494 1519 2494 1521 2494 1520 2495 1521 2495 1522 2495 1523 2496 1522 2496 1521 2496 1518 2497 1519 2497 1520 2497 1525 2498 1520 2498 1522 2498 1525 2499 1522 2499 1523 2499 1526 2500 1524 2500 1518 2500 1527 2501 1523 2501 1528 2501 1526 2502 1518 2502 1529 2502 1529 2503 1518 2503 1520 2503 1530 2504 1520 2504 1525 2504 1525 2505 1523 2505 1527 2505 1531 2506 1528 2506 1523 2506 1531 2507 1523 2507 1521 2507 1532 2508 1528 2508 1531 2508 1533 2509 1531 2509 1521 2509 1532 2510 1531 2510 1533 2510 1534 2511 1532 2511 1533 2511 1535 2512 1532 2512 1534 2512 1536 2513 1535 2513 1537 2513 1537 2514 1535 2514 1534 2514 1515 2515 1534 2515 1533 2515 1515 2516 1537 2516 1534 2516 1540 2517 1514 2517 1541 2517 1541 2518 1514 2518 1512 2518 1542 2519 1517 2519 1543 2519 1544 2520 1542 2520 1545 2520 1546 2521 1547 2521 1548 2521 1548 2522 1547 2522 1549 2522 1546 2523 1542 2523 1547 2523 1542 2524 1550 2524 1547 2524 1547 2525 1550 2525 1549 2525 1550 2526 1551 2526 1549 2526 1542 2527 1544 2527 1550 2527 1550 2528 1544 2528 1551 2528 1551 2529 1544 2529 1526 2529 1552 2530 1553 2530 1554 2530 1552 2531 1554 2531 1555 2531 1552 2532 1555 2532 1541 2532 1553 2533 1556 2533 1557 2533 1553 2534 1557 2534 1554 2534 1554 2535 1557 2535 1558 2535 1541 2536 1555 2536 1540 2536 1554 2537 1558 2537 1555 2537 1555 2538 1558 2538 1559 2538 1555 2539 1559 2539 1540 2539 1548 2540 1560 2540 1561 2540 1548 2541 1561 2541 1546 2541 1546 2542 1561 2542 1562 2542 1563 2543 1556 2543 1564 2543 1564 2544 1556 2544 1553 2544 1564 2545 1553 2545 1565 2545 1565 2546 1553 2546 1552 2546 1562 2547 1566 2547 1567 2547 1567 2548 1566 2548 1568 2548 1562 2549 1561 2549 1566 2549 1561 2550 1569 2550 1566 2550 1566 2551 1570 2551 1568 2551 1568 2552 1570 2552 1571 2552 1561 2553 1560 2553 1569 2553 1566 2554 1569 2554 1572 2554 1566 2555 1572 2555 1570 2555 1564 2556 1573 2556 1563 2556 1565 2557 1574 2557 1564 2557 1564 2558 1574 2558 1573 2558 1574 2559 1575 2559 1573 2559 1565 2560 1576 2560 1577 2560 1565 2561 1577 2561 1574 2561 1574 2562 1577 2562 1575 2562 1575 2563 1577 2563 1578 2563 1571 2564 1579 2564 1580 2564 1571 2565 1580 2565 1568 2565 1568 2566 1580 2566 1581 2566 1568 2567 1581 2567 1567 2567 1567 2568 1581 2568 1582 2568 1567 2569 1582 2569 1583 2569 1584 2570 1585 2570 1586 2570 1586 2571 1585 2571 1587 2571 1584 2572 1588 2572 1589 2572 1584 2573 1589 2573 1585 2573 1585 2574 1589 2574 1587 2574 1588 2575 1578 2575 1589 2575 1589 2576 1578 2576 1577 2576 1589 2577 1577 2577 1576 2577 1589 2578 1576 2578 1587 2578 1581 2579 1580 2579 1590 2579 1590 2580 1580 2580 1591 2580 1590 2581 1592 2581 1593 2581 1590 2582 1591 2582 1592 2582 1593 2583 1592 2583 1594 2583 1580 2584 1579 2584 1595 2584 1580 2585 1595 2585 1591 2585 1591 2586 1595 2586 1596 2586 1591 2587 1596 2587 1592 2587 1597 2588 1598 2588 1599 2588 1597 2589 1599 2589 1600 2589 1598 2590 1601 2590 1602 2590 1598 2591 1602 2591 1599 2591 1599 2592 1603 2592 1600 2592 1599 2593 1602 2593 1603 2593 1601 2594 1604 2594 1586 2594 1601 2595 1586 2595 1602 2595 1602 2596 1586 2596 1603 2596 1604 2597 1584 2597 1586 2597 1586 2598 1587 2598 1603 2598 1600 2599 1593 2599 1597 2599 1597 2600 1593 2600 1594 2600 1600 2601 1590 2601 1593 2601 1584 2602 1604 2602 1605 2602 1604 2603 1601 2603 1605 2603 1605 2604 1601 2604 1606 2604 1606 2605 1601 2605 1598 2605 1606 2606 1598 2606 1607 2606 1597 2607 1607 2607 1598 2607 1484 2608 1608 2608 1491 2608 1491 2609 1608 2609 1609 2609 1491 2610 1609 2610 1493 2610 1493 2611 1609 2611 1495 2611 1495 2612 1609 2612 1610 2612 1495 2613 1610 2613 1497 2613 1588 2614 1611 2614 1612 2614 1588 2615 1612 2615 1578 2615 1584 2616 1605 2616 1611 2616 1584 2617 1611 2617 1588 2617 1471 2618 1613 2618 1481 2618 1481 2619 1613 2619 1614 2619 1481 2620 1614 2620 1483 2620 1483 2621 1614 2621 1608 2621 1483 2622 1608 2622 1484 2622 1088 2623 1144 2623 1615 2623 1615 2624 1144 2624 1134 2624 1615 2625 1134 2625 1139 2625 1133 2626 1139 2626 1134 2626 1615 2627 1139 2627 1616 2627 1617 2628 1618 2628 1616 2628 1616 2629 1618 2629 1615 2629 1618 2630 1617 2630 1619 2630 1091 2631 1620 2631 1141 2631 1621 2632 1622 2632 1623 2632 1622 2633 1621 2633 1620 2633 1620 2634 1621 2634 1132 2634 1132 2635 1131 2635 1147 2635 1132 2636 1147 2636 1620 2636 1620 2637 1147 2637 1146 2637 1620 2638 1146 2638 1141 2638 1622 2639 1624 2639 1623 2639 1625 2640 1626 2640 79 2640 79 2641 1626 2641 93 2641 1628 2642 1629 2642 104 2642 104 2643 93 2643 1628 2643 1628 2644 93 2644 1626 2644 1626 2645 1630 2645 1628 2645 1630 2646 1618 2646 1631 2646 1619 2647 1631 2647 1618 2647 1624 2648 1632 2648 1633 2648 1632 2649 1624 2649 1634 2649 1624 2650 1622 2650 1634 2650 1634 2651 1635 2651 1636 2651 195 2652 1637 2652 132 2652 195 2653 132 2653 1636 2653 132 2654 149 2654 1636 2654 1636 2655 149 2655 158 2655 158 2656 231 2656 1636 2656 1457 2657 1426 2657 1638 2657 1426 2658 1459 2658 1638 2658 1638 2659 1459 2659 1639 2659 1459 2660 1460 2660 1639 2660 1639 2661 1460 2661 1462 2661 1478 2662 1640 2662 1477 2662 1477 2663 1640 2663 1641 2663 1477 2664 1641 2664 1480 2664 1480 2665 1641 2665 1642 2665 1480 2666 1642 2666 1479 2666 1479 2667 1642 2667 1468 2667 1643 2668 1489 2668 1505 2668 1643 2669 1505 2669 1644 2669 1644 2670 1505 2670 1504 2670 1644 2671 1504 2671 1503 2671 1644 2672 1503 2672 1645 2672 1645 2673 1503 2673 1502 2673 1465 2674 1646 2674 1473 2674 1473 2675 1646 2675 1613 2675 1473 2676 1613 2676 1470 2676 1470 2677 1613 2677 1471 2677 1647 2678 1451 2678 1453 2678 1647 2679 1453 2679 1648 2679 1648 2680 1453 2680 1447 2680 1648 2681 1447 2681 1452 2681 1648 2682 1452 2682 1649 2682 1649 2683 1452 2683 1450 2683 1649 2684 1450 2684 1419 2684 1650 2685 1414 2685 1413 2685 1650 2686 1413 2686 1651 2686 1651 2687 1413 2687 1416 2687 1416 2688 1407 2688 1651 2688 1409 2689 233 2689 1651 2689 1409 2690 1651 2690 1407 2690 1514 2691 1652 2691 1513 2691 1513 2692 1652 2692 1511 2692 1511 2693 1652 2693 1653 2693 1511 2694 1653 2694 1508 2694 1508 2695 1653 2695 1509 2695 1509 2696 1653 2696 1654 2696 1655 2697 1540 2697 1559 2697 1655 2698 1559 2698 1558 2698 1655 2699 1558 2699 1656 2699 1656 2700 1558 2700 1557 2700 1656 2701 1557 2701 1657 2701 1657 2702 1557 2702 1556 2702 1578 2703 1612 2703 1575 2703 1575 2704 1612 2704 1658 2704 1575 2705 1658 2705 1573 2705 1573 2706 1658 2706 1563 2706 1659 2707 1594 2707 1592 2707 1659 2708 1592 2708 1596 2708 1659 2709 1596 2709 1660 2709 1660 2710 1596 2710 1595 2710 1660 2711 1595 2711 1661 2711 1661 2712 1595 2712 1579 2712 1560 2713 1662 2713 1569 2713 1569 2714 1662 2714 1663 2714 1569 2715 1663 2715 1572 2715 1572 2716 1663 2716 1570 2716 1570 2717 1663 2717 1664 2717 1570 2718 1664 2718 1571 2718 1526 2719 1665 2719 1666 2719 1666 2720 1551 2720 1526 2720 1666 2721 1549 2721 1551 2721 1667 2722 1549 2722 1666 2722 1667 2723 1548 2723 1549 2723 1409 2724 1636 2724 233 2724 233 2725 1636 2725 231 2725 1409 2726 1423 2726 1636 2726 1634 2727 1423 2727 1445 2727 1634 2728 1445 2728 1632 2728 1423 2729 1634 2729 1636 2729 1633 2730 1632 2730 1442 2730 1442 2731 1632 2731 1445 2731 1633 2732 1442 2732 1441 2732 1441 2733 1438 2733 1633 2733 1633 2734 1438 2734 1668 2734 1439 2735 1668 2735 1438 2735 1437 2736 1668 2736 1439 2736 1668 2737 1437 2737 1433 2737 1668 2738 1433 2738 1623 2738 1623 2739 1433 2739 1430 2739 1621 2740 1623 2740 1430 2740 1457 2741 1132 2741 1621 2741 1457 2742 1621 2742 1424 2742 1424 2743 1621 2743 1430 2743 1529 2744 1616 2744 1526 2744 1526 2745 1616 2745 1665 2745 1616 2746 1139 2746 1665 2746 1520 2747 1617 2747 1529 2747 1529 2748 1617 2748 1616 2748 1669 2749 1617 2749 1530 2749 1530 2750 1617 2750 1520 2750 1530 2751 1525 2751 1669 2751 1669 2752 1525 2752 1670 2752 1527 2753 1670 2753 1525 2753 1670 2754 1527 2754 1528 2754 1670 2755 1528 2755 1671 2755 1671 2756 1528 2756 1532 2756 1671 2757 1532 2757 1631 2757 1631 2758 1532 2758 1535 2758 1536 2759 1630 2759 1631 2759 1536 2760 1631 2760 1535 2760 1628 2761 1630 2761 1538 2761 1538 2762 1630 2762 1536 2762 1539 2763 1628 2763 1538 2763 1631 2764 1619 2764 1671 2764 1617 2765 1669 2765 1619 2765 1619 2766 1669 2766 1670 2766 1619 2767 1670 2767 1671 2767 1672 2768 1088 2768 1615 2768 1672 2769 1618 2769 1673 2769 1615 2770 1618 2770 1672 2770 1633 2771 1668 2771 1624 2771 1624 2772 1668 2772 1623 2772 1620 2773 1091 2773 1674 2773 192 2774 1622 2774 1674 2774 1674 2775 1622 2775 1620 2775 1594 2776 1659 2776 1597 2776 1597 2777 1659 2777 1607 2777 1548 2778 1667 2778 1560 2778 1560 2779 1667 2779 1662 2779 1675 2780 1661 2780 1579 2780 1571 2781 1664 2781 1676 2781 1579 2782 1571 2782 1675 2782 1675 2783 1571 2783 1676 2783 1675 2784 1676 2784 1060 2784 1060 2785 1676 2785 322 2785 1060 2786 322 2786 321 2786 1677 2787 1678 2787 1679 2787 1679 2788 1678 2788 1583 2788 1679 2789 1583 2789 1680 2789 1680 2790 1583 2790 1681 2790 1680 2791 1681 2791 1682 2791 1682 2792 1681 2792 1683 2792 1682 2793 1683 2793 1684 2793 1684 2794 1683 2794 1685 2794 1684 2795 1685 2795 1686 2795 1685 2796 1687 2796 1686 2796 1686 2797 1687 2797 1688 2797 1688 2798 1687 2798 1689 2798 1688 2799 1689 2799 1690 2799 1690 2800 1689 2800 1691 2800 1690 2801 1691 2801 1692 2801 1690 2802 1692 2802 1693 2802 1693 2803 1692 2803 1694 2803 1693 2804 1694 2804 1677 2804 1677 2805 1694 2805 1678 2805 1690 2806 1695 2806 1696 2806 1690 2807 1696 2807 1688 2807 1688 2808 1696 2808 1697 2808 1688 2809 1697 2809 1686 2809 1686 2810 1697 2810 1698 2810 1686 2811 1698 2811 1684 2811 1684 2812 1698 2812 1699 2812 1684 2813 1699 2813 1682 2813 1682 2814 1699 2814 1700 2814 1682 2815 1700 2815 1680 2815 1680 2816 1700 2816 1679 2816 1679 2817 1700 2817 1701 2817 1679 2818 1701 2818 1677 2818 1677 2819 1701 2819 1702 2819 1677 2820 1702 2820 1693 2820 1693 2821 1702 2821 1703 2821 1693 2822 1703 2822 1690 2822 1690 2823 1703 2823 1695 2823 1704 2824 1705 2824 1706 2824 1706 2825 1705 2825 1707 2825 1706 2826 1707 2826 1708 2826 1708 2827 1707 2827 1709 2827 1708 2828 1709 2828 1710 2828 1710 2829 1709 2829 1711 2829 1710 2830 1711 2830 1712 2830 1711 2831 1713 2831 1712 2831 1712 2832 1713 2832 1714 2832 1714 2833 1713 2833 1715 2833 1714 2834 1715 2834 1716 2834 1716 2835 1715 2835 1717 2835 1716 2836 1717 2836 1718 2836 1718 2837 1717 2837 1719 2837 1718 2838 1719 2838 1720 2838 1720 2839 1719 2839 1721 2839 1720 2840 1721 2840 1704 2840 1704 2841 1721 2841 1705 2841 1720 2842 1722 2842 1723 2842 1720 2843 1723 2843 1718 2843 1706 2844 1724 2844 1725 2844 1706 2845 1725 2845 1704 2845 1704 2846 1725 2846 1720 2846 1720 2847 1725 2847 1722 2847 1718 2848 1723 2848 1726 2848 1727 2849 1714 2849 1716 2849 1727 2850 1716 2850 1726 2850 1724 2851 1706 2851 1708 2851 1724 2852 1708 2852 1728 2852 1728 2853 1708 2853 1710 2853 1728 2854 1710 2854 1729 2854 1729 2855 1710 2855 1712 2855 1729 2856 1712 2856 1714 2856 1729 2857 1714 2857 1727 2857 1718 2858 1726 2858 1716 2858 1666 2859 1665 2859 1402 2859 1100 2860 1676 2860 1099 2860 1099 2861 1676 2861 1664 2861 1667 2862 1666 2862 1402 2862 1099 2863 1664 2863 1663 2863 1099 2864 1662 2864 275 2864 275 2865 1662 2865 1402 2865 1402 2866 1662 2866 1667 2866 1099 2867 1663 2867 1662 2867 1730 2868 1731 2868 1732 2868 1730 2869 1732 2869 1733 2869 1731 2870 1730 2870 1734 2870 1731 2871 1734 2871 1735 2871 1735 2872 1734 2872 1736 2872 1735 2873 1736 2873 1737 2873 1736 2874 1738 2874 1737 2874 1737 2875 1738 2875 1739 2875 1739 2876 1738 2876 1740 2876 1739 2877 1740 2877 1741 2877 1741 2878 1740 2878 1742 2878 1741 2879 1742 2879 1743 2879 1743 2880 1742 2880 1744 2880 1743 2881 1744 2881 1745 2881 1745 2882 1744 2882 1746 2882 1746 2883 1744 2883 1747 2883 1746 2884 1747 2884 1733 2884 1746 2885 1733 2885 1732 2885 1736 2886 1748 2886 1738 2886 1738 2887 1748 2887 1749 2887 1738 2888 1749 2888 1740 2888 1740 2889 1749 2889 1750 2889 1740 2890 1750 2890 1742 2890 1742 2891 1750 2891 1751 2891 1742 2892 1751 2892 1752 2892 1742 2893 1752 2893 1744 2893 1744 2894 1752 2894 1753 2894 1744 2895 1753 2895 1747 2895 1747 2896 1753 2896 1754 2896 1747 2897 1754 2897 1733 2897 1733 2898 1754 2898 1730 2898 1730 2899 1754 2899 1755 2899 1730 2900 1755 2900 1734 2900 1734 2901 1755 2901 1756 2901 1734 2902 1756 2902 1736 2902 1736 2903 1756 2903 1748 2903 1757 2904 1403 2904 1138 2904 1758 2905 1757 2905 1138 2905 1403 2906 1757 2906 1759 2906 1403 2907 1759 2907 1400 2907 1400 2908 1759 2908 1760 2908 1140 2909 1761 2909 1762 2909 1140 2910 1762 2910 1138 2910 1138 2911 1762 2911 1758 2911 1400 2912 1760 2912 1401 2912 1401 2913 1760 2913 1763 2913 1401 2914 1763 2914 1764 2914 1401 2915 1764 2915 1140 2915 1140 2916 1764 2916 1761 2916 274 2917 1401 2917 1140 2917 274 2918 1140 2918 1101 2918 1406 2919 1765 2919 1766 2919 1766 2920 1765 2920 1143 2920 1143 2921 1765 2921 1767 2921 1143 2922 1767 2922 1768 2922 1769 2923 1770 2923 1144 2923 1144 2924 1770 2924 1771 2924 1771 2925 1772 2925 1773 2925 1771 2926 1773 2926 1405 2926 1144 2927 1774 2927 1769 2927 1770 2928 1772 2928 1771 2928 1143 2929 1768 2929 1144 2929 1144 2930 1768 2930 1774 2930 1405 2931 1773 2931 1775 2931 1405 2932 1775 2932 1406 2932 1406 2933 1775 2933 1765 2933 1768 2934 1776 2934 1774 2934 1774 2935 1776 2935 1769 2935 1769 2936 1776 2936 1777 2936 1769 2937 1777 2937 1770 2937 1770 2938 1777 2938 1778 2938 1770 2939 1778 2939 1772 2939 1772 2940 1778 2940 1779 2940 1772 2941 1779 2941 1773 2941 1773 2942 1779 2942 1780 2942 1773 2943 1780 2943 1775 2943 1775 2944 1780 2944 1781 2944 1775 2945 1781 2945 1765 2945 1765 2946 1781 2946 1782 2946 1765 2947 1782 2947 1767 2947 1767 2948 1782 2948 1783 2948 1767 2949 1783 2949 1768 2949 1768 2950 1783 2950 1776 2950 1784 2951 1785 2951 1786 2951 1784 2952 1786 2952 1787 2952 1787 2953 1786 2953 1788 2953 1787 2954 1788 2954 1789 2954 1789 2955 1788 2955 1790 2955 1789 2956 1790 2956 1791 2956 1791 2957 1790 2957 1792 2957 1791 2958 1792 2958 1793 2958 1793 2959 1792 2959 1794 2959 1793 2960 1794 2960 1795 2960 1793 2961 1795 2961 1796 2961 1796 2962 1795 2962 1797 2962 1796 2963 1797 2963 1798 2963 1798 2964 1797 2964 1799 2964 1798 2965 1799 2965 1800 2965 1800 2966 1799 2966 1784 2966 1784 2967 1799 2967 1785 2967 1801 2968 1762 2968 1761 2968 1801 2969 1761 2969 1802 2969 1802 2970 1761 2970 1803 2970 1803 2971 1761 2971 1764 2971 1803 2972 1764 2972 1804 2972 1804 2973 1764 2973 1763 2973 1804 2974 1763 2974 1760 2974 1804 2975 1760 2975 1805 2975 1805 2976 1760 2976 1759 2976 1805 2977 1759 2977 1806 2977 1806 2978 1759 2978 1757 2978 1806 2979 1757 2979 1807 2979 1807 2980 1757 2980 1808 2980 1808 2981 1757 2981 1758 2981 1808 2982 1758 2982 1762 2982 1808 2983 1762 2983 1801 2983 1732 2984 1809 2984 1746 2984 1746 2985 1809 2985 1810 2985 1746 2986 1810 2986 1745 2986 1745 2987 1810 2987 1811 2987 1745 2988 1811 2988 1743 2988 1743 2989 1811 2989 1812 2989 1743 2990 1812 2990 1741 2990 1741 2991 1812 2991 1813 2991 1741 2992 1813 2992 1739 2992 1739 2993 1813 2993 1737 2993 1737 2994 1813 2994 1814 2994 1737 2995 1814 2995 1735 2995 1735 2996 1814 2996 1815 2996 1735 2997 1815 2997 1731 2997 1731 2998 1815 2998 1816 2998 1731 2999 1816 2999 1732 2999 1732 3000 1816 3000 1809 3000 1726 3001 1817 3001 1818 3001 1726 3002 1818 3002 1727 3002 1727 3003 1818 3003 1819 3003 1727 3004 1819 3004 1729 3004 1729 3005 1819 3005 1820 3005 1729 3006 1820 3006 1728 3006 1728 3007 1820 3007 1821 3007 1728 3008 1821 3008 1724 3008 1724 3009 1821 3009 1822 3009 1724 3010 1822 3010 1725 3010 1725 3011 1822 3011 1823 3011 1725 3012 1823 3012 1722 3012 1722 3013 1823 3013 1824 3013 1722 3014 1824 3014 1723 3014 1723 3015 1824 3015 1726 3015 1726 3016 1824 3016 1817 3016 1497 3017 1610 3017 1502 3017 1502 3018 1610 3018 1645 3018 1468 3019 1642 3019 1462 3019 1462 3020 1642 3020 1639 3020 1825 3021 1640 3021 1478 3021 1489 3022 1643 3022 1826 3022 296 3023 305 3023 942 3023 942 3024 305 3024 1825 3024 942 3025 1825 3025 1826 3025 1826 3026 1825 3026 1478 3026 1826 3027 1478 3027 1489 3027 1827 3028 1828 3028 1829 3028 1829 3029 1828 3029 1830 3029 1829 3030 1830 3030 1831 3030 1831 3031 1830 3031 1832 3031 1831 3032 1832 3032 1833 3032 1831 3033 1833 3033 1834 3033 1834 3034 1833 3034 1835 3034 1834 3035 1835 3035 1836 3035 1836 3036 1835 3036 1837 3036 1836 3037 1837 3037 1838 3037 1838 3038 1837 3038 1839 3038 1838 3039 1839 3039 1840 3039 1840 3040 1839 3040 1841 3040 1840 3041 1841 3041 1842 3041 1842 3042 1841 3042 1843 3042 1842 3043 1843 3043 1827 3043 1827 3044 1843 3044 1828 3044 1844 3045 1845 3045 1827 3045 1827 3046 1845 3046 1842 3046 1842 3047 1845 3047 1846 3047 1842 3048 1846 3048 1840 3048 1840 3049 1846 3049 1847 3049 1840 3050 1847 3050 1838 3050 1838 3051 1847 3051 1848 3051 1838 3052 1848 3052 1836 3052 1836 3053 1848 3053 1849 3053 1836 3054 1849 3054 1834 3054 1834 3055 1849 3055 1850 3055 1834 3056 1850 3056 1851 3056 1834 3057 1851 3057 1831 3057 1831 3058 1851 3058 1852 3058 1831 3059 1852 3059 1829 3059 1829 3060 1852 3060 1844 3060 1829 3061 1844 3061 1827 3061 1853 3062 1854 3062 1855 3062 1853 3063 1855 3063 1856 3063 1856 3064 1855 3064 1857 3064 1856 3065 1857 3065 1858 3065 1858 3066 1857 3066 1859 3066 1858 3067 1859 3067 1860 3067 1860 3068 1859 3068 1861 3068 1861 3069 1859 3069 1862 3069 1861 3070 1862 3070 1863 3070 1863 3071 1862 3071 1864 3071 1863 3072 1864 3072 1865 3072 1865 3073 1864 3073 1866 3073 1865 3074 1866 3074 1867 3074 1867 3075 1866 3075 1868 3075 1867 3076 1868 3076 1869 3076 1869 3077 1868 3077 1853 3077 1853 3078 1868 3078 1854 3078 1853 3079 1870 3079 1871 3079 1872 3080 1863 3080 1865 3080 1871 3081 1869 3081 1853 3081 1871 3082 1873 3082 1869 3082 1869 3083 1873 3083 1867 3083 1867 3084 1873 3084 1874 3084 1867 3085 1874 3085 1865 3085 1872 3086 1865 3086 1874 3086 1863 3087 1872 3087 1875 3087 1863 3088 1875 3088 1861 3088 1861 3089 1875 3089 1876 3089 1861 3090 1876 3090 1860 3090 1860 3091 1876 3091 1858 3091 1858 3092 1876 3092 1877 3092 1858 3093 1877 3093 1856 3093 1856 3094 1877 3094 1878 3094 1856 3095 1878 3095 1853 3095 1853 3096 1878 3096 1870 3096 1825 3097 1095 3097 1640 3097 1640 3098 1095 3098 1096 3098 1398 3099 1639 3099 1642 3099 1641 3100 1640 3100 1096 3100 1457 3101 1638 3101 1398 3101 258 3102 1398 3102 1642 3102 258 3103 1642 3103 1096 3103 1642 3104 1641 3104 1096 3104 1398 3105 1638 3105 1639 3105 1879 3106 1880 3106 1881 3106 1882 3107 1883 3107 1881 3107 1882 3108 1881 3108 1880 3108 1884 3109 1885 3109 1886 3109 1884 3110 1886 3110 1887 3110 1887 3111 1886 3111 1888 3111 1887 3112 1888 3112 1889 3112 1883 3113 1882 3113 1890 3113 1883 3114 1890 3114 1891 3114 1885 3115 1884 3115 1892 3115 1885 3116 1892 3116 1890 3116 1890 3117 1892 3117 1891 3117 1889 3118 1888 3118 1893 3118 1889 3119 1893 3119 1894 3119 1894 3120 1893 3120 1895 3120 1894 3121 1895 3121 1879 3121 1879 3122 1895 3122 1880 3122 1879 3123 1896 3123 1897 3123 1879 3124 1897 3124 1894 3124 1894 3125 1897 3125 1898 3125 1894 3126 1898 3126 1889 3126 1889 3127 1898 3127 1899 3127 1889 3128 1899 3128 1887 3128 1887 3129 1899 3129 1900 3129 1887 3130 1900 3130 1884 3130 1884 3131 1900 3131 1901 3131 1884 3132 1901 3132 1892 3132 1892 3133 1901 3133 1902 3133 1892 3134 1902 3134 1891 3134 1891 3135 1902 3135 1883 3135 1883 3136 1902 3136 1903 3136 1883 3137 1903 3137 1904 3137 1883 3138 1904 3138 1881 3138 1881 3139 1904 3139 1896 3139 1881 3140 1896 3140 1879 3140 1906 3141 265 3141 1645 3141 1093 3142 1826 3142 1092 3142 1092 3143 1826 3143 1643 3143 9 3144 8 3144 1646 3144 1646 3145 8 3145 1907 3145 1645 3146 265 3146 1092 3146 1092 3147 1643 3147 1644 3147 1905 3148 190 3148 1614 3148 1905 3149 1614 3149 1907 3149 1907 3150 1614 3150 1613 3150 1907 3151 1613 3151 1646 3151 1645 3152 1610 3152 1906 3152 1906 3153 1610 3153 1674 3153 1674 3154 1610 3154 1609 3154 1674 3155 1609 3155 1608 3155 1674 3156 1608 3156 192 3156 192 3157 1608 3157 190 3157 190 3158 1608 3158 1614 3158 1092 3159 1644 3159 1645 3159 1399 3160 1908 3160 1909 3160 1131 3161 1910 3161 1911 3161 1396 3162 1912 3162 1913 3162 1396 3163 1913 3163 1397 3163 1130 3164 1914 3164 1915 3164 1130 3165 1915 3165 1131 3165 1131 3166 1915 3166 1910 3166 1131 3167 1911 3167 1912 3167 1131 3168 1912 3168 1396 3168 1399 3169 1909 3169 1130 3169 1130 3170 1909 3170 1914 3170 1397 3171 1913 3171 1916 3171 1397 3172 1916 3172 1908 3172 1397 3173 1908 3173 1399 3173 1094 3174 1147 3174 259 3174 259 3175 1147 3175 1131 3175 259 3176 1131 3176 1396 3176 1919 3177 1404 3177 1920 3177 1142 3178 1921 3178 1918 3178 1920 3179 1922 3179 1919 3179 1923 3180 1921 3180 1141 3180 1141 3181 1921 3181 1142 3181 1404 3182 1924 3182 1920 3182 1922 3183 1925 3183 1919 3183 1919 3184 1925 3184 1141 3184 1141 3185 1925 3185 1923 3185 1921 3186 1926 3186 1927 3186 1921 3187 1927 3187 1918 3187 1918 3188 1927 3188 1928 3188 1918 3189 1928 3189 1929 3189 1918 3190 1929 3190 1917 3190 1917 3191 1929 3191 1930 3191 1917 3192 1930 3192 1924 3192 1924 3193 1930 3193 1931 3193 1924 3194 1931 3194 1920 3194 1920 3195 1931 3195 1932 3195 1920 3196 1932 3196 1922 3196 1922 3197 1932 3197 1933 3197 1922 3198 1933 3198 1925 3198 1925 3199 1933 3199 1934 3199 1925 3200 1934 3200 1935 3200 1925 3201 1935 3201 1923 3201 1923 3202 1935 3202 1926 3202 1923 3203 1926 3203 1921 3203 1936 3204 1937 3204 1938 3204 1938 3205 1937 3205 1939 3205 1938 3206 1939 3206 1940 3206 1938 3207 1940 3207 1941 3207 1941 3208 1940 3208 1942 3208 1941 3209 1942 3209 1943 3209 1943 3210 1942 3210 1944 3210 1944 3211 1942 3211 1945 3211 1944 3212 1945 3212 1946 3212 1946 3213 1945 3213 1947 3213 1946 3214 1947 3214 1948 3214 1948 3215 1947 3215 1949 3215 1948 3216 1949 3216 1950 3216 1950 3217 1949 3217 1951 3217 1950 3218 1951 3218 1952 3218 1952 3219 1951 3219 1937 3219 1952 3220 1937 3220 1936 3220 1953 3221 1915 3221 1954 3221 1954 3222 1915 3222 1914 3222 1954 3223 1914 3223 1955 3223 1955 3224 1914 3224 1909 3224 1955 3225 1909 3225 1956 3225 1956 3226 1909 3226 1908 3226 1956 3227 1908 3227 1957 3227 1957 3228 1908 3228 1916 3228 1957 3229 1916 3229 1958 3229 1958 3230 1916 3230 1913 3230 1958 3231 1913 3231 1959 3231 1959 3232 1913 3232 1912 3232 1959 3233 1912 3233 1960 3233 1960 3234 1912 3234 1911 3234 1960 3235 1911 3235 1910 3235 1960 3236 1910 3236 1953 3236 1953 3237 1910 3237 1915 3237 1880 3238 1961 3238 1962 3238 1880 3239 1962 3239 1882 3239 1882 3240 1962 3240 1963 3240 1882 3241 1963 3241 1890 3241 1890 3242 1963 3242 1964 3242 1890 3243 1964 3243 1965 3243 1890 3244 1965 3244 1885 3244 1885 3245 1965 3245 1966 3245 1885 3246 1966 3246 1886 3246 1886 3247 1966 3247 1967 3247 1886 3248 1967 3248 1888 3248 1888 3249 1967 3249 1968 3249 1888 3250 1968 3250 1893 3250 1893 3251 1968 3251 1969 3251 1893 3252 1969 3252 1895 3252 1895 3253 1969 3253 1961 3253 1895 3254 1961 3254 1880 3254 1870 3255 1970 3255 1971 3255 1870 3256 1971 3256 1871 3256 1871 3257 1971 3257 1972 3257 1871 3258 1972 3258 1873 3258 1873 3259 1972 3259 1973 3259 1873 3260 1973 3260 1874 3260 1874 3261 1973 3261 1974 3261 1874 3262 1974 3262 1872 3262 1872 3263 1974 3263 1975 3263 1872 3264 1975 3264 1875 3264 1875 3265 1975 3265 1976 3265 1875 3266 1976 3266 1876 3266 1876 3267 1976 3267 1877 3267 1877 3268 1976 3268 1977 3268 1877 3269 1977 3269 1878 3269 1878 3270 1977 3270 1970 3270 1878 3271 1970 3271 1870 3271 280 3272 1402 3272 318 3272 318 3273 1402 3273 1665 3273 318 3274 1665 3274 974 3274 1139 3275 973 3275 1665 3275 1665 3276 973 3276 974 3276 1978 3277 286 3277 1672 3277 1672 3278 286 3278 323 3278 1672 3279 323 3279 1089 3279 1672 3280 1089 3280 1088 3280 1540 3281 1655 3281 1514 3281 1514 3282 1655 3282 1652 3282 7 3283 1657 3283 1556 3283 1563 3284 1658 3284 3 3284 1556 3285 1563 3285 7 3285 7 3286 1563 3286 3 3286 7 3287 3 3287 6 3287 6 3288 3 3288 1 3288 6 3289 1 3289 1979 3289 1980 3290 1981 3290 1982 3290 1982 3291 1981 3291 1983 3291 1982 3292 1983 3292 1984 3292 1984 3293 1983 3293 1985 3293 1984 3294 1985 3294 1986 3294 1984 3295 1986 3295 1987 3295 1987 3296 1986 3296 1988 3296 1987 3297 1988 3297 1989 3297 1989 3298 1988 3298 1990 3298 1990 3299 1988 3299 1991 3299 1990 3300 1991 3300 1992 3300 1990 3301 1992 3301 1993 3301 1993 3302 1992 3302 1994 3302 1993 3303 1994 3303 1995 3303 1995 3304 1994 3304 1996 3304 1995 3305 1996 3305 1997 3305 1997 3306 1996 3306 1980 3306 1980 3307 1996 3307 1981 3307 1998 3308 1989 3308 1999 3308 1999 3309 1989 3309 1990 3309 1999 3310 1990 3310 2000 3310 2000 3311 1990 3311 1993 3311 2000 3312 1993 3312 2001 3312 2001 3313 1993 3313 1995 3313 2001 3314 1995 3314 1997 3314 2001 3315 1997 3315 2002 3315 2002 3316 1997 3316 2003 3316 2003 3317 1997 3317 1980 3317 2003 3318 1980 3318 2004 3318 2004 3319 1980 3319 1982 3319 2004 3320 1982 3320 1984 3320 2004 3321 1984 3321 2005 3321 2005 3322 1984 3322 1987 3322 2005 3323 1987 3323 1998 3323 1998 3324 1987 3324 1989 3324 2006 3325 2007 3325 2008 3325 2008 3326 2007 3326 2009 3326 2008 3327 2009 3327 2010 3327 2010 3328 2009 3328 2011 3328 2010 3329 2011 3329 2012 3329 2012 3330 2011 3330 2013 3330 2012 3331 2013 3331 2014 3331 2014 3332 2013 3332 2015 3332 2015 3333 2013 3333 2016 3333 2015 3334 2016 3334 2017 3334 2015 3335 2017 3335 2018 3335 2018 3336 2017 3336 2019 3336 2019 3337 2017 3337 2020 3337 2019 3338 2020 3338 2021 3338 2019 3339 2021 3339 2022 3339 2022 3340 2021 3340 2023 3340 2022 3341 2023 3341 2006 3341 2006 3342 2023 3342 2007 3342 2008 3343 2010 3343 2024 3343 2024 3344 2010 3344 2025 3344 2025 3345 2010 3345 2012 3345 2025 3346 2012 3346 2014 3346 2025 3347 2014 3347 2026 3347 2014 3348 2015 3348 2026 3348 2026 3349 2015 3349 2027 3349 2027 3350 2015 3350 2018 3350 2027 3351 2018 3351 2028 3351 2028 3352 2018 3352 2019 3352 2028 3353 2019 3353 2029 3353 2029 3354 2019 3354 2022 3354 2029 3355 2022 3355 2030 3355 2030 3356 2022 3356 2006 3356 2008 3357 2024 3357 2031 3357 2008 3358 2031 3358 2006 3358 2006 3359 2031 3359 2030 3359 1673 3360 2032 3360 1672 3360 1672 3361 2032 3361 1978 3361 2 3362 3 3362 2033 3362 2033 3363 3 3363 1658 3363 1675 3364 1102 3364 1661 3364 1661 3365 1102 3365 1103 3365 1660 3366 1661 3366 1103 3366 1611 3367 1605 3367 2034 3367 1606 3368 1607 3368 266 3368 266 3369 1607 3369 1103 3369 1103 3370 1607 3370 1659 3370 2032 3371 2034 3371 1978 3371 1978 3372 2034 3372 1605 3372 1978 3373 1605 3373 266 3373 266 3374 1605 3374 1606 3374 1103 3375 1659 3375 1660 3375 2033 3376 1658 3376 1612 3376 2033 3377 1612 3377 2034 3377 2034 3378 1612 3378 1611 3378 2035 3379 2036 3379 2037 3379 2037 3380 2036 3380 2038 3380 2037 3381 2038 3381 2039 3381 2039 3382 2038 3382 2040 3382 2039 3383 2040 3383 2041 3383 2041 3384 2040 3384 2042 3384 2041 3385 2042 3385 2043 3385 2043 3386 2042 3386 2044 3386 2043 3387 2044 3387 2045 3387 2043 3388 2045 3388 2046 3388 2046 3389 2045 3389 2047 3389 2047 3390 2045 3390 2048 3390 2047 3391 2048 3391 2049 3391 2047 3392 2049 3392 2050 3392 2050 3393 2049 3393 2051 3393 2050 3394 2051 3394 2052 3394 2036 3395 2035 3395 2053 3395 2036 3396 2053 3396 2052 3396 2052 3397 2053 3397 2050 3397 2052 3398 2054 3398 2055 3398 2052 3399 2055 3399 2036 3399 2036 3400 2055 3400 2038 3400 2038 3401 2055 3401 2056 3401 2038 3402 2056 3402 2040 3402 2040 3403 2056 3403 2057 3403 2040 3404 2057 3404 2058 3404 2040 3405 2058 3405 2042 3405 2042 3406 2058 3406 2059 3406 2042 3407 2059 3407 2044 3407 2044 3408 2059 3408 2045 3408 2045 3409 2059 3409 2060 3409 2045 3410 2060 3410 2061 3410 2045 3411 2061 3411 2048 3411 2048 3412 2061 3412 2062 3412 2048 3413 2062 3413 2049 3413 2049 3414 2062 3414 2051 3414 2051 3415 2062 3415 2054 3415 2051 3416 2054 3416 2052 3416 2064 3417 1656 3417 1657 3417 7 3418 5 3418 1657 3418 1657 3419 5 3419 2064 3419 2063 3420 1655 3420 2064 3420 2064 3421 1655 3421 1656 3421 2065 3422 72 3422 2066 3422 1625 3423 2066 3423 72 3423 2067 3424 2068 3424 2069 3424 2069 3425 2070 3425 1625 3425 1625 3426 2070 3426 2071 3426 1625 3427 2071 3427 2066 3427 2072 3428 2073 3428 73 3428 73 3429 2073 3429 2067 3429 2067 3430 2073 3430 2074 3430 2067 3431 2074 3431 2068 3431 2068 3432 2070 3432 2069 3432 2072 3433 73 3433 72 3433 2072 3434 72 3434 2065 3434 2075 3435 2069 3435 1625 3435 2075 3436 1625 3436 81 3436 81 3437 1625 3437 79 3437 88 3438 2076 3438 2077 3438 88 3439 2077 3439 104 3439 104 3440 2077 3440 2078 3440 2079 3441 2080 3441 87 3441 87 3442 2080 3442 88 3442 88 3443 2080 3443 2076 3443 104 3444 2081 3444 2082 3444 104 3445 2082 3445 105 3445 2082 3446 2083 3446 105 3446 105 3447 2083 3447 245 3447 104 3448 2078 3448 2081 3448 245 3449 2083 3449 2079 3449 2079 3450 87 3450 245 3450 2077 3451 210 3451 2078 3451 2078 3452 210 3452 211 3452 2078 3453 211 3453 2081 3453 2081 3454 211 3454 214 3454 2081 3455 214 3455 197 3455 2081 3456 197 3456 2082 3456 2082 3457 197 3457 199 3457 2082 3458 199 3458 2083 3458 2083 3459 199 3459 2079 3459 2079 3460 199 3460 202 3460 2079 3461 202 3461 204 3461 2079 3462 204 3462 2080 3462 2080 3463 204 3463 206 3463 2080 3464 206 3464 2076 3464 2076 3465 206 3465 208 3465 2076 3466 208 3466 2077 3466 2077 3467 208 3467 210 3467 78 3468 92 3468 82 3468 82 3469 92 3469 98 3469 82 3470 98 3470 101 3470 82 3471 101 3471 83 3471 83 3472 101 3472 76 3472 76 3473 101 3473 102 3473 76 3474 102 3474 96 3474 76 3475 96 3475 77 3475 77 3476 96 3476 74 3476 74 3477 96 3477 95 3477 74 3478 95 3478 75 3478 75 3479 95 3479 97 3479 75 3480 97 3480 85 3480 85 3481 97 3481 94 3481 85 3482 94 3482 80 3482 80 3483 94 3483 78 3483 78 3484 94 3484 92 3484 171 3485 2066 3485 169 3485 169 3486 2066 3486 2071 3486 169 3487 2071 3487 168 3487 168 3488 2071 3488 2070 3488 168 3489 2070 3489 166 3489 166 3490 2070 3490 2068 3490 166 3491 2068 3491 164 3491 164 3492 2068 3492 162 3492 162 3493 2068 3493 2074 3493 162 3494 2074 3494 159 3494 159 3495 2074 3495 2073 3495 159 3496 2073 3496 175 3496 175 3497 2073 3497 2072 3497 175 3498 2072 3498 173 3498 173 3499 2072 3499 2065 3499 173 3500 2065 3500 171 3500 171 3501 2065 3501 2066 3501 67 3502 51 3502 2053 3502 2053 3503 51 3503 2050 3503 2050 3504 51 3504 54 3504 2050 3505 54 3505 2047 3505 2047 3506 54 3506 56 3506 2047 3507 56 3507 58 3507 2047 3508 58 3508 2046 3508 2046 3509 58 3509 59 3509 2046 3510 59 3510 2043 3510 2043 3511 59 3511 62 3511 2043 3512 62 3512 2041 3512 2041 3513 62 3513 63 3513 2041 3514 63 3514 2039 3514 2039 3515 63 3515 65 3515 2039 3516 65 3516 2037 3516 2037 3517 65 3517 2035 3517 2035 3518 65 3518 67 3518 2035 3519 67 3519 2053 3519 2031 3520 50 3520 36 3520 2031 3521 36 3521 2030 3521 2030 3522 36 3522 37 3522 2030 3523 37 3523 2029 3523 2029 3524 37 3524 39 3524 2029 3525 39 3525 2028 3525 2028 3526 39 3526 41 3526 2028 3527 41 3527 2027 3527 2027 3528 41 3528 43 3528 2027 3529 43 3529 2026 3529 2026 3530 43 3530 45 3530 2026 3531 45 3531 2025 3531 2025 3532 45 3532 47 3532 2025 3533 47 3533 49 3533 2025 3534 49 3534 2024 3534 2024 3535 49 3535 50 3535 2024 3536 50 3536 2031 3536 1713 3537 1519 3537 1715 3537 1562 3538 1721 3538 1546 3538 1546 3539 1721 3539 1719 3539 1519 3540 1717 3540 1715 3540 1517 3541 1719 3541 1717 3541 1719 3542 1517 3542 1542 3542 1719 3543 1542 3543 1546 3543 1583 3544 1711 3544 1709 3544 1713 3545 1711 3545 1583 3545 1721 3546 1562 3546 1705 3546 1583 3547 1709 3547 1567 3547 1567 3548 1709 3548 1707 3548 1567 3549 1707 3549 1705 3549 1705 3550 1562 3550 1567 3550 1753 3551 1752 3551 1600 3551 1519 3552 1755 3552 1754 3552 1519 3553 1754 3553 2009 3553 1687 3554 1756 3554 1519 3554 1519 3555 1756 3555 1755 3555 1753 3556 1603 3556 1754 3556 1753 3557 1600 3557 1603 3557 1590 3558 1751 3558 1750 3558 1750 3559 1581 3559 1590 3559 1600 3560 1752 3560 1590 3560 1590 3561 1752 3561 1751 3561 1581 3562 1750 3562 1749 3562 1581 3563 1749 3563 1582 3563 1749 3564 1748 3564 1582 3564 1582 3565 1748 3565 1687 3565 1687 3566 1748 3566 1756 3566 1694 3567 1692 3567 1519 3567 1691 3568 1689 3568 1519 3568 1713 3569 1694 3569 1519 3569 1689 3570 1687 3570 1519 3570 1692 3571 1691 3571 1519 3571 1583 3572 1678 3572 1713 3572 1713 3573 1678 3573 1694 3573 1687 3574 1685 3574 1582 3574 1685 3575 1683 3575 1582 3575 1582 3576 1683 3576 1681 3576 1582 3577 1681 3577 1583 3577 1576 3578 2013 3578 1587 3578 2007 3579 2023 3579 1533 3579 1533 3580 2023 3580 2021 3580 2084 3581 2020 3581 2017 3581 2013 3582 2011 3582 1587 3582 1587 3583 2011 3583 2009 3583 1587 3584 2009 3584 1603 3584 2017 3585 2016 3585 2084 3585 2084 3586 2016 3586 1576 3586 2084 3587 1576 3587 1565 3587 2016 3588 2013 3588 1576 3588 1754 3589 1603 3589 2009 3589 1517 3590 1717 3590 1519 3590 1521 3591 1519 3591 2009 3591 2007 3592 1533 3592 2009 3592 2009 3593 1533 3593 1521 3593 1512 3594 1506 3594 1515 3594 1981 3595 1996 3595 1515 3595 2021 3596 2020 3596 1533 3596 1533 3597 2020 3597 2084 3597 1533 3598 2084 3598 1985 3598 1985 3599 2084 3599 1986 3599 1996 3600 1994 3600 1515 3600 1515 3601 1994 3601 2085 3601 1533 3602 1985 3602 1983 3602 1994 3603 1992 3603 2085 3603 2084 3604 1988 3604 1986 3604 1533 3605 1983 3605 1981 3605 1533 3606 1981 3606 1515 3606 1992 3607 1991 3607 2085 3607 2085 3608 1991 3608 1988 3608 2085 3609 1988 3609 2084 3609 1552 3610 2062 3610 2061 3610 2056 3611 2055 3611 1515 3611 1512 3612 2054 3612 2062 3612 2085 3613 2056 3613 1515 3613 1512 3614 2062 3614 1552 3614 1512 3615 1552 3615 1541 3615 2061 3616 2060 3616 1552 3616 1515 3617 2055 3617 2054 3617 1515 3618 2054 3618 1512 3618 2085 3619 2059 3619 2058 3619 2060 3620 2059 3620 1552 3620 1552 3621 2059 3621 2085 3621 1552 3622 2085 3622 1565 3622 1565 3623 2085 3623 2084 3623 2058 3624 2057 3624 2085 3624 2085 3625 2057 3625 2056 3625 2001 3626 2086 3626 2000 3626 2000 3627 2086 3627 2087 3627 2000 3628 2087 3628 1999 3628 1999 3629 2087 3629 2088 3629 1999 3630 2088 3630 1998 3630 1998 3631 2088 3631 2005 3631 2005 3632 2088 3632 2089 3632 2005 3633 2089 3633 2090 3633 2005 3634 2090 3634 2004 3634 2004 3635 2090 3635 2091 3635 2004 3636 2091 3636 2003 3636 2003 3637 2091 3637 2092 3637 2003 3638 2092 3638 2002 3638 2002 3639 2092 3639 2093 3639 2002 3640 2093 3640 2001 3640 2001 3641 2093 3641 2086 3641 1414 3642 1650 3642 1419 3642 1419 3643 1650 3643 1649 3643 1646 3644 1465 3644 9 3644 9 3645 1465 3645 1451 3645 2094 3646 11 3646 12 3646 12 3647 11 3647 9 3647 12 3648 9 3648 13 3648 13 3649 9 3649 1451 3649 13 3650 1451 3650 1647 3650 2095 3651 2096 3651 2097 3651 2097 3652 2096 3652 2098 3652 2097 3653 2098 3653 2099 3653 2097 3654 2099 3654 2100 3654 2100 3655 2099 3655 2101 3655 2101 3656 2099 3656 2102 3656 2101 3657 2102 3657 2103 3657 2103 3658 2102 3658 2104 3658 2103 3659 2104 3659 2105 3659 2105 3660 2104 3660 2106 3660 2105 3661 2106 3661 2107 3661 2107 3662 2106 3662 2108 3662 2107 3663 2108 3663 2109 3663 2109 3664 2108 3664 2110 3664 2109 3665 2110 3665 2111 3665 2111 3666 2110 3666 2112 3666 2111 3667 2112 3667 2095 3667 2095 3668 2112 3668 2096 3668 2113 3669 2103 3669 2114 3669 2114 3670 2103 3670 2105 3670 2114 3671 2105 3671 2115 3671 2115 3672 2105 3672 2107 3672 2115 3673 2107 3673 2116 3673 2116 3674 2107 3674 2109 3674 2116 3675 2109 3675 2117 3675 2117 3676 2109 3676 2111 3676 2117 3677 2111 3677 2118 3677 2118 3678 2111 3678 2095 3678 2118 3679 2095 3679 2119 3679 2119 3680 2095 3680 2097 3680 2119 3681 2097 3681 2120 3681 2120 3682 2097 3682 2121 3682 2121 3683 2097 3683 2100 3683 2121 3684 2100 3684 2122 3684 2122 3685 2100 3685 2101 3685 2122 3686 2101 3686 2113 3686 2113 3687 2101 3687 2103 3687 2123 3688 2124 3688 2125 3688 2123 3689 2125 3689 2126 3689 2126 3690 2125 3690 2127 3690 2127 3691 2125 3691 2128 3691 2127 3692 2128 3692 2129 3692 2129 3693 2128 3693 2130 3693 2129 3694 2130 3694 2131 3694 2131 3695 2130 3695 2132 3695 2131 3696 2132 3696 2133 3696 2133 3697 2132 3697 2134 3697 2133 3698 2134 3698 2135 3698 2135 3699 2134 3699 2136 3699 2135 3700 2136 3700 2137 3700 2137 3701 2136 3701 2138 3701 2137 3702 2138 3702 2139 3702 2139 3703 2138 3703 2140 3703 2139 3704 2140 3704 2124 3704 2139 3705 2124 3705 2123 3705 2141 3706 2126 3706 2127 3706 2141 3707 2127 3707 2142 3707 2142 3708 2127 3708 2129 3708 2142 3709 2129 3709 2143 3709 2143 3710 2129 3710 2131 3710 2143 3711 2131 3711 2133 3711 2143 3712 2133 3712 2144 3712 2144 3713 2133 3713 2135 3713 2144 3714 2135 3714 2145 3714 2145 3715 2135 3715 2137 3715 2145 3716 2137 3716 2146 3716 2146 3717 2137 3717 2139 3717 2146 3718 2139 3718 2147 3718 2141 3719 2148 3719 2126 3719 2126 3720 2148 3720 2123 3720 2123 3721 2148 3721 2149 3721 2123 3722 2149 3722 2139 3722 2139 3723 2149 3723 2147 3723 2150 3724 2151 3724 2152 3724 2150 3725 2152 3725 2153 3725 2153 3726 2152 3726 2154 3726 2153 3727 2154 3727 2155 3727 2154 3728 2156 3728 2155 3728 2155 3729 2156 3729 2157 3729 2157 3730 2156 3730 2158 3730 2157 3731 2158 3731 2159 3731 2159 3732 2158 3732 2160 3732 2159 3733 2160 3733 2161 3733 2161 3734 2160 3734 2162 3734 2161 3735 2162 3735 2163 3735 2163 3736 2162 3736 2164 3736 2151 3737 2150 3737 2165 3737 2151 3738 2165 3738 2166 3738 2166 3739 2165 3739 2163 3739 2166 3740 2163 3740 2164 3740 2166 3741 2167 3741 2151 3741 2151 3742 2167 3742 2168 3742 2151 3743 2168 3743 2152 3743 2152 3744 2168 3744 2169 3744 2152 3745 2169 3745 2154 3745 2154 3746 2169 3746 2170 3746 2154 3747 2170 3747 2156 3747 2156 3748 2170 3748 2171 3748 2156 3749 2171 3749 2158 3749 2158 3750 2171 3750 2172 3750 2158 3751 2172 3751 2160 3751 2160 3752 2172 3752 2173 3752 2160 3753 2173 3753 2162 3753 2162 3754 2173 3754 2174 3754 2162 3755 2174 3755 2164 3755 2164 3756 2174 3756 2175 3756 2164 3757 2175 3757 2166 3757 2166 3758 2175 3758 2167 3758 235 3759 1651 3759 233 3759 15 3760 13 3760 2177 3760 2177 3761 13 3761 1647 3761 235 3762 1650 3762 1651 3762 1650 3763 235 3763 1649 3763 1649 3764 235 3764 2176 3764 1649 3765 2176 3765 2177 3765 2177 3766 1647 3766 1648 3766 1648 3767 1649 3767 2177 3767 123 3768 2178 3768 2179 3768 1637 3769 2180 3769 2181 3769 2182 3770 2183 3770 2184 3770 2184 3771 2183 3771 2185 3771 2186 3772 2187 3772 124 3772 124 3773 2187 3773 2180 3773 124 3774 2180 3774 1637 3774 123 3775 2179 3775 2186 3775 123 3776 2186 3776 124 3776 2178 3777 123 3777 2183 3777 2183 3778 123 3778 2185 3778 2181 3779 2188 3779 1637 3779 1637 3780 2188 3780 2184 3780 2184 3781 2188 3781 2182 3781 137 3782 132 3782 2189 3782 2189 3783 132 3783 1637 3783 2189 3784 1637 3784 2184 3784 157 3785 2190 3785 2191 3785 157 3786 2191 3786 158 3786 158 3787 2191 3787 2192 3787 158 3788 2192 3788 2193 3788 158 3789 2193 3789 143 3789 143 3790 2194 3790 2195 3790 2196 3791 2190 3791 157 3791 143 3792 2193 3792 2194 3792 2195 3793 242 3793 144 3793 2195 3794 144 3794 143 3794 238 3795 2196 3795 157 3795 242 3796 2195 3796 2197 3796 242 3797 2197 3797 238 3797 238 3798 2197 3798 2198 3798 238 3799 2198 3799 2196 3799 2192 3800 225 3800 2193 3800 2193 3801 225 3801 227 3801 2193 3802 227 3802 2194 3802 2194 3803 227 3803 229 3803 2194 3804 229 3804 2195 3804 2195 3805 229 3805 216 3805 2195 3806 216 3806 2197 3806 2197 3807 216 3807 218 3807 2197 3808 218 3808 2198 3808 2198 3809 218 3809 220 3809 2198 3810 220 3810 2196 3810 2196 3811 220 3811 2190 3811 2190 3812 220 3812 222 3812 2190 3813 222 3813 223 3813 2190 3814 223 3814 2191 3814 2191 3815 223 3815 2192 3815 2192 3816 223 3816 225 3816 130 3817 155 3817 131 3817 131 3818 155 3818 150 3818 131 3819 150 3819 133 3819 133 3820 150 3820 148 3820 133 3821 148 3821 147 3821 133 3822 147 3822 134 3822 134 3823 147 3823 146 3823 134 3824 146 3824 129 3824 129 3825 146 3825 127 3825 127 3826 146 3826 145 3826 127 3827 145 3827 139 3827 139 3828 145 3828 152 3828 139 3829 152 3829 136 3829 136 3830 152 3830 138 3830 138 3831 152 3831 151 3831 138 3832 151 3832 155 3832 138 3833 155 3833 130 3833 184 3834 2180 3834 2187 3834 184 3835 2187 3835 183 3835 183 3836 2187 3836 2186 3836 183 3837 2186 3837 180 3837 180 3838 2186 3838 2179 3838 180 3839 2179 3839 179 3839 179 3840 2179 3840 2178 3840 179 3841 2178 3841 177 3841 177 3842 2178 3842 2183 3842 177 3843 2183 3843 176 3843 176 3844 2183 3844 2182 3844 176 3845 2182 3845 188 3845 188 3846 2182 3846 2188 3846 188 3847 2188 3847 186 3847 186 3848 2188 3848 2181 3848 186 3849 2181 3849 2180 3849 186 3850 2180 3850 184 3850 2165 3851 107 3851 120 3851 2165 3852 120 3852 2163 3852 2163 3853 120 3853 119 3853 2163 3854 119 3854 2161 3854 2161 3855 119 3855 116 3855 2161 3856 116 3856 2159 3856 2159 3857 116 3857 114 3857 2159 3858 114 3858 2157 3858 2157 3859 114 3859 113 3859 2157 3860 113 3860 2155 3860 2155 3861 113 3861 111 3861 2155 3862 111 3862 2153 3862 2153 3863 111 3863 109 3863 2153 3864 109 3864 2150 3864 2150 3865 109 3865 107 3865 2150 3866 107 3866 2165 3866 2149 3867 2148 3867 17 3867 2149 3868 17 3868 32 3868 2149 3869 32 3869 2147 3869 2147 3870 32 3870 30 3870 2147 3871 30 3871 2146 3871 2146 3872 30 3872 2145 3872 2145 3873 30 3873 28 3873 2145 3874 28 3874 26 3874 2145 3875 26 3875 2144 3875 2144 3876 26 3876 24 3876 2144 3877 24 3877 2143 3877 2143 3878 24 3878 22 3878 2143 3879 22 3879 2142 3879 2142 3880 22 3880 20 3880 2142 3881 20 3881 2141 3881 2141 3882 20 3882 18 3882 2141 3883 18 3883 2148 3883 2148 3884 18 3884 17 3884 1463 3885 2199 3885 1449 3885 2200 3886 1862 3886 1859 3886 1859 3887 1857 3887 2200 3887 2200 3888 1857 3888 1432 3888 1432 3889 1857 3889 1855 3889 1854 3890 1429 3890 1427 3890 1854 3891 1427 3891 1855 3891 1866 3892 1864 3892 1466 3892 1868 3893 1454 3893 1429 3893 1868 3894 1429 3894 1854 3894 1868 3895 1466 3895 1454 3895 1466 3896 1864 3896 1862 3896 1466 3897 1862 3897 2200 3897 1868 3898 1866 3898 1466 3898 1434 3899 1896 3899 1904 3899 1434 3900 1904 3900 1903 3900 1499 3901 1898 3901 1496 3901 1434 3902 1903 3902 2201 3902 2201 3903 1903 3903 1902 3903 2124 3904 1897 3904 1896 3904 2201 3905 1902 3905 1901 3905 1901 3906 1900 3906 2201 3906 2201 3907 1900 3907 1487 3907 1487 3908 1900 3908 1899 3908 1499 3909 1899 3909 1898 3909 1496 3910 1898 3910 1897 3910 1496 3911 1897 3911 1492 3911 1487 3912 1899 3912 1499 3912 2124 3913 1486 3913 1492 3913 2124 3914 1492 3914 1897 3914 2202 3915 2128 3915 1444 3915 1444 3916 2128 3916 2125 3916 2124 3917 2140 3917 1486 3917 1463 3918 2136 3918 2134 3918 1444 3919 2125 3919 2124 3919 2138 3920 1482 3920 2140 3920 2140 3921 1482 3921 1486 3921 1482 3922 2138 3922 2136 3922 1482 3923 2136 3923 1469 3923 1469 3924 2136 3924 1463 3924 1463 3925 2134 3925 2202 3925 2202 3926 2134 3926 2132 3926 2132 3927 2130 3927 2202 3927 2202 3928 2130 3928 2128 3928 2175 3929 2174 3929 2203 3929 2203 3930 2174 3930 2173 3930 2203 3931 2173 3931 2199 3931 2173 3932 2172 3932 2199 3932 1415 3933 2169 3933 2168 3933 2167 3934 1415 3934 2168 3934 1415 3935 2167 3935 2203 3935 2203 3936 2167 3936 2175 3936 2199 3937 2172 3937 2171 3937 1446 3938 2171 3938 2170 3938 2199 3939 2171 3939 1446 3939 2199 3940 1446 3940 1449 3940 1415 3941 1418 3941 2169 3941 2169 3942 1418 3942 1446 3942 1446 3943 2170 3943 2169 3943 2203 3944 1417 3944 1415 3944 1444 3945 1417 3945 2203 3945 1896 3946 1434 3946 2124 3946 2124 3947 1434 3947 1440 3947 2124 3948 1440 3948 1444 3948 1855 3949 1427 3949 1432 3949 1444 3950 2112 3950 2110 3950 2110 3951 2202 3951 1444 3951 2099 3952 2098 3952 2203 3952 2199 3953 2099 3953 2203 3953 1444 3954 2096 3954 2112 3954 2110 3955 2108 3955 2202 3955 2202 3956 2108 3956 2106 3956 2098 3957 2096 3957 2203 3957 2203 3958 2096 3958 1444 3958 2104 3959 2102 3959 2199 3959 2202 3960 2106 3960 2104 3960 2199 3961 2102 3961 2099 3961 1463 3962 2202 3962 2199 3962 2199 3963 2202 3963 2104 3963 1839 3964 1837 3964 2200 3964 2201 3965 1835 3965 1833 3965 1830 3966 1828 3966 1434 3966 1434 3967 1828 3967 1432 3967 1432 3968 1828 3968 1843 3968 1839 3969 2200 3969 1841 3969 1841 3970 2200 3970 1432 3970 2200 3971 1837 3971 2201 3971 2201 3972 1837 3972 1835 3972 1843 3973 1841 3973 1432 3973 1833 3974 1832 3974 2201 3974 2201 3975 1832 3975 1434 3975 1434 3976 1832 3976 1830 3976 2201 3977 1487 3977 1474 3977 2201 3978 1474 3978 2200 3978 2200 3979 1474 3979 1466 3979 2204 3980 2032 3980 1673 3980 2204 3981 1673 3981 2205 3981 141 3982 149 3982 132 3982 126 3983 93 3983 90 3983 1637 3984 195 3984 124 3984 124 3985 195 3985 196 3985 231 3986 90 3986 2206 3986 2206 3987 90 3987 88 3987 2207 3988 2206 3988 1629 3988 1629 3989 2206 3989 88 3989 1629 3990 88 3990 104 3990 231 3991 158 3991 143 3991 231 3992 143 3992 90 3992 90 3993 143 3993 141 3993 90 3994 141 3994 126 3994 126 3995 141 3995 132 3995 1625 3996 72 3996 1627 3996 1627 3997 72 3997 2208 3997 1627 3998 2208 3998 2209 3998 196 3999 2208 3999 124 3999 124 4000 2208 4000 72 4000 124 4001 72 4001 126 4001 126 4002 72 4002 70 4002 126 4003 70 4003 93 4003 93 4004 70 4004 79 4004 2122 4005 2210 4005 2121 4005 2121 4006 2210 4006 2211 4006 2121 4007 2211 4007 2120 4007 2120 4008 2211 4008 2212 4008 2120 4009 2212 4009 2119 4009 2119 4010 2212 4010 2213 4010 2119 4011 2213 4011 2118 4011 2118 4012 2213 4012 2214 4012 2118 4013 2214 4013 2117 4013 2117 4014 2214 4014 2215 4014 2117 4015 2215 4015 2116 4015 2116 4016 2215 4016 2216 4016 2116 4017 2216 4017 2115 4017 2115 4018 2216 4018 2114 4018 2114 4019 2216 4019 2217 4019 2114 4020 2217 4020 2113 4020 2113 4021 2217 4021 2218 4021 2113 4022 2218 4022 2122 4022 2122 4023 2218 4023 2210 4023 1405 4024 288 4024 1771 4024 1771 4025 288 4025 286 4025 1398 4026 300 4026 1457 4026 1457 4027 300 4027 299 4027 1457 4028 299 4028 975 4028 1457 4029 975 4029 1132 4029 1955 4030 988 4030 996 4030 1955 4031 996 4031 1954 4031 1954 4032 996 4032 995 4032 1954 4033 995 4033 1953 4033 1953 4034 995 4034 994 4034 1953 4035 994 4035 993 4035 1953 4036 993 4036 1960 4036 1960 4037 993 4037 992 4037 1960 4038 992 4038 1959 4038 1959 4039 992 4039 1958 4039 1958 4040 992 4040 991 4040 1958 4041 991 4041 990 4041 1958 4042 990 4042 1957 4042 1957 4043 990 4043 989 4043 1957 4044 989 4044 1956 4044 1956 4045 989 4045 988 4045 1956 4046 988 4046 1955 4046 1803 4047 978 4047 987 4047 1803 4048 987 4048 1802 4048 1802 4049 987 4049 986 4049 1802 4050 986 4050 1801 4050 1801 4051 986 4051 985 4051 1801 4052 985 4052 1808 4052 1808 4053 985 4053 984 4053 1808 4054 984 4054 1807 4054 1807 4055 984 4055 983 4055 1807 4056 983 4056 982 4056 1807 4057 982 4057 1806 4057 1806 4058 982 4058 981 4058 1806 4059 981 4059 1805 4059 1805 4060 981 4060 980 4060 1805 4061 980 4061 1804 4061 1804 4062 980 4062 979 4062 1804 4063 979 4063 978 4063 1804 4064 978 4064 1803 4064 1091 4065 1090 4065 1674 4065 292 4066 1906 4066 1674 4066 292 4067 1674 4067 1090 4067 1927 4068 1033 4068 1928 4068 1928 4069 1033 4069 1031 4069 1928 4070 1031 4070 1929 4070 1932 4071 1027 4071 1933 4071 1933 4072 1027 4072 1025 4072 1933 4073 1025 4073 1934 4073 1934 4074 1025 4074 1024 4074 1934 4075 1024 4075 1935 4075 1935 4076 1024 4076 1037 4076 1935 4077 1037 4077 1036 4077 1935 4078 1036 4078 1926 4078 1926 4079 1036 4079 1033 4079 1926 4080 1033 4080 1927 4080 1782 4081 1007 4081 1021 4081 1782 4082 1021 4082 1783 4082 1783 4083 1021 4083 1020 4083 1783 4084 1020 4084 1776 4084 1776 4085 1020 4085 1017 4085 1776 4086 1017 4086 1777 4086 1777 4087 1017 4087 1015 4087 1777 4088 1015 4088 1778 4088 1778 4089 1015 4089 1013 4089 1778 4090 1013 4090 1779 4090 1779 4091 1013 4091 1011 4091 1779 4092 1011 4092 1780 4092 1781 4093 1008 4093 1782 4093 1782 4094 1008 4094 1007 4094 322 4095 1676 4095 336 4095 336 4096 1676 4096 1100 4096 1062 4097 1102 4097 1060 4097 1060 4098 1102 4098 1675 4098 1825 4099 305 4099 1095 4099 1095 4100 305 4100 304 4100 942 4101 1826 4101 940 4101 940 4102 1826 4102 1093 4102 2221 4103 1809 4103 1816 4103 2221 4104 1816 4104 2222 4104 2222 4105 1816 4105 1815 4105 2222 4106 1815 4106 2223 4106 2223 4107 1815 4107 2224 4107 2224 4108 1815 4108 1814 4108 2224 4109 1814 4109 1813 4109 2224 4110 1813 4110 2225 4110 2225 4111 1813 4111 1812 4111 2225 4112 1812 4112 2226 4112 2226 4113 1812 4113 2227 4113 2227 4114 1812 4114 1811 4114 2227 4115 1811 4115 2228 4115 2228 4116 1811 4116 1810 4116 2228 4117 1810 4117 2221 4117 2221 4118 1810 4118 1809 4118 1133 4119 1800 4119 1784 4119 1133 4120 1784 4120 1101 4120 1101 4121 1784 4121 1787 4121 257 4122 1793 4122 1135 4122 1135 4123 1793 4123 1796 4123 1787 4124 1789 4124 1101 4124 1101 4125 1789 4125 272 4125 1135 4126 1796 4126 1798 4126 1135 4127 1798 4127 1133 4127 1133 4128 1798 4128 1800 4128 272 4129 1789 4129 1791 4129 272 4130 1791 4130 257 4130 257 4131 1791 4131 1793 4131 1794 4132 899 4132 1136 4132 1788 4133 1786 4133 283 4133 1136 4134 1797 4134 1795 4134 1136 4135 1795 4135 1794 4135 899 4136 1794 4136 898 4136 1134 4137 1785 4137 1799 4137 1134 4138 1799 4138 1136 4138 1136 4139 1799 4139 1797 4139 1794 4140 1792 4140 898 4140 898 4141 1792 4141 284 4141 284 4142 1792 4142 1790 4142 1786 4143 1785 4143 283 4143 283 4144 1785 4144 1134 4144 1790 4145 1788 4145 284 4145 284 4146 1788 4146 283 4146 283 4147 1134 4147 267 4147 267 4148 1134 4148 1144 4148 267 4149 1144 4149 1771 4149 1818 4150 1817 4150 2229 4150 2229 4151 1817 4151 1824 4151 2229 4152 1824 4152 2230 4152 2230 4153 1824 4153 2231 4153 2231 4154 1824 4154 1823 4154 2231 4155 1823 4155 2232 4155 2232 4156 1823 4156 1822 4156 2232 4157 1822 4157 2233 4157 2233 4158 1822 4158 1821 4158 2233 4159 1821 4159 2234 4159 2234 4160 1821 4160 1820 4160 2234 4161 1820 4161 2235 4161 2235 4162 1820 4162 1819 4162 2235 4163 1819 4163 2236 4163 2236 4164 1819 4164 1818 4164 2236 4165 1818 4165 2237 4165 2237 4166 1818 4166 2229 4166 2238 4167 1970 4167 2239 4167 2239 4168 1970 4168 1977 4168 2239 4169 1977 4169 2240 4169 2240 4170 1977 4170 1976 4170 2240 4171 1976 4171 2241 4171 2241 4172 1976 4172 1975 4172 2241 4173 1975 4173 2242 4173 2242 4174 1975 4174 1974 4174 2242 4175 1974 4175 2243 4175 2243 4176 1974 4176 1973 4176 2243 4177 1973 4177 2244 4177 2244 4178 1973 4178 1972 4178 2244 4179 1972 4179 2245 4179 2245 4180 1972 4180 1971 4180 2245 4181 1971 4181 2238 4181 2238 4182 1971 4182 1970 4182 1946 4183 250 4183 1944 4183 1147 4184 1941 4184 1137 4184 1137 4185 1941 4185 1943 4185 1137 4186 1943 4186 1944 4186 250 4187 1946 4187 1948 4187 250 4188 1948 4188 261 4188 261 4189 1948 4189 1950 4189 1137 4190 1944 4190 251 4190 251 4191 1944 4191 250 4191 1094 4192 1952 4192 1936 4192 1936 4193 1938 4193 1147 4193 1147 4194 1938 4194 1941 4194 261 4195 1950 4195 1094 4195 1094 4196 1950 4196 1952 4196 1094 4197 1936 4197 1147 4197 1937 4198 1951 4198 276 4198 1145 4199 1942 4199 1940 4199 1145 4200 1940 4200 1146 4200 1146 4201 1940 4201 1939 4201 1146 4202 1939 4202 1937 4202 277 4203 1949 4203 1947 4203 277 4204 1947 4204 252 4204 252 4205 1947 4205 1945 4205 1146 4206 1937 4206 276 4206 252 4207 1945 4207 1145 4207 1145 4208 1945 4208 1942 4208 276 4209 1951 4209 1949 4209 276 4210 1949 4210 277 4210 263 4211 1919 4211 1141 4211 263 4212 1141 4212 276 4212 276 4213 1141 4213 1146 4213 2246 4214 1961 4214 1969 4214 2246 4215 1969 4215 2247 4215 2247 4216 1969 4216 1968 4216 2247 4217 1968 4217 2248 4217 2248 4218 1968 4218 1967 4218 2248 4219 1967 4219 2249 4219 2249 4220 1967 4220 1966 4220 2249 4221 1966 4221 2250 4221 2250 4222 1966 4222 1965 4222 2250 4223 1965 4223 1964 4223 2250 4224 1964 4224 2251 4224 2251 4225 1964 4225 1963 4225 2251 4226 1963 4226 2252 4226 2252 4227 1963 4227 1962 4227 2252 4228 1962 4228 2253 4228 2253 4229 1962 4229 1961 4229 2253 4230 1961 4230 2246 4230 257 4231 1135 4231 255 4231 255 4232 1135 4232 1138 4232 255 4233 1138 4233 1403 4233 268 4234 1766 4234 1143 4234 268 4235 1143 4235 899 4235 899 4236 1143 4236 1136 4236 252 4237 1145 4237 253 4237 253 4238 1145 4238 1142 4238 249 4239 1399 4239 1130 4239 249 4240 1130 4240 251 4240 251 4241 1130 4241 1137 4241 2254 4242 2255 4242 2256 4242 2257 4243 2255 4243 2258 4243 2259 4244 2260 4244 2258 4244 2258 4245 2260 4245 2257 4245 2257 4246 2261 4246 2255 4246 2256 4247 2262 4247 2254 4247 2255 4248 2261 4248 2256 4248 2261 4249 1695 4249 1703 4249 2261 4250 1703 4250 2256 4250 2256 4251 1703 4251 1702 4251 2256 4252 1702 4252 2262 4252 2262 4253 1702 4253 1701 4253 2262 4254 1701 4254 2254 4254 2254 4255 1701 4255 1700 4255 2254 4256 1700 4256 2255 4256 2255 4257 1700 4257 1699 4257 2255 4258 1699 4258 2258 4258 2258 4259 1699 4259 1698 4259 2258 4260 1698 4260 2259 4260 2259 4261 1698 4261 1697 4261 2259 4262 1697 4262 2260 4262 2260 4263 1697 4263 2257 4263 2257 4264 1697 4264 1696 4264 2257 4265 1696 4265 2261 4265 2261 4266 1696 4266 1695 4266 2263 4267 2264 4267 2265 4267 2265 4268 2266 4268 2267 4268 2265 4269 2264 4269 2266 4269 2263 4270 2268 4270 2269 4270 2268 4271 2263 4271 2265 4271 2265 4272 2267 4272 2270 4272 2265 4273 1845 4273 1844 4273 2265 4274 1844 4274 1852 4274 2265 4275 1852 4275 2268 4275 2268 4276 1852 4276 1851 4276 2268 4277 1851 4277 2269 4277 2269 4278 1851 4278 1850 4278 2269 4279 1850 4279 2263 4279 2263 4280 1850 4280 1849 4280 2263 4281 1849 4281 2264 4281 2264 4282 1849 4282 1848 4282 2264 4283 1848 4283 1847 4283 2264 4284 1847 4284 2266 4284 2266 4285 1847 4285 2267 4285 2267 4286 1847 4286 1846 4286 2267 4287 1846 4287 2270 4287 2270 4288 1846 4288 1845 4288 2270 4289 1845 4289 2265 4289 2271 4290 2272 4290 2273 4290 2273 4291 2274 4291 2271 4291 2273 4292 2272 4292 2275 4292 2273 4293 2275 4293 2276 4293 2273 4294 2277 4294 2274 4294 2278 4295 2276 4295 2275 4295 2278 4296 2275 4296 2279 4296 2279 4297 2275 4297 2272 4297 2279 4298 2272 4298 2280 4298 2280 4299 2272 4299 2281 4299 2281 4300 2272 4300 2271 4300 2281 4301 2271 4301 2282 4301 2282 4302 2271 4302 2274 4302 2282 4303 2274 4303 2283 4303 2283 4304 2274 4304 2277 4304 2283 4305 2277 4305 2284 4305 2284 4306 2277 4306 2273 4306 2284 4307 2273 4307 2285 4307 2285 4308 2273 4308 2276 4308 2285 4309 2276 4309 2278 4309 2283 4310 2286 4310 2282 4310 2282 4311 2286 4311 2287 4311 2282 4312 2287 4312 2288 4312 2282 4313 2288 4313 2281 4313 2281 4314 2288 4314 2289 4314 2281 4315 2289 4315 2280 4315 2280 4316 2289 4316 2290 4316 2280 4317 2290 4317 2279 4317 2279 4318 2290 4318 2291 4318 2279 4319 2291 4319 2278 4319 2278 4320 2291 4320 2292 4320 2278 4321 2292 4321 2285 4321 2285 4322 2292 4322 2293 4322 2285 4323 2293 4323 2284 4323 2284 4324 2293 4324 2286 4324 2284 4325 2286 4325 2283 4325 2227 4326 2292 4326 2291 4326 2227 4327 2291 4327 2226 4327 2226 4328 2291 4328 2290 4328 2226 4329 2290 4329 2225 4329 2225 4330 2290 4330 2289 4330 2225 4331 2289 4331 2224 4331 2224 4332 2289 4332 2288 4332 2224 4333 2288 4333 2223 4333 2223 4334 2288 4334 2287 4334 2223 4335 2287 4335 2222 4335 2222 4336 2287 4336 2286 4336 2222 4337 2286 4337 2221 4337 2221 4338 2286 4338 2293 4338 2221 4339 2293 4339 2228 4339 2228 4340 2293 4340 2292 4340 2228 4341 2292 4341 2227 4341 2294 4342 2295 4342 2296 4342 2294 4343 2296 4343 2297 4343 2298 4344 2296 4344 2299 4344 2295 4345 2294 4345 2300 4345 2300 4346 2301 4346 2295 4346 2298 4347 2297 4347 2296 4347 2302 4348 2300 4348 2294 4348 2302 4349 2294 4349 2303 4349 2303 4350 2294 4350 2304 4350 2304 4351 2294 4351 2297 4351 2304 4352 2297 4352 2305 4352 2305 4353 2297 4353 2298 4353 2305 4354 2298 4354 2306 4354 2306 4355 2298 4355 2299 4355 2306 4356 2299 4356 2307 4356 2307 4357 2299 4357 2296 4357 2307 4358 2296 4358 2308 4358 2308 4359 2296 4359 2295 4359 2308 4360 2295 4360 2309 4360 2309 4361 2295 4361 2301 4361 2309 4362 2301 4362 2310 4362 2310 4363 2301 4363 2300 4363 2310 4364 2300 4364 2302 4364 2310 4365 2311 4365 2309 4365 2309 4366 2311 4366 2312 4366 2309 4367 2312 4367 2308 4367 2308 4368 2312 4368 2313 4368 2308 4369 2313 4369 2307 4369 2307 4370 2313 4370 2314 4370 2307 4371 2314 4371 2306 4371 2306 4372 2314 4372 2305 4372 2305 4373 2314 4373 2315 4373 2305 4374 2315 4374 2304 4374 2304 4375 2315 4375 2316 4375 2304 4376 2316 4376 2303 4376 2303 4377 2316 4377 2317 4377 2303 4378 2317 4378 2302 4378 2302 4379 2317 4379 2318 4379 2302 4380 2318 4380 2311 4380 2302 4381 2311 4381 2310 4381 2236 4382 2318 4382 2235 4382 2235 4383 2318 4383 2317 4383 2235 4384 2317 4384 2234 4384 2234 4385 2317 4385 2316 4385 2234 4386 2316 4386 2233 4386 2233 4387 2316 4387 2315 4387 2233 4388 2315 4388 2232 4388 2232 4389 2315 4389 2314 4389 2232 4390 2314 4390 2231 4390 2231 4391 2314 4391 2313 4391 2231 4392 2313 4392 2230 4392 2230 4393 2313 4393 2312 4393 2230 4394 2312 4394 2229 4394 2229 4395 2312 4395 2237 4395 2237 4396 2312 4396 2311 4396 2237 4397 2311 4397 2236 4397 2236 4398 2311 4398 2318 4398 2319 4399 2320 4399 2321 4399 2322 4400 2323 4400 2320 4400 2323 4401 2324 4401 2325 4401 2322 4402 2320 4402 2319 4402 2323 4403 2325 4403 2320 4403 2319 4404 2321 4404 2326 4404 2324 4405 2327 4405 2328 4405 2324 4406 2328 4406 2325 4406 2325 4407 2328 4407 2329 4407 2325 4408 2329 4408 2320 4408 2320 4409 2329 4409 2330 4409 2320 4410 2330 4410 2321 4410 2321 4411 2330 4411 2331 4411 2321 4412 2331 4412 2326 4412 2326 4413 2331 4413 2332 4413 2326 4414 2332 4414 2319 4414 2319 4415 2332 4415 2333 4415 2319 4416 2333 4416 2322 4416 2322 4417 2333 4417 2334 4417 2322 4418 2334 4418 2323 4418 2323 4419 2334 4419 2327 4419 2323 4420 2327 4420 2324 4420 2327 4421 2335 4421 2328 4421 2328 4422 2335 4422 2336 4422 2328 4423 2336 4423 2329 4423 2329 4424 2336 4424 2337 4424 2329 4425 2337 4425 2330 4425 2330 4426 2337 4426 2338 4426 2330 4427 2338 4427 2331 4427 2331 4428 2338 4428 2339 4428 2331 4429 2339 4429 2332 4429 2332 4430 2339 4430 2340 4430 2332 4431 2340 4431 2333 4431 2333 4432 2340 4432 2341 4432 2333 4433 2341 4433 2342 4433 2333 4434 2342 4434 2334 4434 2334 4435 2342 4435 2327 4435 2327 4436 2342 4436 2335 4436 2335 4437 2240 4437 2241 4437 2335 4438 2241 4438 2336 4438 2336 4439 2241 4439 2337 4439 2337 4440 2241 4440 2242 4440 2337 4441 2242 4441 2338 4441 2338 4442 2242 4442 2243 4442 2338 4443 2243 4443 2244 4443 2338 4444 2244 4444 2339 4444 2339 4445 2244 4445 2340 4445 2340 4446 2244 4446 2245 4446 2340 4447 2245 4447 2341 4447 2341 4448 2245 4448 2238 4448 2341 4449 2238 4449 2342 4449 2342 4450 2238 4450 2239 4450 2342 4451 2239 4451 2335 4451 2335 4452 2239 4452 2240 4452 2343 4453 2344 4453 2345 4453 2346 4454 2347 4454 2348 4454 2347 4455 2349 4455 2348 4455 2350 4456 2351 4456 2348 4456 2348 4457 2349 4457 2350 4457 2348 4458 2345 4458 2344 4458 2348 4459 2344 4459 2346 4459 2343 4460 2352 4460 2353 4460 2343 4461 2353 4461 2344 4461 2344 4462 2353 4462 2346 4462 2346 4463 2353 4463 2354 4463 2346 4464 2354 4464 2355 4464 2346 4465 2355 4465 2347 4465 2347 4466 2355 4466 2356 4466 2347 4467 2356 4467 2349 4467 2349 4468 2356 4468 2357 4468 2349 4469 2357 4469 2350 4469 2350 4470 2357 4470 2358 4470 2350 4471 2358 4471 2351 4471 2351 4472 2358 4472 2359 4472 2351 4473 2359 4473 2348 4473 2348 4474 2359 4474 2360 4474 2348 4475 2360 4475 2345 4475 2345 4476 2360 4476 2352 4476 2345 4477 2352 4477 2343 4477 2358 4478 2361 4478 2359 4478 2359 4479 2361 4479 2362 4479 2359 4480 2362 4480 2360 4480 2360 4481 2362 4481 2363 4481 2360 4482 2363 4482 2352 4482 2352 4483 2363 4483 2364 4483 2352 4484 2364 4484 2353 4484 2353 4485 2364 4485 2365 4485 2353 4486 2365 4486 2354 4486 2354 4487 2365 4487 2366 4487 2354 4488 2366 4488 2355 4488 2355 4489 2366 4489 2367 4489 2355 4490 2367 4490 2356 4490 2356 4491 2367 4491 2368 4491 2356 4492 2368 4492 2357 4492 2357 4493 2368 4493 2361 4493 2357 4494 2361 4494 2358 4494 2363 4495 2248 4495 2364 4495 2364 4496 2248 4496 2249 4496 2364 4497 2249 4497 2365 4497 2365 4498 2249 4498 2250 4498 2365 4499 2250 4499 2366 4499 2366 4500 2250 4500 2367 4500 2367 4501 2250 4501 2251 4501 2367 4502 2251 4502 2368 4502 2368 4503 2251 4503 2252 4503 2368 4504 2252 4504 2361 4504 2361 4505 2252 4505 2253 4505 2361 4506 2253 4506 2246 4506 2361 4507 2246 4507 2362 4507 2362 4508 2246 4508 2247 4508 2362 4509 2247 4509 2363 4509 2363 4510 2247 4510 2248 4510 2185 4511 2369 4511 2184 4511 123 4512 2370 4512 2185 4512 2185 4513 2370 4513 2369 4513 243 4514 242 4514 237 4514 237 4515 242 4515 238 4515 123 4516 2371 4516 2370 4516 246 4517 245 4517 241 4517 241 4518 245 4518 87 4518 2067 4519 2372 4519 73 4519 73 4520 2372 4520 239 4520 2373 4521 2374 4521 2375 4521 2376 4522 2377 4522 2378 4522 2378 4523 2377 4523 2379 4523 2380 4524 2379 4524 2381 4524 2380 4525 2381 4525 2382 4525 2383 4526 2384 4526 2385 4526 2385 4527 2384 4527 2373 4527 2380 4528 2382 4528 2385 4528 2385 4529 2382 4529 2383 4529 2379 4530 2380 4530 2378 4530 2386 4531 2387 4531 2388 4531 2388 4532 2387 4532 2389 4532 2388 4533 2389 4533 2390 4533 2391 4534 2392 4534 2390 4534 2390 4535 2392 4535 2388 4535 2386 4536 2393 4536 2387 4536 2394 4537 2395 4537 2386 4537 2386 4538 2395 4538 2393 4538 2391 4539 2396 4539 2392 4539 2392 4540 2396 4540 2394 4540 2394 4541 2396 4541 2397 4541 2394 4542 2397 4542 2395 4542 2398 4543 2399 4543 2400 4543 2401 4544 2402 4544 2399 4544 2394 4545 2403 4545 2401 4545 2401 4546 2403 4546 2402 4546 2401 4547 2399 4547 2398 4547 2398 4548 2400 4548 2404 4548 2405 4549 2406 4549 2407 4549 2408 4550 2409 4550 2410 4550 2405 4551 2407 4551 2411 4551 2405 4552 2411 4552 2412 4552 2411 4553 2408 4553 2413 4553 2414 4554 2415 4554 2405 4554 2405 4555 2415 4555 2406 4555 2413 4556 2412 4556 2411 4556 2385 4557 2415 4557 2414 4557 2408 4558 2410 4558 2373 4558 2373 4559 2410 4559 2416 4559 2373 4560 2416 4560 2385 4560 2417 4561 2418 4561 2405 4561 2405 4562 2418 4562 2414 4562 2404 4563 2419 4563 2398 4563 2398 4564 2419 4564 2420 4564 2420 4565 2421 4565 2398 4565 2398 4566 2421 4566 2405 4566 2405 4567 2421 4567 2417 4567 2385 4568 2422 4568 2423 4568 2385 4569 2423 4569 2386 4569 2386 4570 2423 4570 2424 4570 2385 4571 2414 4571 2422 4571 2386 4572 2424 4572 2404 4572 2404 4573 2424 4573 2419 4573 2394 4574 2425 4574 2403 4574 2426 4575 2427 4575 2386 4575 2404 4576 2426 4576 2386 4576 2427 4577 2428 4577 2386 4577 2386 4578 2428 4578 2394 4578 2428 4579 2425 4579 2394 4579 2388 4580 2392 4580 2380 4580 2380 4581 2392 4581 2378 4581 2429 4582 2380 4582 2430 4582 2380 4583 2429 4583 2431 4583 2380 4584 2431 4584 2388 4584 2386 4585 2432 4585 2433 4585 2385 4586 2434 4586 2430 4586 2385 4587 2430 4587 2380 4587 2388 4588 2431 4588 2435 4588 2385 4589 2436 4589 2434 4589 2388 4590 2435 4590 2437 4590 2386 4591 2433 4591 2385 4591 2385 4592 2433 4592 2436 4592 2388 4593 2437 4593 2386 4593 2386 4594 2437 4594 2432 4594 2411 4595 2409 4595 2408 4595 2408 4596 2373 4596 2375 4596 2438 4597 2387 4597 2439 4597 2439 4598 2387 4598 2440 4598 2440 4599 2387 4599 2393 4599 2440 4600 2393 4600 2395 4600 2440 4601 2395 4601 2441 4601 2441 4602 2395 4602 2397 4602 2441 4603 2397 4603 2442 4603 2442 4604 2397 4604 2396 4604 2442 4605 2396 4605 2443 4605 2443 4606 2396 4606 2391 4606 2443 4607 2391 4607 2444 4607 2444 4608 2391 4608 2390 4608 2444 4609 2390 4609 2445 4609 2445 4610 2390 4610 2389 4610 2445 4611 2389 4611 2438 4611 2438 4612 2389 4612 2387 4612 2446 4613 2430 4613 2434 4613 2446 4614 2434 4614 2447 4614 2447 4615 2434 4615 2436 4615 2447 4616 2436 4616 2448 4616 2448 4617 2436 4617 2433 4617 2448 4618 2433 4618 2449 4618 2449 4619 2433 4619 2432 4619 2449 4620 2432 4620 2450 4620 2450 4621 2432 4621 2437 4621 2450 4622 2437 4622 2451 4622 2451 4623 2437 4623 2435 4623 2451 4624 2435 4624 2452 4624 2452 4625 2435 4625 2431 4625 2452 4626 2431 4626 2429 4626 2452 4627 2429 4627 2453 4627 2453 4628 2429 4628 2454 4628 2454 4629 2429 4629 2430 4629 2454 4630 2430 4630 2446 4630 2455 4631 2374 4631 2373 4631 2455 4632 2373 4632 2456 4632 2456 4633 2373 4633 2384 4633 2456 4634 2384 4634 2457 4634 2457 4635 2384 4635 2383 4635 2457 4636 2383 4636 2458 4636 2458 4637 2383 4637 2382 4637 2458 4638 2382 4638 2459 4638 2459 4639 2382 4639 2381 4639 2459 4640 2381 4640 2460 4640 2460 4641 2381 4641 2379 4641 2460 4642 2379 4642 2461 4642 2461 4643 2379 4643 2377 4643 2461 4644 2377 4644 2462 4644 2462 4645 2377 4645 2374 4645 2462 4646 2374 4646 2455 4646 2463 4647 2403 4647 2425 4647 2463 4648 2425 4648 2464 4648 2464 4649 2425 4649 2428 4649 2464 4650 2428 4650 2465 4650 2465 4651 2428 4651 2427 4651 2465 4652 2427 4652 2466 4652 2466 4653 2427 4653 2426 4653 2466 4654 2426 4654 2467 4654 2467 4655 2426 4655 2404 4655 2467 4656 2404 4656 2400 4656 2467 4657 2400 4657 2468 4657 2468 4658 2400 4658 2399 4658 2468 4659 2399 4659 2469 4659 2469 4660 2399 4660 2402 4660 2469 4661 2402 4661 2470 4661 2470 4662 2402 4662 2403 4662 2470 4663 2403 4663 2463 4663 2471 4664 2419 4664 2424 4664 2471 4665 2424 4665 2472 4665 2472 4666 2424 4666 2423 4666 2472 4667 2423 4667 2473 4667 2473 4668 2423 4668 2422 4668 2473 4669 2422 4669 2474 4669 2474 4670 2422 4670 2414 4670 2474 4671 2414 4671 2418 4671 2474 4672 2418 4672 2475 4672 2475 4673 2418 4673 2417 4673 2475 4674 2417 4674 2476 4674 2476 4675 2417 4675 2421 4675 2476 4676 2421 4676 2477 4676 2477 4677 2421 4677 2420 4677 2477 4678 2420 4678 2478 4678 2478 4679 2420 4679 2419 4679 2478 4680 2419 4680 2471 4680 2479 4681 2415 4681 2480 4681 2480 4682 2415 4682 2385 4682 2480 4683 2385 4683 2481 4683 2481 4684 2385 4684 2416 4684 2481 4685 2416 4685 2482 4685 2482 4686 2416 4686 2410 4686 2482 4687 2410 4687 2483 4687 2483 4688 2410 4688 2409 4688 2483 4689 2409 4689 2484 4689 2484 4690 2409 4690 2411 4690 2484 4691 2411 4691 2485 4691 2485 4692 2411 4692 2407 4692 2485 4693 2407 4693 2486 4693 2486 4694 2407 4694 2406 4694 2486 4695 2406 4695 2479 4695 2479 4696 2406 4696 2415 4696 2408 4697 2487 4697 2413 4697 2488 4698 2489 4698 2412 4698 2412 4699 2489 4699 2398 4699 2412 4700 2398 4700 2405 4700 2490 4701 2401 4701 2491 4701 2394 4702 2401 4702 2490 4702 2394 4703 2492 4703 2493 4703 2378 4704 2392 4704 2207 4704 2207 4705 2392 4705 2206 4705 2374 4706 2377 4706 2376 4706 2374 4707 2376 4707 2375 4707 2375 4708 2376 4708 2494 4708 2441 4709 2495 4709 2496 4709 2444 4710 2497 4710 2498 4710 2444 4711 2498 4711 2443 4711 2441 4712 2496 4712 2440 4712 2440 4713 2496 4713 2499 4713 2439 4714 2500 4714 2501 4714 2439 4715 2501 4715 2438 4715 2438 4716 2501 4716 2445 4716 2445 4717 2501 4717 2497 4717 2445 4718 2497 4718 2444 4718 2495 4719 2441 4719 2442 4719 2440 4720 2499 4720 2500 4720 2440 4721 2500 4721 2439 4721 2495 4722 2442 4722 2502 4722 2502 4723 2442 4723 2443 4723 2502 4724 2443 4724 2498 4724 2503 4725 2448 4725 2504 4725 2504 4726 2448 4726 2449 4726 2503 4727 2447 4727 2448 4727 2503 4728 2505 4728 2446 4728 2446 4729 2505 4729 2454 4729 2454 4730 2505 4730 2506 4730 2454 4731 2506 4731 2453 4731 2453 4732 2506 4732 2452 4732 2447 4733 2503 4733 2446 4733 2506 4734 2507 4734 2452 4734 2452 4735 2507 4735 2508 4735 2452 4736 2508 4736 2451 4736 2451 4737 2508 4737 2509 4737 2451 4738 2509 4738 2450 4738 2504 4739 2449 4739 2510 4739 2510 4740 2449 4740 2450 4740 2510 4741 2450 4741 2509 4741 2458 4742 2511 4742 2512 4742 2458 4743 2512 4743 2457 4743 2513 4744 2460 4744 2514 4744 2457 4745 2512 4745 2515 4745 2457 4746 2515 4746 2456 4746 2456 4747 2515 4747 2516 4747 2456 4748 2516 4748 2455 4748 2455 4749 2516 4749 2517 4749 2455 4750 2517 4750 2462 4750 2462 4751 2517 4751 2518 4751 2462 4752 2518 4752 2461 4752 2461 4753 2518 4753 2514 4753 2461 4754 2514 4754 2460 4754 2460 4755 2513 4755 2459 4755 2459 4756 2513 4756 2519 4756 2459 4757 2519 4757 2458 4757 2458 4758 2519 4758 2511 4758 2520 4759 2469 4759 2521 4759 2521 4760 2469 4760 2470 4760 2521 4761 2470 4761 2522 4761 2522 4762 2470 4762 2463 4762 2522 4763 2463 4763 2523 4763 2523 4764 2463 4764 2524 4764 2524 4765 2463 4765 2464 4765 2524 4766 2464 4766 2525 4766 2525 4767 2464 4767 2465 4767 2525 4768 2465 4768 2526 4768 2526 4769 2465 4769 2466 4769 2526 4770 2466 4770 2527 4770 2527 4771 2466 4771 2467 4771 2527 4772 2467 4772 2528 4772 2528 4773 2467 4773 2468 4773 2528 4774 2468 4774 2520 4774 2520 4775 2468 4775 2469 4775 2529 4776 2471 4776 2472 4776 2529 4777 2472 4777 2530 4777 2530 4778 2472 4778 2531 4778 2531 4779 2472 4779 2473 4779 2531 4780 2473 4780 2532 4780 2532 4781 2473 4781 2533 4781 2533 4782 2473 4782 2474 4782 2533 4783 2474 4783 2534 4783 2534 4784 2474 4784 2475 4784 2534 4785 2475 4785 2476 4785 2534 4786 2476 4786 2535 4786 2535 4787 2476 4787 2477 4787 2535 4788 2477 4788 2536 4788 2536 4789 2477 4789 2478 4789 2536 4790 2478 4790 2537 4790 2537 4791 2478 4791 2471 4791 2537 4792 2471 4792 2529 4792 2538 4793 2485 4793 2486 4793 2538 4794 2486 4794 2479 4794 2538 4795 2479 4795 2539 4795 2539 4796 2479 4796 2480 4796 2539 4797 2480 4797 2540 4797 2540 4798 2480 4798 2541 4798 2541 4799 2480 4799 2481 4799 2541 4800 2481 4800 2542 4800 2542 4801 2481 4801 2482 4801 2542 4802 2482 4802 2543 4802 2543 4803 2482 4803 2483 4803 2543 4804 2483 4804 2544 4804 2544 4805 2483 4805 2484 4805 2544 4806 2484 4806 2545 4806 2545 4807 2484 4807 2485 4807 2545 4808 2485 4808 2538 4808 2546 4809 2487 4809 2547 4809 2547 4810 2487 4810 2408 4810 2548 4811 2489 4811 2549 4811 2549 4812 2489 4812 2488 4812 2550 4813 2490 4813 2551 4813 2551 4814 2490 4814 2491 4814 2394 4815 236 4815 2492 4815 2492 4816 236 4816 232 4816 2494 4817 2220 4817 2375 4817 2375 4818 2220 4818 2219 4818 2502 4819 2552 4819 2553 4819 2502 4820 2553 4820 2495 4820 2495 4821 2553 4821 2554 4821 2495 4822 2554 4822 2496 4822 2496 4823 2554 4823 2555 4823 2496 4824 2555 4824 2499 4824 2499 4825 2555 4825 2556 4825 2499 4826 2556 4826 2500 4826 2500 4827 2556 4827 2557 4827 2500 4828 2557 4828 2501 4828 2501 4829 2557 4829 2558 4829 2501 4830 2558 4830 2497 4830 2497 4831 2558 4831 2559 4831 2497 4832 2559 4832 2498 4832 2498 4833 2559 4833 2502 4833 2502 4834 2559 4834 2552 4834 2509 4835 2560 4835 2561 4835 2509 4836 2561 4836 2510 4836 2510 4837 2561 4837 2504 4837 2504 4838 2561 4838 2562 4838 2504 4839 2562 4839 2563 4839 2504 4840 2563 4840 2503 4840 2503 4841 2563 4841 2564 4841 2503 4842 2564 4842 2505 4842 2505 4843 2564 4843 2565 4843 2505 4844 2565 4844 2506 4844 2506 4845 2565 4845 2566 4845 2506 4846 2566 4846 2567 4846 2506 4847 2567 4847 2507 4847 2507 4848 2567 4848 2508 4848 2508 4849 2567 4849 2560 4849 2508 4850 2560 4850 2509 4850 2519 4851 2568 4851 2511 4851 2511 4852 2568 4852 2569 4852 2511 4853 2569 4853 2512 4853 2512 4854 2569 4854 2570 4854 2512 4855 2570 4855 2515 4855 2515 4856 2570 4856 2516 4856 2516 4857 2570 4857 2571 4857 2516 4858 2571 4858 2517 4858 2517 4859 2571 4859 2572 4859 2517 4860 2572 4860 2518 4860 2518 4861 2572 4861 2573 4861 2518 4862 2573 4862 2514 4862 2514 4863 2573 4863 2574 4863 2514 4864 2574 4864 2513 4864 2513 4865 2574 4865 2575 4865 2513 4866 2575 4866 2519 4866 2519 4867 2575 4867 2568 4867 2576 4868 2527 4868 2577 4868 2577 4869 2527 4869 2528 4869 2577 4870 2528 4870 2520 4870 2577 4871 2520 4871 2578 4871 2578 4872 2520 4872 2521 4872 2578 4873 2521 4873 2579 4873 2579 4874 2521 4874 2580 4874 2580 4875 2521 4875 2522 4875 2580 4876 2522 4876 2581 4876 2581 4877 2522 4877 2523 4877 2581 4878 2523 4878 2582 4878 2582 4879 2523 4879 2524 4879 2582 4880 2524 4880 2583 4880 2583 4881 2524 4881 2525 4881 2583 4882 2525 4882 2584 4882 2584 4883 2525 4883 2526 4883 2584 4884 2526 4884 2527 4884 2584 4885 2527 4885 2576 4885 2585 4886 2533 4886 2586 4886 2586 4887 2533 4887 2534 4887 2586 4888 2534 4888 2587 4888 2587 4889 2534 4889 2535 4889 2587 4890 2535 4890 2536 4890 2587 4891 2536 4891 2588 4891 2588 4892 2536 4892 2537 4892 2588 4893 2537 4893 2589 4893 2589 4894 2537 4894 2529 4894 2589 4895 2529 4895 2590 4895 2590 4896 2529 4896 2530 4896 2590 4897 2530 4897 2591 4897 2591 4898 2530 4898 2531 4898 2591 4899 2531 4899 2592 4899 2592 4900 2531 4900 2532 4900 2592 4901 2532 4901 2585 4901 2585 4902 2532 4902 2533 4902 2593 4903 2543 4903 2594 4903 2594 4904 2543 4904 2544 4904 2594 4905 2544 4905 2595 4905 2595 4906 2544 4906 2545 4906 2595 4907 2545 4907 2538 4907 2595 4908 2538 4908 2596 4908 2596 4909 2538 4909 2597 4909 2597 4910 2538 4910 2539 4910 2597 4911 2539 4911 2598 4911 2598 4912 2539 4912 2540 4912 2598 4913 2540 4913 2599 4913 2599 4914 2540 4914 2541 4914 2599 4915 2541 4915 2542 4915 2599 4916 2542 4916 2600 4916 2600 4917 2542 4917 2593 4917 2593 4918 2542 4918 2543 4918 2601 4919 4 4919 2602 4919 2601 4920 2602 4920 2603 4920 2603 4921 2602 4921 2604 4921 2605 4922 2606 4922 2604 4922 2606 4923 2605 4923 1979 4923 1979 4924 2605 4924 6 4924 2607 4925 2608 4925 2609 4925 2609 4926 2608 4926 2610 4926 2609 4927 2610 4927 2611 4927 2611 4928 2610 4928 2612 4928 2611 4929 2612 4929 2613 4929 2611 4930 2613 4930 2614 4930 2614 4931 2613 4931 2615 4931 2614 4932 2615 4932 2616 4932 2616 4933 2615 4933 2617 4933 2616 4934 2617 4934 2618 4934 2618 4935 2617 4935 2619 4935 2618 4936 2619 4936 2620 4936 2620 4937 2619 4937 2621 4937 2620 4938 2621 4938 2607 4938 2607 4939 2621 4939 2622 4939 2607 4940 2622 4940 2608 4940 2623 4941 2624 4941 2625 4941 2625 4942 2624 4942 2626 4942 2627 4943 2628 4943 2624 4943 2627 4944 2624 4944 2623 4944 2627 4945 2629 4945 2628 4945 2628 4946 2629 4946 2630 4946 2625 4947 2626 4947 2631 4947 2631 4948 2626 4948 2630 4948 2631 4949 2630 4949 2629 4949 2603 4950 2632 4950 2633 4950 2634 4951 2635 4951 2603 4951 2634 4952 2603 4952 2633 4952 2634 4953 2636 4953 2635 4953 2635 4954 2636 4954 2637 4954 2632 4955 2606 4955 2638 4955 2638 4956 2606 4956 2637 4956 2638 4957 2637 4957 2636 4957 2639 4958 247 4958 2640 4958 2640 4959 247 4959 246 4959 2640 4960 246 4960 240 4960 240 4961 246 4961 241 4961 2064 4962 2601 4962 2063 4962 2063 4963 2601 4963 2639 4963 91 4964 103 4964 100 4964 100 4965 103 4965 2641 4965 0 4966 2 4966 2642 4966 2642 4967 2 4967 2033 4967 2034 4968 2642 4968 2033 4968 2643 4969 2204 4969 2644 4969 2644 4970 2204 4970 2205 4970 2547 4971 2645 4971 2546 4971 2487 4972 2546 4972 2549 4972 2487 4973 2549 4973 2488 4973 2646 4974 2647 4974 2548 4974 2548 4975 2549 4975 2648 4975 2548 4976 2648 4976 2646 4976 2648 4977 2549 4977 2649 4977 2551 4978 2491 4978 2650 4978 2650 4979 2491 4979 2489 4979 2650 4980 2489 4980 2548 4980 2550 4981 2551 4981 2651 4981 2654 4982 2653 4982 2655 4982 2654 4983 2655 4983 2656 4983 2656 4984 2655 4984 2657 4984 12 4985 2653 4985 2094 4985 2094 4986 2653 4986 2652 4986 2658 4987 2659 4987 2660 4987 2660 4988 2659 4988 2661 4988 2660 4989 2661 4989 2662 4989 2662 4990 2661 4990 2663 4990 2662 4991 2663 4991 2664 4991 2664 4992 2663 4992 2665 4992 2664 4993 2665 4993 2666 4993 2666 4994 2665 4994 2667 4994 2666 4995 2667 4995 2668 4995 2668 4996 2667 4996 2669 4996 2668 4997 2669 4997 2670 4997 2668 4998 2670 4998 2671 4998 2671 4999 2670 4999 2672 4999 2672 5000 2670 5000 2673 5000 2672 5001 2673 5001 2658 5001 2658 5002 2673 5002 2659 5002 2674 5003 2675 5003 2676 5003 2676 5004 2675 5004 2677 5004 2678 5005 2679 5005 2676 5005 2678 5006 2676 5006 2677 5006 2678 5007 2680 5007 2679 5007 2679 5008 2680 5008 2681 5008 2675 5009 2674 5009 2682 5009 2682 5010 2674 5010 2681 5010 2682 5011 2681 5011 2680 5011 2683 5012 2652 5012 2684 5012 2685 5013 2686 5013 2652 5013 2685 5014 2652 5014 2683 5014 2685 5015 2687 5015 2686 5015 2686 5016 2687 5016 2688 5016 2684 5017 2654 5017 2689 5017 2689 5018 2654 5018 2688 5018 2689 5019 2688 5019 2687 5019 2690 5020 194 5020 2691 5020 2691 5021 194 5021 193 5021 1907 5022 2692 5022 1905 5022 1905 5023 2692 5023 2693 5023 8 5024 10 5024 1907 5024 1907 5025 10 5025 2692 5025 154 5026 2694 5026 153 5026 153 5027 2694 5027 156 5027 2656 5028 15 5028 2177 5028 2176 5029 2695 5029 2656 5029 2176 5030 2656 5030 2177 5030 2492 5031 232 5031 2206 5031 2206 5032 232 5032 231 5032 2207 5033 1629 5033 2696 5033 2696 5034 1629 5034 2220 5034 2696 5035 2220 5035 2494 5035 2558 5036 2697 5036 2698 5036 2558 5037 2698 5037 2559 5037 2559 5038 2698 5038 2552 5038 2552 5039 2698 5039 2699 5039 2552 5040 2699 5040 2553 5040 2553 5041 2699 5041 2700 5041 2553 5042 2700 5042 2554 5042 2554 5043 2700 5043 2701 5043 2554 5044 2701 5044 2555 5044 2555 5045 2701 5045 2702 5045 2555 5046 2702 5046 2556 5046 2556 5047 2702 5047 2703 5047 2556 5048 2703 5048 2557 5048 2557 5049 2703 5049 2704 5049 2557 5050 2704 5050 2558 5050 2558 5051 2704 5051 2697 5051 2561 5052 2705 5052 2706 5052 2561 5053 2706 5053 2562 5053 2562 5054 2706 5054 2707 5054 2562 5055 2707 5055 2563 5055 2563 5056 2707 5056 2708 5056 2563 5057 2708 5057 2564 5057 2564 5058 2708 5058 2709 5058 2564 5059 2709 5059 2565 5059 2565 5060 2709 5060 2710 5060 2565 5061 2710 5061 2566 5061 2566 5062 2710 5062 2711 5062 2566 5063 2711 5063 2567 5063 2567 5064 2711 5064 2712 5064 2567 5065 2712 5065 2713 5065 2567 5066 2713 5066 2560 5066 2560 5067 2713 5067 2714 5067 2560 5068 2714 5068 2561 5068 2561 5069 2714 5069 2705 5069 2572 5070 2715 5070 2573 5070 2573 5071 2715 5071 2716 5071 2573 5072 2716 5072 2574 5072 2574 5073 2716 5073 2717 5073 2574 5074 2717 5074 2575 5074 2575 5075 2717 5075 2718 5075 2575 5076 2718 5076 2568 5076 2568 5077 2718 5077 2719 5077 2568 5078 2719 5078 2569 5078 2569 5079 2719 5079 2720 5079 2569 5080 2720 5080 2570 5080 2570 5081 2720 5081 2721 5081 2570 5082 2721 5082 2571 5082 2571 5083 2721 5083 2722 5083 2571 5084 2722 5084 2572 5084 2572 5085 2722 5085 2715 5085 2584 5086 2576 5086 2578 5086 2581 5087 2578 5087 2579 5087 2578 5088 2581 5088 2582 5088 2578 5089 2582 5089 2583 5089 2578 5090 2583 5090 2584 5090 2579 5091 2580 5091 2581 5091 2578 5092 2576 5092 2577 5092 2587 5093 2588 5093 2591 5093 2587 5094 2591 5094 2592 5094 2585 5095 2586 5095 2587 5095 2587 5096 2592 5096 2585 5096 2591 5097 2588 5097 2589 5097 2591 5098 2589 5098 2590 5098 2595 5099 2596 5099 2597 5099 2597 5100 2598 5100 2595 5100 2595 5101 2598 5101 2599 5101 2595 5102 2599 5102 2600 5102 2595 5103 2593 5103 2594 5103 2595 5104 2600 5104 2593 5104 2605 5105 2604 5105 6 5105 6 5106 2604 5106 2602 5106 6 5107 2602 5107 4 5107 2622 5108 2617 5108 2615 5108 2622 5109 2621 5109 2617 5109 2617 5110 2621 5110 2619 5110 2615 5111 2608 5111 2622 5111 2608 5112 2615 5112 2613 5112 2613 5113 2612 5113 2610 5113 2613 5114 2610 5114 2608 5114 2723 5115 2625 5115 2631 5115 2625 5116 2723 5116 2724 5116 2625 5117 2724 5117 2725 5117 2623 5118 2726 5118 2727 5118 2728 5119 2729 5119 2631 5119 2631 5120 2729 5120 2723 5120 2625 5121 2725 5121 2623 5121 2623 5122 2725 5122 2726 5122 2623 5123 2727 5123 2730 5123 2623 5124 2730 5124 2627 5124 2627 5125 2730 5125 2731 5125 2731 5126 2728 5126 2627 5126 2627 5127 2728 5127 2631 5127 2629 5128 2627 5128 2631 5128 2732 5129 2632 5129 2733 5129 2733 5130 2632 5130 2638 5130 2632 5131 2732 5131 2734 5131 2633 5132 2735 5132 2736 5132 2737 5133 2738 5133 2634 5133 2638 5134 2738 5134 2739 5134 2739 5135 2733 5135 2638 5135 2632 5136 2734 5136 2633 5136 2633 5137 2734 5137 2735 5137 2633 5138 2736 5138 2634 5138 2634 5139 2736 5139 2737 5139 2634 5140 2738 5140 2638 5140 2636 5141 2634 5141 2638 5141 2699 5142 221 5142 2700 5142 2700 5143 221 5143 219 5143 2700 5144 219 5144 2701 5144 2701 5145 219 5145 2702 5145 2702 5146 219 5146 217 5146 2702 5147 217 5147 2703 5147 2703 5148 217 5148 230 5148 2703 5149 230 5149 2704 5149 2704 5150 230 5150 228 5150 2704 5151 228 5151 2697 5151 2697 5152 228 5152 226 5152 2697 5153 226 5153 2698 5153 2698 5154 226 5154 224 5154 2698 5155 224 5155 2699 5155 2699 5156 224 5156 221 5156 2718 5157 205 5157 2719 5157 2719 5158 205 5158 203 5158 2719 5159 203 5159 201 5159 2719 5160 201 5160 2720 5160 2720 5161 201 5161 200 5161 2720 5162 200 5162 2721 5162 2721 5163 200 5163 198 5163 2721 5164 198 5164 2722 5164 2722 5165 198 5165 215 5165 2722 5166 215 5166 2715 5166 2715 5167 215 5167 213 5167 2715 5168 213 5168 2716 5168 2716 5169 213 5169 212 5169 2716 5170 212 5170 209 5170 2716 5171 209 5171 2717 5171 2717 5172 209 5172 207 5172 2717 5173 207 5173 2718 5173 2718 5174 207 5174 205 5174 2714 5175 2741 5175 2705 5175 2705 5176 2741 5176 2742 5176 2705 5177 2742 5177 2706 5177 2706 5178 2742 5178 2743 5178 2706 5179 2743 5179 2707 5179 2707 5180 2743 5180 2744 5180 2707 5181 2744 5181 2708 5181 2708 5182 2744 5182 2745 5182 2708 5183 2745 5183 2709 5183 2709 5184 2745 5184 2746 5184 2709 5185 2746 5185 2710 5185 2710 5186 2746 5186 2747 5186 2710 5187 2747 5187 2711 5187 2711 5188 2747 5188 2712 5188 2712 5189 2747 5189 2748 5189 2712 5190 2748 5190 2713 5190 2713 5191 2748 5191 2741 5191 2713 5192 2741 5192 2714 5192 2749 5193 99 5193 2641 5193 2641 5194 99 5194 100 5194 187 5195 2750 5195 189 5195 189 5196 2750 5196 2751 5196 189 5197 2751 5197 2752 5197 178 5198 2753 5198 2754 5198 178 5199 2754 5199 181 5199 181 5200 2754 5200 2755 5200 181 5201 2755 5201 182 5201 182 5202 2755 5202 2756 5202 182 5203 2756 5203 2757 5203 182 5204 2757 5204 185 5204 185 5205 2757 5205 2758 5205 185 5206 2758 5206 187 5206 187 5207 2758 5207 2750 5207 174 5208 2759 5208 2760 5208 174 5209 2760 5209 160 5209 160 5210 2760 5210 2761 5210 163 5211 2762 5211 2763 5211 163 5212 2763 5212 165 5212 165 5213 2763 5213 167 5213 167 5214 2763 5214 2764 5214 167 5215 2764 5215 2765 5215 167 5216 2765 5216 170 5216 170 5217 2765 5217 2766 5217 170 5218 2766 5218 172 5218 172 5219 2766 5219 2759 5219 172 5220 2759 5220 174 5220 2767 5221 2768 5221 2769 5221 2769 5222 2768 5222 2371 5222 2768 5223 2767 5223 2693 5223 194 5224 2690 5224 2770 5224 194 5225 2770 5225 196 5225 2770 5226 2208 5226 196 5226 1627 5227 2209 5227 2644 5227 1627 5228 2644 5228 2205 5228 2772 5229 2773 5229 2774 5229 2774 5230 2773 5230 2775 5230 2774 5231 2775 5231 2776 5231 2776 5232 2775 5232 2777 5232 2776 5233 2777 5233 2778 5233 2778 5234 2777 5234 2779 5234 2778 5235 2779 5235 2780 5235 2780 5236 2779 5236 2781 5236 2780 5237 2781 5237 2782 5237 2782 5238 2781 5238 2783 5238 2782 5239 2783 5239 2784 5239 2784 5240 2783 5240 2785 5240 2784 5241 2785 5241 2786 5241 2786 5242 2785 5242 2787 5242 2786 5243 2787 5243 2772 5243 2772 5244 2787 5244 2773 5244 2643 5245 2644 5245 2788 5245 2691 5246 2789 5246 2790 5246 2790 5247 2789 5247 2791 5247 2792 5248 2793 5248 2794 5248 2795 5249 2796 5249 2797 5249 2792 5250 2794 5250 2798 5250 2799 5251 2791 5251 2789 5251 2800 5252 2801 5252 2802 5252 2691 5253 2803 5253 2789 5253 2804 5254 2791 5254 2799 5254 2550 5255 2805 5255 2691 5255 2691 5256 2805 5256 2803 5256 2806 5257 2804 5257 2807 5257 2807 5258 2804 5258 2808 5258 2807 5259 2808 5259 2801 5259 2798 5260 2809 5260 2792 5260 2792 5261 2809 5261 2795 5261 2795 5262 2809 5262 2796 5262 2643 5263 2810 5263 2547 5263 2801 5264 2808 5264 2811 5264 2801 5265 2811 5265 2802 5265 2804 5266 2806 5266 2794 5266 2794 5267 2793 5267 2804 5267 2804 5268 2793 5268 2812 5268 2643 5269 2813 5269 2814 5269 2802 5270 2815 5270 2816 5270 2817 5271 2813 5271 2812 5271 2812 5272 2813 5272 2643 5272 2643 5273 2814 5273 2810 5273 2818 5274 2819 5274 2820 5274 2793 5275 2817 5275 2812 5275 2821 5276 2822 5276 2547 5276 2821 5277 2796 5277 2823 5277 2816 5278 2823 5278 2800 5278 2815 5279 2802 5279 2824 5279 2824 5280 2802 5280 2818 5280 2820 5281 2825 5281 2818 5281 2818 5282 2825 5282 2824 5282 2646 5283 2826 5283 2647 5283 2550 5284 2826 5284 2827 5284 2547 5285 2810 5285 2828 5285 2547 5286 2828 5286 2821 5286 2829 5287 2645 5287 2830 5287 2830 5288 2645 5288 2547 5288 2830 5289 2547 5289 2822 5289 2821 5290 2823 5290 2816 5290 2802 5291 2816 5291 2800 5291 2826 5292 2651 5292 2647 5292 2827 5293 2831 5293 2550 5293 2550 5294 2831 5294 2819 5294 2829 5295 2832 5295 2649 5295 2649 5296 2832 5296 2648 5296 2821 5297 2828 5297 2797 5297 2826 5298 2550 5298 2651 5298 2819 5299 2818 5299 2550 5299 2550 5300 2818 5300 2805 5300 2796 5301 2821 5301 2797 5301 2829 5302 2649 5302 2645 5302 2645 5303 2649 5303 2549 5303 2645 5304 2549 5304 2546 5304 2488 5305 2412 5305 2487 5305 2413 5306 2487 5306 2412 5306 2646 5307 2648 5307 2833 5307 2833 5308 2648 5308 2834 5308 2835 5309 2646 5309 2833 5309 2646 5310 2835 5310 2826 5310 2835 5311 2836 5311 2826 5311 2826 5312 2836 5312 2837 5312 2826 5313 2837 5313 2827 5313 2837 5314 2838 5314 2827 5314 2827 5315 2838 5315 2831 5315 2831 5316 2838 5316 2839 5316 2831 5317 2839 5317 2819 5317 2819 5318 2839 5318 2840 5318 2819 5319 2840 5319 2841 5319 2819 5320 2841 5320 2820 5320 2841 5321 2842 5321 2820 5321 2820 5322 2842 5322 2825 5322 2825 5323 2842 5323 2843 5323 2825 5324 2843 5324 2844 5324 2825 5325 2844 5325 2824 5325 2824 5326 2844 5326 2815 5326 2844 5327 2845 5327 2815 5327 2815 5328 2845 5328 2816 5328 2845 5329 2846 5329 2816 5329 2816 5330 2846 5330 2847 5330 2816 5331 2847 5331 2821 5331 2847 5332 2848 5332 2821 5332 2848 5333 2849 5333 2821 5333 2821 5334 2849 5334 2822 5334 2822 5335 2849 5335 2850 5335 2822 5336 2850 5336 2830 5336 2850 5337 2851 5337 2830 5337 2830 5338 2851 5338 2829 5338 2829 5339 2851 5339 2852 5339 2829 5340 2852 5340 2832 5340 2834 5341 2648 5341 2853 5341 2853 5342 2648 5342 2832 5342 2853 5343 2832 5343 2852 5343 2647 5344 2651 5344 2650 5344 2650 5345 2651 5345 2551 5345 2647 5346 2650 5346 2548 5346 2489 5347 2491 5347 2398 5347 2398 5348 2491 5348 2401 5348 14 5349 2657 5349 12 5349 12 5350 2657 5350 2655 5350 12 5351 2655 5351 2653 5351 2668 5352 2658 5352 2660 5352 2666 5353 2662 5353 2664 5353 2662 5354 2666 5354 2660 5354 2668 5355 2660 5355 2666 5355 2672 5356 2668 5356 2671 5356 2668 5357 2672 5357 2658 5357 2854 5358 2675 5358 2855 5358 2675 5359 2854 5359 2856 5359 2677 5360 2856 5360 2857 5360 2858 5361 2859 5361 2678 5361 2678 5362 2859 5362 2860 5362 2682 5363 2861 5363 2855 5363 2682 5364 2855 5364 2675 5364 2857 5365 2858 5365 2677 5365 2677 5366 2858 5366 2678 5366 2675 5367 2856 5367 2677 5367 2678 5368 2860 5368 2682 5368 2682 5369 2860 5369 2861 5369 2680 5370 2678 5370 2682 5370 2684 5371 2862 5371 2863 5371 2683 5372 2864 5372 2865 5372 2685 5373 2866 5373 2867 5373 2689 5374 2868 5374 2869 5374 2689 5375 2869 5375 2862 5375 2689 5376 2862 5376 2684 5376 2683 5377 2865 5377 2866 5377 2683 5378 2866 5378 2685 5378 2684 5379 2863 5379 2683 5379 2683 5380 2863 5380 2864 5380 2867 5381 2870 5381 2685 5381 2685 5382 2870 5382 2689 5382 2689 5383 2870 5383 2868 5383 2687 5384 2685 5384 2689 5384 2691 5385 2790 5385 2690 5385 2694 5386 154 5386 140 5386 2694 5387 140 5387 2871 5387 2392 5388 2394 5388 2493 5388 2392 5389 2493 5389 2492 5389 2392 5390 2492 5390 2206 5390 2378 5391 2207 5391 2696 5391 2376 5392 2378 5392 2696 5392 2376 5393 2696 5393 2494 5393 2727 5394 2872 5394 2730 5394 2730 5395 2872 5395 2873 5395 2730 5396 2873 5396 2731 5396 2731 5397 2873 5397 2874 5397 2731 5398 2874 5398 2728 5398 2728 5399 2874 5399 2875 5399 2728 5400 2875 5400 2729 5400 2729 5401 2875 5401 2876 5401 2729 5402 2876 5402 2723 5402 2723 5403 2876 5403 2877 5403 2723 5404 2877 5404 2724 5404 2724 5405 2877 5405 2878 5405 2724 5406 2878 5406 2725 5406 2725 5407 2878 5407 2879 5407 2725 5408 2879 5408 2726 5408 2726 5409 2879 5409 2880 5409 2726 5410 2880 5410 2727 5410 2727 5411 2880 5411 2872 5411 2736 5412 2881 5412 2737 5412 2737 5413 2881 5413 2882 5413 2737 5414 2882 5414 2738 5414 2738 5415 2882 5415 2883 5415 2738 5416 2883 5416 2884 5416 2738 5417 2884 5417 2739 5417 2739 5418 2884 5418 2885 5418 2739 5419 2885 5419 2733 5419 2733 5420 2885 5420 2886 5420 2733 5421 2886 5421 2732 5421 2732 5422 2886 5422 2887 5422 2732 5423 2887 5423 2734 5423 2734 5424 2887 5424 2888 5424 2734 5425 2888 5425 2735 5425 2735 5426 2888 5426 2889 5426 2735 5427 2889 5427 2736 5427 2736 5428 2889 5428 2881 5428 2871 5429 140 5429 142 5429 2890 5430 2750 5430 2758 5430 2890 5431 2758 5431 2891 5431 2891 5432 2758 5432 2757 5432 2891 5433 2757 5433 2892 5433 2892 5434 2757 5434 2756 5434 2892 5435 2756 5435 2893 5435 2893 5436 2756 5436 2755 5436 2893 5437 2755 5437 2894 5437 2894 5438 2755 5438 2754 5438 2894 5439 2754 5439 2895 5439 2895 5440 2754 5440 2753 5440 2895 5441 2753 5441 2896 5441 2896 5442 2753 5442 2752 5442 2896 5443 2752 5443 2897 5443 2897 5444 2752 5444 2751 5444 2897 5445 2751 5445 2898 5445 2898 5446 2751 5446 2750 5446 2898 5447 2750 5447 2890 5447 2899 5448 2762 5448 2900 5448 2900 5449 2762 5449 2761 5449 2900 5450 2761 5450 2901 5450 2901 5451 2761 5451 2760 5451 2901 5452 2760 5452 2902 5452 2902 5453 2760 5453 2903 5453 2903 5454 2760 5454 2759 5454 2903 5455 2759 5455 2904 5455 2904 5456 2759 5456 2766 5456 2904 5457 2766 5457 2765 5457 2904 5458 2765 5458 2905 5458 2905 5459 2765 5459 2764 5459 2905 5460 2764 5460 2906 5460 2906 5461 2764 5461 2763 5461 2906 5462 2763 5462 2907 5462 2907 5463 2763 5463 2899 5463 2899 5464 2763 5464 2762 5464 2770 5465 2690 5465 2790 5465 2770 5466 2790 5466 2791 5466 2208 5467 2770 5467 2791 5467 2209 5468 2208 5468 2791 5468 2209 5469 2791 5469 2812 5469 2804 5470 2812 5470 2791 5470 2788 5471 2812 5471 2643 5471 2644 5472 2209 5472 2812 5472 2788 5473 2644 5473 2812 5473 2908 5474 2775 5474 2773 5474 2908 5475 2773 5475 2909 5475 2909 5476 2773 5476 2787 5476 2909 5477 2787 5477 2910 5477 2910 5478 2787 5478 2785 5478 2910 5479 2785 5479 2911 5479 2911 5480 2785 5480 2783 5480 2911 5481 2783 5481 2912 5481 2912 5482 2783 5482 2781 5482 2912 5483 2781 5483 2913 5483 2913 5484 2781 5484 2779 5484 2913 5485 2779 5485 2914 5485 2914 5486 2779 5486 2777 5486 2914 5487 2777 5487 2915 5487 2915 5488 2777 5488 2775 5488 2915 5489 2775 5489 2908 5489 2916 5490 2803 5490 2917 5490 2917 5491 2803 5491 2805 5491 2917 5492 2805 5492 2918 5492 2918 5493 2805 5493 2818 5493 2918 5494 2818 5494 2919 5494 2919 5495 2818 5495 2802 5495 2919 5496 2802 5496 2811 5496 2919 5497 2811 5497 2920 5497 2920 5498 2811 5498 2808 5498 2920 5499 2808 5499 2921 5499 2921 5500 2808 5500 2804 5500 2921 5501 2804 5501 2922 5501 2922 5502 2804 5502 2799 5502 2922 5503 2799 5503 2923 5503 2923 5504 2799 5504 2789 5504 2923 5505 2789 5505 2916 5505 2916 5506 2789 5506 2803 5506 2924 5507 2801 5507 2800 5507 2924 5508 2800 5508 2925 5508 2925 5509 2800 5509 2823 5509 2925 5510 2823 5510 2926 5510 2926 5511 2823 5511 2796 5511 2926 5512 2796 5512 2927 5512 2927 5513 2796 5513 2809 5513 2927 5514 2809 5514 2928 5514 2928 5515 2809 5515 2798 5515 2928 5516 2798 5516 2929 5516 2929 5517 2798 5517 2794 5517 2929 5518 2794 5518 2930 5518 2930 5519 2794 5519 2806 5519 2930 5520 2806 5520 2931 5520 2931 5521 2806 5521 2807 5521 2931 5522 2807 5522 2924 5522 2924 5523 2807 5523 2801 5523 2932 5524 2792 5524 2795 5524 2932 5525 2795 5525 2933 5525 2933 5526 2795 5526 2797 5526 2933 5527 2797 5527 2934 5527 2934 5528 2797 5528 2828 5528 2934 5529 2828 5529 2935 5529 2935 5530 2828 5530 2810 5530 2935 5531 2810 5531 2936 5531 2936 5532 2810 5532 2814 5532 2936 5533 2814 5533 2937 5533 2937 5534 2814 5534 2813 5534 2937 5535 2813 5535 2938 5535 2938 5536 2813 5536 2817 5536 2938 5537 2817 5537 2939 5537 2939 5538 2817 5538 2793 5538 2939 5539 2793 5539 2940 5539 2940 5540 2793 5540 2792 5540 2940 5541 2792 5541 2932 5541 2941 5542 2942 5542 2843 5542 2849 5543 2848 5543 2943 5543 2943 5544 2848 5544 2847 5544 2943 5545 2847 5545 2846 5545 2846 5546 2845 5546 2944 5546 2845 5547 2844 5547 2944 5547 2944 5548 2844 5548 2942 5548 2942 5549 2844 5549 2843 5549 2941 5550 2843 5550 2842 5550 2941 5551 2842 5551 2945 5551 2945 5552 2842 5552 2841 5552 2945 5553 2841 5553 2946 5553 2946 5554 2841 5554 2840 5554 2946 5555 2840 5555 2839 5555 2946 5556 2839 5556 2947 5556 2947 5557 2839 5557 2838 5557 2947 5558 2838 5558 2948 5558 2948 5559 2838 5559 2949 5559 2949 5560 2838 5560 2837 5560 2837 5561 2836 5561 2949 5561 2949 5562 2836 5562 2950 5562 2950 5563 2836 5563 2835 5563 2950 5564 2835 5564 2833 5564 2833 5565 2834 5565 2853 5565 2853 5566 2852 5566 2951 5566 2951 5567 2852 5567 2851 5567 2951 5568 2851 5568 2952 5568 2952 5569 2851 5569 2850 5569 2952 5570 2850 5570 2849 5570 2953 5571 2855 5571 2954 5571 2954 5572 2855 5572 2861 5572 2954 5573 2861 5573 2955 5573 2955 5574 2861 5574 2860 5574 2955 5575 2860 5575 2956 5575 2956 5576 2860 5576 2859 5576 2956 5577 2859 5577 2957 5577 2957 5578 2859 5578 2858 5578 2957 5579 2858 5579 2958 5579 2958 5580 2858 5580 2857 5580 2958 5581 2857 5581 2959 5581 2959 5582 2857 5582 2856 5582 2959 5583 2856 5583 2960 5583 2960 5584 2856 5584 2961 5584 2961 5585 2856 5585 2854 5585 2961 5586 2854 5586 2855 5586 2961 5587 2855 5587 2953 5587 2962 5588 2862 5588 2869 5588 2962 5589 2869 5589 2868 5589 2962 5590 2868 5590 2963 5590 2963 5591 2868 5591 2870 5591 2963 5592 2870 5592 2964 5592 2964 5593 2870 5593 2867 5593 2964 5594 2867 5594 2965 5594 2965 5595 2867 5595 2866 5595 2965 5596 2866 5596 2966 5596 2966 5597 2866 5597 2865 5597 2966 5598 2865 5598 2967 5598 2967 5599 2865 5599 2864 5599 2967 5600 2864 5600 2863 5600 2967 5601 2863 5601 2968 5601 2968 5602 2863 5602 2969 5602 2969 5603 2863 5603 2862 5603 2969 5604 2862 5604 2962 5604 2970 5605 2874 5605 2971 5605 2971 5606 2874 5606 2873 5606 2971 5607 2873 5607 2872 5607 2971 5608 2872 5608 2972 5608 2972 5609 2872 5609 2880 5609 2972 5610 2880 5610 2973 5610 2973 5611 2880 5611 2879 5611 2973 5612 2879 5612 2974 5612 2974 5613 2879 5613 2975 5613 2975 5614 2879 5614 2878 5614 2975 5615 2878 5615 2877 5615 2975 5616 2877 5616 2976 5616 2976 5617 2877 5617 2876 5617 2976 5618 2876 5618 2977 5618 2977 5619 2876 5619 2875 5619 2977 5620 2875 5620 2978 5620 2978 5621 2875 5621 2874 5621 2978 5622 2874 5622 2970 5622 2979 5623 2882 5623 2980 5623 2980 5624 2882 5624 2881 5624 2980 5625 2881 5625 2981 5625 2981 5626 2881 5626 2889 5626 2981 5627 2889 5627 2982 5627 2982 5628 2889 5628 2888 5628 2982 5629 2888 5629 2983 5629 2983 5630 2888 5630 2887 5630 2983 5631 2887 5631 2984 5631 2984 5632 2887 5632 2886 5632 2984 5633 2886 5633 2985 5633 2985 5634 2886 5634 2885 5634 2985 5635 2885 5635 2986 5635 2986 5636 2885 5636 2884 5636 2986 5637 2884 5637 2987 5637 2987 5638 2884 5638 2883 5638 2987 5639 2883 5639 2979 5639 2979 5640 2883 5640 2882 5640 2890 5641 2988 5641 2989 5641 2890 5642 2989 5642 2898 5642 2898 5643 2989 5643 2990 5643 2898 5644 2990 5644 2897 5644 2897 5645 2990 5645 2896 5645 2896 5646 2990 5646 2991 5646 2896 5647 2991 5647 2895 5647 2895 5648 2991 5648 2992 5648 2895 5649 2992 5649 2894 5649 2894 5650 2992 5650 2993 5650 2894 5651 2993 5651 2893 5651 2893 5652 2993 5652 2994 5652 2893 5653 2994 5653 2892 5653 2892 5654 2994 5654 2995 5654 2892 5655 2995 5655 2891 5655 2891 5656 2995 5656 2996 5656 2891 5657 2996 5657 2890 5657 2890 5658 2996 5658 2988 5658 2903 5659 2997 5659 2902 5659 2902 5660 2997 5660 2998 5660 2902 5661 2998 5661 2901 5661 2901 5662 2998 5662 2999 5662 2901 5663 2999 5663 2900 5663 2900 5664 2999 5664 3000 5664 2900 5665 3000 5665 2899 5665 2899 5666 3000 5666 2907 5666 2907 5667 3000 5667 3001 5667 2907 5668 3001 5668 2906 5668 2906 5669 3001 5669 3002 5669 2906 5670 3002 5670 2905 5670 2905 5671 3002 5671 3003 5671 2905 5672 3003 5672 2904 5672 2904 5673 3003 5673 3004 5673 2904 5674 3004 5674 3005 5674 2904 5675 3005 5675 2903 5675 2903 5676 3005 5676 2997 5676 2909 5677 3006 5677 2908 5677 2908 5678 3006 5678 3007 5678 2908 5679 3007 5679 2915 5679 2915 5680 3007 5680 3008 5680 2915 5681 3008 5681 3009 5681 2915 5682 3009 5682 2914 5682 2914 5683 3009 5683 3010 5683 2914 5684 3010 5684 2913 5684 2913 5685 3010 5685 3011 5685 2913 5686 3011 5686 2912 5686 2912 5687 3011 5687 3012 5687 2912 5688 3012 5688 2911 5688 2911 5689 3012 5689 3013 5689 2911 5690 3013 5690 2910 5690 2910 5691 3013 5691 3014 5691 2910 5692 3014 5692 2909 5692 2909 5693 3014 5693 3006 5693 2992 5694 2920 5694 2993 5694 2993 5695 2920 5695 2921 5695 2993 5696 2921 5696 2994 5696 2994 5697 2921 5697 2922 5697 2994 5698 2922 5698 2995 5698 2995 5699 2922 5699 2996 5699 2996 5700 2922 5700 2923 5700 2996 5701 2923 5701 2988 5701 2988 5702 2923 5702 2916 5702 2988 5703 2916 5703 2989 5703 2989 5704 2916 5704 2917 5704 2989 5705 2917 5705 2990 5705 2990 5706 2917 5706 2918 5706 2990 5707 2918 5707 2991 5707 2991 5708 2918 5708 2919 5708 2991 5709 2919 5709 2992 5709 2992 5710 2919 5710 2920 5710 3007 5711 2924 5711 2925 5711 3007 5712 2925 5712 3008 5712 3008 5713 2925 5713 2926 5713 3008 5714 2926 5714 3009 5714 3009 5715 2926 5715 2927 5715 3009 5716 2927 5716 3010 5716 3010 5717 2927 5717 2928 5717 3010 5718 2928 5718 3011 5718 3011 5719 2928 5719 2929 5719 3011 5720 2929 5720 3012 5720 3012 5721 2929 5721 3013 5721 3013 5722 2929 5722 2930 5722 3013 5723 2930 5723 2931 5723 3013 5724 2931 5724 3014 5724 3014 5725 2931 5725 3006 5725 3006 5726 2931 5726 2924 5726 3006 5727 2924 5727 3007 5727 3001 5728 2937 5728 3002 5728 3002 5729 2937 5729 2938 5729 3002 5730 2938 5730 3003 5730 3003 5731 2938 5731 2939 5731 3003 5732 2939 5732 3004 5732 3004 5733 2939 5733 2940 5733 3004 5734 2940 5734 3005 5734 3005 5735 2940 5735 2932 5735 3005 5736 2932 5736 2997 5736 2997 5737 2932 5737 2933 5737 2997 5738 2933 5738 2998 5738 2998 5739 2933 5739 2934 5739 2998 5740 2934 5740 2999 5740 2999 5741 2934 5741 2935 5741 2999 5742 2935 5742 3000 5742 3000 5743 2935 5743 2936 5743 3000 5744 2936 5744 3001 5744 3001 5745 2936 5745 2937 5745 3015 5746 2849 5746 2943 5746 3015 5747 3016 5747 2849 5747 2849 5748 3017 5748 2952 5748 2943 5749 3018 5749 3015 5749 2853 5750 3019 5750 3020 5750 3021 5751 3022 5751 2952 5751 2952 5752 3022 5752 3023 5752 3020 5753 3022 5753 3021 5753 2951 5754 3024 5754 3019 5754 3023 5755 3024 5755 2952 5755 2952 5756 3024 5756 2951 5756 2951 5757 3019 5757 2853 5757 2853 5758 3025 5758 3026 5758 2853 5759 3026 5759 2833 5759 2853 5760 3020 5760 3025 5760 2833 5761 3026 5761 3027 5761 2833 5762 3027 5762 2950 5762 2949 5763 3028 5763 3029 5763 3030 5764 3031 5764 3032 5764 2949 5765 2950 5765 3033 5765 3033 5766 3028 5766 2949 5766 3031 5767 2948 5767 3029 5767 2950 5768 3034 5768 3033 5768 2949 5769 3029 5769 2948 5769 3032 5770 3034 5770 3030 5770 3030 5771 3034 5771 2950 5771 2946 5772 3035 5772 3036 5772 3037 5773 3038 5773 2948 5773 2948 5774 3038 5774 2947 5774 3038 5775 3039 5775 2947 5775 2947 5776 3039 5776 2946 5776 3039 5777 3035 5777 2946 5777 3040 5778 3041 5778 2946 5778 3042 5779 3043 5779 2941 5779 2941 5780 3043 5780 3044 5780 3043 5781 3045 5781 3044 5781 3046 5782 3040 5782 2946 5782 2945 5783 2946 5783 3041 5783 3041 5784 3042 5784 2945 5784 2945 5785 3042 5785 2941 5785 2941 5786 3047 5786 3048 5786 2942 5787 2941 5787 3048 5787 2942 5788 3048 5788 3049 5788 2942 5789 3049 5789 3050 5789 2942 5790 3050 5790 2944 5790 3051 5791 2944 5791 3050 5791 2944 5792 3052 5792 2846 5792 2846 5793 3052 5793 3053 5793 3054 5794 3052 5794 2944 5794 3053 5795 3055 5795 3018 5795 2846 5796 3053 5796 3018 5796 2846 5797 3018 5797 2943 5797 3056 5798 3037 5798 3030 5798 3057 5799 3044 5799 3036 5799 3044 5800 3057 5800 3058 5800 3044 5801 3058 5801 3030 5801 3030 5802 3058 5802 3056 5802 3059 5803 3060 5803 3030 5803 2950 5804 3059 5804 3030 5804 3021 5805 3061 5805 3062 5805 3021 5806 3062 5806 3020 5806 3020 5807 3062 5807 3025 5807 3017 5808 3063 5808 2952 5808 3064 5809 3065 5809 3021 5809 3066 5810 3067 5810 3018 5810 3063 5811 3064 5811 2952 5811 2952 5812 3064 5812 3021 5812 3021 5813 3065 5813 3068 5813 3069 5814 3067 5814 3066 5814 3066 5815 3068 5815 3069 5815 2944 5816 3051 5816 3070 5816 3044 5817 3071 5817 3047 5817 3072 5818 3071 5818 3044 5818 3044 5819 3047 5819 2941 5819 3073 5820 3072 5820 3066 5820 2944 5821 3070 5821 3066 5821 3066 5822 3070 5822 3073 5822 3030 5823 3074 5823 3044 5823 3044 5824 3074 5824 3075 5824 3060 5825 3061 5825 3030 5825 3030 5826 3061 5826 3021 5826 3030 5827 3021 5827 3076 5827 3076 5828 3077 5828 3030 5828 3030 5829 3077 5829 3078 5829 3021 5830 3079 5830 3076 5830 3079 5831 3021 5831 3080 5831 3068 5832 3066 5832 3021 5832 3021 5833 3066 5833 3080 5833 3066 5834 3081 5834 3082 5834 3066 5835 3082 5835 3080 5835 3072 5836 3044 5836 3066 5836 3066 5837 3044 5837 3083 5837 3066 5838 3083 5838 3081 5838 3044 5839 3075 5839 3084 5839 3044 5840 3084 5840 3083 5840 3046 5841 2946 5841 3044 5841 3044 5842 2946 5842 3036 5842 3044 5843 3045 5843 3046 5843 3054 5844 2944 5844 3066 5844 3085 5845 3054 5845 3066 5845 3055 5846 3085 5846 3066 5846 3066 5847 3018 5847 3055 5847 3037 5848 2948 5848 3030 5848 3030 5849 2948 5849 3031 5849 3027 5850 3059 5850 2950 5850 3030 5851 3078 5851 3074 5851 3086 5852 2956 5852 2957 5852 3086 5853 2957 5853 3087 5853 3087 5854 2957 5854 3088 5854 3088 5855 2957 5855 2958 5855 3088 5856 2958 5856 2959 5856 3088 5857 2959 5857 3089 5857 3089 5858 2959 5858 2960 5858 3089 5859 2960 5859 3090 5859 3090 5860 2960 5860 2961 5860 3090 5861 2961 5861 3091 5861 3091 5862 2961 5862 3092 5862 3092 5863 2961 5863 2953 5863 3092 5864 2953 5864 2954 5864 3092 5865 2954 5865 3093 5865 3093 5866 2954 5866 2955 5866 3093 5867 2955 5867 3094 5867 3094 5868 2955 5868 2956 5868 3094 5869 2956 5869 3086 5869 3095 5870 2964 5870 3096 5870 3096 5871 2964 5871 2965 5871 3096 5872 2965 5872 3097 5872 3097 5873 2965 5873 2966 5873 3097 5874 2966 5874 3098 5874 3098 5875 2966 5875 2967 5875 3098 5876 2967 5876 3099 5876 3099 5877 2967 5877 2968 5877 3099 5878 2968 5878 3100 5878 3100 5879 2968 5879 2969 5879 3100 5880 2969 5880 3101 5880 3101 5881 2969 5881 2962 5881 3101 5882 2962 5882 3102 5882 3102 5883 2962 5883 2963 5883 3102 5884 2963 5884 3103 5884 3103 5885 2963 5885 3095 5885 3095 5886 2963 5886 2964 5886 2972 5887 3104 5887 3105 5887 2972 5888 3105 5888 2971 5888 2971 5889 3105 5889 3106 5889 2971 5890 3106 5890 2970 5890 2970 5891 3106 5891 3107 5891 2970 5892 3107 5892 2978 5892 2978 5893 3107 5893 3108 5893 2978 5894 3108 5894 2977 5894 2977 5895 3108 5895 3109 5895 2977 5896 3109 5896 2976 5896 2976 5897 3109 5897 3110 5897 2976 5898 3110 5898 2975 5898 2975 5899 3110 5899 3111 5899 2975 5900 3111 5900 2974 5900 2974 5901 3111 5901 3112 5901 2974 5902 3112 5902 2973 5902 2973 5903 3112 5903 3104 5903 2973 5904 3104 5904 2972 5904 2981 5905 3113 5905 2980 5905 2980 5906 3113 5906 3114 5906 2980 5907 3114 5907 2979 5907 2979 5908 3114 5908 2987 5908 2987 5909 3114 5909 3115 5909 2987 5910 3115 5910 2986 5910 2986 5911 3115 5911 3116 5911 2986 5912 3116 5912 2985 5912 2985 5913 3116 5913 3117 5913 2985 5914 3117 5914 2984 5914 2984 5915 3117 5915 3118 5915 2984 5916 3118 5916 2983 5916 2983 5917 3118 5917 3119 5917 2983 5918 3119 5918 2982 5918 2982 5919 3119 5919 3120 5919 2982 5920 3120 5920 2981 5920 2981 5921 3120 5921 3113 5921 3121 5922 3054 5922 3085 5922 3121 5923 3085 5923 3122 5923 3122 5924 3085 5924 3055 5924 3122 5925 3055 5925 3123 5925 3123 5926 3055 5926 3124 5926 3124 5927 3055 5927 3053 5927 3124 5928 3053 5928 3125 5928 3125 5929 3053 5929 3052 5929 3125 5930 3052 5930 3126 5930 3126 5931 3052 5931 3054 5931 3126 5932 3054 5932 3121 5932 3127 5933 3046 5933 3045 5933 3127 5934 3045 5934 3128 5934 3128 5935 3045 5935 3043 5935 3128 5936 3043 5936 3129 5936 3129 5937 3043 5937 3042 5937 3129 5938 3042 5938 3130 5938 3130 5939 3042 5939 3041 5939 3130 5940 3041 5940 3131 5940 3131 5941 3041 5941 3040 5941 3131 5942 3040 5942 3132 5942 3132 5943 3040 5943 3046 5943 3132 5944 3046 5944 3127 5944 3133 5945 3020 5945 3019 5945 3133 5946 3019 5946 3134 5946 3134 5947 3019 5947 3024 5947 3134 5948 3024 5948 3135 5948 3135 5949 3024 5949 3136 5949 3136 5950 3024 5950 3023 5950 3136 5951 3023 5951 3022 5951 3136 5952 3022 5952 3137 5952 3137 5953 3022 5953 3020 5953 3137 5954 3020 5954 3133 5954 3138 5955 3029 5955 3028 5955 3138 5956 3028 5956 3139 5956 3139 5957 3028 5957 3033 5957 3139 5958 3033 5958 3140 5958 3140 5959 3033 5959 3034 5959 3140 5960 3034 5960 3141 5960 3141 5961 3034 5961 3032 5961 3141 5962 3032 5962 3142 5962 3142 5963 3032 5963 3031 5963 3142 5964 3031 5964 3143 5964 3143 5965 3031 5965 3029 5965 3143 5966 3029 5966 3138 5966 3079 5967 3144 5967 3145 5967 3146 5968 3074 5968 3147 5968 3147 5969 3074 5969 3078 5969 3147 5970 3078 5970 3148 5970 3148 5971 3078 5971 3077 5971 3148 5972 3077 5972 3076 5972 3148 5973 3076 5973 3145 5973 3145 5974 3076 5974 3079 5974 3144 5975 3079 5975 3080 5975 3144 5976 3080 5976 3149 5976 3149 5977 3080 5977 3082 5977 3149 5978 3082 5978 3150 5978 3150 5979 3082 5979 3081 5979 3150 5980 3081 5980 3151 5980 3151 5981 3081 5981 3152 5981 3152 5982 3081 5982 3083 5982 3152 5983 3083 5983 3084 5983 3084 5984 3153 5984 3152 5984 3074 5985 3146 5985 3075 5985 3075 5986 3153 5986 3084 5986 3154 5987 3051 5987 3155 5987 3155 5988 3051 5988 3050 5988 3155 5989 3050 5989 3156 5989 3156 5990 3050 5990 3049 5990 3156 5991 3049 5991 3157 5991 3157 5992 3049 5992 3048 5992 3157 5993 3048 5993 3158 5993 3158 5994 3048 5994 3047 5994 3158 5995 3047 5995 3159 5995 3159 5996 3047 5996 3071 5996 3159 5997 3071 5997 3160 5997 3160 5998 3071 5998 3072 5998 3160 5999 3072 5999 3161 5999 3161 6000 3072 6000 3073 6000 3161 6001 3073 6001 3162 6001 3162 6002 3073 6002 3070 6002 3162 6003 3070 6003 3154 6003 3154 6004 3070 6004 3051 6004 3163 6005 3063 6005 3017 6005 3163 6006 3017 6006 3164 6006 3164 6007 3017 6007 3016 6007 3164 6008 3016 6008 3165 6008 3165 6009 3016 6009 3015 6009 3165 6010 3015 6010 3166 6010 3166 6011 3015 6011 3018 6011 3166 6012 3018 6012 3067 6012 3166 6013 3067 6013 3167 6013 3167 6014 3067 6014 3069 6014 3167 6015 3069 6015 3168 6015 3168 6016 3069 6016 3068 6016 3168 6017 3068 6017 3169 6017 3169 6018 3068 6018 3065 6018 3169 6019 3065 6019 3170 6019 3170 6020 3065 6020 3064 6020 3170 6021 3064 6021 3163 6021 3163 6022 3064 6022 3063 6022 3171 6023 3059 6023 3027 6023 3171 6024 3027 6024 3172 6024 3172 6025 3027 6025 3026 6025 3172 6026 3026 6026 3173 6026 3173 6027 3026 6027 3025 6027 3173 6028 3025 6028 3174 6028 3174 6029 3025 6029 3062 6029 3174 6030 3062 6030 3175 6030 3175 6031 3062 6031 3061 6031 3175 6032 3061 6032 3176 6032 3176 6033 3061 6033 3060 6033 3176 6034 3060 6034 3177 6034 3177 6035 3060 6035 3059 6035 3177 6036 3059 6036 3178 6036 3178 6037 3059 6037 3171 6037 3179 6038 3037 6038 3180 6038 3180 6039 3037 6039 3056 6039 3180 6040 3056 6040 3181 6040 3181 6041 3056 6041 3058 6041 3181 6042 3058 6042 3182 6042 3182 6043 3058 6043 3057 6043 3182 6044 3057 6044 3183 6044 3183 6045 3057 6045 3036 6045 3183 6046 3036 6046 3184 6046 3184 6047 3036 6047 3035 6047 3184 6048 3035 6048 3185 6048 3185 6049 3035 6049 3039 6049 3185 6050 3039 6050 3186 6050 3186 6051 3039 6051 3038 6051 3186 6052 3038 6052 3187 6052 3187 6053 3038 6053 3037 6053 3187 6054 3037 6054 3179 6054 3188 6055 3092 6055 3093 6055 3188 6056 3093 6056 3189 6056 3189 6057 3093 6057 3094 6057 3189 6058 3094 6058 3190 6058 3190 6059 3094 6059 3086 6059 3190 6060 3086 6060 3191 6060 3191 6061 3086 6061 3087 6061 3191 6062 3087 6062 3192 6062 3192 6063 3087 6063 3088 6063 3192 6064 3088 6064 3193 6064 3193 6065 3088 6065 3089 6065 3193 6066 3089 6066 3194 6066 3194 6067 3089 6067 3090 6067 3194 6068 3090 6068 3195 6068 3195 6069 3090 6069 3091 6069 3195 6070 3091 6070 3196 6070 3196 6071 3091 6071 3092 6071 3196 6072 3092 6072 3188 6072 3197 6073 3102 6073 3198 6073 3198 6074 3102 6074 3103 6074 3198 6075 3103 6075 3199 6075 3199 6076 3103 6076 3095 6076 3199 6077 3095 6077 3200 6077 3200 6078 3095 6078 3096 6078 3200 6079 3096 6079 3201 6079 3201 6080 3096 6080 3097 6080 3201 6081 3097 6081 3202 6081 3202 6082 3097 6082 3098 6082 3202 6083 3098 6083 3203 6083 3203 6084 3098 6084 3099 6084 3203 6085 3099 6085 3204 6085 3204 6086 3099 6086 3100 6086 3204 6087 3100 6087 3205 6087 3205 6088 3100 6088 3101 6088 3205 6089 3101 6089 3197 6089 3197 6090 3101 6090 3102 6090 3104 6091 3107 6091 3105 6091 3104 6092 3112 6092 3109 6092 3104 6093 3109 6093 3108 6093 3105 6094 3107 6094 3106 6094 3109 6095 3112 6095 3111 6095 3109 6096 3111 6096 3110 6096 3104 6097 3108 6097 3107 6097 3120 6098 3115 6098 3114 6098 3120 6099 3114 6099 3113 6099 3116 6100 3120 6100 3119 6100 3120 6101 3116 6101 3115 6101 3119 6102 3118 6102 3116 6102 3118 6103 3117 6103 3116 6103 3122 6104 3123 6104 3126 6104 3126 6105 3123 6105 3125 6105 3122 6106 3126 6106 3121 6106 3125 6107 3123 6107 3124 6107 3127 6108 3131 6108 3132 6108 3130 6109 3131 6109 3127 6109 3127 6110 3129 6110 3130 6110 3129 6111 3127 6111 3128 6111 3136 6112 3137 6112 3134 6112 3133 6113 3134 6113 3137 6113 3135 6114 3136 6114 3134 6114 3140 6115 3138 6115 3139 6115 3143 6116 3138 6116 3140 6116 3143 6117 3140 6117 3142 6117 3142 6118 3140 6118 3141 6118 3149 6119 3150 6119 3206 6119 3144 6120 3149 6120 3206 6120 3207 6121 3148 6121 3145 6121 3146 6122 3147 6122 3208 6122 3145 6123 3144 6123 3207 6123 3207 6124 3144 6124 3206 6124 3151 6125 3206 6125 3150 6125 3208 6126 3207 6126 3206 6126 3208 6127 3206 6127 3151 6127 3208 6128 3151 6128 3152 6128 3147 6129 3148 6129 3207 6129 3147 6130 3207 6130 3208 6130 3146 6131 3208 6131 3153 6131 3153 6132 3208 6132 3152 6132 3209 6133 3154 6133 3155 6133 3209 6134 3155 6134 3210 6134 3210 6135 3155 6135 3156 6135 3210 6136 3156 6136 3211 6136 3211 6137 3156 6137 3157 6137 3211 6138 3157 6138 3212 6138 3212 6139 3157 6139 3158 6139 3212 6140 3158 6140 3213 6140 3213 6141 3158 6141 3159 6141 3213 6142 3159 6142 3160 6142 3213 6143 3160 6143 3214 6143 3214 6144 3160 6144 3161 6144 3214 6145 3161 6145 3215 6145 3215 6146 3161 6146 3162 6146 3215 6147 3162 6147 3216 6147 3216 6148 3162 6148 3209 6148 3209 6149 3162 6149 3154 6149 3217 6150 3170 6150 3163 6150 3217 6151 3163 6151 3218 6151 3218 6152 3163 6152 3164 6152 3218 6153 3164 6153 3219 6153 3219 6154 3164 6154 3220 6154 3220 6155 3164 6155 3165 6155 3220 6156 3165 6156 3221 6156 3221 6157 3165 6157 3166 6157 3221 6158 3166 6158 3222 6158 3222 6159 3166 6159 3167 6159 3222 6160 3167 6160 3223 6160 3223 6161 3167 6161 3168 6161 3223 6162 3168 6162 3224 6162 3224 6163 3168 6163 3169 6163 3224 6164 3169 6164 3225 6164 3225 6165 3169 6165 3170 6165 3225 6166 3170 6166 3217 6166 3226 6167 3175 6167 3227 6167 3227 6168 3175 6168 3176 6168 3227 6169 3176 6169 3228 6169 3228 6170 3176 6170 3177 6170 3228 6171 3177 6171 3229 6171 3229 6172 3177 6172 3178 6172 3229 6173 3178 6173 3230 6173 3230 6174 3178 6174 3171 6174 3230 6175 3171 6175 3231 6175 3231 6176 3171 6176 3172 6176 3231 6177 3172 6177 3232 6177 3232 6178 3172 6178 3173 6178 3232 6179 3173 6179 3233 6179 3233 6180 3173 6180 3234 6180 3234 6181 3173 6181 3174 6181 3234 6182 3174 6182 3226 6182 3226 6183 3174 6183 3175 6183 3235 6184 3179 6184 3236 6184 3236 6185 3179 6185 3180 6185 3236 6186 3180 6186 3237 6186 3237 6187 3180 6187 3181 6187 3237 6188 3181 6188 3238 6188 3238 6189 3181 6189 3182 6189 3238 6190 3182 6190 3239 6190 3239 6191 3182 6191 3183 6191 3239 6192 3183 6192 3240 6192 3240 6193 3183 6193 3184 6193 3240 6194 3184 6194 3241 6194 3241 6195 3184 6195 3185 6195 3241 6196 3185 6196 3242 6196 3242 6197 3185 6197 3186 6197 3242 6198 3186 6198 3243 6198 3243 6199 3186 6199 3235 6199 3235 6200 3186 6200 3187 6200 3235 6201 3187 6201 3179 6201 3196 6202 3193 6202 3195 6202 3195 6203 3193 6203 3194 6203 3191 6204 3189 6204 3190 6204 3189 6205 3191 6205 3192 6205 3189 6206 3192 6206 3193 6206 3193 6207 3196 6207 3188 6207 3193 6208 3188 6208 3189 6208 3203 6209 3204 6209 3205 6209 3199 6210 3201 6210 3198 6210 3201 6211 3202 6211 3198 6211 3205 6212 3197 6212 3203 6212 3203 6213 3197 6213 3198 6213 3201 6214 3199 6214 3200 6214 3203 6215 3198 6215 3202 6215 3244 6216 3212 6216 3245 6216 3245 6217 3212 6217 3213 6217 3245 6218 3213 6218 3246 6218 3246 6219 3213 6219 3214 6219 3246 6220 3214 6220 3247 6220 3247 6221 3214 6221 3215 6221 3247 6222 3215 6222 3248 6222 3248 6223 3215 6223 3216 6223 3248 6224 3216 6224 3249 6224 3249 6225 3216 6225 3209 6225 3249 6226 3209 6226 3250 6226 3250 6227 3209 6227 3210 6227 3250 6228 3210 6228 3251 6228 3251 6229 3210 6229 3211 6229 3251 6230 3211 6230 3252 6230 3252 6231 3211 6231 3212 6231 3252 6232 3212 6232 3244 6232 3253 6233 3223 6233 3224 6233 3253 6234 3224 6234 3254 6234 3254 6235 3224 6235 3225 6235 3254 6236 3225 6236 3255 6236 3255 6237 3225 6237 3217 6237 3255 6238 3217 6238 3256 6238 3256 6239 3217 6239 3218 6239 3256 6240 3218 6240 3257 6240 3257 6241 3218 6241 3219 6241 3257 6242 3219 6242 3258 6242 3258 6243 3219 6243 3220 6243 3258 6244 3220 6244 3259 6244 3259 6245 3220 6245 3221 6245 3259 6246 3221 6246 3222 6246 3259 6247 3222 6247 3260 6247 3260 6248 3222 6248 3223 6248 3260 6249 3223 6249 3253 6249 3261 6250 3229 6250 3230 6250 3261 6251 3230 6251 3262 6251 3262 6252 3230 6252 3231 6252 3262 6253 3231 6253 3263 6253 3263 6254 3231 6254 3232 6254 3263 6255 3232 6255 3264 6255 3264 6256 3232 6256 3233 6256 3264 6257 3233 6257 3265 6257 3265 6258 3233 6258 3234 6258 3265 6259 3234 6259 3266 6259 3266 6260 3234 6260 3226 6260 3266 6261 3226 6261 3267 6261 3267 6262 3226 6262 3227 6262 3267 6263 3227 6263 3268 6263 3268 6264 3227 6264 3228 6264 3268 6265 3228 6265 3269 6265 3269 6266 3228 6266 3229 6266 3269 6267 3229 6267 3261 6267 3270 6268 3242 6268 3243 6268 3270 6269 3243 6269 3271 6269 3271 6270 3243 6270 3235 6270 3271 6271 3235 6271 3272 6271 3272 6272 3235 6272 3236 6272 3272 6273 3236 6273 3273 6273 3273 6274 3236 6274 3237 6274 3273 6275 3237 6275 3238 6275 3273 6276 3238 6276 3274 6276 3274 6277 3238 6277 3275 6277 3275 6278 3238 6278 3239 6278 3275 6279 3239 6279 3276 6279 3276 6280 3239 6280 3240 6280 3276 6281 3240 6281 3277 6281 3277 6282 3240 6282 3241 6282 3277 6283 3241 6283 3278 6283 3278 6284 3241 6284 3242 6284 3278 6285 3242 6285 3270 6285 3251 6286 3246 6286 3250 6286 3250 6287 3246 6287 3247 6287 3247 6288 3248 6288 3250 6288 3249 6289 3250 6289 3248 6289 3246 6290 3251 6290 3252 6290 3252 6291 3244 6291 3246 6291 3244 6292 3245 6292 3246 6292 3254 6293 3260 6293 3253 6293 3255 6294 3256 6294 3257 6294 3257 6295 3258 6295 3254 6295 3254 6296 3258 6296 3259 6296 3257 6297 3254 6297 3255 6297 3259 6298 3260 6298 3254 6298 3268 6299 3263 6299 3264 6299 3268 6300 3264 6300 3265 6300 3269 6301 3262 6301 3263 6301 3268 6302 3265 6302 3267 6302 3267 6303 3265 6303 3266 6303 3268 6304 3269 6304 3263 6304 3269 6305 3261 6305 3262 6305 3272 6306 3273 6306 3274 6306 3274 6307 3275 6307 3271 6307 3271 6308 3275 6308 3276 6308 3276 6309 3277 6309 3271 6309 3271 6310 3278 6310 3270 6310 3274 6311 3271 6311 3272 6311 3271 6312 3277 6312 3278 6312 2219 6313 247 6313 2375 6313 2375 6314 247 6314 2639 6314 2375 6315 2639 6315 2601 6315 2630 6316 2626 6316 2547 6316 2547 6317 2626 6317 2642 6317 2547 6318 2642 6318 2643 6318 2375 6319 2601 6319 2603 6319 2375 6320 2603 6320 2408 6320 2603 6321 2635 6321 2408 6321 2408 6322 2635 6322 2637 6322 2408 6323 2637 6323 2547 6323 2547 6324 2637 6324 2628 6324 2547 6325 2628 6325 2630 6325 2616 6326 2628 6326 2614 6326 2616 6327 2618 6327 2624 6327 2606 6328 2607 6328 2609 6328 2606 6329 2609 6329 2637 6329 2609 6330 2611 6330 2637 6330 2628 6331 2616 6331 2624 6331 2624 6332 2618 6332 1979 6332 2624 6333 1979 6333 2626 6333 2626 6334 1979 6334 1 6334 2626 6335 1 6335 2642 6335 2642 6336 1 6336 0 6336 1979 6337 2618 6337 2620 6337 1979 6338 2620 6338 2606 6338 2606 6339 2620 6339 2607 6339 2637 6340 2611 6340 2628 6340 2628 6341 2611 6341 2614 6341 234 6342 2695 6342 237 6342 237 6343 2695 6343 2740 6343 237 6344 2740 6344 244 6344 237 6345 244 6345 243 6345 2693 6346 191 6346 2768 6346 2768 6347 2369 6347 2371 6347 2371 6348 2369 6348 2370 6348 2771 6349 2075 6349 3279 6349 3280 6350 71 6350 2771 6350 3280 6351 2771 6351 3279 6351 86 6352 2749 6352 2641 6352 2871 6353 142 6353 2694 6353 122 6354 3281 6354 2769 6354 3282 6355 2189 6355 2767 6355 3282 6356 2767 6356 2769 6356 3282 6357 2769 6357 3281 6357 2394 6358 2490 6358 2656 6358 2656 6359 2695 6359 2394 6359 2394 6360 2695 6360 234 6360 2394 6361 234 6361 236 6361 2691 6362 193 6362 191 6362 2679 6363 2550 6363 2676 6363 2676 6364 2550 6364 2691 6364 2659 6365 2652 6365 2686 6365 2094 6366 2674 6366 11 6366 11 6367 2674 6367 2676 6367 2656 6368 2490 6368 2654 6368 191 6369 2693 6369 2691 6369 2691 6370 2693 6370 2692 6370 2691 6371 2692 6371 2676 6371 2676 6372 2692 6372 10 6372 2676 6373 10 6373 11 6373 2679 6374 2681 6374 2550 6374 2550 6375 2681 6375 2686 6375 2550 6376 2686 6376 2490 6376 2490 6377 2686 6377 2688 6377 2490 6378 2688 6378 2654 6378 2673 6379 2670 6379 2094 6379 2094 6380 2670 6380 2674 6380 2670 6381 2669 6381 2674 6381 2652 6382 2659 6382 2673 6382 2652 6383 2673 6383 2094 6383 2667 6384 2665 6384 2681 6384 2663 6385 2661 6385 2686 6385 2661 6386 2659 6386 2686 6386 2669 6387 2667 6387 2674 6387 2674 6388 2667 6388 2681 6388 2681 6389 2665 6389 2663 6389 2681 6390 2663 6390 2686 6390 99 6391 2749 6391 89 6391 89 6392 2749 6392 86 6392 125 6393 128 6393 122 6393 122 6394 128 6394 3281 6394 71 6395 3280 6395 69 6395 2189 6396 3282 6396 137 6396 137 6397 3282 6397 135 6397 135 6398 3282 6398 3281 6398 135 6399 3281 6399 128 6399 3279 6400 2075 6400 84 6400 84 6401 2075 6401 81 6401 69 6402 3280 6402 3279 6402 69 6403 3279 6403 84 6403 2744 6404 2748 6404 2745 6404 2748 6405 2744 6405 2743 6405 2748 6406 2743 6406 2742 6406 2742 6407 2741 6407 2748 6407 2745 6408 2748 6408 2747 6408 2745 6409 2747 6409 2746 6409 2772 6410 2778 6410 2780 6410 2782 6411 2784 6411 2772 6411 2772 6412 2780 6412 2782 6412 2784 6413 2786 6413 2772 6413 2772 6414 2774 6414 2778 6414 2778 6415 2774 6415 2776 6415 2214 6416 2210 6416 2215 6416 2214 6417 2212 6417 2211 6417 2214 6418 2213 6418 2212 6418 2214 6419 2211 6419 2210 6419 2215 6420 2210 6420 2218 6420 2218 6421 2217 6421 2215 6421 2217 6422 2216 6422 2215 6422 3283 6423 3284 6423 3285 6423 3283 6424 3285 6424 3286 6424 3287 6425 3288 6425 3285 6425 3285 6426 3288 6426 3286 6426 3285 6427 3284 6427 3289 6427 3285 6428 3289 6428 3290 6428 3286 6429 3291 6429 3292 6429 3286 6430 3292 6430 3293 6430 3286 6431 3293 6431 3283 6431 3283 6432 3293 6432 3284 6432 3284 6433 3293 6433 3294 6433 3284 6434 3294 6434 3289 6434 3289 6435 3294 6435 3295 6435 3289 6436 3295 6436 3290 6436 3290 6437 3295 6437 3296 6437 3290 6438 3296 6438 3285 6438 3285 6439 3296 6439 3297 6439 3285 6440 3297 6440 3287 6440 3287 6441 3297 6441 3298 6441 3287 6442 3298 6442 3288 6442 3288 6443 3298 6443 3291 6443 3288 6444 3291 6444 3286 6444 3294 6445 3299 6445 3295 6445 3295 6446 3299 6446 3300 6446 3295 6447 3300 6447 3296 6447 3296 6448 3300 6448 3301 6448 3296 6449 3301 6449 3297 6449 3297 6450 3301 6450 3302 6450 3297 6451 3302 6451 3298 6451 3298 6452 3302 6452 3303 6452 3298 6453 3303 6453 3291 6453 3291 6454 3303 6454 3304 6454 3291 6455 3304 6455 3292 6455 3292 6456 3304 6456 3305 6456 3292 6457 3305 6457 3293 6457 3293 6458 3305 6458 3306 6458 3293 6459 3306 6459 3294 6459 3294 6460 3306 6460 3299 6460 3304 6461 110 6461 3305 6461 3305 6462 110 6462 112 6462 3305 6463 112 6463 3306 6463 3306 6464 112 6464 115 6464 3306 6465 115 6465 3299 6465 3299 6466 115 6466 117 6466 3299 6467 117 6467 3300 6467 3300 6468 117 6468 118 6468 3300 6469 118 6469 3301 6469 3301 6470 118 6470 121 6470 3301 6471 121 6471 3302 6471 3302 6472 121 6472 106 6472 3302 6473 106 6473 3303 6473 3303 6474 106 6474 108 6474 3303 6475 108 6475 3304 6475 3304 6476 108 6476 110 6476 2091 6477 2086 6477 2092 6477 2086 6478 2089 6478 2088 6478 2093 6479 2092 6479 2086 6479 2086 6480 2091 6480 2090 6480 2086 6481 2090 6481 2089 6481 2086 6482 2088 6482 2087 6482 3307 6483 3308 6483 3309 6483 3310 6484 3307 6484 3309 6484 3310 6485 3309 6485 3311 6485 3309 6486 3308 6486 3312 6486 3311 6487 3313 6487 3314 6487 3311 6488 3314 6488 3310 6488 3315 6489 3311 6489 3309 6489 3315 6490 3309 6490 3316 6490 3316 6491 3309 6491 3312 6491 3316 6492 3312 6492 3317 6492 3317 6493 3312 6493 3318 6493 3318 6494 3312 6494 3308 6494 3318 6495 3308 6495 3319 6495 3319 6496 3308 6496 3307 6496 3319 6497 3307 6497 3320 6497 3320 6498 3307 6498 3310 6498 3320 6499 3310 6499 3321 6499 3321 6500 3310 6500 3314 6500 3321 6501 3314 6501 3322 6501 3322 6502 3314 6502 3313 6502 3322 6503 3313 6503 3323 6503 3323 6504 3313 6504 3311 6504 3323 6505 3311 6505 3315 6505 3322 6506 3324 6506 3325 6506 3322 6507 3325 6507 3321 6507 3321 6508 3325 6508 3326 6508 3321 6509 3326 6509 3320 6509 3320 6510 3326 6510 3327 6510 3320 6511 3327 6511 3319 6511 3319 6512 3327 6512 3328 6512 3319 6513 3328 6513 3318 6513 3318 6514 3328 6514 3329 6514 3318 6515 3329 6515 3317 6515 3317 6516 3329 6516 3330 6516 3317 6517 3330 6517 3316 6517 3316 6518 3330 6518 3331 6518 3316 6519 3331 6519 3315 6519 3315 6520 3331 6520 3332 6520 3315 6521 3332 6521 3323 6521 3323 6522 3332 6522 3324 6522 3323 6523 3324 6523 3322 6523 3327 6524 64 6524 61 6524 3327 6525 61 6525 3328 6525 3328 6526 61 6526 3329 6526 3329 6527 61 6527 60 6527 3329 6528 60 6528 3330 6528 3330 6529 60 6529 57 6529 3330 6530 57 6530 3331 6530 3331 6531 57 6531 55 6531 3331 6532 55 6532 3332 6532 3332 6533 55 6533 53 6533 3332 6534 53 6534 3324 6534 3324 6535 53 6535 52 6535 3324 6536 52 6536 3325 6536 3325 6537 52 6537 68 6537 3325 6538 68 6538 66 6538 3325 6539 66 6539 3326 6539 3326 6540 66 6540 64 6540 3326 6541 64 6541 3327 6541 3333 6542 3334 6542 3335 6542 3334 6543 3336 6543 3337 6543 3335 6544 3338 6544 3339 6544 3333 6545 3336 6545 3334 6545 3335 6546 3339 6546 3333 6546 3340 6547 3335 6547 3334 6547 3340 6548 3334 6548 3341 6548 3341 6549 3334 6549 3337 6549 3341 6550 3337 6550 3342 6550 3342 6551 3337 6551 3343 6551 3343 6552 3337 6552 3336 6552 3343 6553 3336 6553 3333 6553 3343 6554 3333 6554 3344 6554 3344 6555 3333 6555 3345 6555 3345 6556 3333 6556 3339 6556 3345 6557 3339 6557 3346 6557 3346 6558 3339 6558 3338 6558 3346 6559 3338 6559 3347 6559 3347 6560 3338 6560 3335 6560 3347 6561 3335 6561 3340 6561 3346 6562 3348 6562 3349 6562 3346 6563 3349 6563 3345 6563 3345 6564 3349 6564 3344 6564 3344 6565 3349 6565 3350 6565 3344 6566 3350 6566 3351 6566 3344 6567 3351 6567 3343 6567 3343 6568 3351 6568 3352 6568 3343 6569 3352 6569 3342 6569 3342 6570 3352 6570 3353 6570 3342 6571 3353 6571 3341 6571 3341 6572 3353 6572 3354 6572 3341 6573 3354 6573 3340 6573 3340 6574 3354 6574 3355 6574 3340 6575 3355 6575 3347 6575 3347 6576 3355 6576 3348 6576 3347 6577 3348 6577 3346 6577 3351 6578 46 6578 3352 6578 3352 6579 46 6579 44 6579 3352 6580 44 6580 42 6580 3352 6581 42 6581 3353 6581 3353 6582 42 6582 40 6582 3353 6583 40 6583 3354 6583 3354 6584 40 6584 38 6584 3354 6585 38 6585 3355 6585 3355 6586 38 6586 35 6586 3355 6587 35 6587 3348 6587 3348 6588 35 6588 34 6588 3348 6589 34 6589 3349 6589 3349 6590 34 6590 48 6590 3349 6591 48 6591 3350 6591 3350 6592 48 6592 46 6592 3350 6593 46 6593 3351 6593 3356 6594 3357 6594 3358 6594 3358 6595 3357 6595 3359 6595 3359 6596 3360 6596 3361 6596 3359 6597 3361 6597 3358 6597 3362 6598 3363 6598 3357 6598 3356 6599 3362 6599 3357 6599 3358 6600 3364 6600 3365 6600 3358 6601 3365 6601 3356 6601 3356 6602 3365 6602 3366 6602 3356 6603 3366 6603 3362 6603 3362 6604 3366 6604 3367 6604 3362 6605 3367 6605 3363 6605 3363 6606 3367 6606 3368 6606 3363 6607 3368 6607 3357 6607 3357 6608 3368 6608 3369 6608 3357 6609 3369 6609 3359 6609 3359 6610 3369 6610 3370 6610 3359 6611 3370 6611 3360 6611 3360 6612 3370 6612 3371 6612 3360 6613 3371 6613 3361 6613 3361 6614 3371 6614 3364 6614 3361 6615 3364 6615 3358 6615 3367 6616 3372 6616 3373 6616 3367 6617 3373 6617 3368 6617 3368 6618 3373 6618 3374 6618 3368 6619 3374 6619 3369 6619 3369 6620 3374 6620 3375 6620 3369 6621 3375 6621 3370 6621 3370 6622 3375 6622 3376 6622 3370 6623 3376 6623 3371 6623 3371 6624 3376 6624 3377 6624 3371 6625 3377 6625 3364 6625 3364 6626 3377 6626 3378 6626 3364 6627 3378 6627 3365 6627 3365 6628 3378 6628 3366 6628 3366 6629 3378 6629 3379 6629 3366 6630 3379 6630 3372 6630 3366 6631 3372 6631 3367 6631 3377 6632 21 6632 3378 6632 3378 6633 21 6633 23 6633 3378 6634 23 6634 25 6634 3378 6635 25 6635 3379 6635 3379 6636 25 6636 3372 6636 3372 6637 25 6637 27 6637 3372 6638 27 6638 29 6638 3372 6639 29 6639 3373 6639 3373 6640 29 6640 31 6640 3373 6641 31 6641 3374 6641 3374 6642 31 6642 33 6642 3374 6643 33 6643 3375 6643 3375 6644 33 6644 16 6644 3375 6645 16 6645 3376 6645 3376 6646 16 6646 19 6646 3376 6647 19 6647 3377 6647 3377 6648 19 6648 21 6648 3380 6649 3381 6649 3382 6649 3381 6650 3383 6650 3384 6650 3381 6651 3384 6651 3385 6651 3385 6652 3386 6652 3381 6652 3386 6653 3387 6653 3381 6653 3381 6654 3387 6654 3382 6654 3381 6655 3388 6655 3383 6655 3383 6656 3389 6656 3384 6656 3384 6657 3389 6657 3390 6657 3384 6658 3390 6658 3391 6658 3384 6659 3391 6659 3385 6659 3385 6660 3391 6660 3392 6660 3385 6661 3392 6661 3386 6661 3386 6662 3392 6662 3393 6662 3386 6663 3393 6663 3387 6663 3387 6664 3393 6664 3394 6664 3387 6665 3394 6665 3382 6665 3382 6666 3394 6666 3395 6666 3382 6667 3395 6667 3380 6667 3380 6668 3395 6668 3396 6668 3380 6669 3396 6669 3381 6669 3381 6670 3396 6670 3397 6670 3381 6671 3397 6671 3388 6671 3388 6672 3397 6672 3389 6672 3388 6673 3389 6673 3383 6673 3397 6674 3398 6674 3389 6674 3389 6675 3398 6675 3399 6675 3389 6676 3399 6676 3400 6676 3389 6677 3400 6677 3390 6677 3390 6678 3400 6678 3401 6678 3390 6679 3401 6679 3391 6679 3391 6680 3401 6680 3402 6680 3391 6681 3402 6681 3392 6681 3392 6682 3402 6682 3403 6682 3392 6683 3403 6683 3393 6683 3393 6684 3403 6684 3404 6684 3393 6685 3404 6685 3394 6685 3394 6686 3404 6686 3395 6686 3395 6687 3404 6687 3405 6687 3395 6688 3405 6688 3396 6688 3396 6689 3405 6689 3406 6689 3396 6690 3406 6690 3397 6690 3397 6691 3406 6691 3398 6691 3407 6692 3408 6692 3404 6692 3404 6693 3408 6693 3405 6693 3405 6694 3408 6694 3409 6694 3405 6695 3409 6695 3406 6695 3406 6696 3409 6696 3410 6696 3406 6697 3410 6697 3398 6697 3398 6698 3410 6698 3411 6698 3398 6699 3411 6699 3399 6699 3399 6700 3411 6700 3412 6700 3399 6701 3412 6701 3400 6701 3400 6702 3412 6702 3413 6702 3400 6703 3413 6703 3401 6703 3401 6704 3413 6704 3414 6704 3401 6705 3414 6705 3402 6705 3402 6706 3414 6706 3415 6706 3402 6707 3415 6707 3403 6707 3403 6708 3415 6708 3407 6708 3403 6709 3407 6709 3404 6709 3408 6710 3407 6710 3411 6710 3408 6711 3411 6711 3410 6711 3407 6712 3415 6712 3411 6712 3408 6713 3410 6713 3409 6713 3411 6714 3415 6714 3414 6714 3411 6715 3414 6715 3413 6715 3411 6716 3413 6716 3412 6716</p> + </triangles> + </mesh> + </geometry> + </library_geometries> + <library_materials> + <material name="Mesh001" id="mat_Mesh001"> + <instance_effect url="#effect_Mesh001"/> + </material> + </library_materials> + <library_visual_scenes> + <visual_scene id="myscene"> + <node name="node0" id="node0"> + <instance_geometry url="#geometry0"> + <bind_material> + <technique_common> + <instance_material symbol="ref_Mesh001" target="#mat_Mesh001"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#myscene"/> + </scene> +</COLLADA> diff --git a/kinton_description/meshes/arm/link1.stl b/kinton_description/meshes/arm/link1.stl new file mode 100755 index 0000000000000000000000000000000000000000..fbbd91d197d607a38a2b849fc2e9b4fb685f2ab3 Binary files /dev/null and b/kinton_description/meshes/arm/link1.stl differ diff --git a/kinton_description/meshes/arm/link2.dae b/kinton_description/meshes/arm/link2.dae new file mode 100644 index 0000000000000000000000000000000000000000..a05b0f1fb0b096db05828a4123930da076cd2d18 --- /dev/null +++ b/kinton_description/meshes/arm/link2.dae @@ -0,0 +1,199 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2015-07-29T19:29:02</created> + <modified>2015-07-29T19:29:02</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera_001-camera" name="Camera.003"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp_001-light" name="Lamp.003"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>9.99987e-4</adapt_thresh> + <area_shape>1</area_shape> + <area_size>0.1</area_size> + <area_sizey>0.1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <shadspotsize>45</shadspotsize> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_images/> + <library_effects> + <effect id="Material_002-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.07084059 0.06348874 0.06348874 1</color> + </diffuse> + <specular> + <color sid="specular">0.125 0.125 0.125 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="Material_002-material" name="Material_002"> + <instance_effect url="#Material_002-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Link2-mesh" name="Link2"> + <mesh> + <source id="Link2-mesh-positions"> + <float_array id="Link2-mesh-positions-array" count="6831">11.0303 31.46888 8.25 11.55 31.50078 8.800003 11.01502 31.48526 8.800002 18.98497 31.48529 8.250002 18.40747 31.3464 8.250353 18.96966 31.4689 8.800002 18.45 31.50078 8.800003 11.00139 31.44179 21.20001 11.02246 31.49281 21.75 11.55 31.50078 21.2 11.56887 31.29795 21.74969 26.63668 30.40078 8.25 26.91268 29.97578 8.25 23.55 30.46745 8.25 20.17753 30.04058 8.250111 20.18028 30.58959 8.25 20.34526 30.55049 8.800002 20.07887 30.06842 21.7499 26.91268 29.97578 21.75 23.55 30.45078 21.75 26.63668 30.40078 21.75 20.49951 30.53585 21.75 19.08884 31.31485 21.75 18.41541 31.36979 21.75 10.72031 30.45705 7.799742 9.962555 30.10176 5.999999 9.921108 30.06842 8.250108 11.5676 31.32686 8.25 11.55 31.37347 7.8 18.46128 31.30422 7.799998 19.44847 30.39931 6.000001 19.4127 30.41452 7.799955 20.39868 30.01958 6 3.363317 30.40078 21.75 3.087318 29.97578 21.75 6.449998 30.45078 21.75 9.822494 30.04059 21.74989 9.785202 30.57299 21.75 9.819779 30.58961 8.800003 9.654755 30.55049 8.25 3.087318 29.97578 8.25 6.449999 30.43411 8.25 3.363317 30.40078 8.25 11.55 31.37347 22.2 10.71318 30.46979 22.20007 10.55151 30.39931 24 9.601349 30.01959 24 19.27971 30.45704 22.20026 18.45 31.37347 22.2 20.03745 30.10175 24 23.55 30.50078 21.2 20.21477 30.57301 21.2 7.474161 35.9122 6.005999 21.58632 35.89371 6.001434 25.5 29.97578 6.000001 25.5 30.40078 6.000001 6.449999 30.50078 21.2 22.08741 35.9323 23.99186 7.416837 35.9009 23.99639 25.5 30.40078 24 25.5 29.97578 24 25.5 12.20078 24 25.48903 32.14241 26.81253 25.48956 3.854628 26.80154 25.5 23.90078 24 25.5 23.80078 18 25.5 32.15111 24 25.5 12.00078 6.000001 25.5 5.500775 6.000001 25.5 22.00078 18 25.5 12.10078 18 25.5 12.00078 12 25.5 32.15111 6.000001 25.5 24.00078 6.000001 25.5 24.00078 12 25.5 22.00078 12 25.5 10.57863 16.31818 25.5 5.500775 12 25.5 5.500775 18 25.5 5.500775 24 25.5 7.316803 13.82036 25.5 9.792489 13.14352 25.5 10.70706 13.89139 25.5 8.608265 13.00341 25.5 11.01858 15.0424 25.5 7.394661 16.24933 25.5 6.986646 15.12886 25.5 8.879416 17.07831 4.5 30.40078 6.000001 4.5 32.15111 6.000001 4.562783 32.11987 3.060118 4.5 12.30078 18 4.5 22.00078 18 4.5 22.00078 12 4.5 32.15111 24 4.5 30.40078 24 4.5 29.97578 24 4.5 23.80078 24 4.5 6.945026 15.03435 4.5 5.500775 18 4.5 12.00078 12 4.5 12.10078 24 4.5 12.00078 6.000001 4.5 5.500775 6.000001 4.5 5.500775 12 4.506263 3.854344 26.78077 4.5 23.90078 18 4.5 24.00078 12 4.5 24.00078 6.000001 4.5 29.97578 6.000001 4.5 5.500775 24 4.5 7.308334 13.92224 4.5 9.725068 13.09846 4.5 10.75885 13.97551 4.5 8.202416 13.10529 4.5 11.0149 15.12889 4.5 12.00078 18 4.5 10.5087 16.39766 4.5 7.557541 16.4344 4.5 8.947842 17.05535 9.169621 35.53861 27 16.00534 35.33716 27.00001 20.10977 35.36128 27 6.471645 33.27794 27 4.555796 32.11632 26.9368 17.36837 33.99873 27 6.699188 32.00235 27 7.352264 34.97311 27.00001 6.913956 35.41765 26.98843 14.31445 35.45014 27 21.81558 35.43798 27 23.42721 32.31284 26.99999 25.30431 32.09492 26.98923 23.36838 33.99873 27.00001 9.212296 15.86841 27.00001 19.43839 30.99312 27 18.45404 17.23451 27.00002 21.04622 30.4577 27 16.47453 30.89581 27 14.39404 30.50319 27 10.34717 35.11633 27 23.9287 8.872676 27.00022 23.10268 5.126755 27.00001 25.31664 3.910252 26.98814 7.43837 30.9931 26.99999 11.24996 34.18698 27 12.92788 34.47581 27 18.92793 34.47586 27 16.87617 0.3007753 27 18.48116 0.7960129 27 23.46288 11.84766 27 12.50441 33.25126 27 11.49573 32.51015 27 7.527542 4.113205 26.99997 6.326157 6.881775 27 22.63358 31.05121 27 12.51485 17.57689 27 21.61585 15.07471 27.00001 6.920247 12.80122 26.99997 9.890748 30.61835 27 20.79706 2.209595 26.99999 23.19016 0.701355 26.98928 15.51379 17.91491 27 12.72479 31.80554 27 18.45658 32.63182 27 6.115705 9.892441 27 10.92737 31.39587 27 13.12425 0.3006592 26.99997 10.12806 1.455864 27.00001 6.771877 0.7485657 26.99257 8.64386 30.51807 27 17.42721 32.31287 27 19.06554 8.369668 3 23.02268 8.779026 3 19.09848 9.725098 3 22.71303 10.09892 2.999999 20.12193 10.85989 3 22.43441 7.557556 3.000002 21.38279 7.019164 3 20.02741 7.189327 3 21.64291 10.93134 3 14.78662 5.00771 3 15.38128 0.9804018 3 16.87396 3.793648 3 16.87357 2.093151 3 13.8914 1.294491 3 13.55275 4.461166 3 15.95993 4.794918 3 12.93947 2.703602 3 6.986708 8.705695 3 10.71301 10.09895 3 10.54274 7.699505 3 9.548416 7.041272 3 7.861732 7.257668 3.000001 11.02268 8.779065 3 7.248208 10.03598 3 8.130219 10.82198 2.999999 9.484745 10.99885 3 15.87167 13.16213 3 17.0279 15.4716 3 14.12194 16.85989 3 14.34753 13.051 3 16.74041 13.97889 2.999998 15.81546 16.88818 3 13.0243 15.5699 3 13.20001 14.05185 2.999999 23.03106 8.87748 0.8000006 22.59709 7.76683 0.8000016 21.48476 7.002702 0.8000005 19.66659 7.402 0.8000005 18.9658 8.951386 0.8000006 19.304 10.09482 0.8000006 20.34752 10.95054 0.8000006 21.87169 10.83942 0.8000003 22.74045 10.02267 0.800001 16.87396 2.207901 0.8000007 16.0948 1.30526 0.8000007 14.96303 0.9663093 0.8000007 13.83495 1.35276 0.8000012 13.09845 2.276527 0.8000004 13.06553 3.631851 0.8000003 13.76537 4.597336 0.8000006 15.03434 5.056524 0.8000006 16.43442 4.444 0.8000009 16.98144 3.384407 0.8000004 11.03473 8.705602 0.8000004 10.36557 7.51466 0.8000005 9.307388 6.989326 0.8000005 7.975525 7.242695 0.8000006 7.179153 8.130219 0.8000006 6.98671 9.295866 0.8000006 7.735261 10.6218 0.8000011 9.38127 11.02115 0.8000006 10.65768 10.18082 0.800001 17.03106 14.87752 0.8000004 16.50279 13.6289 0.8000003 15.4674 13.03739 0.8000005 14.28739 13.09483 0.8000004 13.05619 14.25533 0.8000005 13.20001 15.94969 0.8000004 14.05292 16.78303 0.8000003 15.20938 17.02477 0.8000004 16.56587 16.33319 0.8000005 24.8 8.359658 19.01934 24.8 8.440377 22.95611 24.8 10.036 19.24822 24.8 7.335915 22.1699 24.8 10.82197 20.13018 24.8 10.12029 22.75521 24.8 11.01223 21.30737 24.8 6.978033 20.50745 24.8 7.906723 7.304008 24.8 9.050189 6.9658 24.8 8.093138 10.87357 24.8 10.16654 7.352481 24.8 10.85693 9.79245 24.8 10.98153 8.448739 24.8 9.956978 10.82016 24.8 7.04127 9.54841 24.8 7.131691 8.195694 19.36645 10.95036 0.8000003 21.17249 11.56429 0.8000005 22.52173 10.99454 0.7999995 23.44447 9.794274 0.8000005 23.36013 8.109543 0.8000003 22.2926 6.780286 0.8000005 20.18442 6.563576 0.8000005 18.75002 7.814621 0.8000006 18.50427 9.491402 0.8000004 16.36847 5.120178 0.8000005 17.34246 3.991867 0.8000005 17.47533 2.527557 0.8000004 16.92839 1.374161 0.8000002 15.89023 0.640255 0.8 14.40392 0.5281091 0.8000004 12.83636 1.615127 0.8000004 12.50426 3.491383 0.8000006 13.36644 4.950359 0.8000003 14.95379 5.543857 0.8000005 6.491446 9.268579 0.8000005 6.940601 10.45797 0.8000005 8.113236 11.38026 0.8000004 10.01935 11.36003 0.8000006 11.44447 9.794278 0.8000004 11.29158 7.897137 0.8000004 10.08961 6.70248 0.8000006 8.855671 6.496805 0.8000006 7.613075 6.869095 0.8000003 6.67939 8.011162 0.8000003 16.56162 17.00844 0.8000003 17.54035 15.36206 0.8000003 17.07211 13.52573 0.8000005 15.89025 12.64026 0.8000004 14.40394 12.5281 0.8000006 13.31467 13.14328 0.8000006 12.58192 14.21191 0.8000006 12.57374 15.68227 0.8000003 13.36646 16.95037 0.8000004 14.95376 17.54386 0.8000006 13.58239 6.572584 0.4986315 12.72731 7.323413 0.4982395 12.2301 8.496164 0.4644194 17.80634 8.82914 0.4987512 17.5013 10.40805 0.4908443 15.8999 11.6909 0.4997668 15.41301 10.47298 0.1138553 14.39954 11.75628 0.500804 13.3605 11.2893 0.4876675 12.37141 10.09146 0.4969471 14.58954 7.533817 0.1126184 14.87804 6.155289 0.5030251 16.51824 6.589136 0.4959799 16.34238 8.18763 0.1079425 17.5279 7.722002 0.4987769 14.00416 9.512124 0.0314064 18.72205 4.092762 3 18.88288 5.522536 3 20.06729 4.519064 3 19.46201 3.974333 3 18.42526 4.848921 3 19.75545 5.414249 3.000001 10.97994 3.955698 3 10.07478 4.237276 3 10.95124 5.557365 3 11.52273 5.082402 3 11.49034 4.404555 3 10.10439 5.315661 3 19.81641 12.66612 3 19.5165 14.05718 3 18.63443 12.68983 2.999999 19.25902 12.42099 3 18.42896 13.26315 3 20.07396 13.29195 3 18.66373 13.82757 3 11.58513 13.15729 3 9.913943 13.19462 3 11.16481 13.99919 3 10.42473 12.48118 3 11.17098 12.53285 3.000001 10.28549 13.917 3 5.199999 11.07206 21.20945 5.199999 8.877472 23.03106 5.199999 8.431656 19.02431 5.199999 10.1808 22.6577 5.199998 10.26512 19.34607 5.199999 7.049103 20.27539 5.199998 7.360466 22.28198 5.199999 7.600737 10.54077 5.199998 7.805981 7.326756 5.199998 10.44396 10.43442 5.199999 10.7439 7.861752 5.199999 9.295864 6.98671 5.199999 9.222542 11.02268 5.199999 6.955346 8.791444 5.199998 10.98238 9.382836 26.2 8.536004 22.98101 26.2 7.394646 22.2493 26.2 6.954715 20.61564 26.2 8.255303 19.0562 26.2 9.949738 19.20003 26.2 10.86987 20.19569 26.2 10.96027 21.54844 26.2 10.04936 22.76854 26.2 8.054528 10.78268 26.2 7.206624 9.959915 26.2 7.001821 8.61974 26.2 7.684402 7.448357 26.2 8.951374 6.965801 26.2 10.52645 7.583527 26.20001 11.01858 9.042401 26.2 10.66563 10.16988 26.2 9.400319 11.01684 19.36641 7.051193 0 18.50427 8.510163 0 18.75002 10.18693 0 19.99461 11.33714 0 21.67864 11.44412 0 22.92838 10.62741 0 23.52835 9.277943 0 23.04047 7.438217 0 21.17037 6.437702 0 16.8785 1.285934 0 15.17513 0.436705 0 13.36644 1.051193 0 12.44647 2.72176 0 12.88002 4.36834 0 13.99463 5.337146 0 15.28093 5.493119 0 16.46236 5.081856 0 17.36012 3.892044 0 17.49399 2.641235 0 6.810257 7.706772 0 6.437526 9.323873 -0.02375614 7.425528 11.03497 0 9.261693 11.53078 0 10.62581 10.92987 0 11.52106 9.500149 0 11.2283 7.817902 0 10.19991 6.758092 0 8.325814 6.52867 0 13.81618 17.22859 0 15.22594 17.57742 -0.02762818 17.06302 16.57187 0 17.52714 14.7857 0 16.87853 13.28596 0 15.38422 12.48646 0 13.52545 12.89581 0 12.57279 14.31287 0 12.64318 16.0025 0 12.69443 10.68237 0 14.69503 6.194725 0 17.58205 7.772034 0 16.3472 6.491794 0 13.23498 6.754639 0 12.26127 8.308152 0 12.22757 9.476159 0 14.19174 11.70765 0 15.75697 11.73468 0 17.16339 10.80997 0 17.76836 9.531891 0 20.07917 4.564671 0 19.30137 3.915346 0 18.48252 4.389416 0 18.58107 5.263882 0 19.18837 5.570243 0 19.76991 5.389282 0 11.52073 4.43252 0 10.74448 3.899626 0 9.94586 4.523178 0 10.23677 5.423513 0 11.04423 5.528891 0 11.49009 5.112045 0 18.76199 12.54682 0 18.41843 13.36227 0 18.85363 13.968 0 19.66594 13.97455 0 20.07888 13.12326 0 19.57175 12.4924 0 11.04801 12.44373 0 10.20959 12.621 0 9.936383 13.29203 0 10.20492 13.84115 0 10.77109 14.06571 0 11.33115 13.82068 0 11.58752 13.20105 0 3.8 9.465554 22.98101 3.8 7.952179 22.76855 3.8 7.041274 21.54842 3.8 7.131695 20.19568 3.8 8.359654 19.01934 3.8 10.03599 19.2482 3.8 10.82196 20.13016 3.8 11.01222 21.30737 3.8 10.48682 22.3656 3.8 8.779013 11.02268 3.8 7.557557 10.43441 3.799999 6.923889 8.856402 3.799999 7.893684 7.267487 3.8 9.215018 6.993158 3.8 10.46116 7.552744 3.8 11.03524 8.963041 3.8 10.4008 10.54078 26.2 6.919697 22.46237 26.2 6.478525 21.05301 26.2 6.867928 19.61423 26.2 8.417405 18.49705 26.2 10.29475 18.81025 26.2 11.38319 20.10923 26.2 11.41396 21.80365 26.2 10.19601 23.2752 26.2 8.300278 23.44514 26.2 6.43109 9.042946 26.2 7.132812 7.273712 26.2 8.631905 6.48339 26.2 10.29477 6.810256 26.2 11.38319 8.109227 26.2 11.41398 9.803643 26.2 10.37353 11.14125 26.2 8.946689 11.52223 26.2 7.335277 10.95735 17.88566 12.06144 0 12.04201 12.1641 0 6.928927 12.29855 -5.25415e-5 11.50089 17.05866 -3.82185e-4 22.57794 4.64487 -5.4121e-5 19.32081 1.412883 -4.63724e-5 6.593672 6.64224 -6.44922e-5 11.36269 1.076919 -5.10812e-5 8.445631 3.157408 -4.48704e-4 11.83668 5.997285 0 14.04069 0.3342067 -1.6135e-4 16.30174 0.2503326 0.05710399 21.28105 2.980921 1.14441e-5 17.94458 6.17403 0 23.62583 7.159073 0.02813339 23.57922 11.04057 0.04043388 21.19638 15.26155 0.0260725 22.66049 13.20214 -6.12736e-5 18.24748 17.08269 -6.12736e-5 8.512092 14.8411 -1.25527e-4 10.54076 31.60073 3.800001 11.36014 32.10955 3.8 10.62573 31.07166 3.800001 9.261734 30.47078 3.800001 8.963065 30.96631 3.800001 7.614227 30.86792 3.8 7.693176 31.4411 3.800002 6.581928 32.21192 3.800001 6.956539 32.77372 3.800001 6.572778 33.68864 3.800002 7.386284 34.24028 3.800002 7.366455 34.95038 3.800003 8.523133 34.97891 3.800001 9.175152 35.56483 3.800001 10.03256 34.77871 3.800001 10.87846 34.71562 3.800001 11.01684 33.40028 3.800001 11.49509 33.37372 3.800001 17.47627 33.58173 3.800002 17.0783 32.87941 3.800001 17.29158 31.89711 3.799999 16.24932 31.39467 3.799999 16.27634 30.82463 3.8 14.79144 30.95535 3.800001 14.83038 30.46294 3.8 13.4567 31.00507 3.8 13.44835 31.6844 3.8 12.58193 32.21191 3.800002 12.96579 32.95137 3.800001 12.53465 33.462 3.800001 13.38629 34.24028 3.800003 13.06043 34.64619 3.800001 14.52315 34.97891 3.800002 14.73929 35.55756 3.800001 16.19301 34.70688 3.800001 16.56165 35.00839 3.800001 20.61969 31.00184 3.800001 20.62598 30.50586 3.8 19.27374 31.13278 3.8 19.44833 31.68442 3.800001 18.54553 32.41759 3.800001 18.93947 33.29795 3.800001 18.62307 33.90609 3.800002 19.89136 34.70701 3.800001 19.54369 35.06076 3.8 21.17515 35.56484 3.800001 21.20937 35.02478 3.800001 22.69323 34.21197 3.8 22.70703 34.8584 3.800001 23.47627 33.58171 3.800001 22.98101 32.53599 3.800001 23.36014 32.10958 3.800002 22.12272 31.27834 3.800002 22.29071 30.77834 3.8 17.03106 33.12404 5.199999 16.6577 31.82075 5.199998 15.38129 30.9804 5.199998 13.89136 31.29453 5.2 12.99763 32.53409 5.199998 13.32675 34.19556 5.2 14.96695 35.08235 5.199999 16.50275 34.37265 5.200003 11.01778 32.95752 5.199999 10.65768 31.82074 5.2 9.712159 31.11236 5.199998 8.523118 31.02264 5.199999 7.267479 31.89369 5.199999 7.056202 33.74625 5.199999 8.287415 34.90672 5.2 9.467438 34.96415 5.200001 10.63237 34.25082 5.199998 22.8881 32.28775 5.2 22.16989 31.33592 5.199998 20.68643 30.9688 5.2 19.38626 31.76132 5.2 18.95654 33.22781 5.199999 19.69312 34.56042 5.2 21.3192 35.05801 5.199999 22.91915 33.80756 5.199999 16.29069 30.77833 6 16.19992 35.24344 6.000002 12.53038 33.71217 6.000001 14.18442 30.56358 6.000001 13.5437 35.06077 6.000002 14.73327 35.50944 6.000001 17.44447 33.7943 6.000001 12.75003 31.81461 6.000003 17.36011 32.10946 6 3.8 7.292877 22.83685 3.8 8.419831 23.47627 3.8 10.31154 23.21064 3.8 11.45014 21.68556 3.8 11.39661 20.20974 3.8 10.38463 18.83435 3.8 8.510155 18.50427 3.8 7.395813 19.07269 3.8 6.618359 20.10922 3.8 6.587562 21.80362 3.8 11.50474 8.855622 3.799999 11.02706 7.419086 3.8 9.583987 6.545529 3.8 8.31289 6.57279 3.8 7.051201 7.366425 3.8 6.457694 8.95379 3.799999 7.115857 10.74706 3.8 8.405579 11.43648 3.8 9.701226 11.44515 3.8 11.2232 10.29073 16.08966 35.29904 24 15.16109 30.48312 24 14.8557 35.50473 24 13.61424 35.13364 24.00001 12.6794 33.9904 24 16.74706 31.11585 24 17.29158 34.1044 23.99999 12.50427 32.51015 24 13.5255 30.89579 24 17.49509 32.62786 24 27 9.054865 23.52223 27 7.628082 23.14129 27 6.503185 21.60595 27 6.803169 19.71941 27 8.095444 18.62308 27 9.584023 18.54554 27 10.70697 19.14166 27 11.47345 20.40394 27 11.29907 22.08962 27 10.27808 23.17554 27 8.009705 11.34247 27 6.758089 10.1999 27 6.492106 8.733283 27 7.051193 7.366432 27 8.510167 6.504266 27 10.18694 6.750021 27 11.22858 7.816154 27 11.53077 9.2617 27 10.92986 10.62578 27 9.701241 11.44514 6.42404 11.47881 0.2049589 7.613267 13.99343 0.2160646 12.38154 17.55109 0.2007522 9.559539 16.07903 0.1985559 15.3784 17.90847 0.2113971 17.60616 17.51064 0.2000465 19.87337 16.48 0.2001152 22.83166 13.26258 0.1944351 23.93979 8.840793 0.2020568 22.67921 4.449137 0.2000522 20.7277 2.153606 0.2082824 18.3243 0.7279549 0.2195425 14.21605 0.1184622 0.1829581 11.18979 0.9193548 0.2060203 8.535511 2.822274 0.1916303 6.849318 5.387055 0.2063484 6.089956 8.242409 0.1950645 11.54342 32.63181 3 10.56165 30.99312 3 8.95379 30.4577 3 7.190964 31.17526 3 6.434453 33.15273 3 7.273712 34.86874 2.999999 8.625946 35.49569 3 9.890229 35.36131 3 11.07211 34.47583 2.999999 17.54343 32.63182 3 16.70693 31.1431 2.999999 15.17515 30.43671 3 13.36642 31.05119 3 12.50426 32.51016 3 12.83435 34.38464 3 14.20972 35.39661 3.000001 15.68555 35.45015 3 17.0721 34.47583 3 23.52836 33.27791 3 23.30083 32.00232 3 22.56167 30.99314 3.000001 20.73927 30.444 3 19.06043 31.35535 3.000002 18.45725 32.93902 3 19.09938 34.73073 3 20.83038 35.53861 3 22.64775 34.97311 3 12.44568 32.71696 5.199999 13.07263 31.39581 5.200003 14.10921 30.61837 5.199999 15.58427 30.54655 5.199999 17.04049 31.43824 5.200002 17.52223 33.05487 5.199999 17.0721 34.4758 5.199997 16.09509 35.2572 5.200003 14.60804 35.54074 5.199999 12.98288 34.55016 5.200001 6.598343 35.32402 3.160294 6.881756 35.41988 3.017579 7.694607 35.81151 3.01191 7.74868 35.97624 3.212341 7.131287 35.75386 3.189651 22.42627 35.94533 3.150131 23.20697 35.25261 3.007048 23.31583 35.42696 3.150955 22.51633 35.75707 3.013025 8.931485 30.49359 5.199999 10.19989 30.75808 5.2 11.09897 31.62779 5.199998 11.53883 32.84668 5.199999 11.0721 34.47584 5.199999 9.890259 35.36131 5.2 8.184388 35.43796 5.2 6.87999 34.3683 5.199998 6.459967 32.93778 5.200091 6.829071 31.74463 5.199996 7.719391 30.80319 5.2 21.38425 30.48647 5.199999 22.87849 31.28594 5.2 23.49509 32.62783 5.199999 23.36014 33.892 5.199998 22.46237 35.08189 5.200002 21.05302 35.52302 5.199999 19.61424 35.13361 5.2 18.59008 33.8083 5.199923 18.60274 32.13317 5.199911 19.71939 30.80318 5.199999 18.45 31.50078 21.2 18.97756 31.4928 21.2 3 9.595948 23.43649 3 8.300293 23.44515 3 6.778341 22.2907 3 6.505848 20.62599 3 7.005051 19.45673 3 8.01117 18.67938 3 9.712182 18.53038 3 11.19837 19.71939 3 11.51843 21.16105 3 10.88567 22.74709 3 9.373719 11.49509 3 8.109543 11.36014 3 6.919689 10.46236 3 6.462937 8.830387 3 7.005066 7.456726 3 8.211907 6.581924 3 9.688675 6.572789 3 10.95036 7.366447 3 11.56484 9.175136 3 10.71564 10.87846 7.786041 35.97985 26.78604 7.709168 35.83433 26.9769 6.61924 35.34641 26.84786 7.14592 35.76467 26.79472 23.33537 35.37339 26.90147 22.56895 35.71352 26.99762 22.29459 35.96166 26.83856 22.94742 35.69298 26.8626 26.98095 29.92629 6.000001 26.86558 30.34259 12 27 29.84132 12 26.98095 29.92629 24 27 29.84132 18 26.85821 30.37008 18 25.4377 32.12395 3.060986 26.57174 5.500775 18 27 6.160235 18 26.57174 5.500775 24 27 6.160235 24 27 12.00078 24 27 12.00078 18 26.57174 5.500775 6.000001 27 6.160235 6.000001 26.57174 5.500775 12 27 6.160235 12 27 12.00078 12 27 12.00078 6.000001 24.7 8.440354 16.95611 24.7 9.895598 13.1489 24.7 8.202408 13.10529 24.7 7.457451 16.30057 24.7 10.1203 16.75522 24.7 6.976772 15.20936 24.7 10.90671 14.28737 24.7 10.96415 15.46739 24.7 7.218544 14.05292 26.2 23.70078 18 26.2 23.70078 24 26.2 22.00078 18 26.2 12.30078 24 26.2 12.30078 18 22.36479 0.05023193 26.84581 22.28172 0.2333679 26.99332 23.28699 0.5354676 26.83815 23.29921 0.5495873 3.156712 23.11601 0.6261821 3.009716 22.30854 0.2473545 3.004819 22.36647 0.05174827 3.149365 13.29313 0.2397108 3.000343 16.14298 0.1541881 3.027975 19.71109 1.349764 2.999998 22.40017 3.999111 3.000004 23.64376 6.750176 2.999998 23.90232 9.727979 2.999993 23.13904 12.67996 2.999999 21.44847 15.18114 2.999995 19.02115 16.97631 2.999998 16.13454 17.86038 3 13.11822 17.73226 2.999999 10.31695 16.60657 2.999999 8.050642 14.612 2.999999 6.304803 11.26484 3 6.196531 7.491283 2.999999 7.555746 3.969334 3.000001 10.31693 1.394976 2.999999 7.770114 0.02578735 26.79841 7.147633 0.2499812 26.85361 6.614468 0.6482778 26.81757 7.738377 0.1792526 26.97955 7.648861 0.05474376 3.131938 7.046406 0.4283104 3.004494 6.722746 0.5298505 3.153679 4.643987 3.90351 3.022284 3.019055 29.92628 6 6.758313 35.53181 5.999996 23.14945 35.63521 5.999997 6.441095 32.84488 6.000039 7.273712 31.13281 6.000005 8.625977 30.50586 6.000002 10.08965 30.70248 6 11.05652 31.56502 6.000005 11.52835 32.7236 6.000001 11.04045 34.56335 6.000001 9.584229 35.455 6.000001 8.313141 35.42827 6.000001 7.060455 34.64624 6.000007 18.83434 31.61691 6 20.20972 30.60495 6 21.47855 30.52377 6 22.62575 31.07168 6 23.52106 32.50139 6 23.2283 34.18368 6.000004 22.19995 35.24344 6.000001 20.93147 35.50796 6.000001 19.71944 35.1984 6.000002 18.51922 33.68942 5.999989 3.019055 29.92628 24 3.134418 30.34259 18 3 29.84132 18 9.687531 30.56362 21.2 3 29.84132 12 3.141792 30.37009 12 17.47627 33.5817 24.8 17.36013 32.1095 24.80001 16.46231 30.91967 24.8 14.83037 30.46294 24.8 13.09938 31.27083 24.8 12.44568 33.28459 24.8 13.21652 34.78503 24.80001 14.73929 35.55755 24.8 16.56165 35.00845 24.80002 11.52223 33.05486 24 11.29157 31.89712 24.80001 11.2283 31.81789 24 10.36847 30.88136 24 9.896576 30.59219 24.8 8.739293 30.44399 24 7.994644 30.66441 24.8 7.060486 31.35526 24 7.024963 31.4549 24.80003 6.434452 32.84881 24.8 6.457249 32.93902 24 6.880028 34.36836 24.00001 7.060455 34.64624 24.80002 7.994598 35.33711 24 8.524636 35.49945 24.8 9.478516 35.47778 24 10.19992 35.24344 24.8 10.95734 34.66629 23.99999 11.44448 33.79426 24.8 23.52223 32.94668 24.8 23.54342 32.63181 24 22.95736 31.33529 24.8 22.70699 31.14317 24 21.17515 30.43671 24 21.26172 30.47078 24.8 19.81625 30.77298 24.8 19.54376 30.94067 23.99999 18.75002 31.81459 24.79999 18.62306 32.09546 24.00001 18.49145 33.26858 24.8 18.63163 33.99873 24.00001 19.06046 34.64625 24.79999 19.81619 35.22859 24 20.73929 35.55756 24.8 21.05302 35.52302 24 22.46234 35.08188 24.00001 22.36847 35.12018 24.80002 23.22833 34.18362 24.8 23.26959 34.06836 24 3.428258 5.500775 24 3 6.160235 24 3.428258 5.500775 18 3 6.160235 18 3 12.00078 18 3 12.00078 24 3.428258 5.500775 12 3 6.160235 12 3.428258 5.500775 6.000001 3 6.160235 6.000001 3 12.00078 12 3 12.00078 6.000001 5.299999 8.207886 16.87396 5.3 9.467354 13.03642 5.299999 8.105957 13.14889 5.299999 7.094849 14.28737 5.299999 9.38443 16.98145 5.299999 11.05653 15.03436 5.299999 10.49517 13.61898 5.299999 10.444 16.43439 5.299999 7.11337 15.81547 3.8 12.30078 18 3.8 12.30078 24 3.8 22.00078 18 3.8 23.70078 24 3.8 23.70078 18 10.63237 31.75071 24.8 8.966974 30.91919 24.8 7.448334 31.68445 24.79999 6.993155 32.78653 24.8 7.200005 33.9497 24.8 8.19571 34.86986 24.79999 9.382843 34.98238 24.8 10.43442 34.44398 24.79999 11.02268 33.22249 24.8 16.91916 32.194 24.8 15.64285 31.07019 24.79999 14.4505 31.05877 24.8 13.32676 31.806 24.8 12.9867 33.29586 24.8 13.61896 34.49515 24.8 15.03434 35.05652 24.8 16.69322 34.212 24.8 21.14013 30.94952 24.8 19.69321 31.44109 24.8 18.95654 32.77373 24.8 19.38624 34.2402 24.79998 20.68645 35.03276 24.79999 22.16992 34.66562 24.8 22.88811 33.7138 24.80001 22.98102 32.53601 24.8 22.36555 31.51464 24.79998 6.636341 35.40026 24.00001 23.12401 35.64931 23.99999 25.30107 3.907418 3.00904 25.48838 3.858725 3.186638 27 24.00078 24 27 24.00078 18 23.55 30.50078 8.800003 27 24.00078 12 27 24.00078 6.000001 4.504457 3.85205 3.233356 3 24.00078 6.000001 3 24.00078 12 6.449999 30.50078 8.800003 3 24.00078 18 3 24.00078 24 10.92031 32.26616 26.2 9.717225 31.07389 26.20001 8.02742 31.18932 26.2 6.939471 32.7036 26.2 7.448349 34.31712 26.19998 8.450592 34.94279 26.20001 9.815476 34.88818 26.2 10.87396 33.79364 26.20001 17.03106 33.12405 26.2 16.4642 31.52084 26.20001 15.04245 30.98298 26.2 13.89139 31.29446 26.20001 13.06553 32.36969 26.2 13.21014 34.06402 26.19999 14.96695 35.08235 26.2 16.50275 34.37265 26.20002 23.0279 33.47163 26.2 22.6577 31.82076 26.20001 21.38128 30.9804 26.2 19.73529 31.37973 26.20001 19.03642 32.53422 26.2 19.14891 33.89561 26.19999 20.44875 34.98153 26.2 21.95993 34.79494 26.20002 11.32062 32.01119 26.2 6.504909 33.37372 26.2 7.252945 34.88567 26.19999 8.64383 35.48348 26.2 9.890809 35.38319 26.20001 11.05936 34.45798 26.19999 11.50855 33.26858 26.2 9.144288 30.4968 26.2 10.38577 30.86794 26.20001 6.708412 31.89714 26.19999 7.910355 30.7025 26.20001 17.24997 31.8146 26.19999 16.18381 30.77295 26.2 14.73827 30.47079 26.20001 13.37427 31.07166 26.20001 12.55486 32.30028 26.20001 13.12151 34.71562 26.19997 14.41576 35.45502 26.20001 16.09761 35.32464 26.2 17.46962 33.71218 26.20001 12.56351 33.59591 26.19999 23.24997 31.81459 26.19998 18.72479 34.19598 26.2 23.50855 33.26861 26.2 22.80905 34.82625 26.2 21.26671 35.50944 26.2 20.00943 35.32098 26.2 22.18385 30.77298 26.2 20.73827 30.47078 26.2 18.50441 32.75029 26.2 19.04268 31.33525 26.2 4.663486 3.900454 26.98461 15.1436 5.077661 28.8 15.4766 5.526242 28.8 17.00109 2.623066 28.8 16.8785 1.28595 28.79999 16.30685 1.441101 28.80002 15.77061 0.6139641 28.79999 15.03696 0.9663097 28.8 14.31094 0.5248261 28.8 13.60234 1.492844 28.79999 16.73254 4.107841 28.8 16.92839 4.627396 28.79999 17.56919 3.066923 28.8 12.81026 1.706772 28.8 12.94465 3.05371 28.8 12.49704 3.584143 28.8 13.56558 4.443985 28.79999 13.61421 5.133614 28.79998 17.54342 3.369751 30 16.56165 5.008415 30 15.16109 5.518435 30 13.7194 5.198376 30 12.53038 3.712177 30 12.75003 1.814606 30 13.81619 0.772953 30 15.05301 0.4785243 30 16.27638 0.8246765 30 17.17557 1.72348 30 18.97731 9.222477 28.8 18.58192 9.789635 28.8 19.68179 10.57863 28.8 19.45673 10.99648 28.80004 23.04429 9.127192 28.79999 23.52836 9.277955 28.8 23.2283 7.817932 28.8 22.55166 7.684425 28.79999 22.19991 6.758095 28.8 21.03305 6.919192 28.8 20.93144 6.493585 28.8 19.71942 6.803169 28.79999 18.62306 8.09549 28.79999 19.36761 7.75074 28.8 21.1357 11.03105 28.8 22.38104 10.49515 28.8 22.79302 10.80479 28.79999 21.04293 11.57046 28.8 23.53883 9.154883 30 22.87848 10.71564 30 21.38423 11.51508 30 19.52546 11.10573 30 18.50427 9.491394 30 18.62277 8.201081 30 19.27371 7.132797 30 20.62598 6.505847 30 22.0896 6.702481 30 23.17552 7.723434 30 11.01226 9.293614 28.8 11.4768 9.480362 28.8 11.34247 8.009701 28.79999 10.7518 7.965595 28.79999 10.1999 6.75809 28.79999 9.551251 7.020017 28.8 8.31095 6.524826 28.8 8.20752 7.144627 28.79999 7.286983 7.902618 28.8 6.810261 7.706787 28.8 6.977318 9.222525 28.8 6.483388 9.36964 28.8 7.457269 10.30205 28.8 7.025006 10.54677 28.80005 7.99461 11.33714 28.8 8.790555 11.07206 28.8 9.685547 11.45015 28.8 10.38103 10.49514 28.79997 10.92838 10.62744 28.79999 11.49509 9.373726 30 10.87847 10.71564 30 9.384232 11.51508 30 7.912735 11.27727 30 6.810266 10.29478 30 6.483386 8.631924 30 7.273697 7.132812 30 8.625985 6.505846 30 9.890238 6.64026 30.00001 11.21067 7.690027 30 17.21066 16.31153 28.8 16.98837 15.6282 28.79999 14.62598 17.49571 28.8 15.49255 17.02352 28.8 15.89026 17.36127 28.8 17.50202 14.82585 28.8 15.99062 12.6806 28.79999 15.8698 13.17957 28.79999 17.14127 13.62804 28.79999 16.75181 13.9656 28.79998 14.69262 12.98932 28.8 14.73326 12.4921 28.8 13.19095 13.17526 28.8 13.63443 13.51468 28.79997 12.92169 14.87942 28.79999 12.43446 15.15275 28.8 13.68179 16.57862 28.8 13.27373 16.86876 28.79998 17.39615 15.79005 30 16.70697 16.85846 30.00003 15.38422 17.51509 30 13.71938 17.19837 30 12.62307 15.9061 30.00001 12.54553 14.41758 30.00001 13.41911 12.97447 29.99998 15.26169 12.47077 30 16.6258 13.0717 29.99998 17.44514 14.3003 30 14.68297 0.02368623 30.00013 15.09376 0.0802564 27 18.39227 0.7334327 30.00012 20.99976 2.388 29.99995 22.86002 4.764465 29.99998 23.96088 8.442776 30.00004 23.37291 12.10236 30 21.86151 14.71454 29.99994 19.56598 16.67395 29.99997 16.74893 17.75674 30 13.73209 17.83923 30 10.1282 16.5458 29.99998 7.527533 13.88831 29.99996 6.117483 10.32847 30 6.394192 6.620483 30.00001 8.134881 3.210114 30.00003 11.10106 0.9680846 30 17.0125 14.87492 27 16.61373 13.76131 27 15.63221 13.0841 27 14.4516 13.04127 27 13.12643 14.09314 27 13.12602 15.79363 27 13.90517 16.69626 27 15.38436 17.04683 27 16.75182 16.03594 27 10.951 8.404526 27 10.10861 7.294495 26.99998 8.618725 6.980401 27 7.342308 7.820747 27 6.982218 8.957509 27 7.286974 10.09894 27 8.515244 10.99884 27 10.02448 10.75887 27 10.91047 9.710503 27 22.90261 8.300873 27 22.23459 7.40419 27 21.1357 6.970505 27 19.83012 7.335899 27.00001 18.98316 8.601254 27 19.45923 10.40082 27 21.03696 11.03524 27 22.16504 10.64882 26.99999 22.95633 9.61773 27 17.01225 2.70787 27 16.38103 1.506401 27 14.96564 0.9450266 27 13.5656 1.557564 27.00001 12.9217 3.122138 27 13.8773 4.723222 27.00001 15.55126 4.981534 27 16.75182 4.035934 27 18.55485 9.701226 27 19.53763 11.08185 26.99998 20.71908 11.49312 27 22.00537 11.33714 27.00001 22.97498 10.54675 26.99998 23.51657 9.36606 27.00002 23.09156 7.507286 27 21.26072 6.443988 27 19.43834 6.993149 27 18.60383 8.211533 27 7.537655 11.08187 26.99999 9.391964 11.54075 27 10.85837 10.70697 27.00001 11.5589 9.156685 27.00004 10.93955 7.355318 27.00001 9.475337 6.502087 27.00001 8.009385 6.680592 27 6.724796 7.805546 27.00001 6.554852 9.701238 27.00001 22.85111 9.8956 24 18.99998 8.422844 24 21.8273 7.090368 24 22.93445 8.369668 24 21.71262 10.90671 24 20.18454 10.88818 24 19.21736 9.947068 24 20.1283 7.16214 24 18.96527 8.705616 26.2 19.8773 7.278328 26.19999 21.72462 7.049104 26.20001 22.90154 8.27652 26.2 22.93446 9.631897 26.20001 21.82729 10.91119 26.2 20.28785 10.8892 26.20001 19.34231 10.18081 26.2 23.49815 9.483948 26.20002 22.92731 10.60583 26.19993 21.89079 11.38319 26.2 20.19635 11.41397 26.2 19.00366 10.54324 26.2 18.50491 9.373719 26.2 18.78934 7.690018 26.2 20.52341 6.475306 26.2 22.38577 6.867928 26.2 23.32062 8.011185 26.20001 11.0811 9.05612 24 10.17962 10.68475 24 7.244795 10.1203 24 8.69261 11.01222 24 7.681816 7.422916 23.99999 9.313557 6.968791 24 7.018555 8.617119 24 10.48668 7.635826 23.99999 6.968938 8.87749 26.2 7.497223 7.628891 26.20001 8.85989 6.949519 26.2 10.30684 7.441104 26.2 11.04345 8.773725 26.2 10.61375 10.24023 26.20001 9.476861 10.97891 26.2 8.128346 10.83943 26.2 7.259563 10.02264 26.2 10.08722 11.27727 26.19999 8.838952 11.51843 26.2 7.631538 11.12019 26.20001 6.771678 10.18363 26.20001 6.47777 8.946685 26.20001 6.927895 7.525726 26.20001 8.5234 6.47531 26.2 10.18381 6.772964 26.20001 11.24997 7.814602 26.2 11.50806 9.03676 26.20006 11.18974 10.29478 26.2 22.73045 31.99701 10.56305 22.78842 32.034 8.800264 21.38514 32.00078 8.800003 8.614861 32.00078 8.800003 7.267949 32.00078 8.800003 7.30056 31.99689 10.51912 22.76136 32.01206 6.000002 19.20868 32.02183 6 22.79132 32.02183 7.8 19.26795 32.00078 7.8 21.38514 32.00078 21.2 22.75739 32.00571 21.2 22.72302 31.99631 19.40189 22.76136 32.01206 22.2 19.20868 32.02183 22.2 22.79132 32.02183 24 19.10659 32.15955 24 10.76137 32.01206 5.999999 7.250519 32.00447 6.000001 10.79132 32.02183 7.8 7.182821 32.05828 7.8 7.277375 31.99607 19.4574 7.267949 32.00078 21.2 8.614861 32.00078 21.2 10.89342 32.15955 22.2 7.250519 32.00447 22.2 10.79132 32.02183 24 7.238628 32.01206 24 6.449999 30.40078 22.2 3 30.40078 24 17.56229 32.00077 9.043201 12.45692 32.00078 8.953798 16.86796 32.00077 7.273697 15.27717 32.00078 11.52835 13.62726 32.00077 11.14126 16.80402 32.00078 10.79301 15.15196 32.00077 6.434452 13.17452 32.00075 7.190918 12.77779 32.00075 10.16293 12.50131 32.00077 20.52467 17.48396 32.00077 20.43157 16.62659 32.00078 22.92841 12.61319 32.00078 21.77059 17.36051 32.00077 21.89029 16.54938 32.00078 18.98286 13.28515 32.00078 22.87848 15.06614 32.00078 23.56919 15.38647 32.00077 18.52183 14.09467 32.00077 18.62308 13.09241 32.00084 19.37158 14.23901 67.40445 20.916 29.299 67.2605 20.95198 29.31282 67.70624 20.677 14.2417 67.96846 20.28967 29.28328 67.96535 20.23142 29.71352 67.68244 20.23883 29.80463 67.28676 20.56873 29.9692 67.25888 20.17734 9.023535 67.25566 15.52607 9.331376 67.32314 16.88123 9.868958 67.32054 18.08087 10.77173 67.24324 19.23706 11.84875 67.21743 20.104 13.8092 67.97946 9.811463 11.90405 67.97136 10.65137 10.07916 67.97856 12.82544 12.05225 67.98299 19.43433 13.10413 67.39951 20.64783 12.60254 67.75055 20.1853 11.61865 67.72711 19.61572 10.68018 67.81287 18.62036 9.961243 67.96276 16.96533 9.34515 67.80937 15.1084 9.095529 67.31407 14.07016 9.345978 67.41526 13.1582 9.671908 67.31406 12.29103 10.46754 67.30768 11.07995 10.73425 67.73559 11.21497 11.54523 67.39944 10.14664 12.76482 67.25958 9.43282 12.78284 67.70215 9.706543 14.3088 67.18672 9.042177 14.3464 67.65976 9.256165 29.18205 41.33435 21.01885 29.64343 41.34195 20.80988 29.97309 40.44046 20.39597 29.13168 67.65039 9.233399 29.22822 67.22029 9.03093 29.25249 37.10486 23.46265 29.24036 38.40466 22.15955 29.28655 39.86047 21.35931 29.76732 39.77283 21.04511 29.71246 37.84009 22.23108 29.95578 37.38122 22.11023 29.78701 36.56641 23.68945 29.41543 36.11499 25.19409 29.97732 35.42639 25.08447 29.30872 67.95015 9.686066 29.77577 67.6119 9.69394 29.9809 67.11083 9.722306 29.57202 67.3219 9.205079 29.97649 33.99322 26.1167 29.77078 33.17999 26.64246 29.31941 33.33835 26.94171 29.60245 34.35644 26.51929 29.16692 34.45587 26.66238 29.77744 35.33935 25.68115 29.26476 35.5238 25.95044 29.25391 41.35145 8.991501 29.75249 41.31915 9.293457 29.99365 25.0094 26.04773 29.84827 25.36591 26.51709 29.33456 25.23859 26.91822 29.35704 39.8338 8.645127 29.27783 38.32275 7.777832 29.30329 37.11713 6.560303 29.32219 36.0448 4.634521 29.75957 37.15332 7.133789 29.7262 35.92187 4.924805 29.98114 37.03186 7.692749 29.76431 38.9281 8.561951 29.9595 40.27856 9.498047 29.96542 22.90772 24.41144 29.98787 22.81226 23.68402 29.86777 23.84827 25.81982 29.76247 22.43407 24.06282 29.38924 23.93359 26.38315 29.3881 22.94653 25.5282 29.33878 22.05413 23.4296 29.24256 22.31369 24.53482 29.9844 33.85571 3.887634 29.97524 35.26257 4.757812 29.70715 35.13104 4.030334 29.24258 35.01776 3.653503 29.81824 33.5383 3.455231 29.33843 34.15527 3.261688 29.33323 33.33241 3.05732 29.99352 23.12457 5.367157 29.88821 22.58497 6.121887 29.38023 22.05962 6.581604 29.96815 25.28418 3.721832 29.72533 23.14876 4.588684 29.74194 24.11591 3.801331 29.38809 22.36154 5.426361 29.64223 25.28343 3.273788 29.2428 23.90802 3.59845 29.27783 25.25294 3.070789 29.19078 22.97571 4.382782 23.76141 36.47984 6.005026 24.54329 36.78007 6.007778 25.61035 37.54785 7.063232 24.60017 36.97913 6.870262 25.82752 38.10612 8.495499 25.42627 37.69214 7.600464 26.40625 38.26245 7.736938 26.47108 38.79085 8.675911 27.39144 39.2489 8.373604 26.27025 38.50467 9.019822 26.93409 39.26761 8.578289 26.625 39.10693 9.475251 27.14794 40.20239 8.996582 26.75669 39.68268 9.607911 26.9354 41.2984 10.13049 26.96857 41.08062 9.62822 27.35211 41.64093 9.167359 27.70682 41.18654 8.989144 26.90443 63.99501 9.810906 27.49217 64.55092 9.075394 24.38635 36.8294 23.53261 24.37525 36.75785 23.99894 25.64795 37.86182 21.52039 26.32106 38.60073 21.42957 25.92407 37.67773 22.8125 24.84542 37.16889 22.71064 26.00537 38.21899 21.96387 25.18665 37.20959 23.31445 26.72693 39.49193 20.40701 26.78594 39.43812 21.03157 27.41348 39.75873 21.3909 26.38638 38.64409 20.84982 26.52197 38.35913 22.1803 27.01782 39.04956 21.71973 27.65079 41.1506 21.01285 27.15765 41.08145 20.70418 26.9167 40.81415 19.90769 26.97359 41.48249 20.3395 26.9181 63.99454 20.02938 27.0882 64.15143 20.54608 27.57319 64.64389 20.95 14.50035 64.37314 20.79034 14.26984 64.8419 20.96069 14.08484 64.05008 20.29462 13.17993 64.50921 20.63695 12.28176 64.68769 20.32345 11.01428 64.70503 19.4764 10.14514 64.67748 18.47797 9.417267 64.77002 17.20429 9.025136 64.67487 15.41391 9.123681 64.58793 14.08154 9.441681 64.71699 12.73553 10.47046 64.61319 11.10852 11.43555 64.5273 10.24951 12.60767 64.76619 9.495881 14.24866 64.59627 9.082505 12.8418 64.38269 9.604249 9.767151 64.25559 17.29663 11.61719 64.34071 19.67651 9.932862 64.19575 12.4928 9.447019 64.13011 15.18117 10.77637 64.14633 18.61963 12.5625 64.01959 19.75977 13.979 64.03176 9.724305 12.40186 64.03348 10.33447 11.09424 64.0344 11.36035 10.01709 64.00515 13.33044 10.44769 64.01191 17.6875 0.02398997 35.25017 6.294739 0.03020286 34.67744 4.970764 0.02323937 32.86094 3.797897 0.2436447 33.46161 3.61496 0.3297081 35.70815 6.256958 0.4703617 34.4129 3.916748 0.3736696 32.52763 3.223209 0.3849335 35.22024 4.965149 0.6879578 34.9787 4.35675 0.7689304 35.97448 6.574554 0.762085 35.67184 5.424316 0.7355995 33.50461 3.304069 0.8080397 32.42464 3.030445 0.6932182 25.49434 3.053652 0.2877426 25.29859 3.327423 0.01061677 25.06068 3.850445 0.7749062 35.97151 23.4325 0.01068627 22.99478 5.770569 0.122796 23.76782 4.232697 0.1095504 22.61995 5.959503 0.5846825 22.97214 4.451721 0.5852083 22.07174 6.576782 0.6855812 24.4234 3.344727 0.6613999 23.64356 3.812866 0.6607246 22.317 5.50293 0.03592491 32.66582 26.31555 0.030447 34.59875 25.09094 0.01944279 35.2288 23.68948 0.2769165 34.44824 25.81323 0.377121 33.5152 26.50751 0.5047455 35.3241 25.08972 0.3209114 35.69526 23.78 0.6152191 32.43344 26.93713 0.7576294 34.58935 26.04138 0.7503357 35.67956 24.54712 0.8320618 33.52417 26.70209 0.772789 22.03889 23.49217 0.3616461 22.25275 23.68904 0.01130449 22.82085 23.92823 0.6806336 25.52274 26.94416 0.0168209 25.20473 26.18417 0.1576271 22.99106 24.98186 0.1575469 24.1911 26.09798 0.3180237 25.21936 26.69397 0.5796051 23.50797 26.06343 0.7574387 22.33423 24.58151 0.7574271 22.95924 25.58832 0.7574387 24.46594 26.68704 23.78114 36.40714 23.21265 22.98716 36.13167 23.99938 22.77248 36.0449 23.19873 22.84527 36.02726 22.20033 24.34155 36.4588 21.07904 25.02721 37.03404 21.41755 23.54531 36.16033 21.19761 23.5527 36.22887 22.201 22.80791 36.0138 21.1996 24 36.01715 18.91602 25.67639 36.5424 18.70874 25.68062 36.51425 11.43182 24.3904 36.51 8.772217 26.29105 37.35795 19.57416 27.84021 38.9191 14.27232 27.5005 37.89341 14.29732 27.73563 38.61375 16.34699 26.49651 37.27268 11.12163 27.41202 39.11677 11.61475 27.4148 39.09569 18.37744 27.18535 38.15396 11.68082 27.17969 38.15409 18.33948 26.77555 37.05265 16.85558 26.20211 36.50518 14.44443 25.50295 36.23021 17.07471 26.97352 37.16194 14.19078 25.05172 36.03945 13.72253 23.55475 36.22843 7.797422 22.80959 36.01501 8.805964 23.54965 36.1521 8.801334 22.77719 36.0256 7.799653 25.12961 37.11646 8.636017 22.4273 35.98677 6.002552 27 22.14764 5.666946 27 23.35333 3.986572 27 24.93593 3.082226 26.99996 36.06314 4.595032 27 34.24093 3.163555 27 22.10469 24.11813 27 23.20728 25.90648 27 24.96518 26.90899 26.99994 35.77527 25.8371 27 33.64136 26.95167 11.49322 35.99969 23.20804 16.66461 35.92624 23.77892 13.91345 35.9079 23.86317 3.000067 35.88048 24.00087 18.79028 35.99809 23.0636 3 35.3913 25.14319 3 34.30524 26.30768 3 32.74826 26.94886 3 25.2366 26.95655 3 23.5671 26.21379 3 22.14764 24.33305 3 24.9652 3.091009 3 23.43872 3.913788 3 22.16687 5.576172 3 33.36896 3.136543 3 35.3085 4.695618 3.000011 35.879 5.999474 13.95232 35.90323 6.103236 17.18619 35.94914 6.34729 20.38158 36.03702 7.784134 11.32812 36.00062 6.877289 27 36.80462 6.000001 27 36.80462 24 13.8743 65.80078 12.66256 14.69412 65.80078 12.94874 15.38041 65.80079 12.45501 13.29372 65.80075 13.89136 12.7804 65.80078 13.69809 12.97962 65.80078 15.38126 12.4114 65.80078 15.17304 12.96438 65.80089 16.57414 13.81999 65.80078 16.65771 14.40495 65.80078 17.55301 14.95674 65.80079 17.01778 16.31637 65.8008 13.44836 16.74914 65.80078 13.08394 16.99895 65.80078 14.61971 17.5033 65.80077 14.40406 17.43007 65.80078 15.9086 16.85614 65.80079 15.79251 16.09811 65.80081 16.71306 16.31987 65.80078 17.23354 14.84281 68.00077 12.4104 13.25085 68.00079 13.08397 12.4354 68.00077 14.60807 12.75843 68.00078 16.3062 13.89 68.00074 17.32154 15.37625 68.00078 17.56694 16.7403 68.00076 16.89554 17.52213 68.00078 15.60799 17.34427 68.00078 13.88861 16.30278 68.00073 12.78089 16.9595 64.00078 15.54842 27.61868 64.00078 17.65405 16.86911 64.00079 14.19572 15.90764 64.00079 16.87358 27.84655 64.00074 13.44348 15.94891 64.0008 13.2 14.04383 64.00078 16.82017 13.06943 64.00076 15.6429 13.058 64.0008 14.45052 13.68356 64.00077 13.44839 14.79475 64.00077 12.99232 23.24268 35.20077 16.19991 22.68398 35.20078 16.17963 23.01413 35.20077 14.87114 23.47595 35.20077 14.31092 22.40006 35.20077 13.45925 22.03404 35.2008 12.62955 20.77829 35.20077 12.97732 20.04616 35.20087 12.63857 19.29389 35.20076 13.80698 18.9798 35.20068 13.50708 18.46216 35.20077 14.83036 19.08959 35.20077 15.82729 19.08052 35.20074 16.70787 20.54026 35.20076 17.00448 20.70964 35.20074 17.52063 22.18283 35.20079 17.22833 21.69696 35.20078 16.88158 17.48014 35.20077 20.31942 16.72243 35.20077 19.87727 17.00694 35.20077 21.21339 17.15305 35.20077 22.40338 16.46039 35.20077 22.44728 15.58094 35.20078 23.47627 16.11854 35.20076 18.68613 15.29517 35.20077 18.96526 14.61351 35.20077 18.52184 13.81995 35.20079 19.34232 13.27003 35.20077 19.0994 13.04049 35.20077 20.45159 12.46216 35.20077 20.83039 13.18856 35.20077 21.97261 13.02768 35.20078 22.64775 14.30013 35.20077 22.90263 14.3313 35.20077 23.41735 15.28629 35.20076 22.99283 17.50006 35.20076 8.528935 17.24268 35.20075 10.19991 17.03446 35.20077 9.036986 16.55963 35.20077 10.30688 16.18288 35.20077 11.22832 16.50794 35.20077 7.60236 16.78428 35.20077 7.216492 15.68789 35.20076 6.572786 14.94707 35.20077 6.944648 14.00202 35.20077 6.63163 13.5568 35.20077 7.565559 12.77219 35.20078 7.816223 12.976 35.20077 8.790637 12.47 35.20077 9.261732 13.21777 35.20076 9.947083 13.19597 35.20075 10.79301 14.13745 35.20077 10.8562 14.72283 35.20077 11.52835 15.45248 35.20077 10.97854 7.505623 35.20077 16.38104 7.52494 35.20076 17.07209 8.707119 35.20077 17.01226 8.863839 35.20083 17.51221 6.639482 35.20077 15.89023 6.944249 35.20077 14.96565 6.505074 35.20077 14.62597 7.132034 35.20077 13.2737 7.667618 35.20078 13.4341 8.396431 35.20078 12.55209 9.123264 35.20076 12.96894 9.658585 35.20075 12.56442 10.37184 35.20077 13.49718 10.7627 35.20075 13.19705 11.42751 35.20078 14.31315 11.01145 35.20077 14.69262 11.36851 35.20072 15.98334 10.8212 35.20077 15.86978 10.17194 35.20069 17.24779 10.03523 35.20077 16.75178 15.72391 37.00074 23.89388 18.40491 37.00038 23.25845 18.45 37.00077 22.2 20.23163 37.00077 22.2 11.55 37.00077 21.2 9.768365 37.00077 22.2 12.37991 37.00046 23.56818 11.55 37.00077 22.2 20.23163 37.00077 7.8 18.3143 37.00038 6.717817 18.45 37.00077 7.8 15.79865 37.00079 6.107753 13.09407 37.00077 21.71264 16.74312 37.00076 22.13825 19.39388 37.00078 13.75072 14.94193 37.00076 11.06969 23.96417 37.00077 15.57452 12.9614 37.0008 6.310558 11.55 37.00077 7.8 9.750977 37.00226 7.722588 13.9648 37.00076 22.75181 7.001924 37.00077 14.51526 6.069054 37.00077 15.96163 7.241914 37.00077 16.02448 22.7431 37.00077 16.13828 18.45 37.00077 21.2 18.98587 37.00077 14.87114 10.18004 37.00075 13.34231 16.83864 37.00076 8.128319 9.699891 37.00077 16.90262 15.90765 37.00077 19.12643 6.54454 37.00077 12.12949 7.766052 37.00073 13.40291 8.876742 37.00077 12.96894 10.95951 37.00077 14.45159 21.50232 37.00077 8.83885 20.70482 37.00077 12.96527 23.36398 37.00077 11.87296 22.02184 37.00077 13.25955 13.44032 37.00077 10.30684 22.84256 37.00083 19.26947 21.38514 37.00077 21.2 16.99594 37.00077 9.299241 18.45 37.00077 8.800003 16.49437 37.00077 10.38106 16.9595 37.00077 20.45159 15.29288 37.00077 23.01226 14.20709 37.00077 19.12605 10.81144 37.00077 15.97259 20.30304 37.00076 16.88156 19.31604 37.00077 16.17963 12.94874 37.00077 8.859892 11.55 37.00077 8.800003 8.437285 37.00077 8.858872 13.62812 37.00077 7.497223 21.29287 37.00077 17.01227 22.92688 37.00077 14.28276 16.02185 37.00076 7.259557 14.87671 37.00077 6.968938 13.1126 37.00077 20.18453 7.291328 37.00077 19.50675 8.614861 37.00077 21.2 8.383065 37.00077 16.95632 3 22.00078 12 3 22.00078 18 0 29.52657 14.40746 1.2 29.44919 14.06337 0 28.43222 12.80388 1.2 27.91527 12.54324 0 26.51592 12.45134 1.2 25.97528 12.61692 0 24.86739 13.47668 1.2 24.83838 13.60513 1.2 24.43269 14.83681 0 24.44775 15.59501 1.2 24.76724 16.31987 0 25.42656 17.03557 1.2 26.29795 17.52548 0 27.04456 17.62109 1.2 28.22469 17.28751 0 28.82968 16.84012 1.2 29.3901 16.0109 0 29.46646 15.68201 1.199998 29.00815 14.78925 1.2 28.79494 15.95993 1.2 27.79369 16.87397 1.2 26.09315 16.87358 1.2 24.92949 15.20945 1.2 25.73645 13.34605 1.2 27.39329 13.00342 1.2 28.56049 13.6932 0 29.52656 8.407433 1.2 29.2198 7.697113 0 28.59368 6.952217 1.2 28.11217 6.655739 0 26.73486 6.392077 1.2 26.16889 6.514053 0 25.18158 7.180023 1.2 24.7058 7.7901 0 24.52502 8.29831 1.2 24.48176 9.72564 0 24.4972 9.594849 0 25.23998 10.90533 1.2 25.88127 11.37038 0 26.42406 11.49244 0 27.70001 11.49837 1.2 27.36409 11.53237 1.2 28.59369 11.04779 0 29.25565 10.33696 1.2 29.59507 9.376351 1.2 28.48749 7.635101 1.2 27.14438 6.923116 1.2 25.56639 7.556778 1.2 24.9781 8.778244 1.2 28.97486 8.564728 1.2 25.28774 10.09814 1.2 26.68155 11.05723 1.2 28.30763 10.55965 1.2 28.94637 9.543488 3 30.40078 6.000001 1.2 29.33817 19.87425 1.2 28.80073 20.051 1.2 27.80508 19.13091 1.2 28.11219 18.65575 1.2 26.28352 19.07313 1.2 26.16889 18.51404 1.2 25.26035 19.97815 1.2 24.58504 19.98207 1.2 24.96971 21.12329 1.2 24.52503 21.70166 1.2 25.40367 22.23393 1.2 25.49675 23.14706 1.2 26.35788 22.93057 1.2 27.16509 23.56802 1.2 27.87886 22.85912 1.2 28.59372 23.04779 1.2 28.98734 21.5464 1.2 29.52658 21.59258 0 29.57969 21.28272 0 29.27365 19.79349 0 28.39658 18.83819 0 26.73485 18.39208 0 25.18161 19.18002 0 24.39537 20.7105 0 25.06212 22.76454 0 27.04457 23.62108 0 28.82965 22.84009 6.449999 30.40078 7.8 6.449999 36.00078 7.8 6.449999 36.00078 8.800003 3 29.00846 20.79478 3 28.80078 21.94891 3 27.94785 22.78227 3 26.79139 23.024 3 25.70022 22.54333 3 25.04466 21.56038 3 25.18058 20.04387 3 26.35785 19.06944 3 27.71339 19.09407 3 28.64832 19.83428 3 29.00847 8.794838 3 28.65472 10.26434 3 27.13647 11.03027 3 25.8309 10.66488 3 25.04466 9.560402 3 25.12678 8.207169 3 25.90604 7.304474 3 27.03775 6.965537 3 28.44807 7.539635 27 22.00078 12 27 22.00078 18 30 29.55284 15.17839 28.8 29.52713 15.48914 30 29.18483 16.40024 28.8 28.68147 17.01178 30 27.61884 17.54755 28.8 27.05486 17.5727 30 25.89186 17.32207 28.8 25.58728 17.1755 30 24.90019 16.48636 28.8 24.53434 15.80465 30 24.44204 15.27309 28.8 24.57631 14.07658 30 24.63377 13.99054 30 25.58728 12.82449 28.8 25.69454 12.75845 30 27.26771 12.4194 28.8 26.93079 12.44267 28.8 28.22467 12.71245 30 28.65907 13.03233 28.8 29.3901 13.9891 30 29.40811 14.09091 28.80001 29.02909 14.68129 28.8 28.3657 13.51332 28.8 27.2959 12.98672 28.8 25.65035 13.41556 28.8 24.94952 15.14011 28.8 25.62889 16.50278 28.8 26.70241 16.99607 28.8 27.88371 16.83328 28.8 28.7417 16.02115 29.9976 29.58998 9.164774 28.8 29.3382 10.1257 30 28.91684 10.74913 28.8 28.49072 11.07962 30 27.59676 11.5033 28.8 27.26774 11.5806 30 26.09219 11.43007 28.8 25.79327 11.27236 30 24.76722 10.31985 28.8 24.83838 10.39485 28.8 24.39536 8.710511 30 24.43383 8.623787 30 25.10523 7.259674 28.8 25.33452 7.011459 30 26.39278 6.477875 28.8 26.72872 6.441158 30 28.11217 6.655741 28.8 28.22465 6.712452 30 29.21983 7.697113 28.8 29.49415 8.190621 28.8 27.21414 6.993064 28.8 28.58521 7.649563 28.8 29.01305 9.292832 28.8 25.87808 7.27755 28.8 28.48749 10.36493 28.8 27.47762 10.97813 28.8 26.28859 10.88841 28.8 25.23222 10.04858 28.8 25.01977 8.535218 27 30.40078 6.000001 28.8 29.39009 19.98911 28.8 27.16503 18.43198 28.8 28.39658 18.83819 28.8 28.44805 19.53963 28.8 24.97288 20.52915 28.8 24.45513 20.4996 28.8 24.7058 22.20989 28.8 27.03776 18.96553 28.8 25.49674 18.85295 28.8 25.90595 19.30447 28.8 25.34308 22.18003 28.8 25.79334 23.27239 28.8 26.28857 22.88842 28.8 27.48692 23.57598 28.8 27.47766 22.97813 28.8 28.73331 22.10709 28.8 29.11432 22.50458 28.8 29.54627 21.25551 28.8 29.00847 20.79482 30 29.52657 21.59259 30 28.43224 23.19614 30 26.72869 23.55884 30 25.15551 22.86198 30 24.40717 21.063 30 25.06212 19.23547 30 26.82776 18.41141 30 28.49234 18.87727 30 29.4081 20.09091 27 30.40078 24 23.55 30.40078 7.8 27 28.85725 20.20827 27 28.10944 19.29376 27 26.44428 18.99391 27 25.26032 19.97815 27 24.96971 21.1233 27 25.49802 22.37191 27 26.69337 23.01144 27 28.02524 22.7581 27 28.98736 21.54639 27 29.00187 9.377686 27 28.80076 8.051041 27 27.80509 7.130911 27 26.61798 7.018387 27 25.43489 7.667618 27 24.97287 9.470845 27 26.04083 10.79414 27 27.21412 11.00694 27 28.30762 10.55965 8.46997 36.00078 21.18774 6.544536 36.0008 17.87047 6.071622 36.00077 14.86381 6.910851 36.00075 11.09459 8.614861 36.00078 8.800003 9.768365 36.00078 7.8 21.38514 36.00078 8.800003 22.84253 36.00077 10.73038 23.82097 36.00078 13.61258 23.77455 36.00076 16.65582 22.70874 36.00078 19.50659 21.38514 36.00078 21.2 20.23163 36.00078 22.2 9.768365 36.00078 22.2 6.449999 36.00078 22.2 6.449999 36.00078 21.2 10.96951 33.58586 24 10.85554 33.83363 22.19999 10.02222 34.75909 24 10.08081 34.70471 22.2 8.776169 35.04312 22.2 8.539757 35.00313 24 7.45639 34.32516 22.2 7.418976 34.2545 24.00005 6.973763 33.17707 24 6.967645 33.07983 22.2 7.012778 32.62691 21.19993 8.601469 34.97264 21.19942 7.73282 34.56329 21.19851 7.887337 34.69898 20.37692 7.187347 33.87496 19.26969 7.094633 33.66273 21.20001 6.978139 32.79099 18.86437 11.02624 33.17705 6.000001 11.00191 33.25324 7.8 10.54362 34.32512 7.8 10.36797 34.53374 6.000003 9.387101 34.99748 7.8 8.776169 35.04311 6 7.75135 34.66393 7.8 7.456398 34.32516 6.000001 7.010557 33.33769 7.8 6.967645 33.07983 6.000001 23.02623 33.17702 22.2 22.93767 33.75618 24 22.47839 34.39755 22.2 21.71469 34.90496 24 21.46039 34.96532 22.2 20.21226 34.89834 24 20.28528 34.90494 22.2 19.06231 33.75615 22.20001 19.14445 33.83362 24 21.39822 34.97854 21.19843 23.00206 32.75381 18.8976 23.00594 32.8767 21.20006 22.81723 33.90176 21.1998 22.88525 33.72928 19.13419 22.07051 34.70655 21.19973 22.2894 34.5531 20.11859 23.01777 33.00113 6 22.93767 33.75617 7.8 22.60446 34.28413 6.000003 21.71469 34.90496 7.800001 21.11987 35.05185 6.000001 20.21224 34.89833 7.799999 19.84807 34.65738 5.999999 19.23202 33.97321 7.8 19.0305 33.58586 6 18.97274 32.83669 7.8 8.565306 35.00164 8.809416 6.99429 32.73552 8.799888 6.969735 32.81995 11.15671 7.182686 33.90149 8.800222 7.319153 34.14259 10.48363 7.929774 34.70661 8.800426 22.9806 32.64506 11.05911 21.3906 34.97066 8.800662 22.43434 34.43464 8.801019 22.1497 34.66365 9.688324 22.92738 33.65472 10.94121 23.00624 33.26139 8.799896 23.55 30.40078 22.2 3 29.49946 20.52468 3 28.64621 19.06043 3 26.8488 18.43446 3 25.13274 19.27374 3 24.50585 20.62599 3 24.77834 22.2907 3 26.10947 23.36012 3 27.37372 23.49509 3 28.54315 22.99634 3 29.32097 21.9906 9.473561 30.51613 17.47515 10.44867 30.95854 17.04419 11.04782 31.51921 16.46306 11.07581 31.51191 13.57456 11.52225 31.50078 15.05305 10.49626 30.98827 12.98411 9.556931 30.54565 12.5394 7.804775 30.50078 17.27521 6.586789 30.50078 15.80362 6.61758 30.50078 14.10922 7.859932 30.50079 12.69921 3 29.50945 8.7333 3 28.95036 7.366455 3 27.28459 6.445676 3 25.45146 6.982834 3 24.5281 8.403946 3 24.70249 10.08963 3 26.0825 11.40039 3 27.99181 11.34247 3 29.24347 10.19991 27 29.36128 9.890229 27 28.47586 11.0721 27 26.63181 11.54342 27 24.99315 10.56168 27 24.4577 8.953758 27 25.05118 7.366425 27 26.71696 6.445674 27 28.55012 6.982849 27 29.47344 8.403946 20.71763 30.50656 12.50092 19.79942 30.79959 12.79741 18.93086 31.51659 13.54213 18.48568 31.50078 15.38423 18.99376 31.50131 16.5005 19.58072 30.92532 17.07941 21.79974 30.50078 12.62279 23.0263 30.50078 13.41909 23.53 30.50078 15.26173 22.66548 30.50078 16.95738 20.71914 30.49474 17.51911 27 29.57046 21.04293 27 29.03961 22.46082 27 28.10443 23.29158 27 26.20724 23.44447 27 24.64153 22.01935 27 24.61835 20.10924 27 25.54361 18.94055 27 27.15275 18.43446 27 28.86876 19.27373 5.299999 25.24269 13.97548 5.299999 28.49517 13.61899 5.299999 27.88365 16.83329 5.3 25.62891 16.5028 5.300007 28.91768 15.73672 5.299999 24.98933 15.30738 5.299999 26.70242 16.99607 5.299999 26.27654 13.09846 5.300004 28.9628 14.56958 5.299999 27.46736 13.03643 24.7 25.05102 14.34751 24.7 28.72324 16.12268 24.7 26.05187 13.2 24.7 27.3933 13.00342 24.7 25.16215 15.8717 24.7 27.296 17.03473 24.7 28.42815 13.57315 24.70001 29.00082 14.62315 24.7 25.97895 16.74046 5.199999 26.77374 18.95654 5.199997 28.66565 22.16986 5.199999 25.19965 19.95599 5.199999 29.03105 20.86431 5.199999 28.38473 19.47949 5.199998 25.07021 21.64289 5.199999 26.04461 22.82018 5.199999 27.5612 22.95612 3.8 26.77901 23.02268 3.8 25.55755 22.43441 3.8 24.92389 20.8564 3.8 25.76126 19.38629 3.8 26.87279 18.98582 3.8 28.03598 19.24822 3.8 28.82197 20.13017 3.8 29.01223 21.30737 3.8 28.25082 22.63239 3.8 28.86878 19.27374 3.8 27.36965 18.48339 3.8 25.50729 18.90847 3.8 24.50209 20.52465 3.799999 24.6806 21.99065 3.8 25.6281 23.1413 3.8 27.27792 23.52836 3.8 28.9731 22.64777 3.8 29.53861 20.83038 5.199999 26.43165 7.024302 5.199999 25.14169 8.121933 5.199998 25.03739 9.467392 5.199999 28.10785 7.267479 5.199999 25.62889 10.50278 5.199998 28.91746 8.367798 5.199998 27.05371 11.05535 5.199999 28.96027 9.548432 5.199998 28.30203 10.54269 3.8 27.46557 10.98101 3.8 26.11788 10.83328 3.8 25.16213 9.871659 3.8 25.05102 8.347535 3.8 25.90671 7.304016 3.8 27.05018 6.965802 3.8 28.31715 7.448372 3.8 28.9428 8.450547 3.8 28.83415 9.986336 3.8 29.08189 10.46234 3.8 29.49311 9.28093 3.8 29.26509 7.784279 3.8 27.58415 6.497042 3.8 25.9126 6.72393 3.799999 24.94075 7.54364 3.8 24.45769 8.95376 3.8 24.77855 10.16284 3.8 25.62804 11.14126 3.8 27.50014 11.52106 24.8 28.35123 7.415592 24.8 25.25766 7.861748 24.8 29.03524 8.963051 24.8 28.60689 10.24933 24.8 27.63222 10.91692 24.8 26.44038 10.95611 24.8 25.11758 9.887497 24.8 26.70568 6.986712 26.2 27.05371 11.05535 26.2 25.49286 10.39766 26.2 24.95472 8.615662 26.2 26.25532 7.0562 26.2 28.10785 7.267471 26.2 28.97891 8.52314 26.2 28.7069 10.19299 26.2 28.19602 11.27521 26.2 26.30032 11.44515 26.2 24.91967 10.46233 26.2 24.47853 9.052961 26.2 24.86795 7.614212 26.2 26.41741 6.497042 26.2 28.08896 6.723949 26.2 29.32467 7.902428 26.2 29.41397 9.803635 24.8 25.02264 20.52313 24.8 25.89368 19.26749 24.8 28.90671 20.28738 24.8 27.74625 19.05621 24.8 28.93134 21.64291 24.8 27.95694 22.82018 24.8 25.16214 21.87168 24.8 26.26614 22.92031 26.2 26.36596 22.95558 26.2 25.30525 22.09475 26.2 24.96631 20.96305 26.2 25.44115 19.69312 26.2 26.4505 19.05822 26.2 27.96742 19.15618 26.2 29.03276 20.68643 26.2 28.6657 22.16983 26.20001 27.71378 22.88811 26.2 29.5151 21.38423 26.2 28.85849 22.70706 26.2 27.58173 23.47627 26.2 25.89713 23.29159 26.2 24.59219 21.89658 26.2 24.66442 19.99458 26.2 26.00283 18.63163 26.2 27.90609 18.62307 26.2 29.19833 19.71934 14.69261 11.01222 24 16.7518 10.03595 24 13.6344 10.48686 23.99999 12.96527 9.295991 24 13.4341 7.668381 24 14.61721 7.019162 24 16.13826 7.257661 24 17.01328 8.705636 24 15.8698 10.82196 23.99998 13.00393 8.702424 26.2 13.60235 7.492844 26.2 15.03696 6.96631 26.2 16.16502 7.352735 26.20002 17.04182 8.594498 26.2 16.6137 10.24026 26.2 15.47686 10.97891 26.20001 14.12835 10.83942 26.2 13.16673 9.883694 26.2 13.1215 10.71561 26.20001 12.50491 9.373711 26.2 12.78932 7.690048 26.20001 14.31448 6.551399 26.20001 16.00537 6.664407 26.20001 17.24998 7.814613 26.20001 17.47534 9.700515 26.19997 16.09759 11.32466 26.2 14.41571 11.45499 26.20001 17.50577 9.576421 27 16.38579 11.13362 27 15.14437 11.50474 27 13.91038 11.29906 26.99999 12.59961 9.919068 27.00001 12.65754 8.009682 27 13.98068 6.641516 27 15.89077 6.618356 27 17.18974 7.706764 27</float_array> + <technique_common> + <accessor source="#Link2-mesh-positions-array" count="2277" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Link2-mesh-normals"> + <float_array id="Link2-mesh-normals-array" count="13746">0.244942 0.9266462 -0.2851849 -0.02899205 0.9991127 -0.03054755 -0.2337695 0.9720327 0.02245473 0.05888164 0.9598782 -0.2741655 -0.106502 0.9904289 -0.08779621 0.318564 0.8927912 0.3184978 0 0 -1 -1.75821e-5 -1.2025e-4 -1 -7.30225e-6 -2.01466e-4 -1 -2.8445e-4 -2.00074e-4 -1 -4.60437e-4 -6.1232e-4 -0.9999998 0.5520847 0.8269162 -0.1068274 0.5991744 0.7995932 0.04050618 -1.69804e-5 -1.20209e-4 1 0 0 1 -6.6044e-6 -2.14404e-4 1 -7.85756e-5 -1.49636e-4 1 -1.06373e-5 -9.56735e-5 1 -0.5653718 0.7396785 -0.3650077 -0.7377601 0.6679057 0.09804069 -0.4348707 0.9004771 0.005333662 0.3709459 0.9282384 0.02779692 0.4386935 0.8986361 0.001126706 0.5620129 0.7618782 -0.3219987 0.682961 0.7303355 0.01320409 6.24498e-7 -4.05556e-7 1 1.81921e-5 -1.24772e-4 1 7.7253e-6 -2.10827e-4 1 2.50929e-4 -1.93792e-4 1 3.83529e-4 -5.20035e-4 0.9999998 -0.5991733 0.7995969 -0.04045063 -0.5520927 0.8269098 0.1068357 1.7511e-5 -1.28474e-4 -1 0 0 -1 7.73671e-6 -2.2125e-4 -0.9999999 7.51747e-5 -1.83989e-4 -1 1.96636e-7 7.43897e-7 -1 -0.7261701 0.6724362 -0.1432016 -0.5457617 0.758073 0.3570289 -0.4326497 0.9015551 -0.003554403 -0.370958 0.9282337 -0.02779525 0.5693671 0.7277543 0.3823544 0.739879 0.6698443 -0.0623511 0.4348787 0.9004733 -0.005333483 0.0215637 0.9956617 0.09051334 0.02783709 0.9982045 0.05303603 3.04086e-4 -0.01475614 0.9998911 -1.86947e-7 0 1 0 -2.50995e-6 1 -0.03646808 0.9952305 0.09047794 -0.01940363 0.9997194 -0.01359081 3.49168e-7 0 -1 0.9999929 1.72765e-5 0.00377959 0.9999924 3.13964e-7 0.003901839 0.9999924 0 0.003902077 0.9999924 0 0.003902077 0.9999915 0 -0.004128694 1 0 0 0.9997754 0 -0.02119463 0.9997754 0 -0.02119463 0.9997755 0 -0.02119463 1 0 0 1 0 0 0.9999924 -1.6302e-7 0.00390321 1 0 0 1 0 0 1 0 0 0.9999915 0 -0.004128694 0.9998633 0.001720011 -0.01644253 0.9999749 -0.0070737 0 0.999975 -0.0070737 0 0.9999781 -0.006615996 -5.07388e-5 0.9999799 -0.006344735 0 0.9999931 0 0.003728091 1 -4.99114e-7 1.54571e-6 1 0 0 1 0 0 1 -1.19613e-6 1.08257e-6 1 1.84658e-6 0 1 1.05634e-6 -2.85896e-7 1 -8.0861e-7 -1.56153e-6 1 1.17728e-6 1.27358e-6 1 3.17063e-6 -2.1153e-6 1 -1.28366e-6 0 1 0 0 1 0 0 -0.9997721 0 -0.0213508 -1 0 0 -0.9998196 0 0.01899534 -0.9998196 0 0.01899534 -0.9998195 0 0.01899534 -1 4.76835e-6 0 -1 -1.36239e-6 0 -0.9999963 -0.002703547 0 -0.9999952 -0.003112792 7.69697e-5 -0.9998196 0 0.01899546 -1 0 0 -1 0 0 -1 0 0 -0.9999986 0 -0.001611113 -0.9999988 0 -0.001611113 -0.9998713 0.001965463 -0.01592487 -0.999772 0 -0.0213508 -0.999772 0 -0.0213508 -0.9999976 0 0.002252161 -0.9999927 -0.003803789 0 -0.9999927 -0.003803789 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999717 0.001712083 0.007329225 -1 4.76835e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.16148e-7 -2.83959e-7 -1 0 0 -1 0 0 -1 0 5.04778e-7 -1 2.19407e-7 -2.04309e-7 -7.88836e-4 0.07402157 0.9972563 1.88106e-6 -3.78462e-6 1 -0.02975493 -0.005312204 0.9995431 -0.04142713 0.01396566 0.9990439 -0.01728844 0.008979976 0.9998102 -0.009578585 0.03078669 0.9994801 1.01465e-4 0.005857586 0.9999828 1.94074e-4 0.002955257 0.9999956 -1.56311e-4 0.009065687 0.9999589 2.30635e-6 -7.61665e-5 1 5.71127e-4 0.02658492 0.9996464 0.00575608 1.91806e-4 0.9999834 0.002264499 0.002447187 0.9999945 0.01280647 0.00736165 0.9998909 0 4.18986e-7 1 5.34066e-7 -1.20612e-5 1 -9.20403e-7 5.225e-6 1 0.004757821 -0.001104116 0.9999881 -0.02128934 0.001612901 0.9997721 -0.0306589 -0.02246052 0.9992775 -2.92166e-6 -2.83817e-6 1 0 0 1 0.001187622 -0.003849029 0.9999918 4.87958e-6 4.2867e-7 1 -2.7708e-6 -3.71459e-6 1 -9.52617e-7 -1.2771e-6 1 -0.005193233 -0.002265274 0.9999839 0.00534439 -0.00335431 0.9999801 0.004047989 -3.6938e-5 0.9999918 5.02824e-6 -3.02136e-6 1 3.2683e-6 3.69005e-7 1 0 3.86913e-7 1 -3.10426e-5 1.13823e-5 1 0.002982556 -0.002367079 0.9999928 0.004075765 -0.002345502 0.999989 0 -4.52842e-7 1 -1.32461e-7 -3.97775e-7 1 -5.982e-6 2.18237e-6 1 -3.5903e-6 -2.08135e-7 1 -9.16767e-7 -1.02472e-6 1 0.001415729 -0.002308607 0.9999963 -3.43286e-7 1.12208e-6 1 1.0024e-4 -1.78898e-5 1 1.59926e-4 -4.21305e-4 0.9999999 0.01672637 0.002243638 0.9998576 -0.002766728 -3.59489e-4 0.9999961 -0.008223116 -5.75449e-4 0.999966 0.004461526 -2.03861e-5 0.9999901 0 2.28297e-6 1 3.93388e-6 -1.26041e-5 1 -0.003579974 -0.009323179 0.9999501 0.001914918 -0.01960682 0.999806 1.52238e-6 0 1 -0.02143955 0.002628147 0.9997667 -2.18075e-4 -5.45378e-4 0.9999998 -1.70048e-6 -2.59216e-7 1 3.17833e-7 3.26134e-6 1 -0.005286395 -0.00101161 0.9999855 -0.001841247 -0.001785337 0.9999968 -3.46812e-7 1.11927e-6 1 -1.05361e-6 3.40034e-6 1 0 -1.74874e-7 -1 -1.84637e-7 -7.65854e-7 -1 -2.90985e-7 2.62436e-7 -1 -1.85893e-7 6.20278e-7 -1 2.86653e-6 -2.94207e-6 -1 0 -2.42573e-7 -1 0 -2.31569e-7 -1 -3.59909e-7 -1.89069e-7 -1 3.13506e-7 1.64692e-7 -1 9.52862e-7 -4.20829e-7 -1 0 -1.47078e-7 -1 0 1.21659e-7 -1 0 1.41124e-7 -1 2.00865e-7 -5.37222e-7 -1 0 4.74845e-7 -1 -4.62292e-7 8.03778e-7 -1 0 1.93441e-7 -1 0 -1.15976e-6 -1 1.66588e-7 -5.02824e-7 -1 8.08261e-7 1.898e-6 -1 0 0 -1 -3.81278e-6 2.0121e-6 -1 -2.79357e-7 -1.32188e-7 -1 4.48311e-7 -1.21211e-7 -1 4.0615e-7 0 -1 1.22912e-6 4.56381e-7 -1 -0.9313476 0.3639085 0.01273912 -0.9006671 0.4337702 -0.02533859 -0.5658485 0.8237005 0.03651189 -0.4555379 0.8897831 -0.02777123 0.1245685 0.9922097 -0.001651108 0.2141289 0.9750138 0.05913501 0.7735119 0.6303434 -0.06592816 0.9090555 0.4111701 0.06750607 0.9983689 -0.02426254 -0.05167913 0.9580919 -0.2833835 0.04187953 0.741905 -0.6691157 -0.04314041 0.6337448 -0.7728319 0.0331403 0.04689556 -0.9982392 -0.03632354 -0.07267028 -0.9967733 0.03409135 -0.6136969 -0.7889387 -0.03085321 -0.6848626 -0.7284806 0.01671195 -0.9692715 -0.2459679 -0.003555834 -0.9734722 -0.2283813 -0.01392716 -0.9988065 2.24041e-4 -0.04884183 -0.9958426 0.09097629 0.004569053 -0.7565507 0.6530543 0.03392887 -0.5960758 0.7993909 -0.07528501 -0.2865606 0.9568414 0.04834961 0.2060677 0.9774822 -0.04543757 0.3240385 0.9458959 0.01673859 0.7819039 0.6233888 -0.003551721 0.8276523 0.5591219 -0.04872828 0.9974333 0.02422904 0.06737703 0.940786 -0.3282751 -0.08460152 0.8089531 -0.5863788 0.0418896 0.3401578 -0.9400278 -0.02530765 0.4048683 -0.9140247 0.02530872 -0.1782926 -0.9830854 -0.04188895 -0.4001019 -0.9145318 0.05958282 -0.7375644 -0.6732965 -0.05167871 -0.8877934 -0.4583324 0.04188203 -0.9136092 0.4061694 -0.01856714 -0.871439 0.4896436 0.02903765 -0.5518179 0.8335716 -0.02559864 -0.4444995 0.8953551 0.02755725 0.1271647 0.9911787 -0.03733575 0.1868844 0.9823774 0.00298053 0.7438654 0.6674675 0.03393292 0.854312 0.51625 -0.06030952 0.9857034 0.1627359 0.04365605 0.9799109 -0.1926254 -0.05167293 0.8691508 -0.4906756 0.06176084 0.6644243 -0.7455831 -0.05144059 0.2355271 -0.9707762 0.04604816 0.1294619 -0.9914531 -0.01613873 -0.5498003 -0.835115 0.01739454 -0.5909436 -0.8065705 -0.01515471 -0.9687427 -0.2476042 0.01515126 -0.9735608 -0.2284167 0.00229454 -0.9806044 0.1888606 -0.05240929 -0.9203176 0.3893744 0.03745889 -0.6843712 0.7279297 -0.04188525 -0.4956127 0.8675332 0.04188388 -0.07265019 0.9964239 -0.04314661 0.04860991 0.9986453 0.01856464 0.6858974 0.7276859 -0.004254817 0.657065 0.75336 0.0267235 0.9919062 0.114812 -0.05422466 0.9943202 -0.0843957 0.06484365 0.7606157 -0.6471977 -0.05097967 0.6988446 -0.7152669 0.003068149 0.2045362 -0.978465 0.0277698 0.01666641 -0.9976452 -0.06653034 -0.4531049 -0.8887323 0.0696491 -0.7563134 -0.6473231 -0.09467333 -0.9494445 -0.3034198 0.08057039 1 0 0 1 0 0 1 -1.75253e-6 0 1 0 0 1 0 0 1 1.00315e-6 9.31363e-7 1 1.55952e-6 -3.66898e-7 1 0 0 1 3.77837e-6 -1.0691e-6 1 1.02181e-6 0 1 0 0 1 -1.941e-6 0 1 -7.08944e-6 -1.8839e-6 5.14777e-7 -3.85918e-7 -1 3.03838e-7 -3.70521e-7 -1 3.03862e-7 -5.05544e-7 -1 -1.84529e-7 1.50916e-7 -1 -1.03278e-6 -6.67294e-7 -1 -7.84028e-7 -1.7097e-6 -1 -1.26725e-6 -1.81845e-6 -1 -6.27663e-7 1.53006e-7 -1 -5.89133e-7 1.35632e-7 -1 -1.52182e-6 -2.64038e-7 -1 -2.47147e-6 1.85032e-6 -1 2.75965e-7 1.00234e-6 -1 0 0 -1 0 0 -1 -1.80149e-7 0 -1 -1.41568e-7 0 -1 2.66827e-7 0 -1 2.87827e-7 0 -1 -6.90737e-7 -5.96265e-7 -1 -2.28511e-7 3.32048e-7 -1 1.67627e-7 0 -1 -3.79346e-7 -2.18656e-7 -1 -7.72762e-7 5.21478e-7 -1 -6.15979e-7 5.31713e-7 -1 -6.70574e-7 1.19222e-6 -1 -3.25237e-7 1.08598e-6 -1 -3.23028e-7 1.09227e-6 -1 -1.68775e-7 8.95454e-7 -1 1.2725e-6 1.88986e-6 -1 6.81342e-7 -3.60114e-7 -1 -2.68032e-7 0 -1 -4.1128e-7 0 -1 -4.3852e-7 0 -1 5.88247e-7 -1.79455e-7 -1 2.16821e-7 -5.99185e-7 -1 1.84525e-7 0 -1 0 -1.28678e-7 -1 0 -5.30783e-7 -1 1.22906e-7 0 -1 7.54468e-7 0 -1 1.05263e-6 -1.4676e-6 -1 0 -8.87985e-7 -1 0 -1.73177e-7 -1 1.66803e-7 -3.14078e-7 -1 -1.40586e-6 -1.1654e-6 -1 -7.03276e-7 2.6469e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.3342e-7 -1 0 -1.36187e-7 -1 4.45201e-7 5.25335e-7 -1 5.48559e-7 4.25061e-7 -1 4.9912e-7 4.08051e-7 -1 5.73762e-7 0 -1 0 2.05903e-7 -1 -5.11771e-7 -2.68033e-7 -1 -2.99118e-7 0 -1 -3.00475e-7 0 -1 3.07784e-7 0 -1 2.6273e-7 -2.83363e-7 -1 -1.60697e-7 0 -1 0 0 -1 0 -2.97725e-7 -1 -2.01609e-7 -3.56981e-7 -1 -1.88682e-7 0 -1 0 0 -1 0 -2.03283e-7 -1 2.28678e-7 0 -1 1.77523e-7 0 -1 -1.52934e-7 0 -1 0 4.63531e-7 -1 0 4.3945e-7 -1 0 4.40218e-7 -1 0 -2.6511e-7 -1 0.2406267 0.04163247 -0.9697244 0.01230722 0.2975637 -0.9546226 -0.2141819 0.1694033 -0.961992 -0.259911 0.0426917 -0.9646884 -0.08976155 -0.2887344 -0.9531922 0.06447619 -0.2594069 -0.9636135 0.2866243 -0.07210844 -0.9553256 0.2328225 -0.2051535 -0.9506344 -0.1766968 -0.2017338 -0.9633701 -0.1897926 -0.1086056 -0.9757989 -0.1845091 -0.09475493 -0.9782524 -0.09086704 0.2166385 -0.9720138 -0.08803713 0.2231935 -0.9707905 0.08192825 -0.2265866 -0.9705392 0.01137888 -0.03765249 -0.9992261 0.04438054 0.02063208 -0.9988017 0.1794194 0.07550114 -0.9808712 0.1797992 0.2310956 -0.9561732 -3.42726e-7 -1.28203e-7 -1 0 0 -1 2.94164e-7 -1.9984e-7 -1 1.60063e-6 1.88926e-6 -1 0 -1.49691e-7 -1 7.21408e-7 -1.3593e-7 -1 -1.1334e-6 7.57619e-7 -1 -6.31112e-7 2.38415e-7 -1 1.1948e-6 -7.71513e-7 -1 1.26104e-6 2.53119e-6 -1 8.80754e-7 0 -1 0 -4.18915e-7 -1 3.0786e-7 0 -1 -2.84342e-7 1.41234e-7 -1 -2.89965e-7 -2.07598e-7 -1 7.80591e-7 -2.04497e-6 -1 -2.82088e-7 1.4509e-7 -1 -1 4.22333e-7 4.17837e-7 -1 -4.432e-7 -4.38481e-7 -1 0 2.90093e-7 -1 -3.77121e-7 -4.16753e-7 -1 1.04625e-6 3.14616e-7 -1 5.16892e-7 -3.10432e-7 -1 0 2.93162e-7 -1 -3.75069e-7 2.72772e-7 -1 -2.77106e-7 2.35225e-7 -1 2.68107e-7 -2.27586e-7 -1 -9.37477e-7 -4.79992e-7 0.02576363 -0.1187021 -0.9925956 -0.02188479 0.539575 -0.8416531 0.0218715 0.5797857 -0.8144754 -0.02575111 0.9652807 -0.2599427 0.03252947 0.9770867 -0.2103415 -0.03668141 0.7674487 0.64006 0.0366832 0.7323482 0.6799415 -0.03252625 -0.08453106 0.9958898 0.02576386 -0.1352383 0.990478 -0.02188366 -0.7342373 0.67854 -0.005584836 -0.7465566 0.6652985 0.02630245 -0.9868482 0.1594955 -0.04845333 -0.9966025 0.06660085 0.05861639 -0.8499433 -0.5236034 -0.03488135 -0.8008242 -0.5978828 0.002383828 -0.139033 -0.9902849 0.1279777 -0.02841126 -0.99137 -0.05912989 0.1711162 -0.9834749 -0.02737617 0.6961295 -0.7173941 0.08986669 0.7800769 -0.6191963 -0.0721631 0.9859467 -0.1506702 0.07216721 0.9951718 0.06652098 -0.07215833 0.8617595 0.5021591 0.05214494 0.7537238 0.6551192 -0.03979998 0.3556492 0.9337718 0.02001458 0.283572 0.9587422 -0.02576267 -0.3649919 0.9306542 -0.07161593 -0.3264613 0.9424936 0.1072272 -0.7978949 0.5931831 -0.1098002 -0.9418104 0.3177059 0.06535971 -0.9935992 -0.09213435 -0.04980117 -0.9531499 -0.2983708 0.07460188 -0.7502229 -0.6569629 -0.1038624 -0.5532425 -0.82652 -0.09840369 0.957282 -0.271897 0.312515 0.9189463 0.2405664 0.6429098 0.7371348 -0.2080852 0.8476209 0.50088 0.1750952 0.9741404 0.142773 -0.175118 0.9741408 -0.1427722 0.175117 0.847607 -0.5008981 -0.1751098 0.6682229 -0.7230572 0.1751183 0.3152849 -0.9274992 -0.2008498 0.06228512 -0.9804433 0.1866852 -0.3867765 -0.9159303 -0.1071239 -0.5439974 -0.8324294 0.1054902 -0.7868376 -0.604909 -0.1223586 -0.9013643 -0.4007492 0.1641413 -0.9895077 0.04953789 -0.1357216 -0.952739 0.2526618 0.1686724 -0.7624394 0.612317 -0.2091745 -0.4537726 0.8481609 0.2733381 -0.9035192 0.4284511 0.009093284 -0.5764127 0.8153741 -0.05397623 -0.4397891 0.8821201 0.1686707 -0.07396358 0.98027 -0.1833034 0.3153188 0.9281145 0.197933 0.5585952 0.8055324 -0.1977095 0.8517011 0.4690245 0.2337122 0.9577631 0.1695235 -0.2322747 0.9525486 -0.2508075 0.1724721 0.8509684 -0.5028755 -0.1515552 0.6487382 -0.7463713 0.1485548 0.3448025 -0.9221964 -0.1751148 0.1196248 -0.9865397 0.111487 -0.3278458 -0.9418023 -0.07433319 -0.2868757 -0.95789 0.01221561 -0.7557252 -0.6523643 -0.0574482 -0.7969399 -0.6013216 0.05743759 -0.994284 -0.1064143 -0.008673071 -0.9952611 -0.0903114 -0.03604459 -0.9098668 0.4132026 0.03749501 0.6005253 0.7725394 0.2062821 0.7692031 0.6288542 -0.113442 0.9715911 0.2250222 0.07331836 0.9875308 0.1476045 -0.0547319 0.9321594 -0.3520146 -0.08464407 0.8538286 -0.4952352 0.1603711 0.6070998 -0.7718905 -0.1887199 0.2559838 -0.9480002 0.1891241 -0.01040232 -0.9798852 -0.1992908 -0.3962979 -0.8996368 0.183307 -0.7253566 -0.660211 -0.1948824 -0.8420985 -0.5272993 0.1132501 -0.9890759 0.07971292 -0.1239948 -0.9833673 0.1711367 0.0608344 -0.7176105 0.6963378 -0.01220482 -0.7041391 0.7084493 -0.04783231 -0.1213449 0.9912382 0.05217552 -0.1626376 0.9757369 0.1465833 0.283746 0.9470615 -0.1502083 0.8399243 -0.5250584 -0.1372614 0.7128482 -0.6819804 0.1635544 0.3473433 -0.9289864 -0.1278159 0.2407377 -0.9697719 0.03984785 -0.3127899 -0.9393051 -0.1409555 -0.4748867 -0.8628312 0.1732193 -0.8319438 -0.4945724 -0.2515308 -0.9495783 -0.2467383 0.1934453 -0.9565249 0.2438976 -0.1599189 -0.9129983 0.3948537 0.1025894 -0.5969195 0.7967353 -0.0943399 -0.4678831 0.8744972 0.1278288 -0.07447981 0.986969 -0.1426358 0.2103668 0.9552276 0.2080528 0.4870208 0.8623498 -0.138433 0.8240008 0.5650048 0.04233354 0.828356 0.5568912 0.06081807 0.9989947 -0.04162007 -0.01665604 0.9960445 0.005544245 0.08868288 -0.7464432 0.6652951 -0.01431399 -0.7152793 0.689924 0.1112678 -0.2548144 0.9617143 -0.1008718 -0.1752214 0.9745032 0.1401464 0.3574818 0.9321803 -0.05697906 0.3034304 0.9435148 0.1330772 0.648805 0.7387953 -0.1823004 0.820634 0.5143562 0.2489932 0.9175069 0.3862559 -0.094801 0.9980536 0.02879309 0.05531644 0.9800122 -0.08312082 -0.1807404 0.9183136 -0.3554262 0.1742771 0.7457077 -0.617686 -0.2497678 0.5474366 -0.7994774 0.2472833 0.4094251 -0.9086833 -0.08164477 0.01719516 -0.9958322 0.08956938 -0.04346585 -0.9962482 -0.07483446 -0.5474573 -0.8326441 0.08363151 -0.6128348 -0.7635934 -0.203368 -0.9666464 0.2431106 -0.08057242 -0.9703817 0.1027297 0.2186452 -0.963724 -0.1871429 -0.1902986 -0.8721895 -0.4128452 0.2623821 -0.6408309 0.7676277 0.009132802 -0.6687976 0.7431421 0.02120035 0.157976 0.9870496 -0.02786713 0.500518 0.8645284 0.04552471 0.9301837 0.3651049 -0.03816705 0.9930614 -0.1119206 0.03609836 0.8266769 -0.5616033 -0.03474378 0.450179 -0.8923773 0.03165072 -0.1231055 -0.9919897 -0.02831095 -0.2971134 -0.9548201 0.006514132 -0.936318 -0.3511494 -0.001591086 -0.9443064 -0.3289515 -0.008739411 -0.9988135 0.04772925 -0.009671688 -0.6603866 0.7509257 3.10948e-4 -0.5657305 0.8240801 0.02900093 0.2967878 0.9540574 -0.0411266 0.6146914 0.7872684 0.04861193 0.9985869 -0.02741503 -0.04552513 0.9511067 -0.3073106 0.03092128 0.2743834 -0.9613582 -0.02245378 0.1293941 -0.9915025 0.01342177 -0.6391205 -0.7690048 -0.01251167 -0.6829439 -0.7304709 2.13049e-4 -0.9989309 -0.04503732 0.01042413 0.06702458 0.9972782 0.03072535 0.3952155 0.9181926 -0.02696496 0.9213513 0.3881812 0.02067244 0.9413422 0.3373622 0.007842123 0.9231922 -0.3840085 -0.01592683 0.8118941 -0.5833077 0.0240848 0.2598888 -0.9652109 -0.02873396 0.008056223 -0.9995774 0.02793174 -0.8080314 -0.5886487 -0.02403777 -0.8994926 -0.4363271 0.02305984 -0.9245071 0.3804754 -0.02291119 -0.7791018 0.6263041 0.02726972 -0.4025013 0.9151972 -0.02017259 -0.8144364 0.5802001 0.007812917 -0.833236 0.552633 0.01773577 -0.06906056 0.9972525 -0.02679616 0.2067614 0.9779081 0.03075051 0.8127018 0.581846 -0.03116261 0.9260076 0.377018 0.01916795 0.8983091 -0.4392993 -0.007544279 0.8891988 -0.4573551 -0.01231914 0.3686581 -0.9294656 0.01359748 0.09300839 -0.9950753 -0.0342732 -0.400626 -0.9156731 0.03227174 -0.9236538 -0.3821689 -0.02847236 -0.8946701 -0.4466692 -0.007228434 0.09338855 0.138422 -0.9859604 -0.123544 0.43936 -0.889775 0.1296585 0.7945544 -0.5931879 -0.143456 0.9779533 -0.1517492 0.05498248 0.9962642 0.06659275 -3.03324e-4 0.6917657 0.722122 -0.03711521 0.6705083 0.740973 0.005392611 -0.1728459 0.9849342 -0.04706758 -0.1351209 0.9897106 0.07546591 -0.7444366 0.6634148 -0.1409994 -0.9084831 0.393418 0.05327457 -0.9857873 0.1593279 0.007173418 -0.895655 -0.4446917 -0.07657939 -0.849151 -0.5225688 0.06574392 -0.5150159 -0.8546556 -0.08104854 -0.274482 -0.9581706 -0.08987337 0.2836811 -0.9546977 0.05498188 0.4332568 -0.8995919 -3.10814e-4 0.927976 -0.3726399 -0.03711432 0.9375396 -0.3458929 0.003871798 0.8647387 0.5022072 0.03140133 0.8531497 0.5207204 -0.02732384 0.2224313 0.9745654 -0.007228851 0.2032746 0.979095 0.02784675 -0.4094878 0.9118906 -0.08415657 -0.5153616 0.8528307 0.1032795 -0.9212505 0.3750078 -0.08345818 -0.9844853 0.1543483 0.07660955 -0.9250705 -0.3719885 -0.007184207 -0.8900896 -0.4557291 -0.05498981 -0.4332605 -0.8995896 0.08986991 -0.2836784 -0.9546989 1 -4.67326e-7 -1.04169e-6 1 3.111e-6 -9.73834e-7 1 5.3305e-6 1.44269e-6 1 2.06876e-6 1.72537e-6 1 1.55626e-6 4.51168e-7 1 -1.09862e-6 -3.18497e-7 1 -8.85253e-7 -7.83591e-7 1 0 0 1 3.47287e-6 -1.44164e-6 1 3.67433e-6 -2.45548e-7 1 6.39741e-7 -1.13728e-6 1 -1.23858e-6 2.20184e-6 1 -2.32053e-6 6.71676e-7 1 0 0 1 1.33631e-6 -7.54036e-6 1 6.49622e-6 -4.9197e-6 1 0 0 1 2.66785e-6 -2.25635e-6 1 -2.05387e-6 1.73708e-6 1 -4.73432e-6 -1.87775e-6 1 -2.9193e-6 -1.70112e-6 1 -2.63783e-6 -2.59009e-6 1 0 0 1 0 0 1 0 0 1 2.72776e-6 -8.17275e-7 1 3.819e-6 -2.5957e-6 1 1.27502e-5 8.9396e-7 1 4.96523e-6 4.93767e-6 1 2.98857e-6 8.98713e-7 1 -5.66191e-6 -1.70263e-6 1 -4.84158e-6 -8.11977e-6 1 5.47127e-6 1.13691e-6 1 1.45323e-6 5.98413e-6 1 -4.5028e-7 -1.85417e-6 0.01434797 0.005597293 -0.9998814 0.03397238 -0.006851315 -0.9993993 -1.08006e-5 1.5731e-5 -1 1.33925e-4 1.81425e-4 -1 1.59758e-5 -5.16191e-6 -1 1.38086e-4 1.76855e-4 -1 0 0 -1 0 0 -1 9.159e-6 -2.55391e-5 -1 1.76839e-4 5.68267e-5 -1 -1.94462e-5 8.83119e-6 -1 2.87289e-5 2.52055e-4 -0.9999999 0.01765227 -0.1938311 -0.9808761 1.12349e-4 3.30691e-4 -1 0.002927303 -0.05668228 -0.9983879 0.03792077 -0.07606071 -0.9963819 1.07768e-5 1.86144e-5 -1 1.45809e-5 1.8644e-5 -1 3.69284e-6 -4.42352e-6 -1 -2.09176e-5 -2.31e-5 -1 -2.14014e-5 -8.02622e-6 -1 0 0 -1 0 0 -1 7.86747e-4 2.37152e-4 -0.9999996 -1.30179e-4 -4.1835e-4 -0.9999999 0.009302198 0.007333457 -0.9999299 0.02537459 -0.04742842 -0.9985523 0.4354889 0.008082032 -0.9001578 0.04262429 -0.01130372 -0.9990272 0.04838281 0.02151113 -0.9985972 0.03146135 0.04814243 -0.9983449 0.01900804 -0.01065069 -0.9997627 0.01209896 0.005868971 -0.9999096 0 0 -1 -2.43322e-5 1.95549e-5 -1 -4.02703e-4 0.01240265 -0.999923 0.012322 0.005603671 -0.9999083 1.58306e-7 -1.96417e-5 -1 2.15456e-5 -1.54795e-5 -1 3.6156e-5 -1.48081e-5 -1 0.006597697 -0.01541823 -0.9998594 0.008444547 -0.1128228 -0.9935792 1.77535e-4 -1.69837e-4 -1 1.09319e-5 5.17226e-5 -1 5.60713e-5 -1.41368e-4 -1 3.22111e-6 -1.2008e-4 -1 1.53993e-5 6.26972e-6 -1 -2.53191e-4 -1.04759e-4 -1 5.7533e-5 -2.81353e-5 -1 -5.04835e-5 -1.15385e-4 -1 3.39326e-5 -4.98345e-5 -1 0 0 -1 2.29208e-6 -3.61307e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.56743e-5 1.41383e-5 -1 0 0 -1 3.67485e-5 6.84154e-6 -1 0 0 -1 -2.33793e-5 2.98188e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.06594e-5 5.23103e-5 -1 9.21246e-6 -4.04427e-5 -1 1.01516e-5 -3.75894e-5 -1 6.56819e-5 4.33951e-4 -0.9999999 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.48116e-4 -9.35007e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.99175e-5 -7.8854e-6 -1 -4.6519e-5 -1.20872e-5 -1 1.5172e-7 0 -1 -2.21727e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.25891e-7 -1 0 0 -1 0 0 -1 2.05249e-6 1.30602e-7 -1 -1.54058e-7 0 -1 0 0 -1 0 -1.64163e-7 -1 0 2.84336e-7 -1 0 0 -1 0 0 -1 -9.832e-5 1.98529e-5 -1 0 0 -1 -7.56818e-6 -2.20363e-5 -1 -1.96467e-4 7.68668e-4 -0.9999997 0 0 -1 0 0 -1 1.13351e-5 4.02817e-5 -1 -2.31871e-6 2.8367e-5 -1 -3.64863e-5 -7.51612e-5 -1 -7.93753e-7 -1.27488e-7 -1 -1.63244e-7 0 -1 4.33097e-7 -7.01236e-7 -1 5.75181e-7 -6.15598e-7 -1 3.51755e-7 2.44729e-6 -1 2.36356e-6 2.17019e-6 -1 9.89347e-7 1.89066e-7 -1 -4.18117e-7 1.12757e-6 -1 -6.87884e-7 1.01442e-6 -1 -8.93784e-7 1.31806e-6 -1 -2.29891e-6 1.27882e-6 -1 -2.34168e-6 3.01276e-6 -1 1.84667e-7 2.01413e-7 -1 0 0 -1 0 -1.82694e-7 -1 -5.11588e-7 -2.35082e-7 -1 -4.74762e-7 4.27876e-7 -1 -1.04452e-6 2.76338e-7 -1 1.2919e-6 6.25843e-7 -1 -7.44924e-7 1.77999e-6 -1 -1.05444e-6 1.71278e-6 -1 5.64854e-7 -1.64623e-6 -1 -7.92832e-7 -1.71058e-6 -1 -4.75058e-7 1.8992e-6 -1 7.88968e-7 1.99916e-6 -1 7.01751e-7 -3.42336e-7 -1 -2.15605e-6 -3.77448e-7 -1 -1.91113e-6 0 -1 -7.09428e-7 -5.98999e-7 -1 1.42219e-6 1.20081e-6 -1 4.23994e-6 -1.88253e-6 -1 1.43027e-6 -4.13807e-6 -1 9.44106e-7 -2.00078e-6 -1 -6.56857e-7 -1.40276e-6 -1 -1.74133e-7 -5.7784e-7 -1 0 -8.20158e-7 -1 6.25714e-7 9.69322e-7 -1 5.97122e-7 6.75418e-7 -1 0 8.87135e-7 -1 -9.03716e-7 -1.37245e-7 -1 -1.77502e-6 2.52643e-7 -1 -1.12504e-6 5.90811e-7 -1 3.23899e-7 -1.70362e-6 -1 9.27599e-7 -1.11028e-6 -1 7.44176e-7 -8.35776e-7 -1 -1.66621e-6 -9.8853e-7 -1 8.42146e-7 1.82616e-6 -1 2.65661e-6 1.78742e-6 -1 8.81783e-7 -4.17614e-7 -1 2.46181e-6 -1.16592e-6 -1 1.29026e-6 -2.20757e-6 -1 -2.50918e-6 3.44847e-6 -1 1.52836e-7 4.34289e-6 -1 -2.99955e-7 9.57589e-7 -1 -0.9582253 0.2745113 -0.08029961 -0.8682324 0.4847624 0.1057267 -0.5474895 0.8315855 -0.09338575 -0.2869643 0.9522938 0.1038646 0.2051813 0.9731975 -0.1038617 0.4749817 0.8750272 0.09338021 0.8076019 0.5822855 -0.09339606 0.9311667 0.3546574 0.08453691 0.9777979 -0.1936932 -0.07996422 0.9502434 -0.3100103 0.03051155 0.5448186 -0.838546 -0.003615856 0.4738615 -0.8764429 -0.08545869 -0.1595705 -0.9794996 0.1229548 -0.4163012 -0.9008732 -0.1229664 -0.8959237 -0.4340178 0.09460026 -0.9203222 -0.3894084 0.03698945 -0.963543 0.2549138 0.08126372 -0.9528197 0.3018305 0.03214114 -0.5978792 0.7980246 -0.07547944 -0.3711249 0.9229308 0.1022983 -0.07508444 0.9951446 -0.06363672 0.3492922 0.9342301 0.07217395 0.5675754 0.8181746 -0.09191662 0.8699676 0.4808956 0.1090672 0.9826473 0.1120673 -0.1478015 0.9519978 -0.2789631 0.1260146 0.6828145 -0.7244349 -0.09465056 0.5441833 -0.8375669 0.04843592 0.04856246 -0.9978821 -0.04327815 -0.1310828 -0.9882986 0.07799428 -0.5197269 -0.8487659 -0.097368 -0.8070747 -0.576302 0.1284775 -0.9545202 -0.2844519 -0.08932238 -0.9978301 0.02038431 -0.06260639 -0.825141 0.5631245 0.04509025 -0.7982512 0.602321 0.002128422 -0.2401064 0.9702253 -0.0318098 -0.1808327 0.9829989 0.03182429 0.5034737 0.864003 -0.003607392 0.5203348 0.85363 -0.02382081 0.9533807 0.3006697 0.02575439 0.9596449 0.2812045 0.002390325 0.8746677 -0.4834665 -0.03488224 0.8272144 -0.5588207 0.05861431 0.2921091 -0.9545882 -0.05859673 0.2343748 -0.972135 0.004684984 -0.4795933 -0.8755452 0.05840301 -0.6107915 -0.7815095 -0.1271876 -0.9796504 -0.1682143 0.1094948 -7.32091e-7 5.19077e-7 -1 8.30836e-7 4.36459e-7 -1 -8.74671e-7 1.93475e-7 -1 3.35846e-7 0 -1 2.44379e-7 5.38927e-7 -1 -3.06769e-6 -1.61154e-6 -1 -1.50276e-6 1.2073e-6 -1 -1 5.85356e-7 -8.27818e-7 -1 0 0 -1 0 0 -1 -1.73651e-7 0 -1 0 6.84291e-7 -1 1.94303e-7 3.22441e-7 -1 5.23289e-7 3.90679e-7 -1 3.81052e-7 1.89192e-7 -1 4.18017e-7 1.46388e-7 -1 0 0 -1 0 -1.93011e-7 -1 -1.55935e-7 -1.31365e-7 -1 0 0 -1 0 0 -1 2.5143e-7 0 -1 2.50626e-7 0 -1 -4.46753e-7 0 -1 -5.47339e-7 4.92159e-7 -1 1.06182e-6 0 -1 -4.36624e-7 3.11155e-7 -1 -7.6871e-7 3.12914e-7 -1 -6.98865e-7 6.08636e-7 -1 3.14202e-7 -2.73636e-7 -1 1.79316e-7 -3.8482e-7 -1 1.24823e-7 -2.67876e-7 -1 -6.52536e-7 -7.36962e-7 -1 -6.09691e-7 -3.72125e-7 -1 -1.10949e-6 -4.1483e-7 -1 -1.00158e-6 0 -1 1.00717e-6 0 -1 4.37117e-7 -9.07606e-7 -1 2.49406e-7 2.25077e-7 -1 3.65821e-7 3.30136e-7 -1 0 8.79277e-7 -1 6.93487e-7 1.32734e-6 -1 2.77944e-7 0 -1 -4.91882e-7 0 -2.03352e-6 1.18419e-6 1 -1.40894e-6 8.20477e-7 1 6.59039e-6 -1.48823e-6 1 -8.77499e-6 -1.16647e-6 1 -3.42345e-7 8.5811e-7 1 1.61197e-5 3.44516e-6 1 3.43194e-6 2.17101e-6 1 -2.04214e-5 1.0103e-5 1 0.1773392 -0.08786916 -0.9802193 -0.1485451 0.2550956 -0.9554374 0.1751078 0.5709635 -0.8020835 -0.2080666 0.7890069 -0.5780799 0.1743481 0.9397195 -0.2941599 -0.1376621 0.9781896 0.1555446 0.04374772 0.9643475 0.2609984 -0.04783344 0.6461867 0.7616789 0.1069696 0.5814845 0.8064945 -0.1351329 0.05154329 0.9894859 0.1773315 -0.1619478 0.970735 -0.1233479 -0.4653006 0.8765163 0.1278328 -0.7602011 0.6369875 -0.09434723 -0.8509475 0.5167078 0.1055184 -0.9942534 0.01805579 -0.1054794 -0.9891432 -0.1023219 0.1164821 -0.765121 -0.6332628 -0.01060187 -0.72851 -0.6849532 -0.09150034 -0.2715438 -0.9580667 -0.151556 0.05988758 -0.9866328 0.1727663 0.3258363 -0.9295065 -0.208181 0.6594294 -0.7223666 0.2407314 0.8776277 -0.4145092 -0.1426457 0.9738875 -0.1766219 0.07573252 0.9229077 0.3774998 0.05203586 0.9282953 0.3681851 -0.04782062 0.5081674 0.8599297 0.04782932 0.4658254 0.883583 -0.04783195 -0.1448493 0.9882969 0.04782891 -0.1926571 0.9800999 -0.04374796 -0.7145909 0.6981733 0.08681547 -0.7635971 0.6398299 -0.1134775 -0.9725164 0.2033095 0.156327 -0.9875423 0.01794654 -0.1381652 -0.9063587 -0.3992797 0.151525 -0.780211 -0.6068863 -0.1485619 -0.5486774 -0.8227287 0.1485506 -0.2551088 -0.9554329 -0.6836633 0.07279241 -0.7261583 -0.494922 0.08864629 -0.8644039 -0.8053946 0.3828907 -0.4524757 -0.4803853 0.299097 -0.8244823 -0.685424 0.6366681 -0.3533378 -0.2820391 0.3800272 -0.8809275 -0.4575426 0.8773389 -0.1446761 -0.07433807 0.4881291 -0.8695998 -0.0692985 0.6047528 -0.7933925 0.09466856 0.5537236 -0.8273017 0.09529763 0.5352621 -0.8392931 0.3516461 0.7735201 -0.5272681 0.2583394 0.4057378 -0.8767198 0.6033101 0.4373776 -0.6668716 0.677659 0.2752501 -0.6819205 0.4504365 0.008238136 -0.8927705 0.7102638 -0.2888312 -0.6419517 0.5575734 -0.4346048 -0.7072698 0.6650651 -0.5671361 -0.4858446 0.3559524 -0.4449546 -0.8217744 0.4763505 -0.805823 -0.3517663 0.1940303 -0.544014 -0.8163338 -0.004828989 -0.6493791 -0.7604495 -0.2007211 -0.7236418 -0.6603436 -0.189653 -0.6967046 -0.6918342 -0.3886524 -0.5450724 -0.7428629 -0.3791571 -0.5345766 -0.7552932 -0.7294574 -0.4767607 -0.4905011 -0.436464 -0.2318561 -0.8693342 -0.904587 -0.2419556 -0.3509699 -0.4538698 -0.03429436 -0.8904078 -0.9820886 0.1048386 -0.1565595 -0.8496586 0.5090481 0.1376601 -0.8162793 0.5775921 0.008688032 -0.4024744 0.9136267 -0.05745005 -0.3141793 0.9434821 0.1055126 0.2330341 0.9667283 -0.1055061 0.3724879 0.9150893 0.1544816 0.779752 0.598911 -0.1824622 0.9065186 0.3468024 0.2407324 0.9846662 0.006101667 -0.1743421 0.8897656 -0.4351629 0.1376602 0.8456498 -0.5319417 -0.0437538 0.4202238 -0.9063641 0.04377204 0.318605 -0.9378375 -0.1376657 -0.1043884 -0.982138 0.1565508 -0.4397917 -0.8821143 -0.168694 -0.5969234 -0.7967346 0.09432059 -0.9046023 -0.4156783 -0.09437388 -0.9549759 -0.2440803 0.1686592 -0.9722636 0.1065917 -0.2081867 -0.85869 0.4824899 0.1727865 -0.7212843 0.6827859 -0.1164147 -0.4149453 0.8997969 0.1348554 -0.2404336 0.9612125 -0.1351382 0.3198308 0.9414176 0.1069642 0.3670687 0.9301137 0.01220995 0.8083384 0.5859105 -0.05742871 0.856112 0.5059087 0.105493 0.9958674 0.03766685 -0.08264005 0.9710867 -0.1710049 0.1665775 0.9068362 -0.4026347 -0.1246327 0.5899427 -0.8017873 0.09541875 0.4725421 -0.870487 -0.1376817 0.03569585 -0.984038 0.1743416 -0.2822191 -0.9365134 -0.2080747 -0.5660599 -0.805558 0.175079 -0.8288438 -0.5313653 -0.1751251 -0.9476518 -0.2422188 0.2080531 -0.9924559 0.07828587 -0.09435409 -0.9832601 0.1753866 0.04938679 -0.8065991 0.5907801 -0.01940596 -0.7760394 0.6234188 -0.09545624 -0.2849177 0.9455447 0.1573755 -0.1607419 0.9820495 -0.09869474 0.4205929 0.9071878 -0.0105803 0.4738332 0.8728754 0.1164929 0.8660936 0.490893 -0.09437245 0.9268489 0.3530078 0.1278149 0.9884356 -0.05149233 -0.1426309 0.9207696 -0.3299938 0.208056 0.7699218 -0.6138558 -0.1743602 0.4188951 -0.8975444 0.1376266 0.2938556 -0.9510716 -0.09545558 -0.2934085 -0.9429466 0.1573626 -0.4167284 -0.9036569 -0.09869945 -0.8564906 -0.5160553 -0.01053303 -0.8813689 -0.4578463 0.116472 1.35373e-6 -1.12915e-6 1 3.18529e-6 4.39901e-6 1 4.63292e-6 4.49441e-6 1 4.06441e-6 0 1 7.11055e-7 -1.18134e-6 1 -2.21279e-7 2.09464e-6 1 -2.3189e-6 1.11321e-6 1 -3.46329e-6 5.26041e-6 1 -7.06331e-6 1.65762e-6 1 -7.32404e-7 1.69304e-6 1 -7.68834e-7 1.43435e-6 1 9.84865e-6 1.11203e-6 1 9.27566e-6 4.27477e-6 1 -2.76148e-6 -1.27265e-6 1 -2.63853e-6 -2.06594e-6 1 2.04252e-7 1.59927e-7 1 1.58352e-6 -1.15382e-6 1 1.51181e-6 -1.22335e-6 1 -0.2597121 0.7792428 -0.5703773 -0.2955491 0.6027035 -0.7412149 -0.5034577 0.6621367 -0.5550721 -0.001063346 0.7726956 -0.6347759 0.002225518 0.589392 -0.8078441 0.3341001 0.4671114 -0.8186477 0.3831604 0.6564934 -0.6497727 6.93652e-7 1.43672e-6 1 -1.67447e-6 4.42447e-6 1 -3.72324e-6 1.60395e-6 1 4.5464e-6 -1.95856e-6 1 4.22323e-6 -2.69767e-6 1 1.67193e-7 7.85963e-7 1 1.67478e-7 7.87303e-7 1 -1.89149e-6 -5.41884e-7 1 -1.1249e-6 -2.03992e-6 1 2.12906e-6 1.34613e-7 1 0 2.2916e-6 1 -4.43587e-7 8.11567e-7 1 -1.37015e-6 6.31871e-7 1 -1.91017e-6 9.92001e-7 1 1.10015e-4 3.26975e-5 1 1.33679e-4 1.52456e-5 1 1.77012e-5 -7.44532e-5 1 -6.80362e-6 -2.38221e-6 1 9.58696e-7 8.34556e-7 1 7.76764e-7 1.50087e-6 1 1.12692e-6 6.41776e-7 1 -3.04714e-6 4.50233e-6 1 -3.32884e-6 5.07913e-7 1 5.21707e-7 4.70971e-7 1 4.39036e-7 6.18525e-7 1 9.18083e-7 8.52394e-7 1 1.4141e-6 -1.73824e-6 1 -2.02352e-6 -2.97044e-6 1 -2.06094e-6 -1.17974e-6 1 5.73922e-7 3.28529e-7 1 5.2567e-7 -7.59551e-7 1 -6.31098e-5 -9.51673e-6 1 -1.11304e-4 6.11646e-5 1 -2.2258e-4 -9.08339e-6 1 -1.32536e-4 -3.81866e-5 1 -1.37588e-4 -4.88323e-5 1 -3.04493e-7 -1.1012e-6 1 -2.5948e-7 -1.36403e-6 1 0.01471424 0.9724759 0.2325384 0.07774919 0.9530619 0.2926226 0.03987115 -0.006677865 -0.9991825 -0.03986769 0.4930928 -0.8690629 0.1533895 0.5971893 -0.787297 -0.1447653 0.8172164 -0.5578535 0.1357214 0.977735 -0.1600437 -0.1278194 0.9916337 0.01802349 0.1233426 0.9126654 0.3896518 -0.1021759 0.795792 0.5968879 0.08096367 0.6093891 0.7887268 -0.08809781 0.4526278 0.8873369 0.1614728 0.08611243 0.983113 -0.2226955 -0.1690685 0.9601159 0.2226801 -0.6090273 0.7612485 -0.1615067 -0.7948895 0.5848643 0.1084287 -0.9704753 0.2154548 -0.1084278 -0.9934511 0.03603368 0.1615115 -0.9166162 -0.3656894 -0.2226955 -0.7811893 -0.5832238 0.1701785 -0.4645306 -0.8690516 -0.1533469 -0.1374086 -0.9785722 -0.06502836 0.006676495 -0.997861 0.05552399 0.1059868 -0.9928162 -0.08992207 0.4695135 -0.8783342 0.1351397 0.5967862 -0.7909384 -0.1069622 0.9333838 -0.3425692 0.04783099 0.9618924 -0.2692123 -0.04782897 0.9355973 0.3498145 -0.01220363 0.9301102 0.3670775 0.05745124 0.5859289 0.8083235 -0.05744999 0.5315678 0.8450652 0.008708298 0.02144128 0.9997322 0.03486299 0.006182074 0.999373 -0.03858745 -0.5174674 0.8548324 -0.004646062 -0.5324529 0.846447 0.06944513 -0.9445624 0.3209037 0.05465269 -0.9474958 0.315063 -0.1489292 -0.9703509 -0.1903663 0.2333733 -0.8702328 -0.4338567 -0.1979301 -0.5923693 -0.7809753 0.1134689 -0.4148409 -0.9027912 -0.2670593 0.8151923 0.5139464 -0.3107456 0.6131497 0.7262814 -0.4503136 0.6454229 0.6169657 0.3171957 0.4842439 0.8154109 0.2696189 0.7129992 0.6472541 0.8379043 0.5441441 -0.04270172 0.9657913 0.2589844 -0.01320266 0.7333598 0.6798015 0.007298409 0.4748137 0.8598325 -0.1877229 0.5909453 0.7948878 0.1376118 0.7333598 0.6798015 -0.007298409 0.8386694 0.5446409 0 0.9644201 0.2586212 0.05485445 0.5006859 0.3432884 -0.7946488 0.8386692 -0.5446412 0 0.8386692 -0.5446412 0 1 -2.40358e-6 8.82865e-7 1 3.61697e-6 0 1 -1.34333e-6 4.93421e-7 1 -5.08714e-7 -8.69576e-7 1 5.56159e-6 0 1 1.06051e-6 1.20185e-6 1 -9.179e-7 -1.56902e-6 1 0 3.99219e-6 1 1.54683e-6 -5.54553e-6 1 -8.68164e-7 -9.83869e-7 1 -4.06048e-7 1.26114e-6 1 0 -3.49628e-6 1 -1.10289e-6 3.42545e-6 1 2.08148e-6 3.30982e-7 0.8386691 -0.5446412 0 0.8386691 -0.5446412 0 1 0 0 1 -3.73624e-6 -5.38386e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.48969e-7 7.31762e-7 1 9.43702e-7 -6.15325e-7 1 -2.53273e-6 -8.41178e-7 1 5.74725e-6 0 1 -2.75184e-7 1.87756e-6 1 0 3.78243e-6 1 -1.31512e-6 8.57505e-7 1 -2.50002e-6 -5.82864e-7 1 0 0 1 0 0 1 0 0 1 -2.02871e-6 1.26405e-7 1 -2.10398e-6 0 1 7.76916e-6 -1.67439e-6 1 0 0 1 0 0 1 0 0 0.2931313 -0.5447029 0.7857308 0.2739694 -0.5248564 0.8058949 0.2516412 -0.5258706 -0.812488 0.3287266 -0.605194 -0.7250374 -0.03029996 -0.9989936 0.03306686 0.06133008 -0.9976958 -0.02901035 0.2312389 -0.9727091 -0.019122 0.3176364 -0.9467138 0.05329394 0.5089851 -0.8585497 -0.06186026 0.7009319 -0.7114456 0.05039477 0.7615367 -0.647509 -0.02817851 0.9109486 -0.4117857 0.02459841 0.9417926 -0.3322427 -0.05139666 0.98312 -0.1803591 -0.03074848 0.9954246 -0.08643054 0.04073655 0.9865809 0.1589797 -0.03719794 0.9681459 0.2503302 0.00532931 0.9463691 0.3209583 -0.03703236 0.8282303 0.559807 0.02551221 0.7750907 0.6299728 -0.04866886 0.6743201 0.7375005 -0.03721982 0.5941795 0.8034135 0.0384407 0.4135739 0.9097826 -0.03538691 0.2926653 0.9555939 0.03445827 0.1755647 0.9839912 -0.03063505 -0.0424205 0.9986869 0.02872568 -0.1182299 0.992434 -0.03311353 -0.372598 0.9272125 0.03804999 -0.4620654 0.8858559 -0.04189115 -0.6602109 0.7501569 0.03723412 -0.7307679 0.6816415 -0.03664815 -0.8860486 0.4621519 0.0365166 -0.9039773 0.4275406 -0.005833208 -0.9941099 0.1027244 -0.03454488 -0.9985483 0.02865052 0.04561263 -0.9658786 -0.2569957 -0.03212106 -0.931618 -0.3595362 0.05311983 -0.8338814 -0.5478428 -0.06715637 -0.6806713 -0.730068 0.06072318 -0.5819489 -0.8120574 -0.04356825 -0.2559118 -0.9657756 -0.04226851 -0.3614896 -0.9312606 0.04559695 -0.2208831 -0.7628876 0.6076292 -0.2370896 -0.4224973 0.8748055 -0.4499582 -0.5378133 0.7129477 -0.4302212 -0.8214959 -0.374238 -8.64999e-7 3.08712e-7 -1 -0.01537179 4.4124e-4 -0.9998817 -8.34105e-7 5.56337e-7 -1 -0.02656418 0.01299148 -0.9995627 -0.02651017 -0.01014184 -0.9995971 -0.02240985 0.001275956 -0.9997481 0 0 -1 2.56454e-7 0 -1 0 0 -1 -1.73347e-5 -2.3015e-6 -1 2.89455e-6 4.31293e-7 -1 -0.04080671 0.01579749 -0.9990422 -3.20424e-4 -7.87185e-4 -0.9999997 -0.0345385 0.004767 -0.999392 -0.007586419 -0.002928256 -0.9999669 -0.007648825 -1.68733e-4 -0.9999708 -3.1519e-7 0 -1 -9.93311e-7 2.50641e-7 -1 -5.99387e-7 2.00387e-7 -1 3.21981e-7 -1.36769e-7 -1 0.02882009 -0.0051409 -0.9995714 -6.63568e-4 0.01827943 -0.9998328 1.57713e-7 9.63646e-7 -1 -0.007384836 0.01592928 -0.9998458 -7.30353e-4 -0.002179086 -0.9999973 0 0 -1 0 3.72506e-7 -1 0.005453586 0.01752656 -0.9998316 1.80695e-7 -1.84845e-6 -1 7.0577e-4 0.03976434 -0.9992088 -0.01663446 0.02005642 -0.9996604 4.28195e-7 0 -1 1.86414e-6 -6.06744e-6 -1 0.02051538 0.00174117 -0.999788 0.02976107 -0.02179872 -0.9993193 2.85634e-4 0.05732184 -0.9983557 -4.10561e-4 0.0238704 -0.9997149 -1.44342e-7 3.09273e-7 -1 -2.99267e-7 -4.25886e-7 -1 0.0377891 0.009716749 -0.9992385 1.37823e-6 -6.79458e-7 -1 -3.31876e-7 9.87226e-7 -1 0.01000475 0.005197167 -0.9999364 0 2.38126e-7 -1 -3.51943e-7 0 -1 -1.62152e-7 6.79121e-7 -1 8.31412e-7 2.99448e-6 -1 -0.00356245 -0.01276659 -0.9999121 0.003965854 0.01727735 -0.999843 -2.58476e-7 0 -1 6.38071e-7 -7.41968e-7 -1 -0.001043736 -0.001118838 -0.9999988 0.003855109 0.004710137 -0.9999815 0.002348184 -0.002380967 -0.9999945 0.003044247 -0.002233266 -0.999993 0.00307095 -0.001390337 -0.9999943 0.004745781 -4.1391e-4 -0.9999886 0.01774013 0.002708971 -0.999839 9.7972e-5 -3.23833e-4 -1 -0.5130844 0.3504532 -0.7835349 -0.9886494 0.04950064 -0.1418526 -0.9486678 0.2826918 0.1418265 -0.7623128 0.6124359 -0.2092881 -0.5106436 0.8339285 0.2092997 -0.09948503 0.9757736 -0.1948555 0.04853242 0.9967883 0.06370055 0.6000049 0.7999947 -0.001622021 0.6518532 0.7473969 -0.1283946 0.8947229 0.4245953 0.1385267 0.9641098 0.1115978 -0.2409111 0.9313795 -0.2729317 0.240916 0.7872269 -0.59151 -0.1743264 0.5122221 -0.8403556 0.1772882 0.3514209 -0.9317385 -0.0914697 -0.1784459 -0.983893 -0.01056486 -0.1872938 -0.9822742 0.007642686 -0.6231402 -0.7791266 0.0682488 -0.7436226 -0.6386374 -0.1979082 -0.9371565 -0.2968778 0.1833065 -0.01355314 0.9998021 0.01456636 -0.023054 0.9996294 -0.01447463 -0.03339695 0.9992222 -0.02096855 -0.3384725 0.9409036 -0.01169359 -0.4692909 0.8830118 0.007487595 -0.6269197 0.7787826 -0.02166742 0.002203166 0.9997299 0.02313131 -0.004989624 0.9998821 -0.01452547 0.5032189 0.8635004 -0.03373318 0.4376334 0.8990563 -0.01322096 0.008585453 0.9999271 -0.008487462 0.009620189 0.9999356 -0.006040096 0.03339177 0.9992224 -0.02096527 0.9537928 0.2950541 0.05676573 0.8872441 0.4314902 -0.1631387 0.7212385 0.6820781 0.1207665 0.4165928 0.8985371 -0.1381361 0.246701 0.9658333 0.0794022 -0.1328541 0.9889424 -0.06589788 -0.2039687 0.9781653 0.03986871 -0.6651665 0.7456312 -0.03984677 -0.6951393 0.7186105 0.01950216 -0.9259662 0.3771004 -0.0195434 -0.9398778 0.3391755 0.03987151 -0.9652777 -0.2559929 -0.05202275 -0.9612978 -0.2753983 -0.007902503 -0.5983873 -0.7986714 0.06369239 -0.5196036 -0.8486074 -0.09938645 -0.04466497 -0.9940517 0.09932839 0.0210247 -0.9996588 -0.01549601 0.5271614 -0.8444299 -0.09507369 0.6291553 -0.7672239 0.1246241 0.9409364 -0.3235229 -0.09985786 0.959447 -0.2817087 -0.01008129 0.971405 0.1477 -0.1858951 0.7519455 0.6313399 0.1897046 0.5848607 0.7948928 -0.1615037 0.1853458 0.9743247 0.1278216 0.06375396 0.9965047 -0.05397945 -0.4309546 0.9023313 0.008724927 -0.4699758 0.8784027 0.08678489 -0.8409268 0.5266016 -0.1246311 -0.9045482 0.4156402 0.09505528 -0.9942311 -0.1061332 0.01550167 -0.9803195 -0.1705964 -0.09935003 -0.7951992 -0.5999712 0.08770936 -0.7144572 -0.6932866 -0.09436434 -0.297378 -0.950091 0.09430521 -0.2038912 -0.977747 -0.04938876 0.247412 -0.9687172 0.01934856 0.2610029 -0.9643448 0.04377835 0.7815525 -0.6216328 -0.05242466 0.791096 -0.611339 -0.02077859 0.9959743 0.007527112 0.08932226 -0.8379044 0.5441441 0.04270136 -0.9657917 0.2589827 0.01320213 -0.7333984 0.6797599 -0.007296502 -0.5958296 0.8014566 -0.05152177 -0.553718 0.8284348 0.0842148 -0.7333971 0.6797614 0.007296562 -0.8386694 0.5446409 4.74402e-7 -0.9644212 0.2586169 -0.05485463 -0.9901224 0.0781117 -0.1164307 -0.8881224 0.4393771 0.1348569 -0.7909182 0.5968062 -0.1351695 -0.3688601 0.9245726 0.09543502 -0.2684941 0.9593628 -0.08679825 0.2427313 0.962057 0.1246109 0.414747 0.888647 -0.1956819 0.8287681 0.5242703 0.1956632 0.9270944 0.3009505 -0.223438 0.9762464 -0.1155045 0.1833076 0.8804904 -0.452344 -0.1418509 0.7695735 -0.6292943 0.1083762 0.4464784 -0.8800929 -0.161535 0.2848338 -0.9528793 0.1043586 -0.1642814 -0.9855542 0.04116427 -0.2840529 -0.942732 -0.1748438 -0.696287 -0.7005311 0.1563348 -0.8315212 -0.5330477 -0.1563096 -0.9811362 -0.1352283 0.1381486 -0.008586108 0.9999271 0.008488237 -0.009620964 0.9999355 0.006040632 -0.03339701 0.9992221 0.02096855 0.01355391 0.9998021 -0.01456058 0.02305257 0.9996294 0.01447373 0.03339177 0.9992224 0.02096527 -0.9824862 0.07918971 -0.168671 -0.9714917 0.2308477 0.05397325 -0.7365988 0.6762739 -0.008716166 -0.676635 0.7233359 -0.1376601 -0.2544314 0.9477385 0.1925006 0.03689694 0.9716873 -0.233372 0.4676195 0.8614891 0.1979107 0.6303774 0.7732769 -0.06831812 0.9207562 0.3900628 -0.007697522 0.9324323 0.3551506 0.06661868 0.9589208 -0.2836359 -0.004657685 0.9397943 -0.3273085 -0.09826493 0.651772 -0.7498786 0.1134697 0.4972871 -0.8533901 -0.1563038 0.09346938 -0.9859905 0.1381526 -0.1493175 -0.9771026 -0.151574 -0.4737091 -0.8632622 0.1742927 -0.7362897 -0.6323292 -0.2409093 -0.9227931 -0.3234884 0.2093042 -0.9325327 0.3268981 -0.1533636 -0.8614928 0.4840527 0.1533731 -0.4172153 0.9046645 -0.08667939 -0.4541853 0.8908367 0.01121258 0.2042272 0.9768484 -0.06370419 0.2936986 0.9507315 0.09925168 0.6961027 0.7125611 -0.08773684 0.7784124 0.6206203 0.09436494 0.9801615 0.174304 -0.09434896 0.9856635 -0.004436075 0.1686646 0.908606 -0.3752784 -0.1833062 0.7094135 -0.6832867 0.1727771 0.4687674 -0.8635631 -0.1857854 0.2295682 -0.9643459 0.1316634 -0.2978695 -0.9515978 -0.07573235 -0.2592551 -0.9656794 0.01581025 -0.7355495 -0.6753172 -0.05397862 -0.7812552 -0.622257 0.04936259 -0.9820377 -0.1871933 -0.02367734 -0.9708514 -0.230678 0.06507909 -0.8386708 -0.5446386 0 -0.8386708 -0.5446386 0 -1 6.89843e-7 0 -1 0 0 -1 1.25266e-7 0 -1 -2.72642e-7 0 -1 -5.67573e-7 1.65492e-7 -1 0 0 -1 -1.76162e-7 1.17487e-6 -1 0 0 -1 0 0 -1 -2.40132e-7 0 -1 4.94289e-7 0 -1 0 0 -1 0 -5.91622e-7 -1 0 0 -0.8386709 -0.5446386 0 -0.8386709 -0.5446386 0 -1 0 0 -1 0 4.72202e-7 -1 -1.42313e-7 -4.33549e-7 -1 1.27375e-7 0 -1 0 0 -1 -3.46016e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -4.00963e-7 -1 0 -4.16242e-7 -1 0 0 -1 0 0 -1 0 -1.33364e-7 -1 3.38915e-7 -1.37281e-7 -1 4.1553e-7 0 -1 8.12215e-7 0 -1 -5.18057e-7 -1.3176e-7 -1 -9.18407e-7 0 -1 3.17678e-7 -1.367e-7 -1 -7.46183e-7 3.2109e-7 -1 0 0 -1 0 0 -1 0 0 2.40057e-5 -1.68927e-5 -1 -4.73378e-7 -1.34571e-6 -1 1.1242e-6 3.19585e-6 -1 2.57956e-6 -2.35819e-6 -1 -6.47634e-5 -3.84255e-5 -1 -5.99557e-5 -4.72926e-5 -1 -3.17417e-6 2.15036e-6 -1 -2.98904e-6 3.81113e-6 -1 -2.86361e-5 2.1646e-5 -1 -2.9434e-5 2.14862e-5 -1 -3.00884e-5 2.48082e-5 -1 7.54565e-6 5.14638e-6 -1 1.54032e-6 -4.82098e-6 -1 -4.18175e-6 1.30883e-5 -1 2.29869e-5 2.10575e-5 -1 6.40314e-6 -4.72374e-6 -1 9.17989e-6 -6.77221e-6 -1 2.12157e-5 -4.33042e-6 -1 8.0312e-6 8.99185e-7 -1 2.48323e-5 -5.84578e-6 -1 2.37474e-5 -1.1507e-5 -1 6.03545e-6 -5.15721e-6 -1 4.21584e-6 -1.50637e-5 -1 -8.01066e-6 1.29514e-6 -1 2.68523e-6 8.11436e-6 -1 2.74625e-7 -7.24467e-6 -1 -8.24674e-6 -3.62419e-6 -1 0 1.27416e-6 -1 0 0 -1 -1.67457e-5 1.62301e-5 -1 -1.68959e-5 1.60217e-5 -1 -1.09243e-6 -6.4333e-7 -1 1.39966e-5 8.24258e-6 -1 1.47182e-5 3.11693e-5 -1 3.51082e-5 3.45379e-5 -1 2.78707e-6 7.07899e-7 -1 1.69768e-6 8.87724e-6 -1 1.23837e-5 1.08453e-5 -1 8.90462e-6 2.05986e-6 -1 6.77957e-6 2.51743e-6 -1 -6.36834e-6 -9.83972e-6 -1 -2.54686e-5 7.75025e-6 -1 -4.64125e-6 2.44601e-5 -1 -1.45347e-6 1.10495e-5 -1 6.39621e-6 1.02592e-5 -1 1.64491e-5 2.63835e-5 -1 1.12475e-5 2.86555e-5 -1 -6.91638e-6 -1.12305e-5 -1 -1.52813e-5 -5.17289e-6 -1 -7.80971e-6 1.00336e-6 -1 -8.37899e-6 1.75359e-6 -1 3.25162e-5 9.47861e-7 -1 1.38931e-5 -6.05021e-5 -1 9.95892e-7 2.52951e-7 -1 -0.318409 0.9478296 0.01531916 -0.5399156 0.8416433 -0.01129543 -0.6211659 0.7836006 0.01108771 0.6339554 0.772887 0.02731794 0.3802819 0.9248233 0.009351551 0.2634574 0.9642314 -0.02912014 0.6877623 -0.001993656 -0.7259332 0 0 1 0 0 1 0.1321449 -0.9910928 0.01651787 0.06651932 -0.9977852 0 0.03615629 0.9975399 0.06005775 0.01548153 0.998049 -0.06048661 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0.8414316 0.5402776 0.009643554 0.8287695 0.5591281 -0.02273583 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0.06651926 0.9977852 0 0.1321462 0.9910927 -0.01651823 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0.2119064 -0.1160407 -0.9703764 -0.1329905 0.4831611 -0.865372 -0.009743213 0.5548311 -0.831906 0.04595553 0.9141799 -0.4026951 -0.04597574 0.9386448 -0.3418073 0.01264786 0.9695342 0.2446291 -0.06062358 0.9770366 0.2042648 0.123224 0.6884299 0.7147589 -0.161439 0.5275813 0.8340237 0.1390063 -0.02549344 0.9899634 -0.008472204 -0.1174901 0.9930379 -0.07616639 -0.6311867 0.7718822 0.1406753 -0.7402549 0.6574445 -0.1108974 -0.9593176 0.2596374 0.09336996 -0.9944539 0.04840928 -0.1082355 -0.9398133 -0.3240926 0.1769495 -0.8232305 -0.539426 -0.2559146 -0.3947472 -0.8824299 0 0 -1 0 0 -1 0.2746848 0.9614008 -0.01602315 0.1414217 0.9899495 0 0 0 1 0 0 1 0.2746853 -0.9614006 0.01602339 0.1414204 -0.9899497 0 0.5828762 -0.3791044 -0.7187039 0.5010662 -0.3338372 -0.7984268 0.4708691 -0.8822031 -2.83014e-4 0.4656476 -0.8849703 -2.36094e-5 -0.005384385 -0.4653937 -0.8850874 0.005939424 -0.5931565 -0.8050653 6.3364e-4 -0.7479915 -0.6637082 -0.01084476 -0.3384857 -0.9409092 -0.3388082 -0.9408553 5.84697e-4 -0.4564924 -0.8897242 -0.002322733 -0.5985368 -0.8010944 0.001270353 -0.4782154 -0.3264185 -0.8153288 -0.6915756 -0.4481915 -0.566434 -0.8340195 -0.001660406 -0.5517325 -0.8434992 0.5366066 -0.02371537 -0.8315213 0.5554584 0.00619924 4.3646e-7 0 1 3.21982e-7 0 -1 0 0 -1 0 -1 0 0 -1 0 -0.02629828 0.9976626 -0.06306952 -0.03602594 0.9920893 -0.1202543 -0.06651926 -0.9977852 0 -0.1321449 -0.9910928 -0.01651793 0 3.2175e-7 1 -1.28793e-6 0 1 -3.73891e-7 0 -1 0 5.01995e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0.9998611 -0.01666438 -0.0665192 0.9977852 0 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 -0.1402505 0.09007674 -0.9860101 0.1677595 0.4020273 -0.9001283 -0.167753 0.6853275 -0.7086504 0.1947655 0.8986142 -0.39314 -0.1947774 0.9807755 -0.01188737 0.1112398 0.9446631 0.3086055 -0.1029972 0.743718 0.6605111 0.04106718 0.6739771 0.7376098 -0.04434013 0.08224713 0.9956252 0.07874852 0.004469215 0.9968845 -0.09100097 -0.4910508 0.8663647 0.1256006 -0.6418092 0.7565087 -0.140672 -0.9203147 0.3650098 0.07617747 -0.973396 0.2160952 0.004537582 -0.9287971 -0.370561 -0.05561149 -0.914736 -0.4002069 0.003688216 -0.458761 -0.888552 0.1257678 -0.3852186 -0.914215 0 0 -1 0 0 -1 0 -1 0 -0.2745797 -0.9610306 -0.03203427 0 0 1 0 0 1 -0.2746844 0.9614009 0.01602309 -0.1414219 0.9899494 0 -0.995171 -0.03019726 -0.09339618 -0.9613603 0.2549502 0.1038597 -0.699158 0.7055024 -0.1159503 -0.4423614 0.8859749 0.139158 0.0674262 0.9871013 -0.1452067 0.4462664 0.8856092 0.1286187 0.8053967 0.5786413 -0.1284922 0.9227168 0.381097 0.05795544 0.9841842 -0.1750211 0.0273714 0.949834 -0.2995635 -0.08987194 0.6769307 -0.7325009 0.07216262 0.5288346 -0.8471212 -0.05214995 0.09429842 -0.9949405 0.03466051 -0.03991985 -0.9976995 -0.0547921 -0.4542444 -0.8872165 0.08067739 -0.7154731 -0.6919046 -0.09678024 -0.897998 -0.4324725 0.08103746 -0.9328977 0.3298534 -0.1445636 -0.6539045 0.742635 0.144576 -0.3523003 0.9312469 -0.09307843 -0.009558439 0.9982661 0.0580824 0.2607682 0.963652 -0.05809211 0.5519043 0.8299956 0.08067911 0.789339 0.606275 -0.09682238 0.9707995 0.2215803 0.09192806 0.990147 -0.0845099 -0.1116557 0.8788338 -0.4633197 0.1139565 0.4979217 -0.8590011 -0.1191275 0.3684634 -0.9289878 0.03487569 -0.4536759 -0.8911504 -0.005396842 -0.4190211 -0.9067573 0.0470367 -0.9179754 -0.388419 -0.08032333 -0.9823079 -0.1099806 0.1515768 -0.9695369 0.2174113 -0.11283 -0.854659 0.515011 0.06573951 -0.5486319 0.8333169 -0.06771987 -0.41821 0.9068588 0.05203503 0.2353159 0.969944 -0.06192785 0.3215132 0.9463706 0.03181022 0.8751724 0.4837843 -0.005105435 0.854793 0.517445 0.0397467 0.9941044 -0.08214032 -0.07077676 0.9554861 -0.2799741 0.09306341 0.6390791 -0.7649748 -0.07994699 0.5196378 -0.8524808 0.05703568 -0.1223432 -0.9908481 -0.05702877 -0.2398933 -0.9693211 0.05355316 -0.776849 -0.6269532 -0.05861008 -0.7980161 -0.6021391 -0.02447545 -0.9932421 -0.07835048 0.08562356 -0.8426482 0.5384402 0.005121827 -0.8353567 0.5492527 0.02237802 0.001290977 0.9999451 -0.01040762 -0.002147793 0.9996055 -0.0280025 0.8321431 0.5545387 0.004963457 0.8272135 0.5618463 -0.006829738 0.8340137 -0.5517438 -1.37083e-4 0.8332317 -0.5529239 1.00307e-4 -2.03455e-4 -1 -6.40047e-5 0.001678884 -0.9999979 -0.001232087 -0.8316579 -0.5552873 -0.001026391 -0.8355433 -0.5494247 1.17581e-4 6.35813e-6 9.81581e-6 1 2.45199e-5 -8.3466e-6 1 -1.1748e-5 -2.08115e-5 1 -1.38174e-5 2.25762e-5 1 6.20675e-6 1.54198e-5 1 -5.1456e-6 -6.92333e-6 1 9.12164e-6 -9.0946e-6 1 2.20542e-5 2.82981e-5 1 3.29261e-5 2.52641e-5 1 7.0334e-6 -6.03002e-6 1 -7.81894e-6 2.68551e-6 1 -1.10782e-5 1.08315e-6 1 -2.07367e-6 1.17058e-5 1 -7.20193e-6 1.36663e-5 1 -1.2867e-5 -1.05039e-5 1 -2.67941e-6 8.48033e-6 1 -2.12653e-5 -8.09774e-6 1 -3.80544e-6 -6.13732e-6 1 4.22826e-6 6.81923e-6 1 5.17702e-6 -1.21421e-5 1 3.15148e-5 -6.3842e-6 1 3.83115e-5 -2.45644e-5 1 -1.05553e-5 1.37164e-5 1 4.59154e-6 4.72086e-6 1 1.02243e-5 1.05122e-5 1 1.05109e-5 9.84708e-6 1 2.65068e-6 7.97753e-6 1 -2.0319e-5 2.94349e-5 1 -8.03849e-6 -3.23622e-5 1 3.33119e-6 -1.55456e-5 1 -3.54103e-6 1.65249e-5 1 3.40533e-5 3.25239e-5 1 4.90635e-6 -1.01447e-5 1 5.65983e-6 -1.07066e-5 1 3.00481e-6 5.37217e-6 1 -1.4495e-5 1.18738e-5 1 -2.65902e-5 2.85818e-5 1 4.50528e-5 -3.17064e-6 1 -8.32942e-6 -1.03247e-5 1 -4.89722e-6 -2.19922e-6 1 1.79153e-5 1.4863e-6 1 1.65891e-5 3.7451e-5 1 -1.27775e-5 8.9589e-6 1 1.40272e-7 -1.10564e-5 1 5.30902e-6 -4.36698e-6 1 9.06238e-6 -1.26041e-5 1 4.47611e-5 -3.1165e-5 1 -3.99543e-7 -1.07415e-5 1 3.33304e-7 -7.90591e-6 1 1.53926e-5 -3.66582e-6 1 1.65156e-6 4.06663e-6 1 -6.47442e-7 -1.59419e-6 1 -1.91684e-5 -1.69083e-6 1 -1.71204e-5 -3.35803e-5 1 3.04562e-6 -1.13282e-5 1 -0.4699205 0.3228163 0.821562 -0.001196622 0.795469 0.6059932 0.003236293 0.5421838 0.8402537 0.5894206 0.3731623 0.7164727 0.1823306 0.1355676 0.9738465 0.6912041 2.74387e-4 0.7226596 0.7334299 -2.50257e-4 0.6797651 0.549739 -0.3640353 0.7518413 0.610798 -0.3977695 0.6846206 -8.20807e-4 -0.7630577 0.6463299 0.00159496 -0.6268592 0.7791309 -3.39562e-6 -0.1656743 0.9861805 -4.41113e-4 -0.1335778 0.9910383 -0.6650791 -0.4303285 0.6103174 -0.569424 -0.3790629 0.7294298 -0.7916122 -0.001985907 0.6110206 0.9890003 0.1363041 0.05744069 0.984392 0.1755979 -0.01174306 0.8048794 0.5895014 -0.06824553 0.6962819 0.7005392 0.1563215 0.3639366 0.9235605 -0.1207736 0.1639501 0.9835047 0.07641166 -0.07993167 0.9938666 -0.07642102 -0.2843268 0.9510871 0.1207961 -0.5956328 0.7941195 -0.1208127 -0.7697944 0.6294705 0.1057519 -0.8873486 0.4526112 -0.08806526 -0.9814628 0.1466882 0.123342 -0.9779984 -0.1433433 -0.151565 -0.9305644 -0.3514405 0.1026626 -0.7157647 -0.6953104 -0.06499642 -0.618103 -0.7806724 0.09219121 -0.3350966 -0.9344408 -0.1205434 -0.07959175 -0.9895186 0.1204908 0.2946522 -0.9469377 -0.1284092 0.3943579 -0.9175226 0.05132567 0.8858217 -0.4601725 -0.05967605 0.8961904 -0.4433876 -0.01581823 0.9974673 -0.006653249 0.07081383 0.9819058 0.1496788 -0.1160051 0.8206625 0.5473251 0.1641594 0.600273 0.7693781 -0.2184714 0.3994401 0.9067429 0.1351475 -0.184134 0.9757019 -0.1187452 -0.2040216 0.9760307 -0.07575726 -0.6916904 0.7079701 0.1426283 -0.8189938 0.5506098 -0.1614871 -0.982598 0.1137331 0.1468536 -0.9929615 -0.03465735 -0.1132535 -0.7546889 -0.6421481 0.134501 -0.698947 -0.7117915 -0.0694679 -0.06666392 -0.9977439 0.007935047 -0.07727926 -0.9968833 -0.01586085 0.4952298 -0.8668618 0.05742818 0.5717309 -0.8136273 -0.1055205 0.89196 -0.4444996 0.08262926 0.9427118 -0.3260068 -0.07081085 0.9879111 -0.1505993 0.03676366 0.929205 0.3534629 0.1078984 0.8404252 0.5035296 -0.2003577 0.4487592 0.880203 0.1544603 0.3141826 0.9434803 -0.1055195 -0.2037141 0.9744739 0.09434634 -0.3473423 0.9289857 -0.127824 -0.6916936 0.7079688 0.142619 -0.8378024 0.5270164 -0.1426216 -0.9787476 0.174057 0.1084309 -0.9892888 -0.03451949 -0.1418317 -0.8920318 -0.4005892 0.2093029 -0.6540304 -0.7056326 -0.2726296 -0.3974245 -0.897211 0.1925259 0.04459524 -0.9918687 -0.1191961 0.1481678 -0.9884695 0.03121739 0.599218 -0.7998265 -0.0348609 0.6558053 -0.748869 0.09546971 0.9567767 -0.2445581 -0.1573836 9.61878e-6 -8.01415e-6 1 5.34553e-5 -1.2033e-5 1 3.81221e-5 -6.85282e-5 1 -2.16823e-6 -4.24077e-5 1 1.0168e-5 -1.67214e-5 1 -4.1455e-6 6.8173e-6 1 -8.26097e-7 6.13236e-7 1 1.92909e-5 1.84262e-5 1 2.33167e-5 1.69086e-5 1 2.9417e-6 5.32045e-7 1 1.83234e-5 2.32646e-5 1 1.24689e-5 1.58805e-6 1 3.00132e-6 2.53267e-6 1 5.31556e-6 4.48555e-6 1 7.10251e-6 2.26488e-6 1 -8.60652e-6 3.37271e-6 1 -8.49909e-6 6.30912e-6 1 -0.9223827 -0.3787714 0.0757783 -0.8536516 -0.5114467 -0.09849447 -0.5232993 -0.8452208 0.1084423 -0.3406044 -0.9353301 -0.0956366 0.2164486 -0.9749836 0.05056571 0.2061614 -0.9779024 0.03470444 0.7803833 -0.6243373 -0.03470849 0.8105052 -0.5843754 0.03983253 0.9925786 0.1148949 -0.03983461 0.9857727 0.1644641 0.03469574 0.6985397 0.7149757 -0.02919012 0.6161007 0.7822449 0.09226441 0.2303 0.9674288 -0.1050875 -0.06077682 0.995255 0.07598567 -0.2718623 0.9608127 -0.05412924 -0.517393 0.8530194 0.06828153 -0.7045392 0.704844 -0.08257949 -0.9278095 0.3598185 0.09848982 -0.9731277 0.217443 -0.07576936 -3.92025e-6 6.3e-7 1 4.70975e-5 -7.04896e-5 1 -1.26291e-5 2.59544e-6 1 -9.06739e-6 3.09603e-6 1 -1.08981e-5 1.23744e-5 1 1.08044e-6 7.82588e-6 1 -1.19794e-6 -8.67696e-6 1 -3.64105e-6 -8.09371e-6 1 -6.67125e-6 -1.28786e-6 1 -5.84073e-6 -1.54892e-6 1 -8.43826e-6 -7.15872e-6 1 -3.87333e-6 -5.46386e-6 1 3.30797e-6 5.68915e-7 1 6.1623e-6 4.12084e-6 1 5.01617e-5 -6.88392e-5 1 0 0 1 8.32265e-6 1.24657e-6 1 -1.12939e-5 -1.69161e-6 1 -0.9204913 -0.3894583 -0.03190588 -0.9004979 -0.4336879 0.03191155 -0.4715018 -0.881288 -0.03189671 -0.399792 -0.91381 0.07153898 0.213869 -0.9711332 -0.1056427 0.3395246 -0.9382804 0.06597805 0.8096404 -0.5868839 0.007055163 0.8425371 -0.5329694 -0.07794141 0.9972144 0.0242179 0.0705468 0.9957787 0.09145319 -0.007806539 0.853071 0.5198043 -0.0455324 0.7583435 0.6433521 0.1049444 0.4188145 0.9033401 -0.09258019 0.2471341 0.9675295 0.0530216 -0.1330226 0.9901368 -0.04397827 -0.2040632 0.9785964 0.02659416 -0.6846858 0.7282537 -0.02918887 -0.7174801 0.6961905 0.02326631 -0.9690062 0.2459394 -0.0232529 -0.9791113 0.2012195 0.02918541 2.70623e-6 -6.73186e-6 1 3.71249e-6 -6.47307e-6 1 3.22113e-6 0 1 7.9855e-6 -2.07026e-6 1 4.38573e-6 -1.09849e-5 1 -4.60757e-6 1.15405e-5 1 1.65547e-5 1.5072e-5 1 5.25903e-6 6.67717e-6 1 8.38139e-6 -9.23755e-7 1 0 0 1 4.6471e-7 1.56024e-6 1 7.00485e-5 -7.11186e-5 1 8.44492e-5 -4.56823e-5 1 -2.56633e-6 -5.10443e-7 1 -1.33997e-6 3.17193e-6 1 1.03234e-5 -2.44373e-5 1 -2.89898e-5 -5.30674e-5 1 -4.22123e-5 1.63518e-6 1 -1.68205e-6 4.18416e-6 1 -0.9955849 0.09094083 0.02324968 -0.908416 -0.4174202 -0.0232529 -0.9021721 -0.431337 -0.005813658 -0.5515756 -0.8332448 0.03830742 -0.4705662 -0.879539 -0.07056015 0.06651568 -0.9952871 0.07056319 0.1594287 -0.9864647 -0.03834003 0.6652915 -0.7465393 0.008145034 0.6310472 -0.7741547 -0.04963994 0.9059183 -0.4168317 0.0745871 0.9743949 -0.1915435 -0.1177521 0.9743953 0.1915403 0.117754 0.8784469 0.4631057 -0.1177447 0.6130332 0.7783438 0.1355404 0.4186969 0.9030761 -0.09563666 -0.1056234 0.9934568 0.04344248 -0.1222929 0.9903183 0.06568259 -0.6201452 0.7800376 -0.08343505 -0.73499 0.6709569 0.0980122 -0.9840217 0.166226 -0.0637958 -2.0796e-6 -7.69724e-6 1 -2.136e-6 1.19353e-7 1 2.40813e-6 8.45885e-6 1 3.89161e-6 6.71202e-6 1 -1.85215e-5 -2.34844e-6 1 0 0 1 -7.08281e-6 2.00804e-5 1 -2.70792e-5 -2.99097e-6 1 -2.38814e-5 -5.77976e-6 1 1.09148e-5 2.64295e-6 1 8.62915e-6 -6.96664e-6 1 -2.24281e-6 -7.85538e-6 1 8.48936e-6 7.88197e-5 1 5.90976e-5 1.2695e-5 1 6.36209e-6 4.3629e-6 1 2.12258e-6 -3.19449e-6 1 -2.07585e-5 1.68216e-5 1 -1.97442e-5 1.82481e-5 1 -0.9975586 -0.03280711 -0.06165003 -0.9790434 -0.1920003 0.06789571 -0.8356866 -0.5390599 -0.1050826 -0.6194896 -0.7792209 0.09511929 -0.4434677 -0.8933535 -0.07249802 -0.1053782 -0.9909966 0.08259087 0.185921 -0.9772882 -0.1016908 0.4188121 -0.9033409 0.09258294 0.7583476 -0.6433506 -0.1049233 0.8902856 -0.4354215 0.1334154 0.9910185 -0.05162835 -0.123356 0.9259037 0.3542069 0.1313001 0.8530081 0.5163663 -0.07578331 0.4038279 0.9116917 0.07577019 0.2624085 0.9599174 -0.09849083 -0.1477478 0.9855715 0.08257883 -0.4016959 0.9118602 -0.08456599 -0.6333727 0.7692134 0.08455675 -0.8278236 0.5520679 -0.09964513 -0.9543969 0.2874401 0.08065152 0.122783 -0.9924317 -0.001901268 0.187729 -0.9811137 0.04662179 0.2948263 -0.9554852 -0.0111953 0.5209944 -0.8535568 -0.002368032 0.5357296 -0.8442733 0.01401084 0.78444 -0.619995 -0.01613134 0.7873924 -0.6163585 -0.01074177 0.9571353 -0.2864573 0.04282903 0.9757071 -0.215151 -0.04130053 0.987896 0.1546855 0.01156938 0.9872092 0.1586112 0.01613891 0.8677821 0.4966827 -0.01614469 0.8655082 0.5007793 -0.01075404 0.6487545 0.7600422 0.03812289 0.5632107 0.8245015 -0.05469131 0.3584718 0.9326221 0.0413987 0.2252561 0.9734188 -0.04141926 0.02730923 0.9987688 0.04141503 -0.1119086 0.9928551 -0.04141545 -0.3372962 0.9398096 0.05467325 -0.4586461 0.8865801 -0.06016165 -0.713411 0.6981582 0.06016498 -0.7998461 0.5977095 -0.05467694 -0.9283311 0.3677116 0.05467534 -0.9631108 0.2663877 -0.03814673 -0.9975084 -0.06972801 0.01072591 -0.9970974 -0.07440829 0.01613169 -0.9172653 -0.3980354 -0.01386559 -0.8898475 -0.4541872 0.04342091 -0.7131616 -0.6979127 -0.06571483 -0.6016862 -0.7960243 0.06571847 -0.3595247 -0.9324787 -0.03500926 -0.2547092 -0.9660546 0.04314708 -0.1111488 -0.9932239 -0.03394705 8.64493e-6 -8.71741e-5 -1 -5.4547e-6 1.08888e-4 1 -5.08976e-5 5.30418e-5 1 -4.26465e-5 2.4438e-4 1 -1.10405e-4 3.79171e-4 1 2.5528e-5 5.50575e-6 1 -4.99783e-5 -1.11696e-6 1 6.73559e-6 -7.16419e-6 1 -2.78235e-6 -6.00083e-7 1 2.7515e-6 8.14e-6 1 -2.21713e-6 3.62004e-5 1 -1.02713e-6 -1.18846e-5 1 -1.85023e-5 7.97237e-6 1 2.22765e-5 3.50562e-5 1 1.92004e-5 -1.26079e-5 1 2.49228e-6 -8.85101e-6 1 -1.17663e-6 -1.18816e-5 1 -3.37879e-7 -1.07576e-6 1 5.92485e-6 1.88638e-5 1 -5.44229e-6 2.1677e-5 1 2.02369e-6 2.80306e-6 1 6.17993e-7 1.1551e-6 1 -3.15898e-4 -1.33656e-4 0.9999999 -6.48586e-5 1.5129e-5 1 -2.04845e-6 -1.46764e-5 1 5.89968e-5 2.41352e-4 1 -7.79032e-6 1.27301e-5 1 -5.98712e-6 1.5411e-5 1 1.43525e-5 -7.07118e-7 1 1.52605e-5 3.06249e-6 1 0 -1.80314e-6 1 2.75042e-7 -1.73985e-7 1 1.28024e-5 1.87912e-4 1 -3.3213e-7 5.15329e-6 1 7.93548e-6 -1.09174e-6 1 6.05924e-6 -7.29674e-6 1 1.82938e-5 -2.9277e-5 1 -9.32241e-6 1.13378e-5 1 -4.22866e-6 2.07072e-5 1 -5.81214e-6 2.17322e-5 1 1.60663e-5 5.92532e-6 1 2.60835e-6 3.86662e-6 1 3.55085e-6 1.34907e-5 1 3.14642e-6 3.04907e-6 1 9.47034e-6 -2.10574e-5 1 1.422e-5 -4.336e-6 1 -2.61071e-6 2.92954e-6 1 -2.96119e-6 3.84624e-5 1 1.72456e-5 -2.09739e-5 1 6.3959e-6 2.93894e-6 1 3.44932e-6 1.04819e-5 1 1.22824e-5 1.24211e-5 1 -9.24882e-7 1.37429e-5 1 -1.22908e-5 4.85076e-6 1 -8.82621e-6 4.3384e-6 1 -3.16826e-6 1.65055e-7 1 -2.72369e-6 -3.19159e-7 1 1.73158e-5 -9.34336e-6 1 2.71703e-7 0 1 4.87368e-6 1.13742e-6 1 -1.84418e-6 -1.09133e-6 1 7.41874e-6 3.43221e-6 1 -1.03857e-5 1.25435e-5 1 -0.9874569 0.1404983 -0.07203489 -0.9409193 0.3369261 0.03393673 -0.6649428 0.7461347 -0.03367596 -0.5676214 0.8226948 0.03129065 -0.1594616 0.9867084 -0.03128242 -0.03623318 0.9987758 0.03367757 0.4444277 0.8951817 -0.03367263 0.619908 0.7809826 0.07602864 0.8818766 0.4605615 -0.1008799 0.9936052 2.36015e-4 0.1129102 0.9079578 -0.406152 -0.1032145 0.7559937 -0.6525756 0.05117225 0.2304758 -0.9724501 -0.03495287 0.2385146 -0.970766 -0.02691113 -0.5942626 -0.8038727 0.02530789 -0.6801547 -0.7291409 -0.07578384 -0.9727101 -0.2183928 0.07835602 -0.9983045 -0.03098052 0.04927974 -0.9794443 0.1920955 -0.06154775 -0.7951956 0.6034607 0.05915397 -0.6171589 0.7835727 -0.07161438 -0.205535 0.9749494 0.08502399 0.09211468 0.9933142 -0.06958371 0.5492197 0.8342192 0.04935663 0.6355818 0.7718765 -0.01557278 0.9531987 0.3019435 0.01556378 0.9730982 0.2283005 -0.03096407 0.9653604 -0.2577459 0.04057621 0.9130077 -0.4059194 -0.0405752 0.5906467 -0.8061672 0.03508555 0.4996919 -0.8652212 -0.04123461 -0.1567112 -0.985565 0.06405758 -0.3401578 -0.9377582 -0.07001578 -0.7625522 -0.6444434 0.05663061 -0.8838012 -0.4643089 -0.0575568 -0.9973794 0.0406832 0.05982649 -0.9437844 0.3222523 -0.07365113 -0.8009916 0.5967329 0.04819172 -0.4491989 0.8914377 -0.0596584 -0.3670964 0.9301662 0.005581915 0.2692701 0.962114 0.04278254 0.4448547 0.8909644 -0.09103161 0.8280082 0.5542316 0.0850284 0.9630888 0.2554049 -0.08502042 0.9627289 -0.2546913 0.09102475 0.8855876 -0.4600343 -0.06405293 0.3726925 -0.9268399 0.04547476 0.2970714 -0.9546756 -0.01851952 -0.3240247 -0.9459204 0.01556932 -0.3950874 -0.9181212 -0.03097128 -0.7925751 -0.6082434 0.04318279 -0.8973013 -0.4350502 -0.07471179 -0.8851407 0.4650335 0.0164178 -0.8621371 0.5063844 -0.01715916 -0.3686196 0.9293958 0.01852482 -0.3502068 0.9366683 0.00280112 0.3444419 0.9384815 -0.02474439 0.4007061 0.9158723 0.02475053 0.9247355 0.380575 -0.005194664 0.9215276 0.3883013 0.003011882 0.9127348 -0.4076505 -0.02713453 0.8566359 -0.5112819 0.06903594 0.3714716 -0.9250622 -0.07917618 0.1519296 -0.9845561 0.08698761 -0.5196204 -0.8513399 -0.07221555 -0.6185609 -0.7853471 0.02474802 -0.9813064 -0.1924312 -0.002823233 -0.9839316 -0.177957 -0.01448863 -1.62082e-6 -6.31104e-7 -1 1.43328e-5 -2.12546e-5 -1 1.20687e-5 -2.0994e-5 -1 1.30019e-5 9.02659e-6 -1 6.47657e-6 4.49636e-6 -1 -1.51451e-6 3.01301e-5 -1 -3.3207e-6 2.97111e-5 -1 -9.3696e-6 -1.82895e-5 -1 2.88884e-5 -1.90575e-5 -1 3.67754e-5 -1.50007e-6 -1 3.30359e-5 6.55339e-7 -1 7.3344e-6 -5.46407e-6 -1 7.60498e-6 -7.71326e-6 -1 -8.6825e-6 8.80612e-6 -1 -4.56652e-6 9.78344e-6 -1 9.97832e-6 3.31128e-5 -1 3.20484e-5 7.88542e-6 -1 -6.84679e-6 -3.12411e-6 -1 -7.183e-6 -2.79688e-6 -1 5.93458e-6 9.5787e-7 -1 2.34062e-6 6.7723e-6 -1 1.47711e-5 1.68281e-5 -1 1.41272e-5 6.48098e-6 -1 5.74765e-5 8.74754e-6 -1 5.52108e-5 6.09478e-6 -1 7.27308e-5 -8.06508e-6 -1 3.03969e-5 -7.60321e-6 -1 3.41273e-5 -5.85652e-5 -1 -9.00208e-6 -2.40971e-5 -1 3.74992e-6 -1.25957e-6 -1 3.70874e-6 -1.17588e-6 -1 -2.7323e-5 -1.93318e-5 -1 -2.77067e-5 -3.74299e-6 -1 -1.88746e-5 -5.71665e-6 -1 -1.00653e-5 -6.5464e-7 -1 -7.20236e-6 -5.92502e-6 -1 5.08387e-6 -9.05842e-6 -1 -6.17981e-6 -7.78554e-6 1 -4.90274e-7 6.34358e-6 1 -1.53393e-7 -1.67726e-6 1 -9.00234e-7 2.03513e-6 1 -1.78237e-6 1.36252e-6 1 6.29909e-6 -4.81529e-6 1 -2.29653e-6 -2.24384e-6 1 -2.53197e-7 6.38382e-7 1 -1.48396e-7 -1.46529e-6 1 5.82997e-6 -8.24475e-6 1 7.58653e-6 7.99857e-6 1 1.52652e-7 1.50731e-6 1 -7.51565e-7 1.06286e-6 1 5.02044e-7 1.27738e-6 1 5.1901e-7 2.5327e-6 1 2.48534e-6 9.12046e-7 1 1.5521e-6 -1.59509e-6 1 1.55383e-6 -1.47296e-6 1 -2.39991e-6 -3.66082e-6 1 0.8413411 0.537614 -0.05582404 0.7442246 0.6660753 0.04973459 0.1230499 0.9916598 -0.03833317 0.04219669 0.9988949 0.02070516 -0.7216429 0.6919558 -0.02070432 -0.7560484 0.6543104 0.01639235 -0.9996083 0.02427673 -0.0139268 -0.9980233 -0.05451005 0.03127628 -0.7552068 -0.6535972 -0.04973196 -0.6636085 -0.7472081 0.03610903 0.01212096 -0.9999256 0.001405477 0.01428097 -0.999898 -2.07666e-4 0.5993568 -0.8000001 -0.0277732 0.6969185 -0.7162202 0.03651505 0.9684559 -0.2475264 -0.02870368 0.9894189 -0.141107 0.03375059 -7.03663e-6 7.63255e-5 1 8.72683e-5 7.70177e-5 1 6.78423e-5 7.03696e-6 1 3.66166e-6 1.56714e-5 1 1.13235e-6 7.46671e-6 1 -1.01693e-5 5.49618e-6 1 5.51868e-6 -5.36874e-6 1 5.33755e-6 -5.53799e-6 1 -1.65346e-6 1.71556e-6 1 -5.48888e-6 -9.27237e-7 1 7.55953e-6 -3.18756e-6 1 2.03562e-5 3.06298e-5 1 -8.35859e-6 7.52599e-6 1 5.59635e-6 -2.16879e-5 1 1.015e-5 -5.07057e-6 1 -1.17802e-5 2.95932e-6 1 -1.80185e-5 -6.89358e-6 1 -2.76319e-5 -2.14341e-6 1 -0.9081894 -0.4165979 -0.0404734 -0.8910893 -0.4534042 0.01960974 -0.6317126 -0.7749551 -0.01959019 -0.5995039 -0.7993792 0.03984862 -0.1202858 -0.9919381 -0.03987497 -0.01805311 -0.9937558 0.1101068 0.3263573 -0.9375346 -0.1204981 0.5831003 -0.7987038 0.1485471 0.8052654 -0.5732157 -0.1515632 0.9149926 -0.3902022 0.1026199 0.9965975 0.03276383 -0.07563072 0.978999 0.1653823 0.1192042 0.8123925 0.5564344 -0.1743534 0.5568654 0.7949567 0.2407175 0.2812817 0.9334268 -0.2226991 -0.2011038 0.9539217 0.2226895 -0.4874454 0.8393118 -0.2407337 -0.7622819 0.6233192 0.1743548 -0.9655949 0.2207865 -0.1374036 -0.9919997 0.1195775 0.04046803 0 3.79772e-6 1 -1.17474e-6 -6.50246e-7 1 -1.88979e-6 3.06762e-6 1 -1.11193e-5 -1.89531e-5 1 7.45391e-6 6.90681e-6 1 1.85965e-6 -1.28646e-5 1 0.9880759 -0.1487123 0.03988432 0.9206632 0.3895347 -0.02533769 0.873875 0.4853508 0.02788209 0.4457037 0.8939823 -0.04630112 0.2675746 0.9614359 0.06359893 -0.3211399 0.9452574 -0.05794268 -0.4939532 0.8687214 0.03651273 -0.8748356 0.4835683 -0.02871149 -0.9219428 0.385853 0.03375083 -0.9583314 -0.2808032 -0.05244493 -0.8724745 -0.4829338 0.07458698 -0.5437929 -0.836941 -0.06179994 -0.2146573 -0.9747347 0.06176197 0.1027522 -0.9933641 -0.05166912 0.5233094 -0.8494653 0.06749939 0.6845017 -0.7280761 -0.03691649 0.9691253 -0.2459522 -0.0174241 2.64409e-5 3.54953e-5 1 8.88164e-6 2.65801e-5 1 1.38625e-5 1.63906e-5 1 -2.52055e-6 -2.98021e-6 1 5.24229e-6 -1.11043e-5 1 5.5451e-6 -1.05685e-5 1 2.55509e-5 -1.73487e-5 1 3.03801e-5 -2.71333e-6 1 6.88443e-6 -6.26177e-6 1 8.52525e-6 5.38518e-6 1 -1.11345e-5 5.98211e-6 1 -7.10726e-6 -1.62428e-5 1 8.71885e-6 -2.16458e-6 1 -7.4068e-6 9.27791e-6 1 -5.83588e-6 2.10576e-5 1 -1.2899e-5 2.23582e-5 1 -4.45259e-6 1.02991e-6 1 -1.10781e-4 -2.18648e-5 1 -1.32505e-4 1.65057e-5 1 2.97169e-5 9.0382e-7 1 -0.9647912 -0.244112 0.09791308 -0.89908 -0.4062722 -0.1630885 -0.6613746 -0.7421758 0.1084369 -0.4892827 -0.8605192 -0.1418071 -0.1873461 -0.9697369 0.1565627 0.2379353 -0.9614775 -0.1376506 0.3132247 -0.949639 -0.008721113 0.7355524 -0.6753139 0.05397969 0.807988 -0.575166 -0.1278266 0.9654829 -0.2294082 0.1233481 0.9802207 0.08787351 -0.1773287 0.944567 0.2992159 0.135141 0.6558082 0.74887 -0.09544301 0.5446521 0.8272859 0.1376669 0.1190239 0.9774647 -0.1743444 -0.1737516 0.9692403 0.1743091 -0.4976616 0.8540276 -0.1515575 -0.6921326 0.7084268 0.1381451 -0.9306628 0.3199848 -0.177416 -0.9779466 0.2065126 0.03119564 -0.02366691 0.9995158 0.02019816 0 0.9999974 0.002263307 0.002748727 0.9999812 -0.005470931 -0.005973696 0.9999114 0.01188981 -0.003591537 0.9999803 -0.005158603 0.002748727 0.9999812 -0.005470991 0.03724855 0.9965521 -0.0741378 -0.002163231 0.9999832 -0.005389213 0.01009607 0.9995138 -0.02950024 0 0.9999964 -0.002701282 -0.04241758 0.9963683 0.0738303 -0.0027498 0.9999873 -0.004235446 0.01609712 -0.9937552 -0.1104149 0.01617485 -0.9991592 -0.03767377 -2.43323e-4 -0.9999999 -2.636e-4 0 -1 0 0 -1 0 0.06956684 -0.997514 0.01123321 1.46671e-6 1 1.58028e-6 -9.33551e-6 1 1.02264e-5 0 1 0 1.55891e-6 1 -3.68457e-6 -5.41218e-6 1 1.10662e-5 -4.82911e-6 1 -1.49492e-5 -7.4197e-5 1 4.49289e-5 9.06761e-7 1 -3.14316e-6 0 1 5.23846e-6 1.45846e-7 1 7.80546e-6 3.89445e-6 1 -8.27061e-6 0 1 0 -1.62443e-6 1 -2.07251e-5 6.71807e-6 1 -7.76436e-5 0 1 0 2.31045e-5 1 6.80842e-5 0.002984464 0.5249657 0.8511182 -0.004268109 0.7431147 0.6691506 0.002125024 0.8645266 0.5025824 0.5300247 0.4332494 0.7289505 0.6147044 0.5837733 0.5304217 0.4957109 0.7646606 0.4117828 0.8315742 0.4559321 0.3171913 -0.138405 0.7108394 0.6896022 -0.1592149 0.7339726 0.6602538 -0.1456889 0.9099076 0.3883848 -0.4085354 0.4571538 0.7900058 -0.2931118 0.8313841 0.4721078 -0.4401434 0.5095718 0.739331 -0.3394513 0.8542897 0.3936522 -0.58228 0.5523004 0.5965856 -0.5609193 0.4265133 0.7095464 -0.6690694 0.4937998 0.5554349 -0.2287711 0.9555619 0.1859166 -0.6430758 0.6854785 0.3414277 -0.6968544 0.6449859 0.3136674 -0.7125815 0.6779947 0.1804181 -0.8001089 0.5800479 0.1528739 -0.2332559 0.972411 -0.002930879 -0.8720797 0.4887987 -0.02351325 -0.6445693 0.7493433 -0.1517071 -0.7456204 0.6531053 -0.1323014 -0.6646445 0.6712439 -0.3281454 -0.7256017 0.5726461 -0.3815476 -0.6026883 0.6907246 -0.3995828 -0.3113351 0.9127908 -0.2643548 -0.4089489 0.7344987 -0.5415464 -0.5733272 0.5491893 -0.6080189 -0.3796585 0.7345393 -0.5624155 -0.3960766 0.4945955 -0.7736269 -0.1939425 0.8810544 -0.4314273 -0.1512218 0.7863386 -0.5990023 -0.2235214 0.5192626 -0.8248663 -0.2044109 0.4168934 -0.8856726 0.4125826 4.88538e-4 0.91092 0.6039349 0.00365591 0.7970253 0.7831898 9.13374e-4 0.6217821 0.9219004 0.003291964 0.387413 0.9255281 0.3786544 -0.004326164 0.8562117 0.5166226 0.001598536 0.5494467 0.8355254 -0.002346038 0.5865567 0.809908 2.47609e-4 -0.002883136 0.8342781 -0.5513364 -2.19403e-4 0.8665457 -0.4990975 -0.001123487 0.4257094 -0.9048593 -0.00161457 0.4122604 -0.9110646 0.3980275 0.2331701 0.8872461 0.5605077 0.1658864 0.8113648 0.8965842 0.1340643 0.4220943 0.3949059 0.4328987 0.8103383 0.5480755 0.4261037 0.7197562 0.806564 0.2923759 0.5137808 0.7660245 0.3109281 0.5626103 0.5970845 0.5707159 0.563714 0.4460443 0.6852852 0.5756986 0.8745072 0.3865725 0.2929143 0.5807656 0.7290762 0.3621591 0.720493 0.5818837 0.3772282 0.4814027 0.6510486 -0.5868452 0.2892336 0.460085 -0.8394438 0.8040955 0.3001344 -0.5131763 0.4488641 0.6541784 -0.6087459 0.7949184 0.1745763 0.5810574 0.5848197 0.1667903 0.7938305 0.3558607 0.2720328 0.89407 0.8165382 0.2834628 0.5029056 0.5369794 0.4899709 0.6867181 0.3710654 0.4913206 0.7879813 0.9081979 0.2442656 0.3398688 0.7554035 0.5630433 0.3351833 0.5286638 0.6144733 0.5856085 0.7516934 0.5572102 0.3528085 0.4514454 0.001808404 -0.8922969 0.5180714 6.88402e-4 -0.8553371 0.7851426 0.003344118 -0.6193061 0.7161853 0.00526148 -0.6978904 -0.9822109 0.002352774 -0.1877663 0.9551295 -4.50038e-4 0.2961882 0.9295068 0.003300189 0.3687902 0.6164444 -0.006519615 0.7873715 0.5522407 -0.001384735 0.8336836 0.4730436 0.771716 -0.4250696 0.5266398 0.739098 -0.4199817 0.8684216 0.4273823 -0.2513725 0.8863846 0.3956891 -0.2403176 0.6324243 0.5569967 -0.5383254 0.4309645 0.5650172 -0.7035803 0.9179883 0.2471501 -0.3101845 0.647943 0.3533335 -0.6747779 0.6201925 0.3843701 -0.6838281 0.663942 0.3588104 -0.6560763 0.515466 0.2238107 -0.8271659 0.8050848 0.04385685 -0.5915362 0.9776111 -0.1372848 0.1594659 0.8937597 -0.1777284 0.4118325 0.8913231 -0.4451517 0.08592522 0.7081139 -0.2872532 0.6450275 0.7467638 -0.5280188 0.4044007 0.7093866 -0.5889398 0.3871957 0.6332583 -0.2707459 0.7250383 0.6113223 -0.518531 0.5978384 0.5336206 -0.7465373 0.3974055 0.4219319 -0.8737509 0.2419354 0.8295168 0.4095196 -0.3797308 0.5776299 0.6054093 -0.5475612 0.3996669 0.6167685 -0.6781321 0.8969665 0.2367675 -0.3733528 0.8357868 0.2371036 -0.4952195 0.6591084 0.2956522 -0.6914954 0.5160591 0.4011557 -0.7568073 0.5715363 0.1943839 -0.7972209 0.9806739 -0.1956267 -0.003033101 0.8597713 -0.5106763 0.001730382 0.7185341 -0.6954913 -8.13987e-4 0.6664551 -0.7455438 0.001396834 0.9321472 0.005236268 -0.3620418 0.8086685 -0.004312634 -0.5882487 0.633378 0.003504037 -0.7738347 0.4869647 -0.004794716 -0.8734085 0.7820011 -0.5534748 -0.2866009 0.9058932 -0.2766237 -0.3206817 0.9393419 -0.2008046 -0.2780545 0.7108551 -0.6323004 -0.3080282 0.7936324 -0.1929333 -0.5769961 0.6138337 -0.7647933 -0.1957024 0.5008468 -0.5516033 -0.666998 0.4806803 -0.3266527 -0.8137841 0.4372335 -0.7365111 -0.5161186 0.4493846 -0.58965 -0.6710935 0.4707363 -0.332833 -0.817086 -0.3514607 0.9170337 -0.1884792 -0.3016433 0.8898374 -0.3423463 -0.598237 0.7951083 -0.09957617 -0.4610891 0.804641 -0.3740986 -0.5669448 0.8100614 -0.1495791 -0.3675737 0.8210917 -0.4366897 -0.2688367 0.6973229 -0.6644303 -0.713577 0.6304495 -0.3055182 -0.7301083 0.6832383 0.01128578 -0.738995 0.662918 0.1201089 -0.8441153 0.5339552 -0.04859358 -0.3498454 0.4481549 -0.8226575 -0.7038305 0.6084839 -0.3665653 -0.9741544 0.1975939 0.1094524 -0.8523136 0.1792974 -0.4913388 -0.280905 0.152359 -0.9475648 -0.980045 0.1504283 -0.1299352 -0.9626352 0.1491852 -0.2260029 -0.4753133 0.4476631 -0.7574135 -0.5909571 0.3300306 -0.7361043 -0.9978889 -0.002275586 -0.06490361 -0.4498004 -8.35317e-4 -0.8931288 -0.7703797 0.002926826 -0.6375787 -0.782052 0.0022794 -0.623209 -0.4077405 0.903943 0.128976 -0.7413495 0.6612051 -0.1149285 -0.5680993 0.7904357 0.2290735 -0.5516617 0.7930635 0.2583014 -0.3881965 0.9078994 0.1581832 0.1636537 0.5899776 0.7906605 -0.3963332 0.9088562 0.1300013 -0.3892631 0.8352823 0.3883009 -0.8975549 0.4238815 0.1213253 -0.6034447 0.5899718 0.5364584 -0.5896096 0.780171 0.2090307 -0.7408807 0.6708101 -0.03330814 -0.8852904 0.4604293 -0.0653131 -0.4301372 0.6940331 0.5773214 -0.6067791 0.587032 0.5359221 -0.9642191 0.2403718 0.1118161 -0.5372388 0.280016 0.7955914 -0.5855798 0.3039471 0.7514734 -0.9910551 0.1208881 -0.05653244 -0.8262599 0.1210411 0.5501306 -0.9913051 -6.30583e-4 0.1315819 -0.9500322 0.001958549 0.3121456 -0.8925606 4.0329e-4 0.4509274 -0.641946 0.003322064 0.7667427 -0.5306082 5.14822e-4 0.8476171 -0.004356861 -0.3434401 0.9391645 0.003759503 -0.6363801 0.7713666 -0.004087209 -0.8362199 0.5483793 0.001851499 -0.9570327 0.2899744 -0.002967894 -0.9978587 0.06534075 -0.262528 -0.4074416 -0.874683 -0.7851343 -0.4594451 0.4153003 -0.5065383 -0.426718 0.7492201 -0.1463618 -0.4006584 0.9044618 -0.4075732 -0.4700573 -0.7828986 -0.746686 -0.4985669 -0.4403305 -0.8256832 -0.524111 0.2086976 -0.7597301 -0.6053021 -0.2375277 -0.7944298 -0.6070541 -0.01914709 -0.7490852 -0.6448919 0.1516111 -0.6354758 -0.6400231 0.431904 -0.6079975 -0.5771517 0.5451926 -0.5571453 -0.6162796 0.5565866 -0.2916015 -0.685442 0.6671866 -0.357596 -0.6854194 0.6342912 -0.1469316 -0.7112947 -0.6873654 -0.2016079 -0.8307996 -0.5187738 -0.3361378 -0.7546921 -0.563428 -0.4878821 -0.732424 -0.4748961 -0.5175499 -0.7426681 -0.4249543 -0.6309927 -0.7643557 -0.1326968 -0.1515437 -0.7652052 0.625696 -0.3687628 -0.8023418 -0.4693205 -0.3069701 -0.9342126 -0.1817031 -0.3251972 -0.8497235 0.41499 -0.1862656 -0.7962606 0.5755642 -0.580888 -0.8043875 -0.1246193 -0.3920562 -0.9129152 0.1134801 -0.463833 -0.8389849 0.2845404 -0.2013117 -0.956973 0.2089887 -0.1600199 -0.9869614 0.01734578 -0.002924025 -0.7502617 -0.6611345 0.00176382 -0.7984474 -0.6020621 -0.9095442 0.2278931 -0.3475541 -0.8358375 0.3367449 -0.4335649 -0.8178013 0.5267908 -0.2317162 -0.8147602 0.5300298 -0.2350199 -0.7546759 0.4886658 -0.4378014 -0.8131251 0.1252358 -0.5684571 -0.5649366 0.630864 -0.5318433 -0.5445196 0.7766884 -0.3166283 -0.5194422 0.3683931 -0.7710164 -0.5316831 0.2635847 -0.8048827 -0.3749052 0.8970971 -0.233801 -0.3536243 0.7955535 -0.4919803 -0.3553939 0.2070997 -0.911485 -0.4049049 0.003646612 -0.9143515 -0.5578004 -0.005334496 -0.8299581 -0.88433 0.003781318 -0.4668469 -0.8543332 -0.002118647 -0.5197214 -0.5186656 0.8549771 3.34179e-4 -0.5196205 0.8543971 3.67823e-4 -0.8317196 0.555196 -9.00888e-6 -0.8399046 0.5427341 4.47204e-4 -0.9829859 -0.1250666 -0.1345261 -0.8133065 -0.2287449 -0.5349843 -0.8988501 -0.361766 -0.2473741 -0.7579894 -0.5405066 -0.3651092 -0.6753556 -0.3201358 -0.6643854 -0.6204596 -0.3894023 -0.6807317 -0.5975313 -0.5158435 -0.6138909 -0.6610412 -0.6573361 -0.3618478 -0.6024385 -0.767889 -0.2177482 -0.4663988 -0.2289068 -0.8544436 -0.9074272 0.2230502 0.3561242 -0.8588989 0.2431542 0.4507425 -0.8112463 0.5308835 0.2450351 -0.8338112 0.4892674 0.2556881 -0.7769013 0.5086376 0.3710959 -0.7024259 0.1237614 0.7009144 -0.4870439 0.4871072 0.724924 -0.5066563 0.8082122 0.3001541 -0.3834378 0.2667641 0.8842017 -0.4760667 0.6303665 0.6131873 -0.3732775 0.8994292 0.2273564 -0.3539535 0.4749979 0.8056638 -0.4601935 -0.8878123 0.003379166 -0.7537014 -0.6572106 -0.002894639 -0.8509325 -0.5252737 0.001220405 -0.9666276 -0.256174 -0.002420902 -0.565344 -0.004511713 0.824843 -0.7302142 0.007055103 0.6831818 -0.8608518 -0.006755113 0.5088108 -0.9759191 -0.1487377 0.1595587 -0.975754 -0.1490942 0.1602343 -0.8477427 -0.1606811 0.5054839 -0.7929799 -0.5744596 0.2029262 -0.7216466 -0.4714837 0.5068821 -0.5890704 -0.7382372 0.3286362 -0.5006496 -0.735462 0.4565585 -0.5643925 -0.6372551 0.5247542 -0.5537877 -0.37962 0.7410855 -0.5741099 -0.341679 0.7440789 -0.3550809 -0.9035149 0.2399554 -0.4042231 -0.2438601 0.8815531 -0.4892171 0.8498157 -0.1961633 -0.3355451 0.9377651 -0.08947652 -0.3378331 0.9411369 -0.01141029 -0.2157025 0.9752856 -0.04785799 -0.1941925 0.9758591 -0.09994095 -0.3582894 0.9316159 -0.06099683 -0.5572088 0.7984135 -0.2281541 -0.4955471 0.8676136 -0.04098498 -0.2738572 0.9610607 -0.0369414 -0.7776659 0.6045838 -0.1723777 -0.6248031 0.7626325 -0.1673702 -0.5773629 0.8163548 0.01472425 -0.8211559 0.4493766 0.3518006 -0.9186342 0.1872724 -0.3479084 -0.9382956 0.3142857 0.1443116 -0.9562416 0.2369039 0.1716933 -0.8128015 0.4394959 -0.3823574 -0.8454705 0.406349 -0.346497 -0.7139875 0.5834928 -0.3869855 -0.7959576 0.5693001 -0.2057887 -0.8332047 0.4332283 0.3436323 -0.9085403 0.2374802 0.3437407 -0.9010938 0.2810933 0.3301765 -0.5354625 0.7990957 -0.2733605 -0.6002008 0.7492997 -0.2798377 -0.6689496 0.7159993 -0.199628 -0.7344518 0.5701895 0.3680549 -0.823454 0.546204 0.1535733 -0.594533 0.7539065 0.2795631 -0.5778112 0.7669729 0.279082 -0.5521222 0.8277987 -0.09955161 -0.5489629 0.833779 -0.05875706 -0.9492977 0.3143745 -0.00158292 -0.812602 0.564067 0.1466509 -0.3797178 0.90687 0.1827601 -0.3683331 0.9130322 -0.1752224 -0.3336348 0.931851 -0.1426233 -0.373945 0.9274477 -0.002442538 -0.9470419 0.2448425 -0.2077595 -0.6487379 0.7501875 0.1278986 -0.2760385 0.9542545 -0.1148958 -0.1785303 0.9834161 -0.03193169 -0.9109261 0.2409508 -0.3348973 -0.8628602 0.4889797 -0.1279492 -0.8603678 0.503624 -0.07829511 -0.8083514 0.5876011 -0.03595644 -0.6230523 0.7743808 0.1101822 -0.3011062 0.9468024 0.113579 -0.1811249 0.9803838 0.07772654 -0.6514452 0.7584988 -0.01729106 -0.413979 0.9072416 0.0743907 -0.3887848 0.9188239 0.06788879 -0.7891585 0.5836614 0.1912282 -0.2522431 0.9672524 0.02821511 -0.6015541 0.7884876 0.1281399 -0.615607 0.778227 0.124059 -0.4023282 0.9118596 0.0815106 -0.3453709 0.9340257 0.09118676 0.06111824 -0.9657971 -0.2519931 0.02553606 -0.8594283 -0.5106181 -0.0345959 -0.8120055 -0.5826236 0.0271297 -0.6444137 -0.7641957 -0.02753543 -0.4959542 -0.8679119 0.04625487 -0.3658847 -0.9295099 0.01775532 0.6898912 -0.7236954 -0.04214906 0.6172023 -0.7856748 0.05336719 0.417927 -0.9069117 0.04948866 0.2404502 -0.969399 0.04738086 -0.9714936 0.232283 -0.02178239 -0.8417468 0.539433 -0.009809732 -0.8511775 0.5247863 0.04818302 -0.6539822 0.754974 -0.0227046 -0.4952644 0.8684455 0.04056227 -0.377601 0.9250796 0.009781002 0.8684962 0.4955993 0.05562847 0.7812508 0.6217336 0.01976341 0.5533323 0.8327261 -0.05560326 0.4622499 0.8850047 0.03642725 0.2470065 0.9683288 -0.004221975 0.9968543 0.07914286 -0.002153277 0.9986138 -0.05259078 -0.00437498 0.9845907 0.1748199 0.001194 0.9938877 0.1103885 2.80634e-4 0.9904673 0.137748 -0.01112437 0.9997676 -0.01847052 -0.01596707 0.9917731 0.1270081 -0.004516124 0.9962285 0.08665078 -0.02500092 0.9671995 0.2527846 0.01348614 0.9191712 0.3936274 -0.03420543 0.843019 0.5367951 -0.03439396 0.7866294 0.6164667 0.01166087 0.7312554 0.6820042 -0.03446042 0.525054 0.850371 0.03101766 0.3806022 0.9242185 -0.0334298 0.2168813 0.9756254 -0.03462511 -0.2386373 0.9704912 0.02987331 -0.4063046 0.9132493 -0.03903365 -0.5400426 0.8407319 -0.03051406 -0.6599043 0.7507299 0.0482766 -0.7972519 0.6017131 -0.0122534 -0.8495399 0.527382 -0.05133503 -0.964067 0.2606524 -0.04442268 -0.2617253 -0.9641196 0.01457035 -0.4744209 -0.8801774 -0.008059084 -0.5144829 -0.8574629 -0.02887773 -0.6873001 -0.7257994 0.01809 -0.7940859 -0.6075363 -0.03802031 -0.8492945 -0.5265486 -0.05534017 -0.9725498 -0.2260185 -0.05719321 0.2415957 -0.96869 -0.0284487 0.55326 -0.8325226 0.008537948 0.611817 -0.7909533 0.02485722 0.6263225 -0.7791677 -0.04026371 0.8393152 -0.5421521 0.01821559 0.9159901 -0.4007869 0.001312255 0.9999873 0.004880011 -0.001056194 0.9852094 -0.171351 -0.02415496 0.9668399 -0.2542382 -0.00700891 0.9817224 -0.1901893 0.00256592 0.996877 -0.07892835 0.004912376 0.9997336 -0.02255332 0.006612896 0.9971097 -0.07568824 -0.1085104 0.9823592 -0.1523026 0.001023471 0.9925999 -0.1214261 0.04372715 0.2960038 -0.9541854 -0.02207541 0.2210283 -0.9750174 5.89999e-4 0.5418586 -0.8404694 -0.02873903 0.4987262 -0.866283 -0.01667004 0.6956527 -0.7181849 -0.004899799 0.7105116 -0.7036685 0.01239264 0.8026064 -0.5963803 0.01517009 0.8736481 -0.4863218 -0.006452918 0.8843752 -0.4667323 -0.01034027 0.890777 -0.4543228 0.001363158 0.833878 0.5519471 -0.01621484 0.9002643 0.4350416 3.27987e-4 0.8723893 0.4888115 -0.005747556 0.7354952 0.6775056 -0.005861759 0.6828964 0.7304917 -0.01611226 0.7078346 0.7061944 -0.0488221 0.442448 0.8954643 -0.01140558 0.4819509 0.876124 -0.002976715 0.556414 0.8309 -0.03056871 0.2229074 0.9743602 0.002054393 0.2617897 0.9651228 -9.89775e-6 1 1.69462e-6 -1.35701e-5 1 1.2215e-5 4.45183e-5 1 3.96602e-5 6.22233e-5 1 -7.36491e-6 -1.40357e-5 1 1.6613e-6 1.92939e-5 1 -8.92944e-5 1.33416e-4 1 -8.78361e-5 1.32457e-4 1 -7.8022e-5 -1.18667e-5 1 1.6275e-5 -9.91882e-6 1 1.66532e-6 2.58837e-5 1 -3.20688e-5 4.65159e-5 1 -7.56614e-6 1.41433e-5 1 -2.30051e-6 1.32342e-5 1 -4.42673e-6 2.85159e-5 1 -9.53832e-6 2.71017e-5 1 -2.54674e-6 5.79846e-5 1 4.85865e-5 -4.36617e-7 1 7.34772e-5 5.74401e-6 1 3.44304e-5 0.1363203 0.05337268 0.989226 0.3888213 -0.0658403 0.9189577 0.6864011 0.05562299 0.7250929 0.8803058 -0.05677199 0.4709974 0.9688072 0.05167371 0.2423684 0.9806948 -0.0586071 -0.1865553 0.9293411 0.04232555 -0.3667884 0.6675851 -0.02812284 -0.7440021 0.5614732 0.0444855 -0.8262983 0.162564 -0.06553554 -0.9845193 -0.1640458 0.07865417 -0.983312 -0.4409888 -0.05337494 -0.8959242 -0.7656146 0.04774814 -0.6415252 -0.854229 -0.03513258 -0.5187085 -0.998201 0.03513002 -0.04858833 -0.9935578 -0.0477429 0.1027783 -0.8670597 0.05337554 0.4953368 -0.7275128 -0.05338329 0.6840142 -0.4171888 0.04042482 0.9079204 -0.2457705 -0.04041773 0.968485 0.002426326 0.999996 0.001491069 0.003575623 0.9999926 -0.001432538 0.007371783 0.9998612 0.0149427 2.43984e-4 0.9999529 0.009696364 0.003168284 0.9999904 -0.003027021 0.004083156 0.9999916 -4.22384e-4 0.001818358 0.9999585 -0.008924841 -0.002962172 0.999971 -0.007023692 -0.007701456 0.9999396 -0.007832109 0.002021908 0.9999671 -0.00784415 -0.006305277 0.9999431 -0.008605122 -0.00671488 0.9999711 -0.003582656 -0.01205384 0.9999213 0.003474831 -0.01301056 0.9999123 0.002470433 -0.012941 0.9999124 0.002765655 -0.004215657 0.99998 0.004735827 -0.001235604 0.9999724 0.007327854 0.001719832 0.9999193 0.0125882 -0.2456867 -0.009385526 -0.9693039 -0.2451476 -0.00906682 -0.9694434 -0.504256 0.009944081 -0.8634969 -0.5394179 -0.009559214 -0.841984 -0.654556 -0.002082943 -0.7560107 -0.665266 -0.00863552 -0.7465564 -0.8357711 -0.006726205 -0.5490369 -0.8455678 -0.01637405 -0.5336168 -0.9349746 0.02229213 -0.3540135 -0.9644748 0.007157921 -0.2640779 -0.9729126 -0.01101094 -0.2309109 -0.9972706 -0.01060336 -0.07306796 -0.9987815 0.00152409 -0.04932779 -0.9766861 -0.009925842 0.2144429 -0.975094 -0.0047459 0.2217415 -0.9123442 0.02104502 0.4088829 -0.868622 -0.01636594 0.4952049 -0.7878184 0.01019918 0.6158232 -0.7540757 -0.01013737 0.6567093 -0.6267844 0.0135647 0.7790747 -0.5557075 -0.02302879 0.8310588 -0.3988529 0.01126956 0.9169457 -0.3316926 -0.01225024 0.943308 -0.2299153 -0.009693264 0.9731623 -0.2884255 0.01322793 0.957411 -4.63384e-4 -1 -3.62059e-4 4.90139e-4 -0.9999969 -0.002481162 -0.001827001 -0.9999886 0.004395723 1.0203e-4 -0.9999989 0.00154978 -4.53576e-6 -1 -5.33702e-6 -1.77076e-6 -1 8.96398e-6 -4.14467e-4 -0.9999998 3.67708e-4 -0.002793788 -0.9999693 -0.007323861 -1.76671e-4 -0.9999801 0.006308436 -0.004789769 -0.9999805 0.003983795 -7.60664e-4 -0.9999898 0.004479944 -0.00282669 -0.9999943 0.001830756 -0.001425802 -0.999999 -1.83221e-5 -0.001171588 -0.9999992 -7.0853e-4 -7.04415e-4 -0.9998838 -0.01522707 -0.006757855 -0.9999473 -0.007721364 -0.003687858 -0.9999528 -0.008985042 -0.004338026 -0.9999553 -0.008399724 0.001814246 -0.9999491 -0.009935379 -0.9507907 0.003065049 0.3098183 -0.9502289 0.004347026 0.3115223 -0.9302433 0.1340659 0.3415753 -0.9461792 0.0136854 -0.3233539 -0.9679732 -0.00154668 0.2510488 -0.9871875 0.005519032 0.1594688 -0.9987204 -0.001418292 -0.05055242 -0.9985372 -0.001817762 -0.05403822 -0.950331 0.001691639 -0.3112363 -0.9591511 -3.64702e-4 -0.282894 -0.9876093 0.003528058 -0.1568927 -0.004240393 0.002661049 0.9999875 -0.005092561 0.002602219 0.9999837 7.84786e-4 -0.001274228 0.9999988 -0.002222299 0.01741135 0.9998459 -5.90102e-4 -0.01555234 -0.9998788 -7.17297e-4 -0.01618844 -0.9998686 -0.03083777 0.003406405 -0.9995187 0.001361191 0.001525521 -0.9999979 -7.08041e-6 -1 6.95959e-6 5.76268e-6 -1 4.7505e-6 -4.29106e-6 -1 -3.53736e-6 3.38438e-5 -1 -5.17116e-5 1.52862e-5 -1 -4.3525e-5 -3.55729e-5 -1 -2.2717e-4 -7.46389e-5 -1 -1.42736e-4 2.13935e-4 -1 4.30591e-5 1.41603e-4 -1 1.18812e-4 -2.58482e-6 -1 1.62679e-6 4.74064e-5 -1 -2.98359e-5 2.17955e-5 -1 -3.00996e-5 2.48446e-5 -1 -4.51061e-5 1.98587e-5 -1 -4.347e-5 1.53702e-5 -1 -1.05355e-5 1.98293e-6 -1 8.22265e-6 -6.97095e-6 -1 3.9438e-6 -1.90239e-6 -1 3.26013e-6 -1.14594e-5 -1 -1.79864e-6 -2.01601e-7 -1 -3.18091e-6 7.45244e-7 -1 1.17586e-5 -2.65394e-6 -1 4.54806e-6 -6.98054e-6 -1 6.74158e-6 -6.09146e-6 -1 9.36411e-6 -7.42576e-6 -1 1.14153e-5 1.36853e-5 -1 3.18338e-5 2.69714e-5 -1 1.75738e-6 -1.69212e-5 -1 -5.69354e-6 -9.31285e-6 -1 5.92255e-6 -6.46297e-6 -1 4.11016e-6 -6.80287e-6 -1 4.02916e-6 -4.56672e-6 -1 -7.13463e-6 9.53454e-6 -1 -7.98845e-6 -1.12511e-5 -1 3.84208e-5 1.39612e-5 -1 2.30539e-5 -2.86801e-5 -1 -1.12664e-5 -2.96613e-5 -1 -1.10908e-5 -2.98348e-5 -1 -1.21988e-5 -1.17005e-5 -1 4.29423e-6 -1.01405e-5 -1 2.62387e-6 -1.63671e-6 -1 8.71388e-6 -4.6999e-6 -1 1.11537e-5 -1.66222e-6 -1 1.72053e-5 3.48606e-6 -1 1.66187e-6 -2.29415e-5 -1 -1.09366e-5 -2.17464e-5 -1 -7.19602e-6 -2.84206e-6 -1 -1.11501e-5 1.16918e-6 -1 -6.8417e-6 3.09169e-6 -1 -8.9393e-6 1.27387e-5 -1 -8.69079e-6 1.25055e-5 -1 -5.2157e-6 -5.74554e-7 -1 6.17568e-6 1.96041e-6 -1 9.53976e-6 4.58206e-6 -1 1.87351e-6 2.66427e-6 -1 -1.11147e-5 9.25912e-6 -1 1.19181e-4 6.35672e-6 -1 -1.12179e-5 0 -1 0 0 -1 0 1.60595e-6 -1 -2.07638e-6 7.54686e-6 -1 -1.41701e-6 6.74791e-6 -1 1.25086e-6 -1.61215e-5 -1 -1.76465e-5 -2.7218e-5 -1 1.70187e-6 -6.31367e-6 -1 2.9366e-5 -1.8874e-5 -1 3.89705e-5 -2.08777e-5 -1 3.63611e-5 1.65293e-5 -1 -1.20349e-5 -6.01837e-6 -1 -3.67563e-5 -8.767e-5 -1 -1.41689e-5 -7.27782e-5 -1 1.44897e-4 -2.46016e-5 -1 -1.54726e-4 -1.17359e-4 -1 -1.29161e-4 -7.7985e-5 -1 -6.08445e-5 2.19393e-4 1 3.73354e-4 0 1 3.64007e-4 8.25468e-7 1 -2.48634e-6 0 1 2.23053e-4 0 0.9999999 -3.5955e-4 2.5727e-4 0.9999999 -3.91811e-4 7.93826e-4 0.9999994 7.70157e-4 -5.55036e-5 1 2.56721e-4 3.15943e-6 1 0 -3.37689e-6 1 1.01713e-5 -3.14382e-6 1 -2.02767e-6 4.71048e-6 1 -2.57354e-6 1.83755e-6 1 -4.63661e-7 0 1 0 -1.64685e-5 1 4.57534e-5 1.61306e-6 1 -2.17668e-5 -4.64718e-6 1 6.02563e-7 6.89349e-7 1 -1.7368e-6 1.7388e-6 1 6.57856e-6 1.28446e-6 1 -3.98452e-6 -4.68181e-6 1 -1.69073e-5 -2.02403e-5 1 -1.64131e-5 0 1 2.96398e-5 4.56007e-6 1 5.64042e-6 -9.06206e-6 1 1.29504e-5 1.81453e-5 1 2.57439e-5 -8.85838e-5 1 7.79246e-5 -5.3849e-5 1 2.59933e-4 -4.19657e-6 1 2.0995e-6 0 1 -8.16198e-7 5.48259e-7 1 -1.39632e-6 3.92391e-6 1 0 1.85869e-6 1 -4.39213e-7 -1.25844e-6 1 6.81244e-7 -1.02401e-5 1 9.88978e-6 2.72723e-6 1 0 1.68561e-6 1 2.43273e-5 1.69063e-6 1 2.14474e-6 -6.39408e-7 1 -2.41914e-6 -1.0998e-6 1 5.05054e-6 9.00804e-7 1 1.87817e-5 -4.91676e-6 1 1.23555e-5 9.29074e-7 1 1.54163e-6 8.60536e-5 0.9999999 -2.39078e-4 -1.13484e-5 1 5.28889e-5 -1.61926e-6 1 -2.00289e-6 6.59167e-6 1 -3.56833e-6 -1.48512e-6 1 1.31361e-6 -4.60799e-6 1 7.47162e-7 -5.96033e-6 1 5.60376e-6 -1.10885e-5 1 2.86442e-5 -7.1021e-6 1 0 -1.76914e-6 1 -1.27938e-5 -3.47137e-6 1 1.81633e-6 -4.46978e-6 1 0 3.90298e-5 1 -7.48253e-6 2.57855e-6 1 1.4228e-6 -9.44565e-7 1 1.83684e-6 4.96899e-6 1 3.1897e-5 1.15302e-5 1 1.28096e-5 0 1 2.6508e-5 2.88566e-7 1 -2.47844e-6 0 1 -3.75656e-6 1.39233e-6 1 5.96e-7 -3.95043e-6 1 1.30252e-5 -1.07209e-5 1 -6.36702e-6 -4.56091e-6 1 2.49182e-6 -3.07947e-7 1 2.6449e-6 -5.89672e-6 1 -2.52415e-6 -0.04071974 -0.03835707 -0.9984341 -0.1922553 0.046328 -0.9802507 -0.6407237 -0.05519455 -0.7657852 -0.7461481 0.03393256 -0.6649147 -0.9871836 0.003759205 -0.1595445 -0.9944312 -0.04166048 -0.09680414 -0.8810996 0.03769898 0.4714258 -0.81762 -0.03769099 0.5745232 -0.3893647 0.03769385 0.9203121 -0.2752102 -0.0376932 0.9606449 0.304129 0.04165077 0.9517199 0.3639256 -0.003762722 0.9314205 0.8237414 -0.03524291 0.5658693 0.9014871 0.07765239 0.425783 0.9851163 -0.0707609 -0.1566484 0.9277077 0.06302785 -0.3679483 0.6313297 -0.06065553 -0.7731388 0.4643517 0.05613118 -0.8838704 -0.4045238 -0.06855887 -0.9119541 -0.5186004 0.01642364 -0.8548591 -0.9071229 -0.0155583 -0.4205782 -0.9362141 0.03096771 -0.3500631 -0.9902796 -0.04057598 0.1330406 -0.9363611 0.07161265 0.3436562 -0.7269675 -0.06615376 0.6834778 -0.3873448 0.07046258 0.9192382 -0.245925 -0.0226891 0.9690232 0.3896592 0.002802908 0.9209548 0.4077203 0.01850396 0.9129194 0.8947874 -0.01851677 0.4461085 0.9035909 -0.002799987 0.4283874 0.9785861 0.02268946 -0.2045832 0.945533 -0.05270528 -0.3212314 0.7019377 0.05513584 -0.710101 0.4508199 -0.09623479 -0.8874121 0.09236359 0.07646936 -0.9927847 -0.4213601 0.01132982 -0.9068227 -0.5150532 -0.06582415 -0.8546271 -0.9118202 0.07388126 -0.4038882 -0.9887127 -0.07973736 -0.1268437 -0.976176 0.06224834 0.2078594 -0.7797222 -0.09477788 0.6189108 -0.5353505 0.1071468 0.8378064 -2.21194e-4 -0.08910572 0.9960221 0.2471382 0.06301826 0.9669288 0.6937978 -0.0630297 0.7174063 0.8170787 0.05245286 0.574135 0.9991955 -0.03822988 0.01211506 0.994568 0.03822314 -0.09681665 0.7654403 -0.05245274 -0.6413656 0.6407147 0.05519789 -0.7657923 0.1922424 -0.04632127 -0.9802536 0.09108954 0.01041334 -0.9957883 -0.1055314 0.0484234 -0.9932363 -0.5154257 -0.05361348 -0.8552555 -0.5795608 3.14082e-4 -0.8149289 -0.9692798 0.02621734 -0.2445596 -0.9919261 -0.08019489 -0.09824132 -0.9136546 0.08560597 0.3973751 -0.7464131 -0.08359217 0.660212 -0.2176471 0.06232947 0.9740353 -0.2848482 -0.005207717 0.9585584 0.4877256 0.0257495 0.8726171 0.5139577 -0.001734793 0.8578138 0.9388295 -0.04146313 0.3418771 0.9888774 0.1100994 0.09999841 0.9669593 -0.07388651 -0.2439887 0.6284532 0.072537 -0.7744578 0.5794305 0.02072799 -0.8147581 0.1307452 -0.05038046 -0.9901351 -0.005223274 9.68428e-4 0.999986 -0.005053937 0.001024544 0.9999867 0.05014091 -0.004175126 -0.9987335 0.01743453 0.005417346 -0.9998334 -0.02565377 -0.9996695 -0.00165677 0.02866089 -0.9992553 -0.02583605 0.0400297 -0.9989299 0.02316433 -0.01710802 -0.9998536 0 0 -1 0 0 -1 0 0 -1 0 -0.07295531 -0.9968765 -0.03024512 0.1077371 -0.8211794 0.560408 -0.1473346 -0.6962265 0.702539 0.1344389 -0.1792913 0.9745671 -0.1199166 0.03767973 0.9920687 0.1199078 0.5243417 0.843023 -0.06478887 0.65465 0.7531505 -0.01052129 0.9497518 0.3128276 0.1338742 0.9721069 0.1925768 -0.125785 0.967741 -0.2183014 0.1184285 0.8213101 -0.5580542 -0.1275287 0.6136896 -0.77918 0.1355335 0.337143 -0.9316465 -0.1534981 -0.1211255 -0.9806972 0.1381552 -0.3969657 -0.9073761 -0.1201077 -0.7331935 -0.6693291 0.07606893 -0.873735 -0.4804173 -0.05058938 -0.9976109 -0.04704606 -1 5.01492e-6 0 -1 -3.51766e-7 1.76885e-6 -1 -1.93191e-7 0 -1 0 0 -1 0 0 -1 0 -1.82879e-7 -1 0 -2.1048e-7 -1 0 0 -1 -2.8882e-7 0 -1 -3.08843e-7 0 -1 0 0 -1 0 -3.61117e-7 -1 0 -3.25471e-7 -1 0 0 -1 0 0 -1 0 1.3528e-7 -1 9.8263e-7 -2.35906e-6 -0.1195159 -0.9689322 0.2165329 0.1036888 -0.8373286 0.5367768 -0.09442925 -0.681918 0.7253076 0.1199125 -0.2864434 0.9505636 -0.1344422 -0.0720573 0.9882981 0.121806 0.4490313 0.8851746 -0.1216331 0.6524119 0.7480401 0.08420449 0.8592935 0.5045043 -0.1004489 0.9883431 0.1144019 0.01052713 0.9997146 0.02144557 0.06480222 0.8681461 -0.49206 -0.1540039 0.7525154 -0.6403151 0.1091492 0.4415737 -0.8905612 -0.09912258 0.004622995 -0.9950644 0.05846595 0.108411 -0.9923855 -0.07605648 -0.3655868 -0.9276647 0.1431642 -0.592083 -0.7930585 -0.1664159 -0.8458663 -0.5067701 0.1664496 -0.9764722 -0.1371009 -1 1.68244e-7 0 -1 0 0 -1 0 -1.77077e-7 -1 0 0 -1 3.65257e-7 3.25374e-7 -1 2.88217e-7 0 -1 1.70347e-7 0 -1 2.71649e-7 0 -1 1.50903e-7 0 -1 0 0 -1 2.43774e-7 -2.07427e-7 -1 0 -1.38001e-7 -1 0 -1.36981e-7 -1 0 0 -1 0 0 -1 1.20361e-7 0 -1 4.3856e-7 2.75672e-7 -1 3.38692e-7 0 1 -1.95918e-6 -7.55417e-6 0.9655939 -0.2589313 -0.02414357 0.9991877 0.04012542 0.003741383 0.9999942 -0.00321567 -0.001066088 0.9963979 0.04001349 -0.07476705 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 1.63589e-7 -1.77024e-7 -1 1.51822e-7 -1.52754e-7 -1 0 -2.94292e-7 -1 0 0 -1 0 0 -1 1.77165e-7 0 -1 1.76787e-7 0 -1 2.80822e-7 0 -1 1.77746e-7 0 -1 1.44603e-7 0 -1 -1.34974e-7 0 -1 0 2.7482e-7 -1 0 1.7651e-7 -1 0 2.65508e-7 -1 1.55967e-7 0 -1 0 0 -1 2.3825e-7 0 -1 0 0 -0.07195609 -0.9914656 0.1087123 0.03908467 -0.978782 0.2011423 -0.00591129 -0.7366102 0.6762918 -0.0591287 -0.7037062 0.7080264 0.08507883 -0.2583385 0.9623009 -0.1344304 -0.07206845 0.9882988 0.1218202 0.4490367 0.88517 -0.1505115 0.6720391 0.7250584 0.1355255 0.8812845 0.4527367 -0.1355302 0.9901704 0.03455865 0.1505118 0.9403085 -0.3052314 -0.1218152 0.8237109 -0.5537703 0.1473415 0.392297 -0.9079611 -0.06729918 0.2440962 -0.967413 -0.007187187 -0.3421552 -0.939616 0.07951372 -0.3995589 -0.9132526 -0.07192295 -0.8396917 -0.5382796 0.07197356 -0.89862 -0.4327839 1 0 0 0.9658758 -0.2590052 6.00117e-4 1 0 0 1 0 0 1 -1.2191e-5 5.32192e-5 1 0 0 1 0 0 0.9989529 0.04011696 0.02199035 0.9967494 0.04002827 0.0699169 0.9999939 -0.003215789 0.001344144 1 0 1.68699e-7 1 0 0 1 0 0 1 0 0 1 0 0 -0.06228262 -0.9822825 -0.176754 0.06494551 -0.7624264 -0.6438075 -0.003751754 -0.6988456 -0.7152627 -0.03392678 -0.2044816 -0.9782823 0.06302237 -0.04683458 -0.9969126 -0.04952698 0.4026302 -0.9140219 0.04164862 0.5891348 -0.8069607 -0.04165309 0.8312282 -0.5543688 0.04953074 0.9302819 -0.3634863 -0.06302303 0.9940275 0.08909249 0.03395104 0.9687111 0.2458577 0.002011716 0.6625325 0.7490305 -0.02474081 0.6374278 0.7701128 0.002801358 -0.01816934 0.999831 0.01851791 -0.03794372 0.9991084 -0.01556968 -0.6206523 0.7839314 0.03094905 -0.6783646 0.7340733 -0.03698295 -0.9357054 0.3508384 0.0632233 -0.9903181 0.1235832 0.02237826 -0.9993264 -0.02908283 -0.06367176 -0.9702544 -0.2335643 0.07572674 -0.844201 -0.5306506 -0.05951923 -0.4496147 -0.8912373 0.05952501 -0.2920876 -0.9545374 -0.0822578 0.2686003 -0.9597331 0.08798158 0.564667 -0.8206159 -0.06311029 0.8130407 -0.5787761 0.06311607 0.9716269 -0.2279421 -0.06310671 0.9961745 0.06044852 0.06312328 0.8991526 0.433059 -0.05117172 0.7559728 0.6525998 0.05965274 0.3719767 0.9263234 -0.005580604 0.286895 0.9579458 -0.04411977 -0.3766625 0.9252993 0.03657805 -0.468052 0.8829436 0.005229592 -0.885654 0.4643164 -0.03504472 -0.9125652 0.4074267 -0.9999949 -0.003143727 -6.22782e-4 -0.9999746 -0.00712341 -3.41872e-5 -0.9999897 -0.00431627 0.001401066 -0.9999915 -0.003545105 -0.002081394 -0.9999911 -0.002899348 -0.003083288 -0.9999938 -0.001588225 -0.003130912 -0.9999982 -0.001550853 0.00105375 -1 0 0 -0.9999555 -0.009392261 8.95691e-4 -0.9999773 -0.006744265 -1.44676e-4 -0.9999845 -0.002436995 0.005020439 -0.9999851 -0.002164244 0.005009055 -0.9999851 0.00158298 -0.005219817 -0.9999851 0.001577138 -0.005233705 -1 0 0 -1 0 0 -1 0 0 -0.9998472 -0.01682931 -0.004722297 -1 0 0 -0.9999984 0.001305878 -0.001198947 -0.999994 0.003433108 -2.57192e-4 -0.9999926 0.00377196 -7.7515e-4 -0.9999949 0.002855718 0.001375317 -0.9999604 0.001883566 0.008698463 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999901 0.004420459 6.20652e-4 -0.9999898 0.004491567 2.1182e-4 -0.9999926 0.003830015 -2.54919e-4 -0.9999711 0.003049552 0.006970286 -0.9999627 0.002414286 0.008295536 -0.9999662 0.002186 0.007923424 -0.9999904 0.003694951 -0.002368688 -0.9999871 0.00483179 -0.001546323 -0.999982 0.002120614 -0.00560981 -0.9990333 0.03852057 0.02118027 -0.9999824 0.005802035 0.001257658 -1 0 0 -1 0 0 0.003916263 -0.002892792 0.9999881 -0.003379642 -0.004919826 0.9999822 -0.004793345 -0.00163418 -0.9999872 -0.04208928 0.008732259 -0.9990757 -0.0280506 -0.9993378 -0.0231747 -0.01661485 -0.9997177 0.01697951 0 -1 0 0 -1 0 0 -1 0 0.02471339 -0.9996946 0 0.02342706 -0.9997256 -2.68306e-4 0.04485142 -0.9948511 0.09088218 -0.05408447 -0.9561104 -0.2879719 0.1184301 -0.8680684 -0.4821118 -0.1610589 -0.5832858 -0.7961393 0.1322286 -0.3231393 -0.9370681 -0.08135885 0.1290394 -0.9882963 0.05152076 0.2609081 -0.9639878 -0.06998997 0.6428341 -0.7628013 0.1037033 0.7887821 -0.6058618 -0.08422809 0.9321964 -0.352016 0.08731442 0.9958871 0.02418678 -0.0367344 0.9883421 0.1477512 0.00831902 0.7741034 0.6330046 0.03253751 0.7621592 0.6465716 -0.03253734 0.2342301 0.9716365 -0.05063205 0.2471728 0.9676477 0.07607382 -0.2035304 0.9761087 -0.09753513 -0.401224 0.9107723 0.0873034 -0.7357259 0.671629 -0.03672313 -0.8157604 0.5772232 0.0036906 -0.9912533 0.1319215 1 1.10665e-5 2.60587e-7 1 -9.37172e-7 -5.99991e-6 1 -5.26024e-6 3.30794e-6 1 6.68528e-7 2.26388e-6 1 -1.72808e-6 -5.85192e-6 1 1.10519e-6 -7.75331e-6 1 -4.0983e-7 2.8751e-6 1 0 2.9034e-6 1 -3.27588e-6 -2.43726e-6 1 -3.67621e-6 -2.29678e-6 1 0 0 1 -3.47954e-6 5.45536e-6 1 -8.06051e-7 5.62071e-6 1 -2.04185e-6 -2.0597e-6 1 -1.9096e-6 -2.14054e-6 1 3.82291e-6 4.28524e-6 1 4.29255e-6 2.18636e-6 1 -1.17254e-6 1.8541e-6 1 1.67138e-6 6.05266e-6 0.1435989 -0.9864378 -0.07949775 -0.1192647 -0.9138712 -0.3880916 0.08226925 -0.7450519 -0.6619135 -0.06286168 -0.4950748 -0.8665734 0.04427611 -0.3786946 -0.924462 -0.07744073 0.04846382 -0.9958183 0.07744109 0.204018 -0.9758993 -0.05914449 0.6411312 -0.7651488 -0.005893051 0.6766297 -0.7363 0.04141592 0.9662774 -0.2541506 -0.045345 0.9802139 -0.1926779 0.003153979 0.8972097 0.4415934 0.06701463 0.8732291 0.48268 -0.07740026 0.5174537 0.8522037 0.07743591 0.3774648 0.9227806 -0.05913692 -0.1027181 0.992951 0.02976137 -0.1783648 0.9835142 -0.02975946 -0.6846659 0.7282493 0.09410852 -0.7552573 0.6486371 -0.1202914 -0.9626442 0.242582 1 0 0 1 3.44632e-6 3.23475e-6 1 -5.8146e-6 -8.07519e-7 1 -9.73685e-6 5.78161e-6 1 5.10644e-7 1.83888e-6 1 2.40481e-6 -2.1151e-6 1 -5.53738e-6 -1.01927e-5 1 3.18086e-6 3.33839e-6 1 2.98875e-6 2.65525e-6 1 3.49962e-6 2.65293e-6 1 3.33195e-6 4.32668e-6 1 -1.79579e-6 2.54027e-6 1 0 0 1 8.91356e-7 1.14993e-6 1 -2.47498e-6 2.69324e-6 1 -3.1247e-6 1.95426e-6 1 2.59842e-6 -1.62511e-6 1 2.86964e-6 -6.58992e-7 1 -9.00383e-6 -3.11156e-6 -1 2.02584e-7 2.7427e-7 -0.9658753 -0.2590069 -6.00933e-4 -1 0 0 -1 0 0 -1 0 2.57939e-5 -0.9989532 0.04011166 -0.02199059 -0.9963856 0.04000854 -0.07493352 -0.9999943 -0.003215312 -0.001029849 -1 -1.01812e-6 3.27392e-7 -1 0 0 -1 -9.63761e-6 -1.3048e-5 1 -2.5728e-6 1.1487e-6 1 1.58714e-6 0 1 -4.39948e-6 -2.37055e-7 1 1.07943e-5 4.51141e-6 1 1.09525e-5 1.74038e-6 1 -2.09816e-6 1.53957e-7 1 1.23275e-6 2.94051e-7 1 0 0 1 3.30496e-7 -4.52378e-6 1 -3.01541e-6 -4.79157e-7 1 -2.85598e-6 2.92326e-6 1 -4.81134e-6 3.72923e-6 1 -2.36118e-6 6.88936e-6 1 1.60592e-6 0 1 0 0 1 0 0 1 0 0 1 -1.95105e-6 -1.86257e-6 1 -3.9655e-6 4.89044e-7 -0.05060899 -0.9912093 0.1222403 0.07607042 -0.9423459 -0.3258795 -0.1431481 -0.8174793 -0.5578855 0.1664413 -0.5422106 -0.8235926 -0.1440274 -0.206073 -0.9678791 0.09697264 0.1756111 -0.9796718 -0.09697574 0.4030991 -0.9100038 0.1257947 0.6932756 -0.7096088 -0.1360288 0.9147189 -0.3805068 0.1070111 0.9837476 -0.1441853 -0.119901 0.9345818 0.3349339 0.1344429 0.8374423 0.5297315 -0.1344478 0.4190894 0.8979353 0.08508354 0.2437778 0.9660917 -0.05913084 -0.2690383 0.9613126 -0.00593084 -0.3132265 0.94966 0.03909528 -0.7563982 0.652942 -0.03908443 -0.797641 0.6018648 0.008292436 -0.9968685 0.07864159 -0.9655928 -0.2589354 0.02414393 -0.9991878 0.04012107 -0.003740966 -1 0 0 -1 0 0 -0.9999942 -0.003215312 0.001065909 -0.9999789 -3.21727e-5 0.006494522 -0.9982268 0.04008251 -0.04400634 -1 0 0 -1 -1.83928e-5 1.95469e-5 -1 0 0 -1 0 -3.42619e-5 -0.9999997 8.14578e-4 -1.2068e-4 -1 -6.17643e-5 3.74326e-6 -0.9999871 4.27797e-4 -0.005043983 0.05200767 -0.9939592 0.09664583 -0.05605226 -0.9116847 0.4070494 0.05905687 -0.7727805 0.6319198 -0.05550241 -0.3764521 0.924772 0.0737468 -0.1767362 0.9814916 -0.079234 0.2859766 0.9549551 0.05841052 0.6381735 0.7676737 -0.05839341 0.794081 0.6050005 0.07923591 0.9662291 0.2452 -0.07374066 0.9731103 -0.2182171 0.03770691 0.9202995 -0.3893931 -0.03367954 0.5992625 -0.7998438 0.04577594 0.4712513 -0.8808102 -0.05116802 0.07513856 -0.9958595 0.06311452 -0.1864922 -0.9804271 -0.07276272 -0.5684751 -0.8194765 0.0828796 -0.7804542 -0.6196954 -0.07400906 -0.9760317 -0.2046577 0.01320469 -0.988618 0.1498667 -0.05958437 -0.9660182 0.2515125 0.08225136 -0.6764003 0.731927 -0.07252311 -0.4307309 0.8995617 0.04521256 -0.0942685 0.9945197 -0.05513161 0.2079424 0.9765862 0.07134807 0.479857 0.8744408 -0.08094608 0.8232721 0.5618457 0.1032176 0.9635346 0.2468751 -0.09759557 0.9855625 -0.1383537 0.08909577 0.7750928 -0.6255343 -0.04461503 0.6216982 -0.7819852 0.02696192 0.1783981 -0.9835889 -0.02696347 0.07521456 -0.9968027 0.04057836 -0.3782866 -0.9247987 -0.04056644 -0.5185959 -0.8540565 0.03136086 -0.8618355 -0.5062175 -0.01517188 -0.8978106 -0.4401203 0.999997 -0.002223312 -0.001095652 1 -1.98378e-6 6.49524e-7 0.9999971 -0.001271545 -0.002091765 0.9999513 -0.009688377 0.0019055 0.9999892 -0.004634559 2.29307e-4 0.9999769 0.003380894 0.005907773 0.9999844 0.005159854 0.002183139 0.9999911 0.002412736 -0.003464519 0.9999966 0.002415239 0.001025736 0.9999563 -0.001717388 -0.009199559 0.9999265 0.001247227 -0.01205682 0.9999198 0.002252638 -0.01246118 1 -8.82307e-7 1.04836e-6 1 0 0 0.9999999 4.9805e-4 -7.37886e-5 0.9999991 4.6469e-4 -0.00131458 1 1.01816e-6 -7.20436e-7 1 2.85683e-6 -9.35375e-7 0.9999966 0.001795232 -0.001911342 1 0 0 1 1.03433e-6 -7.1861e-7 0.9999945 0.002738654 0.001868963 0.9999901 0.002202212 0.003855824 0.9998278 0.00444132 0.01802241 0.9999771 0.005853533 -0.003393948 0.999997 0.002444446 -1.94109e-4 0.9999999 4.19899e-4 -3.15265e-4 0.9999954 6.35714e-4 0.00299102 0.9999882 0.001875102 0.004478693 1 -3.56054e-5 -1.0724e-5 0.9999998 5.30576e-4 1.51605e-4 1 4.98906e-4 -6.63972e-5 0.9999978 -8.65557e-4 0.001953959 0.9999994 1.54191e-4 0.001116812 0.9999771 0.002262473 0.006384849 0.9999963 -0.002520561 9.53391e-4 1 8.22247e-7 -5.40144e-7 0.9998945 -0.01446557 0.001330018 1 -2.80791e-6 1.84455e-6 0.9999659 -0.008262455 -3.01417e-4 0.9994595 -0.03251373 -0.004859089 0.999531 0.005401968 0.03014385 0.9999984 -0.001143813 0.001352727 0.999988 -0.004516124 0.001878619 1 -5.14997e-7 3.9443e-6 1 1.93768e-6 1.8371e-6 0.9991527 -0.03776109 -0.01637393 0.999807 -0.01849406 -0.006627857 0 0 -1 1.12234e-4 -9.6182e-5 -1 1.30599e-4 -8.87922e-5 -1 0.001360118 0.01322084 -0.9999116 0 -1.58026e-4 1 5.77316e-4 0 0.9999998 2.15234e-4 -1.45627e-4 0.9999999 9.86332e-4 0.005693197 0.9999834 -0.7834315 0.1060041 0.6123709 -0.8518475 -0.1728861 0.4944354 -0.9316014 0.1701551 0.3211947 -0.9733767 -0.1705797 0.1531025 -0.9837749 0.1314805 -0.122065 -0.9676237 -0.1314855 -0.2154434 -0.8484923 0.1973521 -0.4910324 -0.7982375 -0.1068511 -0.5927898 -0.507718 -0.07515561 -0.858239 -0.3987376 0.1373567 -0.9067201 -0.2846987 -0.07653999 -0.9555565 -0.070755 0.1230984 -0.9898689 0.07642626 -0.1244934 -0.9892727 0.2347495 0.08925437 -0.9679495 0.4098559 -0.1211738 -0.9040658 0.4895038 0.0904392 -0.8672984 0.7961347 -0.06993961 -0.601064 0.8425287 0.151326 -0.5169584 0.9394387 -0.1254868 -0.318917 0.9727156 0.1701428 -0.157721 0.9852305 -0.1705728 0.01502639 0.9485792 0.1314787 0.2879427 0.9358402 -0.04226732 0.3498808 0.7975874 0.03604239 0.6021258 0.7878833 0 0.6158246 0.5013471 0 0.8652464 0.5136796 0.03081512 0.8574284 0.3201932 -0.06068301 0.9454067 0.2295392 0.09734201 0.9684195 -0.09610992 0.1314914 0.9866474 0.03104192 -0.07942813 0.9963571 -0.2635931 -0.1112717 0.9581948 -0.4620894 0.09199929 0.8820484 -0.5045689 0 0.8633714 0 0.9999994 0.001074731 0 1 1.32998e-5 -0.006556928 0.9999779 0.001022398 -1.84708e-6 1 6.82186e-6 -0.004330217 0.9999906 -1.16077e-4 -0.004629075 0.9999893 0 -0.005117654 0.9999868 1.77635e-4 -0.002359151 0.9999144 0.01287758 0 1 -1.65369e-4 -0.002145946 0.9999315 -0.01151043 -0.004629075 0.9999893 0 -0.004518866 0.9999898 -2.81346e-4 4.81333e-5 1 3.63257e-6 -0.1770844 0.01392447 0.9840971 -0.2935818 -0.07159358 0.9532493 -0.7332475 0.05619037 0.6776362 -0.8626425 -0.05618268 0.5026843 -0.9961988 0.05617976 0.06657189 -0.9918506 -0.04057574 -0.1207731 -0.7826417 0.039303 -0.6212304 -0.7717183 0.024993 -0.6354732 -0.2574931 -0.05876177 -0.9644917 0.02851301 0.09478002 -0.9950898 0.3016114 -0.04843491 -0.9521999 0.769796 0.03822278 -0.6371446 0.8346266 -0.03822791 -0.5494881 0.9987801 0.04844141 -0.009573936 0.9764896 -0.06393003 0.2058666 0.8470811 0.05333119 0.5287812 0.5564736 -0.08292829 0.8267165 0.3793448 0.04358232 0.9242283 -0.01002252 0.9999212 0.007568776 -0.02294629 0.9997063 0.00778836 -0.03227269 0.9994315 0.009749948 -0.06296771 0.9980151 -9.55415e-4 -0.03122258 0.9995104 -0.002031624 -0.009152233 0.9999326 -0.00715357 -0.0177676 0.99982 -0.006648063 -0.01402115 0.9998846 -0.005851209 -0.01013028 0.9998535 -0.01379823 -0.9964296 -0.004144847 -0.08432608 -0.9871475 -0.03915643 -0.1549409 -0.815906 0.03959143 -0.5768275 -0.5631796 -0.04274207 -0.8252284 -0.3796398 0.03422832 -0.924501 0.04706442 -0.03655797 -0.9982226 0.3613117 0.03876495 -0.931639 0.5082631 -0.02118211 -0.8609412 0.8546007 0.03138673 -0.5183363 0.9539887 -0.04219645 -0.2968586 0.9957788 0.02072542 -0.0894156 0.9057783 -0.02930593 0.4227373 0.8898393 -0.01059454 0.4561512 0.5980038 0.0349152 0.8007324 0.394708 -0.03494977 0.9181416 0.07812613 0.0188679 0.996765 -0.1084787 -0.02620673 0.9937533 -0.3683006 0.03655815 0.9289878 -0.767356 -0.04399478 0.6397102 -0.8401772 0.0179919 0.5420136 -0.9874022 -0.04364591 -0.152092 -0.9163088 0.05201154 -0.3970806 -0.6959096 -0.03752517 -0.7171483 -0.4335888 0.03830707 -0.9002963 -0.2011704 -0.03484869 -0.9789361 0.2282369 0.03953742 -0.9728025 0.4335665 -0.03953641 -0.9002539 0.7547301 0.03040331 -0.6553305 0.9030799 -0.03371572 -0.4281472 0.9663385 0.02072596 -0.2564383 0.978565 -0.02368676 0.2045711 0.9253571 0.04273855 0.3766799 0.6927434 -0.05343848 0.7192015 0.3564031 0.07066863 0.931656 0.03484082 -0.04898661 0.9981915 -0.4390774 0.03472518 0.8977779 -0.5063001 0.002176344 0.8623546 -0.8778321 -0.0143966 0.4787521 -0.9301331 0.04056495 0.3649752 -0.9924444 0.1130685 -0.04764235 -0.9979385 -0.02257645 0.06007373 -0.777507 -0.6277738 -0.03718781 -0.7472141 -0.6645698 -0.004245102 -0.2510212 -0.9677523 0.02106684 -0.1622812 -0.985798 -0.04321068 0.4774173 -0.8776137 0.04321032 0.5553191 -0.8313698 -0.02109414 0.9241966 -0.381894 0.004217863 0.9307491 -0.365283 0.01656979 0.9750026 0.2216667 -0.01528906 0.9670867 0.254392 0.005315482 0.4253292 -0.9024017 -0.06903862 0.742232 -0.6695143 0.02902179 0.8156404 -0.5780453 -0.02438008 0.9797698 -0.1985314 0.02523058 0.9966866 -0.07876038 -0.02031534 0.9260429 0.3773972 0.003989696 0.9329829 0.359739 0.01143616 -0.9750058 0.2216714 0.01501888 -0.9854836 0.1685339 -0.02045184 -0.9194754 -0.3931248 0.004213094 -0.8990658 -0.436232 0.03717964 -0.501947 -0.8633886 -0.05108171 -0.3038228 -0.9494432 0.07905226 0.198953 -0.9756569 -0.09225749 0.4760648 -0.8751267 0.08669179 0.8718934 -0.4870103 -0.05121415 0.9304523 -0.3651723 0.03013038 0.9901529 0.1333174 -0.0427038 0.9667003 0.2542904 0.02875542 -0.9750034 0.2216814 0.01502084 -0.9935867 0.08384573 -0.07586354 -0.90889 -0.4079571 0.08654469 -0.6821893 -0.7262517 -0.0847128 -0.4867131 -0.8726686 0.03949713 0.004405081 -0.9994074 -0.03413784 0.05131381 -0.9986813 -0.001584053 0.6844423 -0.728635 0.02509129 0.7060785 -0.7081314 -0.001741707 0.9987494 -0.02258896 -0.0446031 0.9952103 0.08399039 0.05001997 -0.9347363 0.3549813 0.01601159 -0.961532 0.2743842 -0.01302385 -0.9833244 -0.1810386 -0.01726806 -0.9926396 -0.1208328 0.008122622 -0.7960299 -0.60477 0.02428251 -0.732073 -0.6792532 -0.05181044 -0.374566 -0.9255362 0.05552643 -0.9678962 0.2509175 0.01474398 -0.9933152 0.08382314 -0.07936298 -0.9483086 -0.3054907 0.08594375 -0.6820736 -0.7261238 -0.08671784 -0.4579021 -0.8854805 0.07905679 0.00439763 -0.9965584 -0.08277726 0.2955625 -0.9529171 0.06776273 0.6857822 -0.7266241 -0.04147642 0.7943249 -0.6060745 0.04149246 0.9731259 -0.2219992 -0.06117504 0.9904879 0.1128411 0.07874482 0.9425801 0.3328753 -0.02714478 0.9231972 0.3839662 -0.01664358 0.9371071 0.3490313 -0.002740323 0.9610634 -0.2736012 -0.03872388 0.9870694 -0.1594935 0.01599752 0.7324956 -0.6797122 0.03796905 0.4181272 -0.8961514 -0.1486008 -0.4552907 -0.8864892 0.08274781 -0.74693 -0.6613211 -0.06892269 -0.8978699 -0.4377087 0.04733705 -0.9839583 0.1746314 0.03647029 -0.9980953 -0.05569928 -0.02652513 -0.9267445 0.3750118 -0.02260416 -0.7944214 -0.003162443 -0.6073588 -0.79934 -0.01131522 -0.6007725 -0.8875895 7.17554e-5 -0.4606352 0.8954017 -0.004803299 -0.4452335 0.7597808 -0.001251995 -0.6501781 0.855408 0.01647716 -0.5176928 0.7946955 -0.02586179 -0.6064571 -0.8741598 0.03242743 0.4845544 -0.8270764 -0.04972738 0.5598856 -0.7545556 -0.003270745 0.656228 -0.7929279 -0.02812606 0.6086658 0.8018569 -0.03127026 0.5966974 0.7706697 -0.003048539 0.6372275 0.8808192 -0.009335279 0.4733607 0.8554566 -8.47423e-5 0.5178745 -0.02136033 -0.9889774 0.1465172 -0.00331968 -0.9999594 0.00838238 2.43322e-4 -1 2.636e-4 0 -1 0 0 -1 0 -0.06956636 -0.9975141 -0.01123321 -0.05337977 -0.9751583 0.214981 0.01317334 -0.9998114 -0.01427108 -0.06803023 -0.9949575 0.07369941 0.01079809 -0.9999268 0.005455076 0 -1 0 0.03708744 -0.9992941 -0.005988657 0.05338132 -0.9751585 -0.21498 -0.01317119 -0.9998114 0.01426881 0.1014129 -0.9887595 -0.1098641 -0.01619631 -0.9998353 -0.008182227 0 -1 0 -0.03708952 -0.999294 0.005989015 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 -0.003273248 0.01078158 -0.9999365 1.23547e-6 -3.98239e-7 -1 0 0 -1 0 0 -1 -4.72993e-4 0.006296932 -0.9999802 0.001709222 0.004715859 -0.9999874 -6.15202e-7 2.13223e-6 -1 4.68976e-7 1.66192e-7 -1 4.04865e-7 8.03333e-7 -1 -5.9396e-7 2.11392e-6 -1 -4.208e-6 2.63512e-6 -1 5.79577e-6 -4.18046e-6 -1 2.19574e-5 2.50149e-6 -1 1.83452e-5 -1.53325e-5 -1 2.83391e-6 5.96195e-6 -1 2.18338e-7 5.34008e-6 -1 -3.55876e-7 -1.47e-7 -1 0 0 -1 3.28142e-7 -1.84989e-6 -1 4.76572e-7 -1.78731e-6 -1 1.24799e-6 3.00364e-6 -1 2.72192e-6 2.74123e-6 -1 -1.52284e-6 -1.53364e-6 -1 -1.80799e-6 6.63751e-7 -1 -5.33774e-7 -4.39059e-6 -1 -5.31406e-5 -5.79038e-6 -1 -6.48369e-5 -1.70553e-5 -1 -8.92071e-7 -6.34774e-7 -1 1.08886e-5 -6.67746e-6 -1 -8.80348e-5 3.49337e-5 -1 -2.17733e-5 -1.05139e-5 -1 -5.96754e-6 8.97734e-6 -1 -3.71655e-6 -7.53864e-7 -1 -4.42078e-7 3.18266e-6 -1 1.55934e-6 -7.43802e-7 -1 -1.96249e-6 -3.73989e-6 -1 -2.14332e-6 3.65942e-7 -1 3.07774e-7 3.40808e-7 -1 1.22667e-6 1.35833e-6 -1 9.51992e-6 -7.5811e-6 -1 0 0 1 0 0 1 -3.26639e-6 1.05288e-6 1 -0.008133172 -0.001053929 0.9999664 -4.27986e-4 0.001425921 0.9999989 -2.19913e-4 0.001191079 0.9999993 -1.61694e-7 -4.32597e-6 1 1.13e-6 2.49657e-7 1 -6.11911e-6 -8.45409e-6 1 1.06824e-6 -4.44401e-6 1 -1.76486e-6 -9.50816e-7 1 3.81388e-6 2.05472e-6 1 8.34498e-6 -2.7629e-6 1 -5.7995e-6 -7.83441e-6 1 -7.27174e-6 -1.61277e-6 1 0 6.14301e-6 1 2.39928e-6 2.87739e-6 1 7.17182e-7 8.60099e-7 1 1.23136e-5 -1.95151e-5 1 1.91905e-5 1.84466e-6 1 1.18411e-5 0 1 1.2089e-5 -1.92339e-6 1 -3.84635e-7 -7.08608e-7 1 -4.8977e-6 5.16077e-6 1 1.33077e-6 2.85145e-6 1 -6.47786e-7 -1.38802e-6 1 -1.05599e-6 -1.0992e-6 1 8.57265e-6 8.92338e-6 1 1.31288e-5 8.9747e-6 1 1.46553e-5 2.43567e-5 1 1.02555e-6 1.40455e-5 1 2.87048e-6 1.03966e-5 1 1.69001e-5 3.32975e-5 1 -5.24201e-5 7.0155e-5 1 -7.00979e-5 -1.35209e-5 1 3.56032e-6 -7.72524e-6 1 0 0 1 -2.60642e-6 -2.19706e-6 1 0 -2.90616e-6 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 1 1.2612e-7 2.29272e-7 1 0 0 1 0 0 1 0 0 1 0 3.45138e-7 1 0 3.70272e-7 1 0 4.31054e-7 1 0 3.06409e-7 1 5.88887e-7 2.72999e-7 1 2.35964e-7 -1.36066e-7 1 3.46812e-7 -1.99986e-7 1 3.16459e-7 -2.11055e-7 1 2.99785e-7 -1.5021e-7 1 2.80384e-7 -1.40489e-7 1 0 -5.83041e-7 1 -2.47897e-7 -1.99664e-7 1 0 0 1 0 -2.09127e-7 1 -4.31584e-7 -3.33778e-7 1 -4.53903e-7 0 -0.01888 0.05541592 -0.9982849 1.69715e-4 -9.25455e-5 -1 -0.003153979 0 -0.999995 -7.44045e-5 0.002625524 -0.9999965 0 0 -1 0 0 -1 -0.001318633 0.001758694 -0.9999975 0.00374639 0.003198802 -0.999988 0.003264963 -0.009583294 -0.9999488 0.01895207 -0.01035964 -0.9997667 0 -3.27184e-4 -1 2.80335e-4 -6.64368e-6 -0.9999999 7.65298e-4 1.62617e-4 -0.9999997 -2.10257e-4 0 -1 -0.007362186 0.01041465 0.9999186 0 -0.0122615 0.9999248 1.043e-5 0 1 -2.13815e-4 2.21305e-5 1 -6.06115e-7 8.74771e-7 1 0 0 1 -1.11896e-4 6.10171e-5 1 2.63799e-4 1.98222e-4 0.9999999 -7.89602e-5 1.13791e-4 1 0.001685619 4.68028e-4 0.9999984 0.006070375 0.004380941 0.999972 -0.006029009 0.01058524 0.9999258 1.18621e-4 0 1 -2.11642e-4 -5.50895e-5 1 1 0 1.73396e-6 1 -1.71833e-7 0 1 0 -2.11926e-6 -0.1981012 -0.01803165 -0.9800158 -0.410614 0.01696771 -0.9116513 -0.7260804 -0.02628481 -0.6871073 -0.6911599 -0.01040542 -0.722627 -0.8589549 -0.0205475 0.5116388 -0.9567083 0.03332197 0.2891349 -0.9988443 -0.03263264 -0.03528779 -0.9468314 0.04089438 -0.3191207 -0.7181569 0.01025086 0.6958057 -0.4296368 0.004528164 0.9029904 -0.4971083 -0.01241481 0.8675997 0.1187172 0.02330273 -0.9926546 0.3121956 -0.02245706 -0.9497524 0.7702339 0.01830881 -0.6374987 0.8003031 0.002076327 -0.5995923 0.9943541 -0.009200036 -0.105714 0.9995945 0.02193075 0.01816499 0.9069611 -0.02452218 0.4205 0.7498369 0.03537243 0.6606765 0.4954592 -0.02938169 0.8681341 0.09320038 0.02052044 0.995436 -0.00976932 -0.005161583 0.999939 1 5.10946e-7 2.85242e-7 1 4.73541e-7 0 1 4.68098e-7 0 1 3.4731e-7 -3.69379e-7 1 -2.98122e-7 3.17065e-7 1 0 4.61007e-7 1 0 7.30009e-7 1 4.41621e-7 0 1 0 0 1 0 1.7977e-7 1 6.00666e-7 0 1 1.72728e-7 -3.38825e-7 1 -2.00152e-7 3.9262e-7 1 0 3.58471e-7 1 0 3.15859e-7 1 0 -1.80606e-7 1 0 -2.37094e-7 1 0 0 -1 3.13897e-6 1.52017e-6 -1 1.63558e-6 2.57441e-6 -1 0 0 -1 0 0 -1 1.73852e-7 -3.3666e-6 -1 5.38774e-7 -2.9705e-6 -1 6.84596e-7 -3.08552e-6 -1 -3.89556e-7 1.75576e-6 -1 -5.56109e-6 1.85189e-6 -1 -1.25599e-6 -2.43729e-6 -1 6.9567e-6 3.80262e-6 -1 4.10793e-6 7.43188e-6 -1 2.37966e-7 3.3715e-6 -1 -3.10592e-7 3.2767e-6 -1 4.20478e-7 2.11578e-6 -1 0 0 -1 -3.23347e-6 7.58704e-7 -1 -2.26099e-6 -1.09498e-6 -1.8352e-6 0 -1 0.01271736 0.03732764 -0.9992222 -3.09789e-4 2.22781e-4 -1 1.80059e-4 2.59869e-4 -1 3.04397e-7 4.39319e-7 -1 8.62125e-5 1.2913e-4 -1 2.40116e-4 2.27286e-5 -1 -2.18662e-4 -6.41807e-4 -0.9999997 1.2751e-5 -6.4058e-4 -0.9999998 -6.81092e-4 6.25538e-4 -0.9999996 -6.97656e-4 -1.76109e-4 -0.9999997 0.001392841 2.35664e-4 -0.999999 -0.007150173 0.004826486 -0.9999628 0.004163622 0.002140223 -0.9999891 5.33087e-4 0 0.9999999 6.75119e-6 4.46192e-4 0.9999999 6.34009e-7 2.86872e-6 1 2.78327e-6 -9.45616e-7 1 -6.45701e-4 5.30632e-4 0.9999997 2.20051e-4 2.98067e-4 1 0.003010272 -0.001598834 0.9999942 7.0518e-4 7.39617e-4 0.9999995 0 0 1 -5.26105e-4 -0.001544177 0.9999986 2.98239e-4 -0.001533627 0.9999988 -0.001538038 9.66809e-4 0.9999983 0.001391112 5.1848e-4 0.9999989 0.001966893 4.23906e-4 0.999998 -9.75072e-5 -4.88197e-5 1 -1 4.64058e-4 4.73245e-5 -0.999972 -8.24886e-4 0.007422149 -1 4.64187e-4 4.56662e-5 0.004536867 -0.02866208 0.9995788 0.312083 0.01678556 0.9499065 0.6315071 -0.001012802 0.7753694 0.6467205 -0.008730947 0.762677 0.9312461 -0.008905708 0.3642818 0.9711061 0.04135763 0.2350371 0.9490224 -0.04075521 -0.3125627 0.9101552 0.001876056 -0.4142631 0.713156 0.02254933 -0.7006426 0.3606371 0.001028478 -0.9327057 0.4462744 -0.02552324 -0.8945322 -0.1118925 0.00414896 0.9937117 -0.5443444 0.02593034 0.838461 -0.7581132 -0.05083572 0.6501385 -0.9637489 0.04221194 0.2634508 -0.9918119 -0.03618317 -0.1224739 -0.8903085 0.03618198 -0.4539179 -0.6960711 -0.03012663 -0.7173405 -0.2772647 0.02689421 -0.960417 -0.1946149 -7.62018e-5 -0.9808797 -1 -4.83358e-6 -1.80966e-6 -1 1.24812e-6 -2.15715e-6 -1 2.80607e-6 3.15876e-6 -1 -7.31356e-7 3.68388e-6 -1 -7.1508e-7 3.6019e-6 -1 -1.47229e-6 2.75184e-6 -1 2.054e-6 4.20121e-7 -1 1.93518e-6 7.08771e-7 -1 -2.63895e-6 -9.6653e-7 -1 -3.13347e-6 -7.95181e-7 -1 -3.54405e-6 -2.80586e-6 -1 0 -1.80897e-6 -1 1.87894e-7 -3.17135e-6 -1 4.99911e-7 -2.77622e-6 -1 0 -2.15632e-6 -1 0 0 -1 0 0 -1 -1.88234e-6 1.60842e-6 0.9980285 0 0.06276291 0.9999812 -0.006142258 0 0.9970591 0 -0.07663601 6.23001e-6 0 -1 9.45976e-4 -8.14405e-6 -0.9999995 0 0 -1 -7.38075e-7 -1.31499e-6 -1 -5.9775e-5 -2.80729e-5 -1 6.24853e-7 -1.63307e-4 -1 1.31952e-4 -1.57346e-4 -1 -4.97478e-6 2.87945e-6 -1 0 0 -1 1.25471e-4 1.48894e-4 -1 -1.65141e-6 3.75472e-7 -1 9.03117e-4 1.71069e-4 -0.9999997 9.98233e-5 1.82341e-4 -1 5.31076e-4 2.35249e-4 -0.9999998 -2.98208e-6 -1.45992e-7 -1 -0.9991233 0 -0.04186427 -0.999466 -0.005845487 0.03215026 -1 0 0 -2.25342e-5 -6.90402e-6 -1 1.71397e-5 -8.55572e-6 -1 8.79e-7 -4.52445e-5 -1 -4.27825e-5 -4.05872e-5 -1 -4.07185e-7 -1.56981e-6 -1 0 0 -1 1.76557e-6 -3.37808e-6 -1 1.37327e-5 0 -1 -8.772e-6 0 -1 0 3.01116e-6 -1 0 -1.99167e-6 -1 1.0893e-6 6.54244e-7 -1 0 0 -1 0 0 -1 -0.9994883 0 -0.03198707 -0.9999952 -0.003102242 0 -0.9992359 0 0.03908556 0.9929562 0.001966118 0.1184665 0.997212 -0.01334881 -0.07341849 1 0 0 0.002413511 4.4045e-4 0.999997 0 0 1 -1.09661e-5 -5.13236e-6 1 6.49188e-6 -4.18295e-5 1 0 -2.7573e-6 1 -2.18939e-6 -2.02754e-7 1 -2.64938e-6 3.12706e-4 1 -0.006406307 0.01488345 0.9998687 0.002778232 3.49425e-4 0.9999961 1.54324e-4 1.63876e-4 1 -1.7831e-6 -3.38356e-7 1 -0.01529151 0.01620322 0.9997518 0.03386944 -0.01118284 0.9993637 0 -1.57499e-7 1 3.23786e-7 0 1 1.26795e-7 -2.25904e-7 1 -0.04280239 0.07625889 0.9961689 0 0 1 -7.75281e-7 0 1 0 0 1 -1.35627e-4 -1.58705e-4 1 -1.66448e-6 -1.64784e-4 1 6.07638e-5 -2.68652e-5 1 3.37695e-7 -1.28329e-7 1 4.67508e-7 0 1 0 -3.56687e-7 1 -3.15997e-7 1.20083e-7 1 0 0 1 0 0 1 -1 0 -6.24379e-7 -1 1.86425e-6 7.12639e-7 -1 7.10162e-7 -6.28788e-6 -1 2.01645e-6 -6.79963e-7 -1 0 -7.43659e-7 -1 0 -7.49619e-7 -1 1.20448e-6 2.08931e-6 -1 6.26014e-7 5.7115e-6 0.01001793 -0.9257164 0.3780857 -0.00630635 -0.8972856 0.4414053 0.007476449 -0.5087539 0.8608796 0.001903712 -0.4930977 0.8699719 -0.008979678 0.05202358 0.9986056 0.03244102 0.2024047 0.9787644 -0.03913569 0.6464018 0.7619929 0.04944312 0.9165261 0.3969072 -0.01879769 0.9822104 0.1868408 -0.001600205 0.8817324 -0.4717471 0.04093587 0.8188309 -0.5725733 -0.03487694 0.4172712 -0.9081125 0.02982801 2.27587e-4 -0.9995551 -0.006833314 -0.1365121 -0.9906149 0.007466137 -0.6741918 -0.7385187 -0.01556658 -0.7274605 -0.6859729 0.0196942 -0.9836263 -0.1791414 -0.01312053 -0.9991676 -0.03862643 1 -5.38375e-7 0 1 0 -5.75515e-7 1 -4.82403e-7 -7.54899e-7 1 -3.65358e-7 -3.1866e-7 1 -8.45557e-6 9.78671e-7 1 6.20984e-7 -2.77932e-6 1 -1.96856e-6 2.27846e-7 0.009359896 -0.9832513 -0.1820142 -7.90472e-4 -0.9777609 -0.2097218 -0.01488745 -0.6873548 -0.7261693 0.03576129 -0.5381296 -0.8421032 -0.0290932 -0.1364606 -0.9902182 0.02236205 0.217999 -0.9756927 -0.01702421 0.4174783 -0.9085274 0.02248924 0.7283749 -0.6848098 -0.03318452 0.8944498 -0.4459354 0.0387181 0.9966047 -0.07266336 -0.04978525 0.9252747 0.3760164 0.03921407 0.7530468 0.6567975 -0.0261715 0.2520952 0.9673485 0.007473647 0.1449913 0.9894047 -0.006836712 -0.4416279 0.8971722 0.005437552 -0.4822792 0.8760007 -0.00603652 -0.8695133 0.4938725 -7.37232e-4 -0.8779126 0.4788204 -0.02590638 0.999649 0.005542278 -0.002638101 0.9999939 -0.002320349 -0.01020473 0.9999123 0.008443534 -0.005261361 0.9999861 -9.44859e-5 -0.4255698 0.904924 -0.001775026 -0.412499 0.9109562 0.001835525 -0.6846578 0.7288598 -0.002688109 -0.6656932 0.7461789 -0.008337914 0.03224992 0.9994774 -0.00221312 -6.97399e-4 0.9999992 0.001078963 0.00507909 0.9999843 0.002353787 -0.003193557 0.9999949 -3.25664e-4 -8.27358e-6 1 -8.43689e-7 0.7060475 0.7080733 -0.0113579 0.6417933 0.7668091 0.01026463 0.3568583 0.9341133 -0.009200632 0.3046565 0.9524599 0.002151906 -0.01300549 0.9999005 0.005437672 -1 0 -5.69115e-7 -1 1.78655e-7 -5.50369e-7 -1 1.46761e-6 -6.84959e-7 -1 -2.05746e-7 -3.24045e-7 -1 0 8.74976e-7 -1 -3.31115e-7 1.35428e-6 -0.09678167 0.08885836 -0.9913312 0.09684032 0.4318764 -0.8967189 -0.09192913 0.7671023 -0.634904 0.1116473 0.9221764 -0.3703049 -0.1456192 0.9864412 0.0756886 0.145602 0.8596675 0.489665 -0.1274573 0.5316427 0.8373234 0.04361331 0.3386376 0.9399055 0.004832208 -0.2200492 0.9754769 -0.07995373 -0.3077623 0.948098 0.07584571 -0.7444062 0.6634054 -0.08612364 -0.9027985 0.421352 0.06363517 -0.9851891 0.1592263 -0.07216054 -0.9604834 -0.2688207 0.09191417 -0.8633729 -0.4961239 -0.09684151 -0.5772245 -0.8108227 0.09679412 -0.2551172 -0.9620531 -1 1.20568e-6 -2.12487e-7 -1 0 -2.77921e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.47285e-7 0 -1 0 0 -1 1.41459e-7 -1.79858e-7 -1 5.86457e-7 0 -1 5.72669e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 9.30482e-7 0 -1 9.5023e-7 0 0.05398887 0.1060056 -0.9928988 -0.1277948 0.2265346 -0.965583 0.1614796 0.6180816 -0.76935 -0.1426333 0.7640681 -0.6291706 0.07572484 0.9898176 -0.1205276 -0.01581102 0.9867442 -0.1615114 0.0574578 0.9057528 0.4198935 -0.154546 0.8389521 0.5217996 0.2003182 0.4304417 0.8801094 -0.2003673 0.2180121 0.9551564 0.1544821 -0.324941 0.933032 -0.1055298 -0.4637582 0.8796544 0.1055369 -0.859183 0.5006661 -0.1054959 -0.9134404 0.3930612 0.09434324 -0.9882408 -0.1203303 -0.1686799 -0.9411591 -0.2928592 0.1566147 -0.7812737 -0.6042212 -0.1375888 -0.4565981 -0.8789696 -0.008723139 -0.3922868 -0.9198015 -1 -2.88521e-7 -2.21071e-7 -1 3.44327e-7 2.63831e-7 -1 0 0 -1 -2.63736e-7 -1.82894e-7 -1 0 0 -1 1.26517e-6 3.58001e-7 -1 0 -3.62499e-7 0.08453845 0.1085711 -0.9904875 -0.09339588 0.3599967 -0.928267 0.08104997 0.7069334 -0.702621 -0.06573438 0.8664206 -0.4949689 0.06770879 0.9950646 -0.07253903 -0.05204457 0.9956579 0.07717883 0.05202901 0.7722186 0.6332231 -0.09045302 0.6453905 0.7584784 0.08493375 0.282606 0.9554686 -0.1042144 -0.1427913 0.9842509 0.06738185 -0.3551335 0.932384 -0.04379451 -0.8046872 0.5920815 0.01594442 -0.8481592 0.5295014 -0.01594471 -0.999216 0.03623694 0.06763452 -0.995223 -0.07040506 -0.09709006 -0.8298873 -0.5494183 0.09753936 -0.5851121 -0.8050651 -0.06251341 -0.3791455 -0.923223 -1 -1.66463e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 3.1213e-7 -2.06856e-7 -1 3.22956e-7 -2.0162e-7 -1 4.6813e-7 -6.11309e-7 -1 1.35107e-7 -3.54715e-7 -1 0 -6.01638e-7 -1 -1.21932e-7 -4.12244e-7 -1 1.45229e-7 -4.09531e-7 -1 3.81001e-7 5.40898e-7 -1 5.31558e-7 5.20247e-7 -1 0 0 -1 3.92755e-7 -3.01416e-7 -1 4.86139e-7 -1.78402e-7 -1 0 0 -1 0 0 -1 0 0 0.2003561 -0.0297091 -0.9792726 -0.2003552 0.1947935 -0.9601632 0.1544877 0.6804118 -0.7163612 -0.01179462 0.7550525 -0.6555582 -0.06826335 0.9642912 -0.2558954 0.15632 0.9824633 -0.1016364 -0.1381281 0.9369625 0.3209703 0.1516081 0.8288487 0.5385395 -0.1233091 0.6398189 0.7585689 0.1468691 0.2781539 0.9492417 -0.1132539 0.1336367 0.9845378 0.1239894 -0.4800443 0.8684378 -0.1728262 -0.5988407 0.781998 0.1641478 -0.9130098 0.3734547 -0.1223592 -0.9811638 0.1494848 0.101536 -0.9788649 -0.1775218 -0.08262306 -0.9411951 -0.3276055 0.1055243 -0.6704215 -0.7344383 -0.1544548 -0.5495589 -0.8210535 1 3.79746e-7 1.60931e-6 1 4.74751e-7 6.93124e-7 1 1.53775e-6 -1.90353e-6 1 2.63376e-7 1.11615e-6 1 -6.22765e-7 0 1 -1.22273e-6 -4.20312e-6 0.08493572 -0.03274559 -0.9958482 -0.1042184 0.3861876 -0.9165139 0.1142609 0.6242917 -0.77279 -0.1495651 0.9465336 -0.2858396 0.1759342 0.9820565 0.06791239 -0.1759423 0.7559869 0.6304982 0.1229536 0.5132755 0.8493708 -0.08545023 -0.1128959 0.9899257 0.05843675 -0.251774 0.9660202 -0.08225297 -0.818871 0.5680534 0.08986949 -0.9109299 0.4026539 -0.08986711 -0.9829975 -0.1601243 0.05498123 -0.9473378 -0.3154809 0.007170617 -0.5650817 -0.8250039 -0.1028944 -0.4600369 -0.8819178 1 -3.10957e-7 1.61566e-6 1 6.86425e-7 -3.56649e-6 1 1.80986e-6 -1.39515e-6 1 0 0 1 0 -1.03508e-6 1 -9.65326e-7 -1.05118e-6 1 0 0 1 -1.3285e-6 0 1 -1.55624e-6 -4.51115e-7 1 0 0 1 1.6251e-6 -3.56572e-6 1 1.86501e-6 -3.57406e-6 1 0 0 1 0 0 1 0 0 1 1.31143e-6 2.38153e-6 0.1573621 -0.08817481 -0.9835966 -0.1069597 0.510986 -0.8529084 0.04785948 0.5792612 -0.8137359 -0.04784876 0.9476892 -0.3155878 -0.01219224 0.9542709 -0.2986946 0.05743646 0.9636731 0.2608357 -0.1054673 0.9314478 0.3482552 0.1164927 0.5808608 0.8056241 -0.1239789 0.4800295 0.8684474 0.1132593 -0.1336475 0.9845358 -0.1468545 -0.2781584 0.9492427 0.1614928 -0.6810921 0.7141664 -0.1824907 -0.8244677 0.5356774 0.1544733 -0.9869087 0.04635828 -0.05743426 -0.9955189 -0.07512372 0.01218873 -0.8002591 -0.5995305 0.1069788 -0.7659489 -0.6339383 -0.1573736 -0.2445445 -0.9567819 1 -7.3869e-7 2.55053e-6 1 1.09107e-6 1.30151e-6 1 1.58426e-6 -4.20028e-7 1 -1.36843e-6 2.83904e-6 1 -1.06187e-6 1.11793e-6 1 7.54998e-7 -4.23557e-6 0.029352 -0.05909478 -0.9978207 -0.02536123 0.6299517 -0.7762202 0.04508018 0.6879912 -0.7243177 -0.05214029 0.9566558 -0.2865156 0.07216733 0.9920989 -0.102624 -0.07217109 0.9342228 0.3493123 0.09191322 0.8181811 0.5675664 -0.0849325 0.5305146 0.8434103 0.1028974 0.1127089 0.9882858 -0.06096559 -0.06432491 0.996065 0.06583583 -0.7261192 0.6844097 -0.0886141 -0.8174709 0.5691124 0.08453977 -0.9962558 0.0181005 -0.09337264 -0.9664818 -0.2391536 0.09339624 -0.7669914 -0.6348239 -0.06574088 -0.6010223 -0.7965239 0.03974634 -0.04996001 -0.9979601 1 1.26775e-5 2.1705e-6 1 1.16478e-5 2.88223e-6 1 6.74377e-6 -2.42012e-6 1 1.57673e-6 -5.65837e-7 1 2.79112e-6 7.11249e-6 1 -2.53407e-6 5.91691e-6 1 1.52176e-6 -3.55322e-6 1 2.16044e-6 -2.66207e-6 1 5.13478e-7 -1.84759e-6 1 0 0 1 0 0 1 -2.19059e-6 6.82852e-7 1 -3.96796e-6 -3.89649e-6 1 3.97071e-6 3.04227e-7 1 -3.00731e-6 7.627e-6 1 0 -3.57592e-6 1 1.7278e-6 -3.77654e-6 1 0 0 0.1461419 0.1078053 -0.983372 -0.1187525 0.6683605 -0.7342969 0.05969494 0.7289863 -0.6819204 -0.05970096 0.9981429 -0.0121119 0.05204117 0.9979255 0.03789985 -0.04376506 0.7832774 0.62013 0.1376837 0.7067077 0.6939795 -0.192479 0.2944129 0.9360945 0.2333689 0.004371464 0.9723784 -0.1979358 -0.4306576 0.8805427 0.156307 -0.6389631 0.7531894 -0.1748508 -0.9152376 0.3629976 0.1461359 -0.9718313 0.1849003 -0.08447146 -0.9331687 -0.349372 0.0657984 -0.893785 -0.4436427 -0.07950598 -0.662035 -0.7452439 0.1380972 -0.511102 -0.8483537 -0.1748872 -0.07909095 -0.9814068 -2.74232e-5 2.98233e-5 1 5.33806e-6 -3.14988e-6 1 -4.52742e-6 5.63155e-7 1 0 4.79084e-7 1 -5.13479e-7 3.10299e-7 1 4.2917e-6 5.14482e-6 1 2.11665e-5 4.07379e-5 1 0.959329 0.276331 0.05769699 0.8958152 0.4431889 -0.03314793 0.4808056 0.8762007 0.03314059 0.3442271 0.9378945 -0.04314607 -0.1546865 0.9865295 0.05321395 -0.3238486 0.9453884 -0.03691536 -0.8167973 0.5767302 -0.01498687 -0.8552702 0.5168449 0.03720372 -0.9812213 -0.1928628 0.002985239 -0.9671165 -0.2515774 -0.03734415 -0.6650601 -0.7462813 0.02755987 -0.5444499 -0.8379564 -0.03746187 -0.1594132 -0.9863228 0.04189229 0.1027526 -0.993364 -0.05167073 0.4442534 -0.8948369 0.04365652 0.7042296 -0.7085725 -0.04456394 0.8706741 -0.4892135 0.05095857 0.9891825 -0.1363246 -0.05416345 2.13385e-5 -1.94744e-5 1 1.52612e-5 -1.98048e-5 1 -4.17618e-6 5.41952e-6 1 -1.034e-6 7.75533e-6 1 1.06635e-5 5.27559e-6 1 1.20943e-5 1.11744e-5 1 6.5508e-6 6.98117e-6 1 -1.39078e-6 2.08098e-5 1 -1.37919e-5 -1.8969e-5 1 2.60758e-5 -2.82159e-5 1 9.82418e-6 9.95928e-6 1 2.5507e-5 1.41453e-5 1 3.8801e-5 8.93441e-6 1 4.73091e-5 2.25165e-5 1 4.85772e-6 2.31201e-6 1 4.73278e-6 2.5363e-6 1 -5.07349e-6 -1.93213e-5 1 2.29271e-5 -3.23928e-5 1 -0.8103889 -0.5828542 -0.05958777 -0.7571257 -0.6422685 0.1193813 -0.2841905 -0.9506328 -0.1246315 -0.07658785 -0.9883888 0.131232 0.1637713 -0.9825604 -0.08805632 0.490979 -0.8594155 0.1426355 0.7091912 -0.6736159 -0.2080612 0.8947495 -0.4111291 0.1743451 0.9900227 0.03003531 -0.1376695 0.9815301 0.1658022 0.09543728 0.7098807 0.686518 -0.1573607 0.5907888 0.7913304 0.1573682 0.0120542 0.9941901 -0.1069619 -0.06660795 0.9966323 0.04782789 -0.6415152 0.765618 -0.04782682 -0.6779291 0.733569 0.04784107 -0.9846935 0.166446 -0.05171579 -0.991373 0.1184687 0.05607914 -2.09199e-6 -7.68793e-6 -1 -1.53692e-6 2.59791e-7 -1 -1.59138e-6 1.4681e-7 -1 3.85101e-6 4.7159e-6 -1 -9.89507e-7 7.46937e-7 -1 4.68736e-6 3.139e-6 -1 2.42372e-6 2.96807e-6 -1</float_array> + <technique_common> + <accessor source="#Link2-mesh-normals-array" count="4582" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Link2-mesh-vertices"> + <input semantic="POSITION" source="#Link2-mesh-positions"/> + </vertices> + <polylist material="Material_002-material" count="4582"> + <input semantic="VERTEX" source="#Link2-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Link2-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>27 0 0 0 1 0 1 1 0 1 2 1 3 2 4 2 5 2 5 3 4 3 6 3 7 4 8 4 9 4 9 5 8 5 10 5 11 6 12 6 13 6 13 7 12 7 14 7 15 8 13 8 14 8 15 9 14 9 4 9 15 10 4 10 3 10 16 11 15 11 5 11 5 12 15 12 3 12 17 13 18 13 19 13 19 14 18 14 20 14 17 15 19 15 21 15 17 16 21 16 22 16 17 17 22 17 23 17 26 18 27 18 24 18 24 19 27 19 28 19 24 20 25 20 26 20 14 21 32 21 30 21 14 22 30 22 31 22 14 23 31 23 4 23 4 24 31 24 29 24 33 25 34 25 35 25 35 26 34 26 36 26 37 27 35 27 36 27 37 28 36 28 10 28 37 29 10 29 8 29 2 30 0 30 38 30 38 31 0 31 39 31 26 32 40 32 41 32 41 33 40 33 42 33 26 34 41 34 39 34 26 35 39 35 27 35 27 36 39 36 0 36 43 37 10 37 44 37 44 38 10 38 36 38 44 39 36 39 45 39 45 40 36 40 46 40 17 41 23 41 47 41 47 42 23 42 48 42 49 43 17 43 47 43 50 44 51 44 19 44 19 45 51 45 21 45 52 46 53 46 1550 46 54 47 55 47 32 47 32 48 55 48 30 48 35 49 37 49 56 49 56 50 37 50 843 50 49 51 59 51 60 51 61 52 62 52 63 52 64 53 60 53 62 53 62 54 60 54 59 54 62 55 59 55 66 55 67 56 68 56 949 56 69 57 70 57 71 57 72 58 55 58 758 58 758 59 55 59 54 59 758 60 54 60 73 60 73 61 74 61 75 61 70 62 87 62 76 62 62 63 61 63 64 63 69 64 71 64 75 64 75 65 71 65 67 65 75 66 67 66 73 66 73 67 67 67 949 67 73 68 949 68 758 68 68 69 77 69 949 69 949 70 77 70 78 70 949 71 78 71 63 71 63 72 78 72 79 72 63 73 79 73 61 73 83 74 80 74 77 74 81 75 83 75 71 75 71 76 83 76 77 76 76 77 84 77 70 77 70 78 84 78 71 78 71 79 84 79 82 79 71 80 82 80 81 80 86 81 85 81 78 81 77 82 80 82 86 82 77 83 86 83 78 83 85 84 87 84 78 84 78 85 87 85 70 85 88 86 89 86 90 86 91 87 92 87 93 87 94 88 95 88 124 88 124 89 95 89 96 89 124 90 96 90 97 90 100 91 101 91 102 91 102 92 101 92 91 92 103 93 955 93 104 93 104 94 955 94 105 94 124 95 97 95 101 95 91 96 93 96 102 96 102 97 93 97 107 97 102 98 107 98 108 98 103 99 102 99 955 99 955 100 102 100 108 100 955 101 108 101 90 101 90 102 108 102 109 102 90 103 109 103 88 103 101 104 110 104 105 104 105 105 110 105 99 105 105 106 99 106 104 106 104 107 99 107 98 107 104 108 98 108 111 108 100 109 112 109 113 109 111 110 114 110 104 110 100 111 113 111 115 111 105 112 124 112 101 112 116 113 101 113 100 113 116 114 100 114 115 114 116 115 115 115 117 115 99 116 118 116 98 116 119 117 118 117 99 117 104 118 114 118 100 118 100 119 114 119 112 119 116 120 119 120 99 120 117 121 119 121 116 121 120 122 749 122 745 122 121 123 125 123 122 123 123 124 124 124 126 124 124 125 123 125 128 125 123 126 127 126 128 126 127 127 120 127 745 127 120 128 129 128 749 128 749 129 129 129 121 129 749 130 121 130 130 130 130 131 121 131 122 131 127 132 745 132 128 132 131 133 132 133 133 133 133 134 749 134 130 134 749 135 133 135 132 135 138 136 139 136 134 136 120 137 140 137 129 137 129 138 140 138 146 138 141 139 142 139 143 139 1016 140 144 140 124 140 124 141 144 141 126 141 145 142 146 142 140 142 125 143 147 143 122 143 148 144 786 144 149 144 137 145 157 145 150 145 146 146 145 146 151 146 151 147 145 147 152 147 153 148 154 148 1016 148 132 149 131 149 155 149 132 150 155 150 143 150 135 151 134 151 156 151 136 152 157 152 137 152 135 153 138 153 134 153 134 154 139 154 158 154 160 155 161 155 142 155 142 156 161 156 143 156 156 157 162 157 135 157 135 158 162 158 137 158 137 159 162 159 136 159 158 160 139 160 163 160 158 161 163 161 159 161 786 162 160 162 149 162 147 163 125 163 164 163 158 164 159 164 165 164 143 165 155 165 137 165 143 166 137 166 141 166 141 167 137 167 150 167 1016 168 154 168 165 168 160 169 786 169 161 169 138 170 135 170 164 170 159 171 163 171 166 171 167 172 168 172 812 172 168 173 169 173 812 173 159 174 170 174 165 174 165 175 170 175 1016 175 1016 176 170 176 144 176 151 177 152 177 163 177 163 178 152 178 166 178 153 179 1016 179 169 179 153 180 169 180 168 180 164 181 125 181 171 181 164 182 171 182 138 182 173 183 172 183 174 183 174 184 175 184 173 184 175 185 174 185 176 185 176 186 180 186 175 186 177 187 178 187 173 187 173 188 178 188 179 188 173 189 179 189 172 189 185 190 186 190 182 190 182 191 186 191 181 191 183 192 184 192 182 192 185 193 188 193 186 193 182 194 181 194 187 194 182 195 187 195 183 195 189 196 190 196 193 196 191 197 192 197 194 197 194 198 192 198 193 198 189 199 195 199 190 199 190 200 195 200 196 200 190 201 194 201 193 201 190 202 196 202 197 202 198 203 201 203 200 203 199 204 202 204 198 204 198 205 200 205 203 205 198 206 203 206 199 206 200 207 201 207 204 207 201 208 205 208 204 208 173 209 206 209 207 209 173 210 207 210 177 210 177 211 207 211 208 211 177 212 208 212 178 212 178 213 208 213 179 213 179 214 208 214 209 214 179 215 209 215 172 215 172 216 209 216 210 216 172 217 210 217 174 217 174 218 210 218 211 218 174 219 211 219 176 219 176 220 211 220 212 220 176 221 212 221 180 221 180 222 212 222 213 222 180 223 213 223 175 223 175 224 213 224 214 224 175 225 214 225 206 225 175 226 206 226 173 226 183 227 224 227 184 227 184 228 224 228 215 228 184 229 215 229 216 229 184 230 216 230 182 230 182 231 216 231 217 231 182 232 217 232 185 232 185 233 217 233 218 233 185 234 218 234 219 234 185 235 219 235 188 235 188 236 219 236 220 236 188 237 220 237 186 237 186 238 220 238 221 238 186 239 221 239 222 239 186 240 222 240 181 240 181 241 222 241 187 241 187 242 222 242 223 242 187 243 223 243 183 243 183 244 223 244 224 244 194 245 225 245 191 245 191 246 225 246 226 246 191 247 226 247 192 247 192 248 226 248 227 248 192 249 227 249 193 249 193 250 227 250 228 250 193 251 228 251 229 251 193 252 229 252 189 252 189 253 229 253 230 253 189 254 230 254 195 254 195 255 230 255 231 255 195 256 231 256 196 256 196 257 231 257 232 257 196 258 232 258 197 258 197 259 232 259 233 259 197 260 233 260 190 260 190 261 233 261 225 261 190 262 225 262 194 262 199 263 234 263 202 263 202 264 234 264 235 264 202 265 235 265 198 265 198 266 235 266 236 266 198 267 236 267 201 267 201 268 236 268 237 268 201 269 237 269 238 269 201 270 238 270 205 270 205 271 238 271 204 271 204 272 238 272 239 272 204 273 239 273 200 273 200 274 239 274 240 274 200 275 240 275 241 275 200 276 241 276 203 276 203 277 241 277 242 277 203 278 242 278 199 278 199 279 242 279 234 279 243 280 245 280 244 280 245 281 247 281 248 281 243 282 244 282 246 282 244 283 245 283 248 283 247 284 249 284 248 284 243 285 246 285 250 285 251 286 252 286 257 286 252 287 254 287 257 287 256 288 255 288 254 288 257 289 253 289 251 289 255 290 257 290 254 290 251 291 253 291 258 291 251 292 258 292 259 292 211 293 268 293 260 293 211 294 260 294 212 294 212 295 260 295 261 295 212 296 261 296 213 296 213 297 261 297 262 297 213 298 262 298 214 298 214 299 262 299 263 299 214 300 263 300 206 300 206 301 263 301 264 301 206 302 264 302 207 302 207 303 264 303 265 303 207 304 265 304 208 304 208 305 265 305 266 305 208 306 266 306 209 306 209 307 266 307 267 307 209 308 267 308 210 308 210 309 267 309 268 309 210 310 268 310 211 310 223 311 269 311 270 311 223 312 270 312 224 312 224 313 270 313 271 313 224 314 271 314 215 314 215 315 271 315 272 315 215 316 272 316 216 316 216 317 272 317 273 317 216 318 273 318 217 318 217 319 273 319 274 319 217 320 274 320 218 320 218 321 274 321 275 321 218 322 275 322 219 322 219 323 275 323 276 323 219 324 276 324 220 324 220 325 276 325 277 325 220 326 277 326 221 326 221 327 277 327 222 327 222 328 277 328 278 328 222 329 278 329 269 329 222 330 269 330 223 330 230 331 279 331 280 331 230 332 280 332 231 332 231 333 280 333 281 333 231 334 281 334 232 334 232 335 281 335 282 335 232 336 282 336 233 336 233 337 282 337 283 337 233 338 283 338 225 338 225 339 283 339 284 339 225 340 284 340 226 340 226 341 284 341 285 341 226 342 285 342 227 342 227 343 285 343 286 343 227 344 286 344 228 344 228 345 286 345 287 345 228 346 287 346 229 346 229 347 287 347 288 347 229 348 288 348 230 348 230 349 288 349 279 349 242 350 289 350 290 350 242 351 290 351 234 351 234 352 290 352 291 352 234 353 291 353 235 353 235 354 291 354 292 354 235 355 292 355 236 355 236 356 292 356 293 356 236 357 293 357 237 357 237 358 293 358 294 358 237 359 294 359 238 359 238 360 294 360 295 360 238 361 295 361 296 361 238 362 296 362 239 362 239 363 296 363 297 363 239 364 297 364 240 364 240 365 297 365 298 365 240 366 298 366 241 366 241 367 298 367 289 367 241 368 289 368 242 368 302 369 312 369 303 369 305 370 306 370 304 370 308 371 307 371 314 371 301 372 308 372 314 372 310 373 299 373 309 373 311 374 310 374 309 374 312 375 302 375 313 375 313 376 311 376 312 376 309 377 299 377 300 377 309 378 300 378 301 378 309 379 301 379 314 379 305 380 314 380 307 380 305 381 307 381 306 381 312 382 311 382 309 382 312 383 309 383 314 383 312 384 314 384 305 384 303 385 312 385 305 385 303 386 305 386 304 386 316 387 318 387 315 387 316 388 317 388 318 388 316 389 315 389 319 389 316 390 320 390 317 390 323 391 321 391 322 391 321 392 323 392 324 392 324 393 325 393 321 393 323 394 322 394 326 394 329 395 327 395 330 395 327 396 329 396 331 396 328 397 332 397 327 397 331 398 333 398 327 398 327 399 333 399 328 399 339 400 336 400 334 400 334 401 337 401 335 401 337 402 334 402 338 402 334 403 335 403 339 403 341 404 344 404 346 404 346 405 344 405 342 405 341 406 343 406 344 406 346 407 342 407 345 407 344 408 343 408 340 408 349 409 350 409 351 409 347 410 348 410 353 410 347 411 352 411 348 411 349 412 348 412 352 412 349 413 351 413 348 413 349 414 354 414 350 414 248 415 355 415 244 415 244 416 355 416 356 416 244 417 356 417 246 417 246 418 356 418 357 418 246 419 357 419 250 419 250 420 357 420 358 420 250 421 358 421 243 421 243 422 358 422 359 422 243 423 359 423 245 423 245 424 359 424 360 424 245 425 360 425 247 425 247 426 360 426 249 426 249 427 360 427 361 427 249 428 361 428 248 428 248 429 361 429 362 429 248 430 362 430 355 430 257 431 371 431 253 431 253 432 371 432 363 432 253 433 363 433 364 433 253 434 364 434 258 434 258 435 364 435 365 435 258 436 365 436 259 436 259 437 365 437 366 437 259 438 366 438 251 438 251 439 366 439 367 439 251 440 367 440 252 440 252 441 367 441 368 441 252 442 368 442 254 442 254 443 368 443 256 443 256 444 368 444 369 444 256 445 369 445 255 445 255 446 369 446 370 446 255 447 370 447 257 447 257 448 370 448 371 448 265 449 380 449 266 449 266 450 380 450 372 450 266 451 372 451 267 451 267 452 372 452 373 452 267 453 373 453 268 453 268 454 373 454 374 454 268 455 374 455 260 455 260 456 374 456 375 456 260 457 375 457 261 457 261 458 375 458 376 458 261 459 376 459 262 459 262 460 376 460 377 460 262 461 377 461 263 461 263 462 377 462 378 462 263 463 378 463 264 463 264 464 378 464 379 464 264 465 379 465 265 465 265 466 379 466 380 466 271 467 381 467 272 467 272 468 381 468 273 468 273 469 381 469 382 469 273 470 382 470 274 470 274 471 382 471 383 471 274 472 383 472 275 472 275 473 383 473 384 473 275 474 384 474 276 474 276 475 384 475 385 475 276 476 385 476 277 476 277 477 385 477 386 477 277 478 386 478 278 478 278 479 386 479 387 479 278 480 387 480 388 480 278 481 388 481 269 481 269 482 388 482 270 482 270 483 388 483 389 483 270 484 389 484 390 484 270 485 390 485 271 485 271 486 390 486 381 486 287 487 399 487 391 487 287 488 391 488 288 488 288 489 391 489 392 489 288 490 392 490 279 490 279 491 392 491 280 491 280 492 392 492 393 492 280 493 393 493 281 493 281 494 393 494 394 494 281 495 394 495 282 495 282 496 394 496 395 496 282 497 395 497 283 497 283 498 395 498 396 498 283 499 396 499 284 499 284 500 396 500 397 500 284 501 397 501 398 501 284 502 398 502 285 502 285 503 398 503 399 503 285 504 399 504 286 504 286 505 399 505 287 505 296 506 408 506 297 506 297 507 408 507 400 507 297 508 400 508 298 508 298 509 400 509 401 509 298 510 401 510 289 510 289 511 401 511 402 511 289 512 402 512 290 512 402 513 403 513 290 513 290 514 403 514 291 514 291 515 403 515 404 515 291 516 404 516 292 516 292 517 404 517 405 517 292 518 405 518 293 518 293 519 405 519 406 519 293 520 406 520 294 520 294 521 406 521 295 521 295 522 406 522 407 522 295 523 407 523 408 523 295 524 408 524 296 524 313 525 411 525 311 525 311 526 411 526 412 526 311 527 412 527 310 527 310 528 412 528 410 528 310 529 410 529 413 529 310 530 413 530 299 530 299 531 413 531 300 531 300 532 413 532 414 532 300 533 414 533 301 533 301 534 414 534 415 534 301 535 415 535 308 535 308 536 415 536 409 536 308 537 409 537 307 537 307 538 409 538 416 538 307 539 416 539 306 539 306 540 416 540 417 540 306 541 417 541 304 541 304 542 417 542 418 542 418 543 303 543 304 543 313 544 302 544 411 544 411 545 302 545 419 545 419 546 302 546 303 546 419 547 303 547 418 547 317 548 420 548 421 548 317 549 421 549 318 549 318 550 421 550 315 550 315 551 421 551 422 551 315 552 422 552 319 552 319 553 422 553 423 553 319 554 423 554 316 554 316 555 423 555 424 555 316 556 424 556 320 556 320 557 424 557 425 557 320 558 425 558 420 558 320 559 420 559 317 559 324 560 426 560 325 560 325 561 426 561 321 561 321 562 426 562 427 562 321 563 427 563 322 563 322 564 427 564 428 564 322 565 428 565 326 565 326 566 428 566 429 566 326 567 429 567 323 567 323 568 429 568 430 568 323 569 430 569 324 569 324 570 430 570 431 570 324 571 431 571 426 571 330 572 437 572 432 572 330 573 432 573 329 573 329 574 432 574 433 574 329 575 433 575 331 575 331 576 433 576 333 576 333 577 433 577 434 577 333 578 434 578 328 578 328 579 434 579 435 579 328 580 435 580 332 580 332 581 435 581 436 581 332 582 436 582 327 582 327 583 436 583 437 583 327 584 437 584 330 584 334 585 444 585 438 585 334 586 438 586 338 586 338 587 438 587 337 587 438 588 439 588 337 588 337 589 439 589 335 589 335 590 439 590 440 590 335 591 440 591 441 591 335 592 441 592 339 592 339 593 441 593 442 593 339 594 442 594 336 594 336 595 442 595 443 595 336 596 443 596 444 596 336 597 444 597 334 597 445 598 341 598 446 598 446 599 341 599 346 599 446 600 346 600 447 600 447 601 346 601 345 601 447 602 345 602 448 602 448 603 345 603 449 603 449 604 345 604 342 604 449 605 342 605 344 605 449 606 344 606 450 606 450 607 344 607 451 607 451 608 344 608 340 608 451 609 340 609 452 609 452 610 340 610 453 610 453 611 340 611 343 611 453 612 343 612 445 612 445 613 343 613 341 613 454 614 352 614 347 614 454 615 347 615 455 615 455 616 347 616 456 616 456 617 347 617 353 617 456 618 353 618 348 618 456 619 348 619 457 619 457 620 348 620 351 620 457 621 351 621 458 621 458 622 351 622 459 622 459 623 351 623 350 623 459 624 350 624 460 624 460 625 350 625 354 625 460 626 354 626 461 626 461 627 354 627 349 627 461 628 349 628 352 628 461 629 352 629 454 629 356 630 462 630 357 630 357 631 462 631 463 631 357 632 463 632 464 632 357 633 464 633 358 633 358 634 464 634 465 634 358 635 465 635 359 635 359 636 465 636 466 636 359 637 466 637 360 637 360 638 466 638 467 638 360 639 467 639 361 639 361 640 467 640 468 640 361 641 468 641 362 641 362 642 468 642 469 642 362 643 469 643 355 643 355 644 469 644 470 644 355 645 470 645 356 645 356 646 470 646 462 646 364 647 479 647 471 647 364 648 471 648 365 648 365 649 471 649 472 649 365 650 472 650 366 650 366 651 472 651 473 651 366 652 473 652 367 652 367 653 473 653 474 653 367 654 474 654 368 654 368 655 474 655 475 655 368 656 475 656 369 656 369 657 475 657 476 657 369 658 476 658 370 658 370 659 476 659 477 659 370 660 477 660 371 660 371 661 477 661 478 661 371 662 478 662 363 662 363 663 478 663 479 663 363 664 479 664 364 664 482 665 393 665 392 665 486 666 392 666 391 666 427 667 426 667 487 667 428 668 488 668 486 668 428 669 486 669 429 669 488 670 428 670 427 670 489 671 431 671 430 671 489 672 430 672 429 672 489 673 429 673 486 673 488 674 427 674 487 674 390 675 485 675 381 675 383 676 490 676 487 676 491 677 490 677 382 677 490 678 383 678 382 678 381 679 485 679 491 679 381 680 491 680 382 680 485 681 422 681 421 681 485 682 421 682 492 682 421 683 420 683 492 683 492 684 420 684 484 684 420 685 425 685 484 685 493 686 424 686 423 686 423 687 422 687 493 687 493 688 422 688 485 688 484 689 425 689 424 689 380 690 494 690 484 690 380 691 379 691 494 691 378 692 495 692 494 692 494 693 379 693 378 693 378 694 377 694 495 694 495 695 377 695 376 695 495 696 376 696 497 696 436 697 435 697 496 697 432 698 480 698 433 698 437 699 436 699 497 699 497 700 436 700 496 700 496 701 435 701 498 701 498 702 435 702 434 702 498 703 434 703 433 703 498 704 433 704 480 704 402 705 401 705 498 705 483 706 401 706 400 706 483 707 400 707 408 707 482 708 439 708 438 708 483 709 442 709 441 709 483 710 441 710 499 710 440 711 439 711 482 711 444 712 443 712 483 712 499 713 441 713 440 713 483 714 443 714 442 714 499 715 440 715 482 715 375 716 374 716 480 716 497 717 376 717 375 717 480 718 374 718 373 718 480 719 373 719 493 719 373 720 372 720 493 720 493 721 372 721 380 721 487 722 384 722 383 722 489 723 386 723 385 723 384 724 487 724 489 724 489 725 385 725 384 725 485 726 390 726 493 726 390 727 389 727 493 727 493 728 387 728 489 728 489 729 387 729 386 729 389 730 388 730 493 730 493 731 388 731 387 731 391 732 399 732 486 732 394 733 482 733 481 733 482 734 394 734 393 734 486 735 399 735 489 735 489 736 399 736 398 736 398 737 397 737 489 737 396 738 395 738 481 738 397 739 396 739 489 739 489 740 396 740 481 740 395 741 394 741 481 741 483 742 408 742 444 742 444 743 408 743 407 743 444 744 407 744 481 744 404 745 480 745 405 745 481 746 407 746 406 746 406 747 405 747 481 747 481 748 405 748 480 748 480 749 404 749 403 749 480 750 403 750 498 750 498 751 403 751 402 751 493 752 411 752 419 752 493 753 419 753 480 753 493 754 412 754 411 754 413 755 410 755 489 755 489 756 410 756 493 756 493 757 410 757 412 757 414 758 413 758 489 758 481 759 409 759 415 759 481 760 415 760 414 760 481 761 414 761 489 761 481 762 416 762 409 762 416 763 481 763 417 763 417 764 481 764 480 764 419 765 418 765 480 765 480 766 418 766 417 766 487 767 426 767 489 767 489 768 426 768 431 768 375 769 480 769 497 769 497 770 480 770 437 770 480 771 432 771 437 771 481 772 438 772 444 772 481 773 482 773 438 773 380 774 484 774 493 774 493 775 484 775 424 775 500 776 501 776 502 776 500 777 502 777 503 777 500 778 503 778 504 778 504 779 503 779 505 779 504 780 505 780 506 780 506 781 505 781 507 781 506 782 507 782 508 782 508 783 507 783 509 783 508 784 509 784 510 784 510 785 509 785 511 785 510 786 511 786 512 786 512 787 511 787 513 787 512 788 513 788 514 788 514 789 513 789 515 789 514 790 515 790 516 790 516 791 515 791 517 791 516 792 517 792 501 792 516 793 501 793 500 793 534 794 518 794 519 794 519 795 518 795 520 795 519 796 520 796 521 796 521 797 520 797 522 797 521 798 522 798 523 798 523 799 522 799 524 799 523 800 524 800 525 800 523 801 525 801 526 801 526 802 525 802 527 802 526 803 527 803 528 803 528 804 527 804 529 804 528 805 529 805 530 805 530 806 529 806 531 806 530 807 531 807 532 807 532 808 531 808 533 808 532 809 533 809 534 809 534 810 533 810 535 810 534 811 535 811 518 811 536 812 537 812 538 812 536 813 538 813 539 813 539 814 538 814 540 814 539 815 540 815 541 815 541 816 540 816 542 816 541 817 542 817 543 817 543 818 542 818 544 818 543 819 544 819 545 819 543 820 545 820 546 820 546 821 545 821 547 821 547 822 545 822 548 822 547 823 548 823 549 823 547 824 549 824 550 824 550 825 549 825 551 825 550 826 551 826 552 826 552 827 551 827 553 827 552 828 553 828 536 828 536 829 553 829 537 829 554 830 519 830 555 830 555 831 519 831 521 831 555 832 521 832 556 832 556 833 521 833 523 833 556 834 523 834 557 834 557 835 523 835 526 835 557 836 526 836 558 836 558 837 526 837 528 837 558 838 528 838 559 838 559 839 528 839 530 839 559 840 530 840 532 840 559 841 532 841 560 841 560 842 532 842 534 842 560 843 534 843 561 843 561 844 534 844 519 844 561 845 519 845 554 845 562 846 516 846 500 846 562 847 500 847 563 847 563 848 500 848 564 848 564 849 500 849 504 849 564 850 504 850 565 850 565 851 504 851 506 851 565 852 506 852 566 852 566 853 506 853 508 853 566 854 508 854 567 854 567 855 508 855 510 855 567 856 510 856 568 856 568 857 510 857 512 857 568 858 512 858 569 858 569 859 512 859 514 859 569 860 514 860 570 860 570 861 514 861 516 861 570 862 516 862 562 862 578 863 550 863 571 863 571 864 550 864 552 864 571 865 552 865 572 865 572 866 552 866 573 866 573 867 552 867 536 867 573 868 536 868 539 868 573 869 539 869 574 869 574 870 539 870 541 870 574 871 541 871 575 871 575 872 541 872 576 872 576 873 541 873 543 873 576 874 543 874 577 874 577 875 543 875 546 875 577 876 546 876 547 876 577 877 547 877 578 877 578 878 547 878 550 878 579 879 582 879 580 879 581 880 583 880 582 880 583 881 584 881 582 881 584 882 580 882 582 882 579 883 580 883 585 883 582 884 586 884 581 884 585 885 587 885 579 885 447 886 597 886 446 886 446 887 597 887 588 887 446 888 588 888 589 888 446 889 589 889 445 889 445 890 589 890 590 890 445 891 590 891 453 891 453 892 590 892 591 892 453 893 591 893 452 893 452 894 591 894 592 894 452 895 592 895 451 895 451 896 592 896 593 896 451 897 593 897 450 897 450 898 593 898 449 898 449 899 593 899 594 899 449 900 594 900 595 900 449 901 595 901 448 901 448 902 595 902 596 902 448 903 596 903 447 903 447 904 596 904 597 904 460 905 598 905 599 905 460 906 599 906 459 906 459 907 599 907 600 907 459 908 600 908 458 908 458 909 600 909 601 909 458 910 601 910 457 910 457 911 601 911 602 911 457 912 602 912 456 912 456 913 602 913 603 913 456 914 603 914 604 914 456 915 604 915 455 915 455 916 604 916 454 916 454 917 604 917 605 917 454 918 605 918 606 918 454 919 606 919 461 919 461 920 606 920 607 920 461 921 607 921 460 921 460 922 607 922 598 922 608 923 616 923 609 923 616 924 608 924 610 924 610 925 611 925 616 925 616 926 611 926 612 926 608 927 609 927 613 927 608 928 613 928 614 928 616 929 612 929 615 929 614 930 613 930 617 930 469 931 618 931 470 931 470 932 618 932 619 932 470 933 619 933 462 933 462 934 619 934 620 934 462 935 620 935 463 935 463 936 620 936 621 936 463 937 621 937 464 937 464 938 621 938 622 938 464 939 622 939 465 939 465 940 622 940 623 940 465 941 623 941 466 941 466 942 623 942 624 942 466 943 624 943 467 943 467 944 624 944 625 944 467 945 625 945 468 945 468 946 625 946 626 946 468 947 626 947 469 947 469 948 626 948 627 948 469 949 627 949 618 949 478 950 637 950 628 950 478 951 628 951 479 951 479 952 628 952 629 952 479 953 629 953 471 953 471 954 629 954 630 954 471 955 630 955 631 955 471 956 631 956 472 956 472 957 631 957 632 957 472 958 632 958 473 958 473 959 632 959 633 959 473 960 633 960 474 960 474 961 633 961 634 961 474 962 634 962 475 962 475 963 634 963 635 963 475 964 635 964 476 964 476 965 635 965 636 965 476 966 636 966 477 966 477 967 636 967 637 967 477 968 637 968 478 968 392 969 654 969 638 969 392 970 638 970 482 970 482 971 638 971 639 971 482 972 639 972 499 972 499 973 639 973 641 973 499 974 641 974 483 974 483 975 641 975 640 975 483 976 640 976 401 976 640 977 642 977 401 977 401 978 642 978 643 978 401 979 643 979 498 979 643 980 644 980 498 980 498 981 644 981 496 981 496 982 645 982 497 982 497 983 645 983 495 983 495 984 646 984 494 984 494 985 647 985 484 985 484 986 647 986 492 986 492 987 647 987 648 987 492 988 648 988 485 988 485 989 648 989 649 989 485 990 649 990 491 990 491 991 650 991 490 991 490 992 650 992 487 992 487 993 650 993 651 993 487 994 651 994 488 994 488 995 651 995 652 995 488 996 652 996 653 996 488 997 653 997 486 997 486 998 653 998 654 998 486 999 654 999 392 999 517 1000 655 1000 501 1000 501 1001 655 1001 656 1001 501 1002 656 1002 502 1002 502 1003 656 1003 503 1003 503 1004 656 1004 657 1004 503 1005 657 1005 505 1005 505 1006 657 1006 658 1006 505 1007 658 1007 507 1007 507 1008 658 1008 659 1008 507 1009 659 1009 509 1009 509 1010 659 1010 660 1010 509 1011 660 1011 511 1011 511 1012 660 1012 661 1012 511 1013 661 1013 513 1013 513 1014 661 1014 662 1014 513 1015 662 1015 515 1015 515 1016 662 1016 663 1016 515 1017 663 1017 517 1017 517 1018 663 1018 655 1018 518 1019 664 1019 520 1019 520 1020 664 1020 665 1020 520 1021 665 1021 522 1021 522 1022 665 1022 666 1022 522 1023 666 1023 524 1023 524 1024 666 1024 667 1024 524 1025 667 1025 525 1025 525 1026 667 1026 527 1026 527 1027 667 1027 668 1027 527 1028 668 1028 529 1028 529 1029 668 1029 669 1029 529 1030 669 1030 531 1030 531 1031 669 1031 670 1031 531 1032 670 1032 533 1032 533 1033 670 1033 671 1033 533 1034 671 1034 535 1034 535 1035 671 1035 672 1035 535 1036 672 1036 518 1036 518 1037 672 1037 664 1037 549 1038 673 1038 551 1038 551 1039 673 1039 674 1039 551 1040 674 1040 675 1040 551 1041 675 1041 553 1041 553 1042 675 1042 676 1042 553 1043 676 1043 537 1043 537 1044 676 1044 538 1044 538 1045 676 1045 677 1045 538 1046 677 1046 540 1046 540 1047 677 1047 678 1047 540 1048 678 1048 542 1048 542 1049 678 1049 679 1049 542 1050 679 1050 544 1050 544 1051 679 1051 680 1051 544 1052 680 1052 545 1052 545 1053 680 1053 681 1053 545 1054 681 1054 548 1054 548 1055 681 1055 549 1055 549 1056 681 1056 673 1056 559 1057 682 1057 558 1057 558 1058 682 1058 683 1058 558 1059 683 1059 557 1059 557 1060 683 1060 684 1060 557 1061 684 1061 556 1061 556 1062 684 1062 685 1062 556 1063 685 1063 686 1063 556 1064 686 1064 555 1064 555 1065 686 1065 554 1065 554 1066 686 1066 687 1066 554 1067 687 1067 688 1067 554 1068 688 1068 561 1068 561 1069 688 1069 689 1069 561 1070 689 1070 560 1070 560 1071 689 1071 690 1071 560 1072 690 1072 559 1072 559 1073 690 1073 691 1073 559 1074 691 1074 682 1074 696 1075 695 1075 694 1075 693 1076 696 1076 694 1076 692 1077 696 1077 693 1077 695 1078 697 1078 694 1078 700 1079 694 1079 697 1079 699 1080 698 1080 700 1080 697 1081 699 1081 700 1081 565 1082 701 1082 564 1082 564 1083 701 1083 702 1083 564 1084 702 1084 563 1084 563 1085 702 1085 703 1085 563 1086 703 1086 704 1086 563 1087 704 1087 562 1087 562 1088 704 1088 570 1088 570 1089 704 1089 705 1089 570 1090 705 1090 706 1090 570 1091 706 1091 569 1091 569 1092 706 1092 707 1092 569 1093 707 1093 568 1093 568 1094 707 1094 567 1094 567 1095 707 1095 708 1095 567 1096 708 1096 709 1096 567 1097 709 1097 566 1097 566 1098 709 1098 710 1098 566 1099 710 1099 711 1099 566 1100 711 1100 565 1100 565 1101 711 1101 701 1101 573 1102 712 1102 572 1102 572 1103 712 1103 713 1103 572 1104 713 1104 571 1104 571 1105 713 1105 714 1105 571 1106 714 1106 578 1106 578 1107 714 1107 715 1107 578 1108 715 1108 716 1108 578 1109 716 1109 577 1109 577 1110 716 1110 717 1110 577 1111 717 1111 718 1111 577 1112 718 1112 576 1112 576 1113 718 1113 719 1113 576 1114 719 1114 575 1114 575 1115 719 1115 720 1115 575 1116 720 1116 574 1116 574 1117 720 1117 721 1117 574 1118 721 1118 573 1118 573 1119 721 1119 712 1119 722 1120 23 1120 723 1120 723 1121 23 1121 22 1121 724 1122 589 1122 725 1122 725 1123 589 1123 588 1123 725 1124 588 1124 726 1124 726 1125 588 1125 597 1125 726 1126 597 1126 727 1126 727 1127 597 1127 596 1127 727 1128 596 1128 728 1128 728 1129 596 1129 595 1129 728 1130 595 1130 729 1130 729 1131 595 1131 594 1131 729 1132 594 1132 730 1132 730 1133 594 1133 593 1133 730 1134 593 1134 731 1134 731 1135 593 1135 592 1135 731 1136 592 1136 732 1136 732 1137 592 1137 591 1137 732 1138 591 1138 733 1138 733 1139 591 1139 590 1139 733 1140 590 1140 724 1140 724 1141 590 1141 589 1141 734 1142 606 1142 605 1142 734 1143 605 1143 735 1143 735 1144 605 1144 604 1144 735 1145 604 1145 736 1145 736 1146 604 1146 603 1146 736 1147 603 1147 737 1147 737 1148 603 1148 602 1148 737 1149 602 1149 738 1149 738 1150 602 1150 739 1150 739 1151 602 1151 601 1151 739 1152 601 1152 600 1152 739 1153 600 1153 740 1153 740 1154 600 1154 599 1154 740 1155 599 1155 741 1155 741 1156 599 1156 742 1156 742 1157 599 1157 598 1157 742 1158 598 1158 607 1158 742 1159 607 1159 743 1159 743 1160 607 1160 606 1160 743 1161 606 1161 734 1161 747 1162 745 1162 744 1162 128 1163 745 1163 747 1163 128 1164 747 1164 746 1164 749 1165 748 1165 751 1165 750 1166 749 1166 751 1166 11 1167 753 1167 12 1167 12 1168 753 1168 754 1168 12 1169 754 1169 752 1169 21 1170 51 1170 22 1170 22 1171 51 1171 723 1171 18 1172 755 1172 756 1172 18 1173 756 1173 20 1173 20 1174 756 1174 757 1174 758 1175 698 1175 699 1175 759 1176 760 1176 761 1176 761 1177 760 1177 762 1177 763 1178 626 1178 625 1178 763 1179 625 1179 764 1179 763 1180 627 1180 626 1180 762 1181 620 1181 619 1181 620 1182 762 1182 760 1182 623 1183 764 1183 624 1183 619 1184 618 1184 762 1184 762 1185 618 1185 763 1185 763 1186 618 1186 627 1186 764 1187 625 1187 624 1187 760 1188 622 1188 621 1188 764 1189 623 1189 760 1189 760 1190 623 1190 622 1190 760 1191 621 1191 620 1191 765 1192 766 1192 767 1192 767 1193 766 1193 768 1193 769 1194 635 1194 770 1194 770 1195 635 1195 634 1195 629 1196 628 1196 768 1196 769 1197 637 1197 636 1197 769 1198 636 1198 635 1198 768 1199 628 1199 637 1199 768 1200 637 1200 769 1200 770 1201 634 1201 633 1201 632 1202 631 1202 766 1202 629 1203 768 1203 630 1203 630 1204 768 1204 766 1204 770 1205 633 1205 632 1205 770 1206 632 1206 766 1206 766 1207 631 1207 630 1207 773 1208 774 1208 779 1208 771 1209 773 1209 772 1209 774 1210 773 1210 771 1210 775 1211 771 1211 772 1211 772 1212 777 1212 775 1212 775 1213 777 1213 778 1213 776 1214 779 1214 774 1214 780 1215 781 1215 782 1215 782 1216 781 1216 783 1216 782 1217 783 1217 784 1217 785 1218 787 1218 161 1218 785 1219 161 1219 786 1219 790 1220 789 1220 791 1220 791 1221 789 1221 788 1221 650 1222 793 1222 792 1222 491 1223 793 1223 650 1223 793 1224 491 1224 649 1224 793 1225 649 1225 794 1225 649 1226 648 1226 794 1226 794 1227 648 1227 795 1227 648 1228 647 1228 795 1228 795 1229 647 1229 796 1229 647 1230 494 1230 796 1230 494 1231 646 1231 796 1231 796 1232 646 1232 797 1232 646 1233 495 1233 797 1233 797 1234 495 1234 798 1234 798 1235 495 1235 645 1235 798 1236 645 1236 799 1236 645 1237 496 1237 799 1237 496 1238 644 1238 799 1238 799 1239 644 1239 800 1239 644 1240 643 1240 800 1240 800 1241 643 1241 801 1241 801 1242 643 1242 642 1242 801 1243 642 1243 802 1243 642 1244 640 1244 802 1244 802 1245 640 1245 803 1245 803 1246 640 1246 641 1246 803 1247 641 1247 804 1247 804 1248 641 1248 639 1248 804 1249 639 1249 805 1249 639 1250 638 1250 805 1250 638 1251 654 1251 805 1251 805 1252 654 1252 806 1252 806 1253 654 1253 653 1253 806 1254 653 1254 807 1254 653 1255 652 1255 807 1255 807 1256 652 1256 808 1256 808 1257 652 1257 651 1257 650 1258 792 1258 651 1258 651 1259 792 1259 808 1259 810 1260 809 1260 812 1260 810 1261 812 1261 169 1261 811 1262 810 1262 169 1262 815 1263 814 1263 813 1263 804 1264 805 1264 667 1264 806 1265 816 1265 805 1265 677 1266 676 1266 802 1266 660 1267 659 1267 693 1267 659 1268 658 1268 90 1268 90 1269 658 1269 816 1269 666 1270 802 1270 803 1270 666 1271 803 1271 667 1271 667 1272 803 1272 804 1272 797 1273 798 1273 676 1273 676 1274 798 1274 799 1274 693 1275 659 1275 90 1275 816 1276 658 1276 657 1276 816 1277 657 1277 805 1277 806 1278 807 1278 816 1278 816 1279 807 1279 814 1279 805 1280 657 1280 656 1280 799 1281 800 1281 676 1281 676 1282 800 1282 801 1282 676 1283 801 1283 802 1283 674 1284 673 1284 758 1284 671 1285 670 1285 694 1285 662 1286 670 1286 669 1286 694 1287 661 1287 660 1287 814 1288 808 1288 792 1288 667 1289 805 1289 656 1289 667 1290 656 1290 668 1290 681 1291 680 1291 700 1291 670 1292 662 1292 661 1292 670 1293 661 1293 694 1293 660 1294 693 1294 694 1294 677 1295 802 1295 666 1295 677 1296 666 1296 665 1296 948 1297 675 1297 758 1297 758 1298 675 1298 674 1298 700 1299 680 1299 694 1299 694 1300 680 1300 671 1300 671 1301 680 1301 679 1301 671 1302 679 1302 672 1302 758 1303 673 1303 698 1303 677 1304 665 1304 678 1304 678 1305 665 1305 664 1305 673 1306 681 1306 698 1306 678 1307 664 1307 672 1307 678 1308 672 1308 679 1308 668 1309 656 1309 655 1309 662 1310 669 1310 663 1310 793 1311 794 1311 790 1311 681 1312 700 1312 698 1312 668 1313 655 1313 669 1313 669 1314 655 1314 663 1314 808 1315 814 1315 807 1315 794 1316 789 1316 790 1316 789 1317 794 1317 795 1317 789 1318 795 1318 948 1318 948 1319 795 1319 796 1319 948 1320 796 1320 797 1320 797 1321 676 1321 948 1321 948 1322 676 1322 675 1322 90 1323 692 1323 693 1323 585 1324 687 1324 587 1324 587 1325 687 1325 686 1325 587 1326 686 1326 579 1326 579 1327 686 1327 685 1327 579 1328 685 1328 582 1328 582 1329 685 1329 684 1329 582 1330 684 1330 683 1330 582 1331 683 1331 586 1331 586 1332 683 1332 682 1332 586 1333 682 1333 581 1333 581 1334 682 1334 691 1334 581 1335 691 1335 583 1335 583 1336 691 1336 690 1336 583 1337 690 1337 584 1337 584 1338 690 1338 580 1338 580 1339 690 1339 689 1339 580 1340 689 1340 688 1340 580 1341 688 1341 585 1341 585 1342 688 1342 687 1342 26 1343 25 1343 40 1343 40 1344 25 1344 109 1344 40 1345 109 1345 817 1345 52 1346 695 1346 696 1346 52 1347 696 1347 818 1347 818 1348 696 1348 692 1348 695 1349 52 1349 697 1349 697 1350 52 1350 1550 1350 699 1351 697 1351 819 1351 697 1352 1550 1352 819 1352 32 1353 14 1353 54 1353 54 1354 14 1354 12 1354 54 1355 12 1355 752 1355 709 1356 820 1356 710 1356 710 1357 820 1357 821 1357 710 1358 821 1358 711 1358 711 1359 821 1359 822 1359 711 1360 822 1360 701 1360 701 1361 822 1361 823 1361 701 1362 823 1362 702 1362 702 1363 823 1363 824 1363 702 1364 824 1364 703 1364 703 1365 824 1365 825 1365 703 1366 825 1366 704 1366 704 1367 825 1367 826 1367 704 1368 826 1368 705 1368 705 1369 826 1369 706 1369 706 1370 826 1370 827 1370 706 1371 827 1371 707 1371 707 1372 827 1372 828 1372 707 1373 828 1373 829 1373 707 1374 829 1374 708 1374 708 1375 829 1375 820 1375 708 1376 820 1376 709 1376 720 1377 839 1377 830 1377 720 1378 830 1378 721 1378 721 1379 830 1379 831 1379 721 1380 831 1380 712 1380 712 1381 831 1381 832 1381 712 1382 832 1382 833 1382 712 1383 833 1383 713 1383 713 1384 833 1384 834 1384 713 1385 834 1385 714 1385 714 1386 834 1386 715 1386 715 1387 834 1387 835 1387 715 1388 835 1388 716 1388 716 1389 835 1389 836 1389 716 1390 836 1390 717 1390 717 1391 836 1391 837 1391 717 1392 837 1392 838 1392 717 1393 838 1393 718 1393 718 1394 838 1394 839 1394 718 1395 839 1395 719 1395 719 1396 839 1396 720 1396 33 1397 841 1397 34 1397 34 1398 841 1398 842 1398 34 1399 842 1399 840 1399 8 1400 7 1400 37 1400 37 1401 7 1401 843 1401 40 1402 817 1402 844 1402 40 1403 844 1403 42 1403 42 1404 844 1404 845 1404 846 1405 617 1405 847 1405 847 1406 617 1406 613 1406 847 1407 613 1407 848 1407 848 1408 613 1408 609 1408 848 1409 609 1409 849 1409 849 1410 609 1410 616 1410 849 1411 616 1411 850 1411 850 1412 616 1412 615 1412 850 1413 615 1413 851 1413 851 1414 615 1414 612 1414 851 1415 612 1415 852 1415 852 1416 612 1416 611 1416 852 1417 611 1417 853 1417 853 1418 611 1418 610 1418 853 1419 610 1419 608 1419 853 1420 608 1420 854 1420 854 1421 608 1421 614 1421 854 1422 614 1422 846 1422 846 1423 614 1423 617 1423 46 1424 36 1424 96 1424 96 1425 36 1425 34 1425 96 1426 34 1426 840 1426 17 1427 49 1427 18 1427 18 1428 49 1428 60 1428 18 1429 60 1429 755 1429 873 1430 855 1430 856 1430 856 1431 855 1431 857 1431 856 1432 857 1432 858 1432 856 1433 858 1433 859 1433 859 1434 858 1434 860 1434 859 1435 860 1435 861 1435 861 1436 860 1436 862 1436 861 1437 862 1437 863 1437 863 1438 862 1438 864 1438 864 1439 862 1439 865 1439 864 1440 865 1440 866 1440 864 1441 866 1441 867 1441 867 1442 866 1442 868 1442 867 1443 868 1443 869 1443 869 1444 868 1444 870 1444 869 1445 870 1445 871 1445 871 1446 870 1446 872 1446 871 1447 872 1447 873 1447 873 1448 872 1448 855 1448 874 1449 875 1449 876 1449 876 1450 875 1450 877 1450 876 1451 877 1451 878 1451 876 1452 878 1452 879 1452 879 1453 878 1453 880 1453 880 1454 878 1454 881 1454 880 1455 881 1455 882 1455 882 1456 881 1456 883 1456 882 1457 883 1457 884 1457 884 1458 883 1458 885 1458 884 1459 885 1459 886 1459 886 1460 885 1460 887 1460 886 1461 887 1461 888 1461 888 1462 887 1462 889 1462 888 1463 889 1463 890 1463 888 1464 890 1464 891 1464 891 1465 890 1465 892 1465 892 1466 890 1466 893 1466 892 1467 893 1467 875 1467 892 1468 875 1468 874 1468 894 1469 895 1469 896 1469 896 1470 895 1470 897 1470 895 1471 727 1471 897 1471 731 1472 898 1472 730 1472 899 1473 733 1473 724 1473 895 1474 726 1474 727 1474 727 1475 728 1475 897 1475 728 1476 729 1476 897 1476 899 1477 724 1477 725 1477 899 1478 725 1478 895 1478 725 1479 726 1479 895 1479 731 1480 732 1480 898 1480 898 1481 732 1481 899 1481 899 1482 732 1482 733 1482 729 1483 730 1483 897 1483 897 1484 730 1484 898 1484 900 1485 901 1485 902 1485 902 1486 901 1486 903 1486 736 1487 901 1487 735 1487 904 1488 734 1488 901 1488 901 1489 734 1489 735 1489 741 1490 905 1490 740 1490 905 1491 741 1491 742 1491 737 1492 738 1492 903 1492 736 1493 737 1493 901 1493 901 1494 737 1494 903 1494 903 1495 738 1495 739 1495 903 1496 739 1496 740 1496 903 1497 740 1497 905 1497 905 1498 742 1498 904 1498 904 1499 742 1499 743 1499 904 1500 743 1500 734 1500 907 1501 908 1501 906 1501 906 1502 910 1502 907 1502 913 1503 911 1503 912 1503 910 1504 913 1504 907 1504 907 1505 913 1505 912 1505 906 1506 908 1506 909 1506 909 1507 914 1507 906 1507 915 1508 916 1508 917 1508 917 1509 916 1509 918 1509 917 1510 918 1510 919 1510 920 1511 856 1511 859 1511 920 1512 859 1512 921 1512 921 1513 859 1513 861 1513 921 1514 861 1514 922 1514 922 1515 861 1515 863 1515 922 1516 863 1516 864 1516 922 1517 864 1517 923 1517 923 1518 864 1518 924 1518 924 1519 864 1519 867 1519 924 1520 867 1520 925 1520 925 1521 867 1521 869 1521 925 1522 869 1522 926 1522 926 1523 869 1523 871 1523 926 1524 871 1524 927 1524 927 1525 871 1525 873 1525 927 1526 873 1526 928 1526 928 1527 873 1527 856 1527 928 1528 856 1528 920 1528 936 1529 846 1529 929 1529 929 1530 846 1530 847 1530 929 1531 847 1531 848 1531 929 1532 848 1532 930 1532 930 1533 848 1533 849 1533 930 1534 849 1534 931 1534 931 1535 849 1535 850 1535 931 1536 850 1536 932 1536 932 1537 850 1537 851 1537 932 1538 851 1538 933 1538 933 1539 851 1539 934 1539 934 1540 851 1540 852 1540 934 1541 852 1541 853 1541 934 1542 853 1542 935 1542 935 1543 853 1543 854 1543 935 1544 854 1544 936 1544 936 1545 854 1545 846 1545 937 1546 879 1546 880 1546 937 1547 880 1547 938 1547 938 1548 880 1548 882 1548 938 1549 882 1549 939 1549 939 1550 882 1550 884 1550 939 1551 884 1551 940 1551 940 1552 884 1552 886 1552 940 1553 886 1553 941 1553 941 1554 886 1554 888 1554 941 1555 888 1555 942 1555 942 1556 888 1556 891 1556 942 1557 891 1557 892 1557 942 1558 892 1558 943 1558 943 1559 892 1559 874 1559 943 1560 874 1560 944 1560 944 1561 874 1561 876 1561 944 1562 876 1562 945 1562 945 1563 876 1563 937 1563 937 1564 876 1564 879 1564 744 1565 58 1565 747 1565 747 1566 58 1566 946 1566 747 1567 946 1567 746 1567 748 1568 947 1568 751 1568 751 1569 947 1569 750 1569 750 1570 947 1570 57 1570 948 1571 758 1571 949 1571 755 1572 60 1572 64 1572 755 1573 64 1573 950 1573 65 1574 951 1574 64 1574 64 1575 951 1575 950 1575 15 1576 16 1576 13 1576 13 1577 16 1577 952 1577 953 1578 74 1578 954 1578 954 1579 74 1579 73 1579 954 1580 73 1580 752 1580 752 1581 73 1581 54 1581 699 1582 819 1582 758 1582 758 1583 819 1583 72 1583 763 1584 61 1584 762 1584 762 1585 61 1585 79 1585 762 1586 79 1586 761 1586 759 1587 761 1587 78 1587 78 1588 761 1588 79 1588 759 1589 78 1589 760 1589 760 1590 78 1590 70 1590 760 1591 70 1591 764 1591 764 1592 70 1592 763 1592 763 1593 70 1593 61 1593 769 1594 71 1594 768 1594 768 1595 71 1595 77 1595 768 1596 77 1596 767 1596 765 1597 767 1597 68 1597 68 1598 767 1598 77 1598 765 1599 68 1599 766 1599 766 1600 68 1600 67 1600 766 1601 67 1601 770 1601 71 1602 769 1602 67 1602 67 1603 769 1603 770 1603 775 1604 87 1604 771 1604 771 1605 87 1605 85 1605 771 1606 85 1606 774 1606 774 1607 85 1607 776 1607 776 1608 85 1608 86 1608 776 1609 86 1609 80 1609 776 1610 80 1610 779 1610 779 1611 80 1611 773 1611 773 1612 80 1612 83 1612 773 1613 83 1613 772 1613 772 1614 83 1614 81 1614 772 1615 81 1615 82 1615 772 1616 82 1616 777 1616 777 1617 82 1617 84 1617 777 1618 84 1618 778 1618 778 1619 84 1619 76 1619 778 1620 76 1620 775 1620 775 1621 76 1621 87 1621 784 1622 70 1622 782 1622 782 1623 70 1623 69 1623 64 1624 781 1624 65 1624 65 1625 781 1625 780 1625 61 1626 783 1626 64 1626 64 1627 783 1627 781 1627 70 1628 784 1628 61 1628 61 1629 784 1629 783 1629 949 1630 788 1630 948 1630 948 1631 788 1631 789 1631 788 1632 787 1632 791 1632 791 1633 787 1633 785 1633 813 1634 792 1634 793 1634 793 1635 790 1635 791 1635 791 1636 813 1636 793 1636 792 1637 813 1637 814 1637 813 1638 809 1638 810 1638 813 1639 810 1639 815 1639 815 1640 810 1640 811 1640 816 1641 814 1641 815 1641 816 1642 815 1642 955 1642 955 1643 90 1643 816 1643 90 1644 89 1644 692 1644 692 1645 89 1645 818 1645 25 1646 88 1646 109 1646 817 1647 109 1647 108 1647 817 1648 108 1648 956 1648 107 1649 957 1649 108 1649 108 1650 957 1650 956 1650 38 1651 39 1651 958 1651 958 1652 39 1652 41 1652 959 1653 106 1653 960 1653 960 1654 106 1654 97 1654 960 1655 97 1655 840 1655 840 1656 97 1656 96 1656 96 1657 95 1657 46 1657 46 1658 95 1658 45 1658 898 1659 116 1659 897 1659 897 1660 116 1660 99 1660 897 1661 99 1661 896 1661 894 1662 896 1662 110 1662 110 1663 896 1663 99 1663 894 1664 110 1664 895 1664 895 1665 110 1665 101 1665 895 1666 101 1666 899 1666 116 1667 898 1667 101 1667 101 1668 898 1668 899 1668 905 1669 102 1669 903 1669 903 1670 102 1670 103 1670 903 1671 103 1671 902 1671 900 1672 902 1672 104 1672 104 1673 902 1673 103 1673 900 1674 104 1674 901 1674 901 1675 104 1675 100 1675 901 1676 100 1676 904 1676 904 1677 100 1677 905 1677 905 1678 100 1678 102 1678 119 1679 910 1679 906 1679 119 1680 906 1680 118 1680 118 1681 906 1681 914 1681 118 1682 914 1682 98 1682 98 1683 914 1683 909 1683 98 1684 909 1684 111 1684 111 1685 909 1685 908 1685 111 1686 908 1686 114 1686 114 1687 908 1687 907 1687 114 1688 907 1688 112 1688 112 1689 907 1689 912 1689 112 1690 912 1690 113 1690 113 1691 912 1691 911 1691 113 1692 911 1692 115 1692 115 1693 911 1693 117 1693 117 1694 911 1694 913 1694 117 1695 913 1695 910 1695 117 1696 910 1696 119 1696 92 1697 91 1697 917 1697 917 1698 91 1698 915 1698 915 1699 91 1699 916 1699 916 1700 91 1700 101 1700 97 1701 918 1701 101 1701 101 1702 918 1702 916 1702 106 1703 919 1703 97 1703 97 1704 919 1704 918 1704 968 1705 928 1705 961 1705 961 1706 928 1706 920 1706 961 1707 920 1707 962 1707 962 1708 920 1708 921 1708 962 1709 921 1709 963 1709 963 1710 921 1710 922 1710 963 1711 922 1711 964 1711 964 1712 922 1712 923 1712 964 1713 923 1713 924 1713 964 1714 924 1714 965 1714 965 1715 924 1715 925 1715 965 1716 925 1716 966 1716 966 1717 925 1717 926 1717 966 1718 926 1718 967 1718 967 1719 926 1719 927 1719 967 1720 927 1720 968 1720 968 1721 927 1721 928 1721 969 1722 929 1722 970 1722 970 1723 929 1723 930 1723 970 1724 930 1724 971 1724 971 1725 930 1725 931 1725 971 1726 931 1726 972 1726 972 1727 931 1727 932 1727 972 1728 932 1728 973 1728 973 1729 932 1729 933 1729 973 1730 933 1730 974 1730 974 1731 933 1731 934 1731 974 1732 934 1732 975 1732 975 1733 934 1733 935 1733 975 1734 935 1734 936 1734 975 1735 936 1735 976 1735 976 1736 936 1736 969 1736 969 1737 936 1737 929 1737 977 1738 944 1738 978 1738 978 1739 944 1739 945 1739 978 1740 945 1740 979 1740 979 1741 945 1741 937 1741 979 1742 937 1742 980 1742 980 1743 937 1743 938 1743 980 1744 938 1744 939 1744 980 1745 939 1745 981 1745 981 1746 939 1746 982 1746 982 1747 939 1747 940 1747 982 1748 940 1748 983 1748 983 1749 940 1749 941 1749 983 1750 941 1750 984 1750 984 1751 941 1751 942 1751 984 1752 942 1752 977 1752 977 1753 942 1753 943 1753 977 1754 943 1754 944 1754 746 1755 946 1755 124 1755 124 1756 946 1756 94 1756 750 1757 57 1757 744 1757 744 1758 57 1758 58 1758 62 1759 66 1759 748 1759 748 1760 66 1760 947 1760 949 1761 63 1761 788 1761 788 1762 63 1762 787 1762 791 1763 785 1763 813 1763 813 1764 785 1764 809 1764 815 1765 811 1765 955 1765 955 1766 811 1766 105 1766 986 1767 964 1767 965 1767 986 1768 965 1768 987 1768 987 1769 965 1769 966 1769 987 1770 966 1770 988 1770 988 1771 966 1771 967 1771 988 1772 967 1772 989 1772 989 1773 967 1773 990 1773 990 1774 967 1774 968 1774 990 1775 968 1775 991 1775 991 1776 968 1776 961 1776 991 1777 961 1777 985 1777 993 1778 962 1778 992 1778 985 1779 961 1779 993 1779 993 1780 961 1780 962 1780 964 1781 994 1781 963 1781 963 1782 994 1782 995 1782 964 1783 986 1783 994 1783 992 1784 962 1784 963 1784 992 1785 963 1785 995 1785 997 1786 970 1786 998 1786 969 1787 970 1787 996 1787 996 1788 970 1788 997 1788 970 1789 971 1789 998 1789 971 1790 972 1790 998 1790 998 1791 972 1791 999 1791 999 1792 972 1792 973 1792 999 1793 973 1793 1000 1793 1001 1794 974 1794 975 1794 1001 1795 975 1795 1002 1795 1002 1796 975 1796 1003 1796 1003 1797 975 1797 976 1797 1003 1798 976 1798 1004 1798 1004 1799 976 1799 969 1799 1004 1800 969 1800 996 1800 1000 1801 973 1801 974 1801 1000 1802 974 1802 1005 1802 1005 1803 974 1803 1001 1803 1006 1804 977 1804 978 1804 1006 1805 1008 1805 977 1805 977 1806 1008 1806 1009 1806 977 1807 1009 1807 984 1807 984 1808 1009 1808 1010 1808 984 1809 1010 1809 983 1809 983 1810 1010 1810 1011 1810 983 1811 1011 1811 1007 1811 983 1812 1007 1812 982 1812 1006 1813 978 1813 1012 1813 1012 1814 978 1814 979 1814 1012 1815 979 1815 1013 1815 982 1816 1007 1816 1014 1816 982 1817 1014 1817 981 1817 981 1818 1014 1818 1015 1818 981 1819 1015 1819 980 1819 980 1820 1015 1820 1013 1820 980 1821 1013 1821 979 1821 124 1822 128 1822 746 1822 750 1823 744 1823 745 1823 745 1824 749 1824 750 1824 62 1825 748 1825 132 1825 749 1826 132 1826 748 1826 132 1827 143 1827 62 1827 62 1828 143 1828 63 1828 143 1829 161 1829 787 1829 143 1830 787 1830 63 1830 809 1831 785 1831 812 1831 786 1832 812 1832 785 1832 167 1833 812 1833 148 1833 148 1834 812 1834 786 1834 105 1835 811 1835 1016 1835 1016 1836 811 1836 169 1836 124 1837 105 1837 1016 1837 986 1838 123 1838 994 1838 994 1839 123 1839 126 1839 994 1840 126 1840 144 1840 994 1841 144 1841 995 1841 995 1842 144 1842 170 1842 995 1843 170 1843 992 1843 992 1844 170 1844 159 1844 992 1845 159 1845 993 1845 993 1846 159 1846 166 1846 993 1847 166 1847 985 1847 985 1848 166 1848 152 1848 985 1849 152 1849 991 1849 991 1850 152 1850 145 1850 991 1851 145 1851 990 1851 990 1852 145 1852 140 1852 990 1853 140 1853 989 1853 989 1854 140 1854 120 1854 989 1855 120 1855 988 1855 988 1856 120 1856 127 1856 988 1857 127 1857 987 1857 987 1858 127 1858 123 1858 987 1859 123 1859 986 1859 1005 1860 151 1860 1000 1860 1000 1861 151 1861 163 1861 1000 1862 163 1862 999 1862 999 1863 163 1863 139 1863 999 1864 139 1864 998 1864 998 1865 139 1865 138 1865 998 1866 138 1866 997 1866 997 1867 138 1867 996 1867 996 1868 138 1868 171 1868 996 1869 171 1869 1004 1869 1004 1870 171 1870 125 1870 1004 1871 125 1871 1003 1871 1003 1872 125 1872 121 1872 1003 1873 121 1873 129 1873 1003 1874 129 1874 1002 1874 1002 1875 129 1875 1001 1875 1001 1876 129 1876 146 1876 1001 1877 146 1877 1005 1877 1005 1878 146 1878 151 1878 1007 1879 164 1879 1014 1879 1014 1880 164 1880 1015 1880 1015 1881 164 1881 135 1881 1015 1882 135 1882 1013 1882 1013 1883 135 1883 137 1883 1013 1884 137 1884 1012 1884 1012 1885 137 1885 155 1885 1012 1886 155 1886 1006 1886 1006 1887 155 1887 131 1887 1006 1888 131 1888 1008 1888 1008 1889 131 1889 133 1889 1008 1890 133 1890 1009 1890 1009 1891 133 1891 130 1891 1009 1892 130 1892 1010 1892 1010 1893 130 1893 122 1893 1010 1894 122 1894 1011 1894 1011 1895 122 1895 147 1895 1011 1896 147 1896 1007 1896 1007 1897 147 1897 164 1897 1028 1898 1019 1898 1020 1898 1020 1899 1019 1899 1021 1899 1020 1900 1021 1900 1022 1900 1022 1901 1021 1901 1023 1901 1022 1902 1023 1902 1024 1902 1024 1903 1023 1903 1025 1903 1018 1904 1017 1904 1026 1904 1018 1905 1026 1905 1027 1905 1027 1906 1026 1906 1028 1906 1028 1907 1026 1907 1019 1907 1024 1908 1025 1908 1029 1908 1029 1909 1025 1909 1030 1909 1029 1910 1030 1910 1031 1910 1031 1911 1030 1911 1032 1911 1031 1912 1032 1912 1033 1912 1033 1913 1032 1913 1017 1913 1033 1914 1017 1914 1018 1914 1028 1915 1034 1915 1027 1915 1027 1916 1034 1916 1035 1916 1027 1917 1035 1917 1018 1917 1018 1918 1035 1918 1036 1918 1018 1919 1036 1919 1037 1919 1018 1920 1037 1920 1033 1920 1033 1921 1037 1921 1038 1921 1033 1922 1038 1922 1031 1922 1031 1923 1038 1923 1039 1923 1031 1924 1039 1924 1029 1924 1029 1925 1039 1925 1040 1925 1029 1926 1040 1926 1024 1926 1024 1927 1040 1927 1041 1927 1024 1928 1041 1928 1022 1928 1022 1929 1041 1929 1042 1929 1022 1930 1042 1930 1020 1930 1020 1931 1042 1931 1043 1931 1020 1932 1043 1932 1028 1932 1028 1933 1043 1933 1034 1933 1045 1934 1044 1934 1046 1934 1045 1935 1046 1935 1047 1935 1049 1936 1048 1936 1050 1936 1050 1937 1048 1937 1051 1937 1050 1938 1051 1938 1052 1938 1052 1939 1051 1939 1053 1939 1052 1940 1053 1940 1054 1940 1054 1941 1053 1941 1055 1941 1044 1942 1045 1942 1056 1942 1044 1943 1056 1943 1057 1943 1057 1944 1056 1944 1055 1944 1057 1945 1055 1945 1053 1945 1061 1946 1058 1946 1059 1946 1061 1947 1059 1947 1060 1947 1047 1948 1046 1948 1061 1948 1061 1949 1046 1949 1058 1949 1060 1950 1059 1950 1048 1950 1060 1951 1048 1951 1049 1951 1049 1952 1062 1952 1063 1952 1049 1953 1063 1953 1060 1953 1060 1954 1063 1954 1064 1954 1060 1955 1064 1955 1061 1955 1061 1956 1064 1956 1065 1956 1061 1957 1065 1957 1047 1957 1047 1958 1065 1958 1045 1958 1045 1959 1065 1959 1066 1959 1045 1960 1066 1960 1056 1960 1056 1961 1066 1961 1067 1961 1056 1962 1067 1962 1068 1962 1056 1963 1068 1963 1055 1963 1055 1964 1068 1964 1069 1964 1055 1965 1069 1965 1054 1965 1054 1966 1069 1966 1070 1966 1054 1967 1070 1967 1052 1967 1052 1968 1070 1968 1071 1968 1052 1969 1071 1969 1050 1969 1050 1970 1071 1970 1062 1970 1050 1971 1062 1971 1049 1971 1073 1972 1072 1972 1074 1972 1074 1973 1072 1973 1075 1973 1074 1974 1075 1974 1076 1974 1076 1975 1075 1975 1077 1975 1076 1976 1077 1976 1078 1976 1078 1977 1077 1977 1079 1977 1078 1978 1079 1978 1080 1978 1078 1979 1080 1979 1081 1979 1081 1980 1080 1980 1082 1980 1081 1981 1082 1981 1083 1981 1083 1982 1082 1982 1084 1982 1083 1983 1084 1983 1085 1983 1085 1984 1084 1984 1086 1984 1086 1985 1084 1985 1087 1985 1086 1986 1087 1986 1088 1986 1088 1987 1087 1987 1089 1987 1088 1988 1089 1988 1090 1988 1090 1989 1089 1989 1072 1989 1090 1990 1072 1990 1073 1990 1074 1991 1091 1991 1073 1991 1073 1992 1091 1992 1092 1992 1073 1993 1092 1993 1090 1993 1090 1994 1092 1994 1088 1994 1088 1995 1092 1995 1093 1995 1088 1996 1093 1996 1086 1996 1086 1997 1093 1997 1094 1997 1086 1998 1094 1998 1095 1998 1086 1999 1095 1999 1085 1999 1085 2000 1095 2000 1083 2000 1083 2001 1095 2001 1096 2001 1083 2002 1096 2002 1081 2002 1081 2003 1096 2003 1097 2003 1081 2004 1097 2004 1078 2004 1078 2005 1097 2005 1098 2005 1078 2006 1098 2006 1099 2006 1078 2007 1099 2007 1076 2007 1076 2008 1099 2008 1100 2008 1076 2009 1100 2009 1074 2009 1074 2010 1100 2010 1091 2010 1101 2011 1104 2011 1102 2011 1117 2012 1104 2012 1103 2012 1103 2013 1104 2013 1105 2013 1105 2014 1104 2014 1101 2014 1101 2015 1102 2015 1106 2015 1108 2016 1107 2016 1109 2016 1108 2017 1109 2017 1110 2017 1110 2018 1109 2018 1106 2018 1110 2019 1106 2019 1102 2019 1107 2020 1108 2020 1111 2020 1107 2021 1111 2021 1112 2021 1112 2022 1111 2022 1113 2022 1113 2023 1111 2023 1114 2023 1113 2024 1114 2024 1115 2024 1113 2025 1115 2025 1116 2025 1116 2026 1115 2026 1117 2026 1116 2027 1117 2027 1118 2027 1118 2028 1117 2028 1103 2028 1106 2029 1128 2029 1119 2029 1106 2030 1119 2030 1101 2030 1101 2031 1119 2031 1120 2031 1101 2032 1120 2032 1105 2032 1105 2033 1120 2033 1121 2033 1105 2034 1121 2034 1103 2034 1103 2035 1121 2035 1122 2035 1103 2036 1122 2036 1118 2036 1118 2037 1122 2037 1123 2037 1118 2038 1123 2038 1116 2038 1116 2039 1123 2039 1124 2039 1116 2040 1124 2040 1113 2040 1113 2041 1124 2041 1125 2041 1113 2042 1125 2042 1112 2042 1112 2043 1125 2043 1126 2043 1112 2044 1126 2044 1107 2044 1107 2045 1126 2045 1127 2045 1107 2046 1127 2046 1109 2046 1109 2047 1127 2047 1128 2047 1109 2048 1128 2048 1106 2048 1129 2049 1130 2049 148 2049 1129 2050 148 2050 1131 2050 148 2051 149 2051 1131 2051 1131 2052 149 2052 160 2052 1131 2053 160 2053 1132 2053 1132 2054 160 2054 142 2054 1132 2055 142 2055 1133 2055 1133 2056 142 2056 1134 2056 1134 2057 142 2057 141 2057 1134 2058 141 2058 150 2058 1134 2059 150 2059 1135 2059 1135 2060 150 2060 157 2060 1135 2061 157 2061 1136 2061 1136 2062 157 2062 1137 2062 1137 2063 157 2063 136 2063 1137 2064 136 2064 1138 2064 1138 2065 136 2065 162 2065 1138 2066 162 2066 1139 2066 1139 2067 162 2067 156 2067 1139 2068 156 2068 1140 2068 1140 2069 156 2069 134 2069 1140 2070 134 2070 1141 2070 1141 2071 134 2071 158 2071 1141 2072 158 2072 1142 2072 1142 2073 158 2073 165 2073 1142 2074 165 2074 154 2074 1142 2075 154 2075 1143 2075 1143 2076 154 2076 153 2076 1143 2077 153 2077 1144 2077 1144 2078 153 2078 168 2078 1144 2079 168 2079 1145 2079 1145 2080 168 2080 167 2080 1145 2081 167 2081 1129 2081 1129 2082 167 2082 1130 2082 167 2083 148 2083 1130 2083 1043 2084 1131 2084 1132 2084 1043 2085 1042 2085 1131 2085 1131 2086 1042 2086 1129 2086 1129 2087 1042 2087 1041 2087 1143 2088 1096 2088 1142 2088 1134 2089 1071 2089 1133 2089 1133 2090 1071 2090 1070 2090 1095 2091 1142 2091 1096 2091 1139 2092 1121 2092 1138 2092 1120 2093 1138 2093 1121 2093 1139 2094 1140 2094 1122 2094 1134 2095 1135 2095 1063 2095 1138 2096 1120 2096 1137 2096 1137 2097 1120 2097 1119 2097 1133 2098 1070 2098 1069 2098 1139 2099 1122 2099 1121 2099 1100 2100 1069 2100 1091 2100 1091 2101 1069 2101 1068 2101 1135 2102 1136 2102 1064 2102 1037 2103 1036 2103 1100 2103 1064 2104 1063 2104 1135 2104 1063 2105 1062 2105 1134 2105 1134 2106 1062 2106 1071 2106 1069 2107 1100 2107 1133 2107 1129 2108 1041 2108 1040 2108 1141 2109 1142 2109 1094 2109 1140 2110 1123 2110 1122 2110 1137 2111 1119 2111 1136 2111 1136 2112 1119 2112 1128 2112 1091 2113 1068 2113 1067 2113 1065 2114 1091 2114 1066 2114 1129 2115 1040 2115 1145 2115 1145 2116 1040 2116 1039 2116 1038 2117 1144 2117 1039 2117 1039 2118 1144 2118 1145 2118 1136 2119 1128 2119 1127 2119 1091 2120 1126 2120 1125 2120 1091 2121 1065 2121 1136 2121 1136 2122 1065 2122 1064 2122 1143 2123 1097 2123 1096 2123 1100 2124 1036 2124 1133 2124 1133 2125 1036 2125 1035 2125 1035 2126 1034 2126 1133 2126 1133 2127 1034 2127 1132 2127 1132 2128 1034 2128 1043 2128 1142 2129 1095 2129 1094 2129 1136 2130 1127 2130 1126 2130 1136 2131 1126 2131 1091 2131 1091 2132 1125 2132 1092 2132 1144 2133 1098 2133 1097 2133 1144 2134 1097 2134 1143 2134 1141 2135 1094 2135 1093 2135 1141 2136 1093 2136 1140 2136 1140 2137 1093 2137 1123 2137 1123 2138 1093 2138 1124 2138 1124 2139 1093 2139 1092 2139 1092 2140 1125 2140 1124 2140 1091 2141 1067 2141 1066 2141 1099 2142 1038 2142 1100 2142 1100 2143 1038 2143 1037 2143 1038 2144 1099 2144 1144 2144 1144 2145 1099 2145 1098 2145 1102 2146 1146 2146 1110 2146 1110 2147 1146 2147 1147 2147 1110 2148 1147 2148 1108 2148 1108 2149 1147 2149 1148 2149 1108 2150 1148 2150 1111 2150 1111 2151 1148 2151 1149 2151 1111 2152 1149 2152 1114 2152 1114 2153 1149 2153 1150 2153 1114 2154 1150 2154 1115 2154 1115 2155 1150 2155 1151 2155 1115 2156 1151 2156 1117 2156 1117 2157 1151 2157 1152 2157 1117 2158 1152 2158 1153 2158 1117 2159 1153 2159 1104 2159 1104 2160 1153 2160 1154 2160 1104 2161 1154 2161 1102 2161 1102 2162 1154 2162 1146 2162 1155 2163 1072 2163 1163 2163 1072 2164 1155 2164 1075 2164 1075 2165 1155 2165 1156 2165 1075 2166 1156 2166 1077 2166 1077 2167 1156 2167 1157 2167 1077 2168 1157 2168 1079 2168 1079 2169 1157 2169 1158 2169 1079 2170 1158 2170 1080 2170 1080 2171 1158 2171 1159 2171 1080 2172 1159 2172 1082 2172 1082 2173 1159 2173 1160 2173 1082 2174 1160 2174 1084 2174 1084 2175 1160 2175 1161 2175 1084 2176 1161 2176 1087 2176 1087 2177 1161 2177 1162 2177 1087 2178 1162 2178 1089 2178 1089 2179 1162 2179 1163 2179 1089 2180 1163 2180 1072 2180 1172 2181 1164 2181 1048 2181 1048 2182 1164 2182 1051 2182 1051 2183 1164 2183 1165 2183 1051 2184 1165 2184 1053 2184 1053 2185 1165 2185 1166 2185 1053 2186 1166 2186 1167 2186 1053 2187 1167 2187 1057 2187 1057 2188 1167 2188 1168 2188 1057 2189 1168 2189 1044 2189 1044 2190 1168 2190 1169 2190 1044 2191 1169 2191 1046 2191 1046 2192 1169 2192 1170 2192 1046 2193 1170 2193 1058 2193 1058 2194 1170 2194 1171 2194 1058 2195 1171 2195 1059 2195 1059 2196 1171 2196 1172 2196 1059 2197 1172 2197 1048 2197 1019 2198 1173 2198 1174 2198 1019 2199 1174 2199 1021 2199 1021 2200 1174 2200 1175 2200 1021 2201 1175 2201 1023 2201 1023 2202 1175 2202 1025 2202 1025 2203 1175 2203 1176 2203 1025 2204 1176 2204 1177 2204 1025 2205 1177 2205 1030 2205 1030 2206 1177 2206 1032 2206 1032 2207 1177 2207 1178 2207 1032 2208 1178 2208 1017 2208 1017 2209 1178 2209 1179 2209 1017 2210 1179 2210 1026 2210 1026 2211 1179 2211 1180 2211 1026 2212 1180 2212 1173 2212 1026 2213 1173 2213 1019 2213 1168 2214 1181 2214 1169 2214 1169 2215 1181 2215 1182 2215 1169 2216 1182 2216 1170 2216 1170 2217 1182 2217 1183 2217 1170 2218 1183 2218 1184 2218 1170 2219 1184 2219 1171 2219 1171 2220 1184 2220 1185 2220 1171 2221 1185 2221 1172 2221 1172 2222 1185 2222 1186 2222 1172 2223 1186 2223 1164 2223 1164 2224 1186 2224 1187 2224 1164 2225 1187 2225 1165 2225 1165 2226 1187 2226 1188 2226 1165 2227 1188 2227 1166 2227 1166 2228 1188 2228 1167 2228 1167 2229 1188 2229 1189 2229 1167 2230 1189 2230 1168 2230 1168 2231 1189 2231 1190 2231 1168 2232 1190 2232 1181 2232 1161 2233 1191 2233 1192 2233 1161 2234 1192 2234 1162 2234 1162 2235 1192 2235 1193 2235 1162 2236 1193 2236 1163 2236 1163 2237 1193 2237 1194 2237 1163 2238 1194 2238 1155 2238 1155 2239 1194 2239 1195 2239 1155 2240 1195 2240 1156 2240 1156 2241 1195 2241 1196 2241 1156 2242 1196 2242 1157 2242 1157 2243 1196 2243 1197 2243 1157 2244 1197 2244 1158 2244 1158 2245 1197 2245 1198 2245 1158 2246 1198 2246 1159 2246 1159 2247 1198 2247 1199 2247 1159 2248 1199 2248 1160 2248 1160 2249 1199 2249 1191 2249 1160 2250 1191 2250 1161 2250 1150 2251 1149 2251 1148 2251 1150 2252 1148 2252 1147 2252 1146 2253 1154 2253 1150 2253 1147 2254 1146 2254 1150 2254 1150 2255 1154 2255 1153 2255 1153 2256 1152 2256 1150 2256 1152 2257 1151 2257 1150 2257 1177 2258 1175 2258 1174 2258 1177 2259 1173 2259 1180 2259 1177 2260 1179 2260 1178 2260 1175 2261 1177 2261 1176 2261 1177 2262 1174 2262 1173 2262 1177 2263 1180 2263 1179 2263 1200 2264 1201 2264 1203 2264 1201 2265 1202 2265 1203 2265 1204 2266 1205 2266 1200 2266 1200 2267 1205 2267 1206 2267 1200 2268 1206 2268 1201 2268 1202 2269 1201 2269 1207 2269 1201 2270 1208 2270 1209 2270 1201 2271 1209 2271 1207 2271 1207 2272 1209 2272 1210 2272 1207 2273 1210 2273 1202 2273 1202 2274 1210 2274 1211 2274 1202 2275 1211 2275 1203 2275 1203 2276 1211 2276 1212 2276 1203 2277 1212 2277 1200 2277 1200 2278 1212 2278 1213 2278 1200 2279 1213 2279 1204 2279 1204 2280 1213 2280 1205 2280 1205 2281 1213 2281 1214 2281 1205 2282 1214 2282 1215 2282 1205 2283 1215 2283 1206 2283 1206 2284 1215 2284 1208 2284 1206 2285 1208 2285 1201 2285 1212 2286 1216 2286 1217 2286 1212 2287 1217 2287 1213 2287 1213 2288 1217 2288 1218 2288 1213 2289 1218 2289 1219 2289 1213 2290 1219 2290 1214 2290 1214 2291 1219 2291 1215 2291 1215 2292 1219 2292 1220 2292 1215 2293 1220 2293 1221 2293 1215 2294 1221 2294 1208 2294 1208 2295 1221 2295 1222 2295 1208 2296 1222 2296 1209 2296 1209 2297 1222 2297 1223 2297 1209 2298 1223 2298 1210 2298 1210 2299 1223 2299 1224 2299 1210 2300 1224 2300 1211 2300 1211 2301 1224 2301 1225 2301 1211 2302 1225 2302 1216 2302 1211 2303 1216 2303 1212 2303 1216 2304 1186 2304 1185 2304 1216 2305 1185 2305 1217 2305 1217 2306 1185 2306 1184 2306 1217 2307 1184 2307 1218 2307 1218 2308 1184 2308 1183 2308 1218 2309 1183 2309 1219 2309 1219 2310 1183 2310 1182 2310 1219 2311 1182 2311 1220 2311 1220 2312 1182 2312 1181 2312 1220 2313 1181 2313 1221 2313 1221 2314 1181 2314 1190 2314 1221 2315 1190 2315 1222 2315 1222 2316 1190 2316 1189 2316 1222 2317 1189 2317 1223 2317 1223 2318 1189 2318 1188 2318 1223 2319 1188 2319 1224 2319 1224 2320 1188 2320 1187 2320 1224 2321 1187 2321 1225 2321 1225 2322 1187 2322 1186 2322 1225 2323 1186 2323 1216 2323 1226 2324 1228 2324 1232 2324 1228 2325 1226 2325 1227 2325 1228 2326 1227 2326 1229 2326 1230 2327 1231 2327 1232 2327 1231 2328 1233 2328 1232 2328 1226 2329 1232 2329 1233 2329 1228 2330 1234 2330 1232 2330 1232 2331 1234 2331 1235 2331 1232 2332 1235 2332 1230 2332 1230 2333 1235 2333 1236 2333 1230 2334 1236 2334 1231 2334 1231 2335 1236 2335 1237 2335 1231 2336 1237 2336 1233 2336 1233 2337 1237 2337 1238 2337 1233 2338 1238 2338 1226 2338 1226 2339 1238 2339 1239 2339 1226 2340 1239 2340 1227 2340 1227 2341 1239 2341 1240 2341 1227 2342 1240 2342 1229 2342 1229 2343 1240 2343 1241 2343 1229 2344 1241 2344 1228 2344 1228 2345 1241 2345 1242 2345 1228 2346 1242 2346 1234 2346 1239 2347 1253 2347 1243 2347 1239 2348 1243 2348 1240 2348 1240 2349 1243 2349 1244 2349 1240 2350 1244 2350 1241 2350 1241 2351 1244 2351 1245 2351 1241 2352 1245 2352 1242 2352 1242 2353 1245 2353 1246 2353 1242 2354 1246 2354 1234 2354 1234 2355 1246 2355 1247 2355 1234 2356 1247 2356 1248 2356 1234 2357 1248 2357 1235 2357 1235 2358 1248 2358 1249 2358 1235 2359 1249 2359 1236 2359 1236 2360 1249 2360 1250 2360 1236 2361 1250 2361 1237 2361 1237 2362 1250 2362 1251 2362 1237 2363 1251 2363 1238 2363 1238 2364 1251 2364 1252 2364 1238 2365 1252 2365 1253 2365 1238 2366 1253 2366 1239 2366 1252 2367 1194 2367 1253 2367 1253 2368 1194 2368 1193 2368 1253 2369 1193 2369 1243 2369 1243 2370 1193 2370 1192 2370 1243 2371 1192 2371 1244 2371 1244 2372 1192 2372 1191 2372 1244 2373 1191 2373 1245 2373 1245 2374 1191 2374 1246 2374 1246 2375 1191 2375 1199 2375 1246 2376 1199 2376 1247 2376 1247 2377 1199 2377 1198 2377 1247 2378 1198 2378 1248 2378 1248 2379 1198 2379 1197 2379 1248 2380 1197 2380 1249 2380 1249 2381 1197 2381 1196 2381 1249 2382 1196 2382 1250 2382 1250 2383 1196 2383 1195 2383 1250 2384 1195 2384 1251 2384 1251 2385 1195 2385 1194 2385 1251 2386 1194 2386 1252 2386 1254 2387 1255 2387 1256 2387 1257 2388 1258 2388 1259 2388 1260 2389 1261 2389 1262 2389 1262 2390 1261 2390 1263 2390 1264 2391 1265 2391 1266 2391 1267 2392 1268 2392 1269 2392 1269 2393 1268 2393 1270 2393 1271 2394 1272 2394 1273 2394 1273 2395 1272 2395 1274 2395 1275 2396 1276 2396 1277 2396 1278 2397 1279 2397 1280 2397 1280 2398 1279 2398 1281 2398 33 2399 35 2399 1282 2399 44 2400 45 2400 1282 2400 1282 2401 45 2401 95 2401 1282 2402 95 2402 33 2402 33 2403 95 2403 1283 2403 33 2404 1283 2404 841 2404 1285 2405 1284 2405 1286 2405 1287 2406 1285 2406 1288 2406 1287 2407 1289 2407 1285 2407 1285 2408 1289 2408 1284 2408 1290 2409 1291 2409 1286 2409 1286 2410 1291 2410 1285 2410 1285 2411 1292 2411 1288 2411 1295 2412 1293 2412 1296 2412 1293 2413 1297 2413 1294 2413 1293 2414 1294 2414 1298 2414 1293 2415 1295 2415 1297 2415 1295 2416 1296 2416 1299 2416 1298 2417 1301 2417 1302 2417 1298 2418 1302 2418 1303 2418 1295 2419 1299 2419 1300 2419 1303 2420 1293 2420 1298 2420 1304 2421 1305 2421 1306 2421 1304 2422 1306 2422 1307 2422 1307 2423 1306 2423 1308 2423 1306 2424 1305 2424 1310 2424 1309 2425 1306 2425 1310 2425 1308 2426 1306 2426 1309 2426 1310 2427 1311 2427 1309 2427 1307 2428 1322 2428 1321 2428 1307 2429 1321 2429 1304 2429 1307 2430 1320 2430 1322 2430 1321 2431 1322 2431 1316 2431 1320 2432 1323 2432 1322 2432 1322 2433 1323 2433 1316 2433 1320 2434 1324 2434 1323 2434 1323 2435 1324 2435 1315 2435 1323 2436 1315 2436 1316 2436 1324 2437 1314 2437 1315 2437 1320 2438 1325 2438 1324 2438 1324 2439 1325 2439 1314 2439 1325 2440 1313 2440 1314 2440 1325 2441 1326 2441 1313 2441 1313 2442 1326 2442 1312 2442 1325 2443 1319 2443 1326 2443 1326 2444 1327 2444 1312 2444 1326 2445 1319 2445 1328 2445 1326 2446 1328 2446 1327 2446 1328 2447 1319 2447 1329 2447 1319 2448 1331 2448 1330 2448 1319 2449 1330 2449 1329 2449 1319 2450 1318 2450 1331 2450 1331 2451 1318 2451 1332 2451 1331 2452 1332 2452 1330 2452 1318 2453 1334 2453 1332 2453 1332 2454 1334 2454 1333 2454 1318 2455 1317 2455 1334 2455 1317 2456 1336 2456 1334 2456 1334 2457 1336 2457 1333 2457 1333 2458 1336 2458 1335 2458 1305 2459 1337 2459 1338 2459 1305 2460 1338 2460 1310 2460 1310 2461 1338 2461 1339 2461 1310 2462 1339 2462 1311 2462 1311 2463 1353 2463 1352 2463 1311 2464 1352 2464 1309 2464 1309 2465 1352 2465 1308 2465 1308 2466 1352 2466 1351 2466 1317 2467 1351 2467 1340 2467 1317 2468 1340 2468 1336 2468 1336 2469 1340 2469 1341 2469 1336 2470 1341 2470 1335 2470 1337 2471 1344 2471 1338 2471 1338 2472 1344 2472 1345 2472 1338 2473 1345 2473 1339 2473 1344 2474 1343 2474 1346 2474 1344 2475 1346 2475 1345 2475 1345 2476 1346 2476 1347 2476 1345 2477 1347 2477 1339 2477 1343 2478 1342 2478 1346 2478 1342 2479 1348 2479 1346 2479 1346 2480 1348 2480 1347 2480 1342 2481 1349 2481 1348 2481 1348 2482 1350 2482 1347 2482 1354 2483 1351 2483 1352 2483 1341 2484 1340 2484 1354 2484 1354 2485 1352 2485 1353 2485 1340 2486 1351 2486 1354 2486 1356 2487 1355 2487 1358 2487 1356 2488 1358 2488 1357 2488 1357 2489 1358 2489 1359 2489 1355 2490 1360 2490 1358 2490 1358 2491 1360 2491 1361 2491 1358 2492 1361 2492 1359 2492 1355 2493 1350 2493 1360 2493 1350 2494 1349 2494 1360 2494 1360 2495 1349 2495 1361 2495 1350 2496 1348 2496 1349 2496 1362 2497 1341 2497 1354 2497 1362 2498 1354 2498 1363 2498 1363 2499 1354 2499 1353 2499 1363 2500 1353 2500 1375 2500 1375 2501 1353 2501 1899 2501 1364 2502 1355 2502 1365 2502 1365 2503 1355 2503 1356 2503 1365 2504 1356 2504 1366 2504 1366 2505 1356 2505 1357 2505 1370 2506 1369 2506 1371 2506 1370 2507 1371 2507 1372 2507 1372 2508 1371 2508 1373 2508 1372 2509 1373 2509 1385 2509 1369 2510 1368 2510 1371 2510 1371 2511 1368 2511 1374 2511 1371 2512 1374 2512 1373 2512 1368 2513 1367 2513 1374 2513 1374 2514 1375 2514 1373 2514 1374 2515 1367 2515 1375 2515 1367 2516 1362 2516 1363 2516 1367 2517 1363 2517 1375 2517 1364 2518 1378 2518 1376 2518 1364 2519 1365 2519 1378 2519 1377 2520 1376 2520 1379 2520 1378 2521 1365 2521 1380 2521 1376 2522 1378 2522 1381 2522 1376 2523 1381 2523 1379 2523 1365 2524 1366 2524 1380 2524 1378 2525 1380 2525 1381 2525 1379 2526 1381 2526 1383 2526 1379 2527 1383 2527 1382 2527 1385 2528 1386 2528 1372 2528 1372 2529 1386 2529 1370 2529 1370 2530 1386 2530 1387 2530 1385 2531 1384 2531 1386 2531 1384 2532 1388 2532 1386 2532 1386 2533 1388 2533 1389 2533 1386 2534 1389 2534 1387 2534 1388 2535 1390 2535 1389 2535 1391 2536 1377 2536 1392 2536 1392 2537 1377 2537 1379 2537 1392 2538 1379 2538 1393 2538 1393 2539 1379 2539 1382 2539 1384 2540 1394 2540 1388 2540 1388 2541 1394 2541 1398 2541 1388 2542 1398 2542 1390 2542 1390 2543 1398 2543 1400 2543 1391 2544 1392 2544 1395 2544 1391 2545 1395 2545 1396 2545 1391 2546 1396 2546 1394 2546 1392 2547 1397 2547 1395 2547 1394 2548 1396 2548 1398 2548 1392 2549 1393 2549 1397 2549 1396 2550 1395 2550 1399 2550 1398 2551 1396 2551 1400 2551 1395 2552 1397 2552 1401 2552 1395 2553 1401 2553 1399 2553 1396 2554 1399 2554 1400 2554 1402 2555 1405 2555 1403 2555 1403 2556 1407 2556 1404 2556 1406 2557 1407 2557 1405 2557 1409 2558 1404 2558 1407 2558 1407 2559 1403 2559 1405 2559 1404 2560 1409 2560 1408 2560 1412 2561 1410 2561 1408 2561 1412 2562 1408 2562 1409 2562 1409 2563 1407 2563 1406 2563 1409 2564 1406 2564 1411 2564 1409 2565 1411 2565 1413 2565 1410 2566 1412 2566 1414 2566 1412 2567 1409 2567 1415 2567 1415 2568 1409 2568 1413 2568 1414 2569 1417 2569 1418 2569 1414 2570 1418 2570 1419 2570 1415 2571 1416 2571 1417 2571 1415 2572 1417 2572 1412 2572 1412 2573 1417 2573 1414 2573 1410 2574 1414 2574 1419 2574 1417 2575 1416 2575 1420 2575 1418 2576 1421 2576 1419 2576 1417 2577 1420 2577 1418 2577 1418 2578 1420 2578 1421 2578 1422 2579 1519 2579 1423 2579 1425 2580 1424 2580 1427 2580 1425 2581 1427 2581 1428 2581 1428 2582 1427 2582 1429 2582 1429 2583 1427 2583 1422 2583 1434 2584 1429 2584 1426 2584 1423 2585 1429 2585 1422 2585 1429 2586 1434 2586 1428 2586 1431 2587 1430 2587 1433 2587 1431 2588 1425 2588 1435 2588 1435 2589 1425 2589 1428 2589 1433 2590 1424 2590 1425 2590 1433 2591 1425 2591 1431 2591 1428 2592 1434 2592 1435 2592 1435 2593 1432 2593 1431 2593 1430 2594 1431 2594 1437 2594 1437 2595 1431 2595 1436 2595 1436 2596 1431 2596 1432 2596 1439 2597 1438 2597 1430 2597 1439 2598 1430 2598 1437 2598 1439 2599 1440 2599 1438 2599 1441 2600 1440 2600 1439 2600 1441 2601 1439 2601 1437 2601 1442 2602 1441 2602 1437 2602 1442 2603 1437 2603 1436 2603 1443 2604 1442 2604 1444 2604 1442 2605 1443 2605 1441 2605 1441 2606 1443 2606 1445 2606 1445 2607 1440 2607 1441 2607 1440 2608 1445 2608 1464 2608 1456 2609 1457 2609 1458 2609 1450 2610 1459 2610 1449 2610 1448 2611 1460 2611 1447 2611 1444 2612 1446 2612 1443 2612 1456 2613 1458 2613 1455 2613 1453 2614 1454 2614 1461 2614 1450 2615 1451 2615 1459 2615 1453 2616 1461 2616 1452 2616 1451 2617 1452 2617 1462 2617 1451 2618 1462 2618 1459 2618 1449 2619 1459 2619 1463 2619 1449 2620 1463 2620 1448 2620 1448 2621 1463 2621 1460 2621 1447 2622 1460 2622 1464 2622 1447 2623 1464 2623 1446 2623 1457 2624 1465 2624 1458 2624 1458 2625 1465 2625 1466 2625 1458 2626 1466 2626 1455 2626 1454 2627 1455 2627 1467 2627 1454 2628 1467 2628 1461 2628 1452 2629 1461 2629 1462 2629 1443 2630 1446 2630 1445 2630 1455 2631 1466 2631 1467 2631 1461 2632 1467 2632 1468 2632 1460 2633 1463 2633 1464 2633 1446 2634 1464 2634 1445 2634 1461 2635 1468 2635 1462 2635 1459 2636 1462 2636 1469 2636 1459 2637 1469 2637 1463 2637 1463 2638 1469 2638 1464 2638 1462 2639 1468 2639 1469 2639 1457 2640 1421 2640 1465 2640 1465 2641 1421 2641 1420 2641 1472 2642 1471 2642 1473 2642 1471 2643 1475 2643 1473 2643 1470 2644 1474 2644 1471 2644 1471 2645 1474 2645 1477 2645 1471 2646 1477 2646 1475 2646 1472 2647 1473 2647 1476 2647 1475 2648 1477 2648 1478 2648 1477 2649 1474 2649 1480 2649 1473 2650 1475 2650 1481 2650 1473 2651 1481 2651 1476 2651 1474 2652 1479 2652 1480 2652 1477 2653 1480 2653 1478 2653 1476 2654 1481 2654 1482 2654 1482 2655 1483 2655 1476 2655 1476 2656 1483 2656 1484 2656 1476 2657 1484 2657 1485 2657 1476 2658 1485 2658 1472 2658 1486 2659 1479 2659 1474 2659 1486 2660 1474 2660 1501 2660 1501 2661 1474 2661 1470 2661 1501 2662 1470 2662 1497 2662 1485 2663 1488 2663 1487 2663 1485 2664 1484 2664 1488 2664 1487 2665 1488 2665 1489 2665 1488 2666 1490 2666 1489 2666 1488 2667 1484 2667 1492 2667 1488 2668 1492 2668 1493 2668 1488 2669 1493 2669 1490 2669 1489 2670 1490 2670 1494 2670 1489 2671 1494 2671 1491 2671 1484 2672 1483 2672 1492 2672 1496 2673 1495 2673 1498 2673 1495 2674 1499 2674 1498 2674 1496 2675 1500 2675 1497 2675 1497 2676 1500 2676 1501 2676 1496 2677 1498 2677 1500 2677 1495 2678 1502 2678 1499 2678 1498 2679 1499 2679 1503 2679 1500 2680 1504 2680 1501 2680 1499 2681 1502 2681 1505 2681 1498 2682 1503 2682 1500 2682 1501 2683 1504 2683 1486 2683 1499 2684 1505 2684 1503 2684 1491 2685 1506 2685 1507 2685 1491 2686 1507 2686 1489 2686 1489 2687 1507 2687 1508 2687 1489 2688 1508 2688 1487 2688 1509 2689 1502 2689 1513 2689 1513 2690 1502 2690 1495 2690 1513 2691 1495 2691 1510 2691 1508 2692 1511 2692 1510 2692 1510 2693 1511 2693 1512 2693 1510 2694 1512 2694 1513 2694 1508 2695 1507 2695 1511 2695 1511 2696 1514 2696 1512 2696 1511 2697 1507 2697 1515 2697 1511 2698 1515 2698 1516 2698 1511 2699 1516 2699 1514 2699 1512 2700 1514 2700 1517 2700 1512 2701 1517 2701 1513 2701 1507 2702 1506 2702 1515 2702 1513 2703 1517 2703 1509 2703 1518 2704 1519 2704 1422 2704 1520 2705 1518 2705 1525 2705 1518 2706 1520 2706 1519 2706 1520 2707 57 2707 1519 2707 1527 2708 1526 2708 1524 2708 1525 2709 1522 2709 1524 2709 1523 2710 1522 2710 1525 2710 1523 2711 1525 2711 1518 2711 1521 2712 1520 2712 1525 2712 1424 2713 1523 2713 1427 2713 1427 2714 1523 2714 1518 2714 1427 2715 1518 2715 1422 2715 1411 2716 1406 2716 1535 2716 1430 2717 1537 2717 1433 2717 1538 2718 1533 2718 1532 2718 1538 2719 1532 2719 1536 2719 1424 2720 1433 2720 1531 2720 1531 2721 1433 2721 1539 2721 1523 2722 1424 2722 1531 2722 1531 2723 1539 2723 1540 2723 1535 2724 1538 2724 1411 2724 1411 2725 1538 2725 1536 2725 1411 2726 1536 2726 1413 2726 1522 2727 1523 2727 1528 2727 1528 2728 1523 2728 1531 2728 1528 2729 1531 2729 1540 2729 1535 2730 1406 2730 1549 2730 1533 2731 1538 2731 1535 2731 1529 2732 1535 2732 1549 2732 1529 2733 1549 2733 1530 2733 1542 2734 1528 2734 1540 2734 1542 2735 1540 2735 1541 2735 1534 2736 1532 2736 1533 2736 1543 2737 1533 2737 1535 2737 1529 2738 1530 2738 1547 2738 1524 2739 1522 2739 1528 2739 1524 2740 1528 2740 1542 2740 1542 2741 1541 2741 1544 2741 1539 2742 1537 2742 1534 2742 1543 2743 1535 2743 1529 2743 1527 2744 1524 2744 1542 2744 1527 2745 1542 2745 1544 2745 1433 2746 1537 2746 1539 2746 1539 2747 1534 2747 1540 2747 1540 2748 1534 2748 1533 2748 1540 2749 1533 2749 1543 2749 1541 2750 1543 2750 1529 2750 1544 2751 1529 2751 1547 2751 1544 2752 1547 2752 1546 2752 1540 2753 1543 2753 1541 2753 1541 2754 1529 2754 1544 2754 1547 2755 1530 2755 1545 2755 1406 2756 1405 2756 1549 2756 1548 2757 1545 2757 1550 2757 1405 2758 1402 2758 1530 2758 1405 2759 1530 2759 1549 2759 1402 2760 1545 2760 1530 2760 1550 2761 1545 2761 1402 2761 1393 2762 1551 2762 1397 2762 1397 2763 1551 2763 1401 2763 1401 2764 1551 2764 1552 2764 1401 2765 1552 2765 1399 2765 1399 2766 1552 2766 1553 2766 1399 2767 1553 2767 1400 2767 1554 2768 1370 2768 1387 2768 1554 2769 1387 2769 1555 2769 1555 2770 1387 2770 1389 2770 1555 2771 1389 2771 1390 2771 1556 2772 1382 2772 1383 2772 1556 2773 1383 2773 1381 2773 1556 2774 1381 2774 1557 2774 1557 2775 1381 2775 1380 2775 1557 2776 1380 2776 1558 2776 1558 2777 1380 2777 1366 2777 1342 2778 1559 2778 1349 2778 1349 2779 1559 2779 1361 2779 1361 2780 1559 2780 1359 2780 1359 2781 1559 2781 1560 2781 1359 2782 1560 2782 1357 2782 57 2783 1562 2783 1563 2783 57 2784 1563 2784 58 2784 1486 2785 1564 2785 58 2785 58 2786 1563 2786 1486 2786 1486 2787 1563 2787 1561 2787 1520 2788 1521 2788 1565 2788 1565 2789 57 2789 1520 2789 57 2790 1565 2790 1562 2790 1486 2791 1504 2791 1564 2791 1564 2792 1504 2792 1566 2792 1566 2793 1504 2793 1500 2793 1566 2794 1500 2794 1503 2794 1566 2795 1503 2795 1567 2795 1567 2796 1503 2796 1505 2796 1567 2797 1505 2797 1568 2797 1568 2798 1505 2798 1502 2798 1569 2799 1509 2799 1517 2799 1569 2800 1517 2800 1570 2800 1570 2801 1517 2801 1514 2801 1570 2802 1514 2802 1516 2802 1570 2803 1516 2803 1571 2803 1571 2804 1516 2804 1515 2804 1571 2805 1515 2805 1506 2805 1483 2806 1572 2806 1492 2806 1492 2807 1572 2807 1573 2807 1492 2808 1573 2808 1493 2808 1493 2809 1573 2809 1490 2809 1490 2810 1573 2810 1574 2810 1490 2811 1574 2811 1494 2811 1494 2812 1574 2812 1491 2812 1575 2813 1482 2813 1481 2813 1575 2814 1481 2814 1475 2814 1575 2815 1475 2815 1478 2815 1575 2816 1478 2816 1576 2816 1576 2817 1478 2817 1480 2817 1576 2818 1480 2818 1577 2818 52 2819 1578 2819 53 2819 53 2820 1578 2820 1579 2820 1577 2821 1480 2821 1479 2821 1577 2822 1479 2822 52 2822 52 2823 1479 2823 1578 2823 1548 2824 1550 2824 1580 2824 53 2825 1579 2825 1580 2825 53 2826 1580 2826 1550 2826 1479 2827 1581 2827 1578 2827 1367 2828 1410 2828 1419 2828 1367 2829 1419 2829 1362 2829 1368 2830 1408 2830 1410 2830 1368 2831 1410 2831 1367 2831 1404 2832 1408 2832 1369 2832 1408 2833 1368 2833 1369 2833 1369 2834 1403 2834 1404 2834 1370 2835 1554 2835 1369 2835 1369 2836 1554 2836 1582 2836 1369 2837 1582 2837 1403 2837 1429 2838 1423 2838 1342 2838 1342 2839 1423 2839 1583 2839 1342 2840 1583 2840 1559 2840 1342 2841 1426 2841 1429 2841 1343 2842 1434 2842 1426 2842 1343 2843 1426 2843 1342 2843 1435 2844 1343 2844 1432 2844 1432 2845 1343 2845 1344 2845 1343 2846 1435 2846 1434 2846 1337 2847 1436 2847 1344 2847 1344 2848 1436 2848 1432 2848 1584 2849 1585 2849 1586 2849 1585 2850 1584 2850 1587 2850 1587 2851 1584 2851 1588 2851 1587 2852 1588 2852 1589 2852 1589 2853 1588 2853 1590 2853 1589 2854 1590 2854 1591 2854 1589 2855 1591 2855 1592 2855 1592 2856 1591 2856 1593 2856 1592 2857 1593 2857 1594 2857 1586 2858 1585 2858 1595 2858 1586 2859 1595 2859 1596 2859 1596 2860 1595 2860 1597 2860 1596 2861 1597 2861 1598 2861 1598 2862 1597 2862 1599 2862 1599 2863 1597 2863 1600 2863 1599 2864 1600 2864 1601 2864 1599 2865 1601 2865 1602 2865 1602 2866 1601 2866 1594 2866 1602 2867 1594 2867 1593 2867 1586 2868 1603 2868 1584 2868 1584 2869 1603 2869 1604 2869 1584 2870 1604 2870 1588 2870 1588 2871 1604 2871 1605 2871 1588 2872 1605 2872 1590 2872 1590 2873 1605 2873 1606 2873 1590 2874 1606 2874 1591 2874 1591 2875 1606 2875 1607 2875 1591 2876 1607 2876 1593 2876 1593 2877 1607 2877 1608 2877 1593 2878 1608 2878 1602 2878 1602 2879 1608 2879 1609 2879 1602 2880 1609 2880 1599 2880 1599 2881 1609 2881 1610 2881 1599 2882 1610 2882 1598 2882 1598 2883 1610 2883 1611 2883 1598 2884 1611 2884 1596 2884 1596 2885 1611 2885 1612 2885 1596 2886 1612 2886 1586 2886 1586 2887 1612 2887 1603 2887 1308 2888 1610 2888 1609 2888 1351 2889 1610 2889 1308 2889 1608 2890 1307 2890 1609 2890 1609 2891 1307 2891 1308 2891 1611 2892 1351 2892 1612 2892 1351 2893 1611 2893 1610 2893 1603 2894 1351 2894 1317 2894 1603 2895 1317 2895 1604 2895 1604 2896 1317 2896 1318 2896 1351 2897 1603 2897 1612 2897 1604 2898 1318 2898 1319 2898 1604 2899 1319 2899 1605 2899 1605 2900 1319 2900 1325 2900 1605 2901 1325 2901 1606 2901 1606 2902 1325 2902 1320 2902 1606 2903 1320 2903 1607 2903 1607 2904 1320 2904 1608 2904 1608 2905 1320 2905 1307 2905 1335 2906 1457 2906 1333 2906 1333 2907 1457 2907 1456 2907 1333 2908 1456 2908 1332 2908 1332 2909 1456 2909 1455 2909 1332 2910 1455 2910 1330 2910 1330 2911 1455 2911 1454 2911 1330 2912 1454 2912 1329 2912 1329 2913 1454 2913 1453 2913 1329 2914 1453 2914 1328 2914 1328 2915 1453 2915 1327 2915 1327 2916 1453 2916 1452 2916 1327 2917 1452 2917 1451 2917 1327 2918 1451 2918 1312 2918 1312 2919 1451 2919 1450 2919 1312 2920 1450 2920 1313 2920 1313 2921 1450 2921 1314 2921 1314 2922 1450 2922 1449 2922 1314 2923 1449 2923 1315 2923 1315 2924 1449 2924 1448 2924 1315 2925 1448 2925 1316 2925 1316 2926 1448 2926 1447 2926 1316 2927 1447 2927 1321 2927 1321 2928 1447 2928 1446 2928 1321 2929 1446 2929 1304 2929 1304 2930 1446 2930 1444 2930 1440 2931 1616 2931 1613 2931 1613 2932 1614 2932 1440 2932 1464 2933 1616 2933 1440 2933 1615 2934 1420 2934 1617 2934 1615 2935 1617 2935 1613 2935 1613 2936 1617 2936 1614 2936 1615 2937 1618 2937 1420 2937 1420 2938 1618 2938 1465 2938 1616 2939 1464 2939 1619 2939 1619 2940 1464 2940 1620 2940 1620 2941 1464 2941 1469 2941 1620 2942 1469 2942 1468 2942 1620 2943 1468 2943 1621 2943 1621 2944 1468 2944 1622 2944 1622 2945 1468 2945 1467 2945 1622 2946 1467 2946 1466 2946 1622 2947 1466 2947 1623 2947 1623 2948 1466 2948 1465 2948 1623 2949 1465 2949 1618 2949 1536 2950 1420 2950 1416 2950 1536 2951 1416 2951 1415 2951 1536 2952 1415 2952 1413 2952 1537 2953 1430 2953 1438 2953 1420 2954 1536 2954 1617 2954 1536 2955 1532 2955 1617 2955 1617 2956 1532 2956 1534 2956 1617 2957 1534 2957 1614 2957 1438 2958 1440 2958 1537 2958 1537 2959 1440 2959 1614 2959 1537 2960 1614 2960 1534 2960 1436 2961 1337 2961 1442 2961 1442 2962 1337 2962 1305 2962 1442 2963 1305 2963 1444 2963 1444 2964 1305 2964 1304 2964 1457 2965 1335 2965 1421 2965 1421 2966 1335 2966 1341 2966 1421 2967 1341 2967 1419 2967 1419 2968 1341 2968 1362 2968 1624 2969 1625 2969 1626 2969 1624 2970 1626 2970 1627 2970 1627 2971 1626 2971 1628 2971 1627 2972 1628 2972 1629 2972 1629 2973 1628 2973 1630 2973 1629 2974 1630 2974 1631 2974 1631 2975 1630 2975 1632 2975 1631 2976 1632 2976 1633 2976 1633 2977 1632 2977 1634 2977 1634 2978 1632 2978 1635 2978 1634 2979 1635 2979 1636 2979 1636 2980 1635 2980 1637 2980 1636 2981 1637 2981 1638 2981 1638 2982 1637 2982 1639 2982 1639 2983 1637 2983 1640 2983 1639 2984 1640 2984 1625 2984 1639 2985 1625 2985 1624 2985 1642 2986 1641 2986 1643 2986 1643 2987 1641 2987 1644 2987 1643 2988 1644 2988 1645 2988 1645 2989 1644 2989 1646 2989 1641 2990 1642 2990 1647 2990 1647 2991 1642 2991 1648 2991 1647 2992 1648 2992 1649 2992 1649 2993 1648 2993 1650 2993 1649 2994 1650 2994 1651 2994 1651 2995 1650 2995 1652 2995 1651 2996 1652 2996 1653 2996 1653 2997 1652 2997 1654 2997 1653 2998 1654 2998 1655 2998 1655 2999 1654 2999 1656 2999 1655 3000 1656 3000 1657 3000 1657 3001 1656 3001 1646 3001 1646 3002 1656 3002 1658 3002 1646 3003 1658 3003 1645 3003 1659 3004 1660 3004 1661 3004 1661 3005 1660 3005 1662 3005 1663 3006 1662 3006 1660 3006 1659 3007 1661 3007 1664 3007 1659 3008 1664 3008 1665 3008 1665 3009 1664 3009 1666 3009 1666 3010 1664 3010 1667 3010 1666 3011 1667 3011 1668 3011 1668 3012 1667 3012 1669 3012 1668 3013 1669 3013 1670 3013 1670 3014 1669 3014 1671 3014 1670 3015 1671 3015 1672 3015 1672 3016 1671 3016 1673 3016 1672 3017 1673 3017 1674 3017 1674 3018 1673 3018 1675 3018 1674 3019 1675 3019 1676 3019 1676 3020 1675 3020 1677 3020 1676 3021 1677 3021 1663 3021 1663 3022 1677 3022 1662 3022 1679 3023 1678 3023 1680 3023 1679 3024 1680 3024 1681 3024 1679 3025 1682 3025 1678 3025 1678 3026 1682 3026 1683 3026 1683 3027 1682 3027 1684 3027 1683 3028 1684 3028 1685 3028 1683 3029 1685 3029 1686 3029 1686 3030 1685 3030 1687 3030 1686 3031 1687 3031 1688 3031 1688 3032 1687 3032 1689 3032 1688 3033 1689 3033 1690 3033 1690 3034 1689 3034 1691 3034 1690 3035 1691 3035 1692 3035 1690 3036 1692 3036 1693 3036 1693 3037 1692 3037 1694 3037 1693 3038 1694 3038 1695 3038 1681 3039 1680 3039 1696 3039 1696 3040 1680 3040 1697 3040 1696 3041 1697 3041 1694 3041 1694 3042 1697 3042 1695 3042 1698 3043 1699 3043 1700 3043 1700 3044 1699 3044 1701 3044 1710 3045 1757 3045 1702 3045 1703 3046 1704 3046 1705 3046 1706 3047 1707 3047 1708 3047 1708 3048 1707 3048 1709 3048 1716 3049 1715 3049 1717 3049 1705 3050 1704 3050 1718 3050 1705 3051 1718 3051 1702 3051 1702 3052 1718 3052 1710 3052 1719 3053 1720 3053 1721 3053 1746 3054 1727 3054 1757 3054 1724 3055 1728 3055 1748 3055 1720 3056 1719 3056 1729 3056 1730 3057 1731 3057 1729 3057 1732 3058 1724 3058 1725 3058 1713 3059 1712 3059 1742 3059 1713 3060 1729 3060 1724 3060 1713 3061 1737 3061 1729 3061 1714 3062 1754 3062 1722 3062 1714 3063 1722 3063 1738 3063 1738 3064 1722 3064 1723 3064 1738 3065 1723 3065 1739 3065 1741 3066 1740 3066 1742 3066 1728 3067 1743 3067 1723 3067 1711 3068 1744 3068 1698 3068 1698 3069 1744 3069 1704 3069 1704 3070 1744 3070 1718 3070 1732 3071 1746 3071 1745 3071 1732 3072 1745 3072 1728 3072 1732 3073 1728 3073 1724 3073 1723 3074 1747 3074 1748 3074 1723 3075 1748 3075 1728 3075 1734 3076 1733 3076 1741 3076 1712 3077 1713 3077 1724 3077 1749 3078 1716 3078 1750 3078 1749 3079 1750 3079 1751 3079 1749 3080 1751 3080 1729 3080 1749 3081 1729 3081 1737 3081 1749 3082 1752 3082 1716 3082 1716 3083 1752 3083 1715 3083 1711 3084 1698 3084 1700 3084 1722 3085 1753 3085 1723 3085 1729 3086 1731 3086 1725 3086 1729 3087 1725 3087 1724 3087 1742 3088 1712 3088 1741 3088 1741 3089 1712 3089 1734 3089 1736 3090 1754 3090 1735 3090 1735 3091 1754 3091 1714 3091 1726 3092 1708 3092 1755 3092 1755 3093 1708 3093 1709 3093 1708 3094 1726 3094 1741 3094 1741 3095 1726 3095 1740 3095 1723 3096 1743 3096 1711 3096 1723 3097 1711 3097 1700 3097 1729 3098 1719 3098 1730 3098 1733 3099 1734 3099 1736 3099 1733 3100 1736 3100 1735 3100 1756 3101 1709 3101 1715 3101 1756 3102 1715 3102 1752 3102 1709 3103 1756 3103 1755 3103 1757 3104 1758 3104 1759 3104 1757 3105 1759 3105 1702 3105 1758 3106 1760 3106 1720 3106 1720 3107 1760 3107 1721 3107 1723 3108 1753 3108 1747 3108 1746 3109 1757 3109 1745 3109 1757 3110 1727 3110 1758 3110 1758 3111 1727 3111 1760 3111 1760 3112 1727 3112 1680 3112 1680 3113 1727 3113 1697 3113 1697 3114 1727 3114 1746 3114 1697 3115 1746 3115 1695 3115 1695 3116 1746 3116 1693 3116 1693 3117 1746 3117 1732 3117 1693 3118 1732 3118 1690 3118 1690 3119 1732 3119 1725 3119 1690 3120 1725 3120 1688 3120 1688 3121 1725 3121 1731 3121 1688 3122 1731 3122 1686 3122 1686 3123 1731 3123 1730 3123 1686 3124 1730 3124 1719 3124 1686 3125 1719 3125 1683 3125 1683 3126 1719 3126 1721 3126 1683 3127 1721 3127 1678 3127 1678 3128 1721 3128 1760 3128 1678 3129 1760 3129 1680 3129 1677 3130 1713 3130 1742 3130 1677 3131 1742 3131 1662 3131 1662 3132 1742 3132 1740 3132 1662 3133 1740 3133 1661 3133 1661 3134 1740 3134 1726 3134 1661 3135 1726 3135 1664 3135 1664 3136 1726 3136 1755 3136 1664 3137 1755 3137 1667 3137 1667 3138 1755 3138 1756 3138 1667 3139 1756 3139 1752 3139 1667 3140 1752 3140 1669 3140 1669 3141 1752 3141 1749 3141 1669 3142 1749 3142 1671 3142 1671 3143 1749 3143 1673 3143 1673 3144 1749 3144 1737 3144 1673 3145 1737 3145 1675 3145 1675 3146 1737 3146 1713 3146 1675 3147 1713 3147 1677 3147 1658 3148 1744 3148 1645 3148 1645 3149 1744 3149 1711 3149 1645 3150 1711 3150 1643 3150 1643 3151 1711 3151 1743 3151 1643 3152 1743 3152 1642 3152 1642 3153 1743 3153 1728 3153 1642 3154 1728 3154 1648 3154 1648 3155 1728 3155 1745 3155 1648 3156 1745 3156 1650 3156 1650 3157 1745 3157 1757 3157 1650 3158 1757 3158 1652 3158 1652 3159 1757 3159 1710 3159 1652 3160 1710 3160 1654 3160 1654 3161 1710 3161 1718 3161 1654 3162 1718 3162 1656 3162 1656 3163 1718 3163 1744 3163 1656 3164 1744 3164 1658 3164 1637 3165 1753 3165 1640 3165 1640 3166 1753 3166 1722 3166 1640 3167 1722 3167 1625 3167 1625 3168 1722 3168 1626 3168 1626 3169 1722 3169 1754 3169 1626 3170 1754 3170 1628 3170 1628 3171 1754 3171 1736 3171 1628 3172 1736 3172 1734 3172 1628 3173 1734 3173 1630 3173 1630 3174 1734 3174 1632 3174 1632 3175 1734 3175 1712 3175 1632 3176 1712 3176 1724 3176 1632 3177 1724 3177 1635 3177 1635 3178 1724 3178 1748 3178 1635 3179 1748 3179 1637 3179 1637 3180 1748 3180 1747 3180 1637 3181 1747 3181 1753 3181 1509 3182 1569 3182 1502 3182 1502 3183 1569 3183 1568 3183 1482 3184 1575 3184 1483 3184 1483 3185 1575 3185 1572 3185 1506 3186 1491 3186 1761 3186 1761 3187 1491 3187 1574 3187 1571 3188 1506 3188 1762 3188 1762 3189 1506 3189 1761 3189 1762 3190 1761 3190 917 3190 917 3191 1761 3191 93 3191 917 3192 93 3192 92 3192 1779 3193 1763 3193 1764 3193 1764 3194 1763 3194 1765 3194 1764 3195 1765 3195 1766 3195 1766 3196 1765 3196 1767 3196 1766 3197 1767 3197 1768 3197 1768 3198 1767 3198 1769 3198 1768 3199 1769 3199 1770 3199 1770 3200 1769 3200 1771 3200 1771 3201 1769 3201 1772 3201 1771 3202 1772 3202 1773 3202 1773 3203 1772 3203 1774 3203 1773 3204 1774 3204 1775 3204 1775 3205 1774 3205 1776 3205 1775 3206 1776 3206 1777 3206 1777 3207 1776 3207 1778 3207 1777 3208 1778 3208 1779 3208 1779 3209 1778 3209 1780 3209 1779 3210 1780 3210 1763 3210 1764 3211 1781 3211 1779 3211 1779 3212 1781 3212 1782 3212 1779 3213 1782 3213 1777 3213 1777 3214 1782 3214 1783 3214 1777 3215 1783 3215 1775 3215 1775 3216 1783 3216 1784 3216 1775 3217 1784 3217 1773 3217 1773 3218 1784 3218 1785 3218 1773 3219 1785 3219 1771 3219 1771 3220 1785 3220 1770 3220 1770 3221 1785 3221 1786 3221 1770 3222 1786 3222 1768 3222 1768 3223 1786 3223 1787 3223 1768 3224 1787 3224 1766 3224 1766 3225 1787 3225 1788 3225 1766 3226 1788 3226 1764 3226 1764 3227 1788 3227 1781 3227 1807 3228 1789 3228 1790 3228 1790 3229 1789 3229 1791 3229 1790 3230 1791 3230 1792 3230 1792 3231 1791 3231 1793 3231 1792 3232 1793 3232 1794 3232 1794 3233 1793 3233 1795 3233 1794 3234 1795 3234 1796 3234 1796 3235 1795 3235 1797 3235 1796 3236 1797 3236 1798 3236 1798 3237 1797 3237 1799 3237 1798 3238 1799 3238 1800 3238 1798 3239 1800 3239 1801 3239 1801 3240 1800 3240 1802 3240 1801 3241 1802 3241 1803 3241 1801 3242 1803 3242 1804 3242 1804 3243 1803 3243 1805 3243 1805 3244 1803 3244 1806 3244 1805 3245 1806 3245 1807 3245 1807 3246 1806 3246 1789 3246 1790 3247 1792 3247 1808 3247 1808 3248 1792 3248 1809 3248 1809 3249 1792 3249 1794 3249 1809 3250 1794 3250 1810 3250 1810 3251 1794 3251 1796 3251 1810 3252 1796 3252 1811 3252 1790 3253 1808 3253 1812 3253 1790 3254 1812 3254 1807 3254 1811 3255 1796 3255 1798 3255 1811 3256 1798 3256 1813 3256 1813 3257 1798 3257 1801 3257 1813 3258 1801 3258 1814 3258 1814 3259 1801 3259 1804 3259 1814 3260 1804 3260 1805 3260 1814 3261 1805 3261 1815 3261 1815 3262 1805 3262 1807 3262 1815 3263 1807 3263 1816 3263 1807 3264 1812 3264 1816 3264 1577 3265 1817 3265 1576 3265 845 3266 844 3266 1817 3266 1817 3267 844 3267 817 3267 956 3268 1572 3268 817 3268 817 3269 1572 3269 1817 3269 1817 3270 1572 3270 1575 3270 957 3271 1761 3271 956 3271 956 3272 1761 3272 1574 3272 1573 3273 956 3273 1574 3273 1573 3274 1572 3274 956 3274 1575 3275 1576 3275 1817 3275 1819 3276 1818 3276 1820 3276 1820 3277 1818 3277 1821 3277 1820 3278 1821 3278 1822 3278 1822 3279 1821 3279 1823 3279 1822 3280 1823 3280 1824 3280 1824 3281 1823 3281 1825 3281 1824 3282 1825 3282 1826 3282 1826 3283 1825 3283 1827 3283 1826 3284 1827 3284 1828 3284 1828 3285 1827 3285 1829 3285 1828 3286 1829 3286 1830 3286 1830 3287 1829 3287 1831 3287 1830 3288 1831 3288 1832 3288 1832 3289 1831 3289 1833 3289 1832 3290 1833 3290 1834 3290 1834 3291 1833 3291 1835 3291 1818 3292 1819 3292 1834 3292 1818 3293 1834 3293 1835 3293 1835 3294 1836 3294 1818 3294 1818 3295 1836 3295 1837 3295 1818 3296 1837 3296 1838 3296 1818 3297 1838 3297 1821 3297 1821 3298 1838 3298 1839 3298 1821 3299 1839 3299 1823 3299 1823 3300 1839 3300 1840 3300 1823 3301 1840 3301 1825 3301 1825 3302 1840 3302 1841 3302 1825 3303 1841 3303 1827 3303 1827 3304 1841 3304 1842 3304 1827 3305 1842 3305 1829 3305 1829 3306 1842 3306 1843 3306 1829 3307 1843 3307 1831 3307 1831 3308 1843 3308 1833 3308 1833 3309 1843 3309 1844 3309 1833 3310 1844 3310 1835 3310 1835 3311 1844 3311 1836 3311 1568 3312 1569 3312 1283 3312 840 3313 842 3313 841 3313 1762 3314 959 3314 1571 3314 1571 3315 959 3315 960 3315 1283 3316 1564 3316 1566 3316 1570 3317 960 3317 1569 3317 960 3318 1570 3318 1571 3318 841 3319 1283 3319 840 3319 840 3320 1283 3320 1569 3320 840 3321 1569 3321 960 3321 1283 3322 1566 3322 1567 3322 1283 3323 1567 3323 1568 3323 41 3324 1845 3324 1846 3324 41 3325 1846 3325 958 3325 958 3326 1846 3326 1847 3326 1834 3327 1848 3327 1849 3327 1834 3328 1849 3328 1832 3328 1832 3329 1849 3329 1850 3329 1832 3330 1850 3330 1851 3330 1832 3331 1851 3331 1830 3331 1830 3332 1851 3332 1852 3332 1830 3333 1852 3333 1828 3333 1828 3334 1852 3334 1853 3334 1828 3335 1853 3335 1826 3335 1826 3336 1853 3336 1854 3336 1826 3337 1854 3337 1824 3337 1824 3338 1854 3338 1822 3338 1822 3339 1854 3339 1855 3339 1822 3340 1855 3340 1856 3340 1822 3341 1856 3341 1820 3341 1820 3342 1856 3342 1857 3342 1820 3343 1857 3343 1819 3343 1819 3344 1857 3344 1848 3344 1819 3345 1848 3345 1834 3345 1812 3346 1858 3346 1816 3346 1816 3347 1858 3347 1859 3347 1816 3348 1859 3348 1815 3348 1815 3349 1859 3349 1860 3349 1815 3350 1860 3350 1814 3350 1814 3351 1860 3351 1861 3351 1814 3352 1861 3352 1813 3352 1813 3353 1861 3353 1862 3353 1813 3354 1862 3354 1811 3354 1811 3355 1862 3355 1863 3355 1811 3356 1863 3356 1810 3356 1810 3357 1863 3357 1864 3357 1810 3358 1864 3358 1809 3358 1809 3359 1864 3359 1865 3359 1809 3360 1865 3360 1866 3360 1809 3361 1866 3361 1808 3361 1808 3362 1866 3362 1812 3362 1812 3363 1866 3363 1858 3363 1772 3364 1769 3364 1487 3364 1772 3365 1487 3365 1508 3365 1508 3366 1842 3366 1841 3366 1487 3367 1797 3367 1795 3367 1487 3368 1795 3368 1485 3368 1793 3369 1485 3369 1795 3369 1774 3370 1772 3370 1508 3370 1800 3371 1799 3371 1769 3371 1769 3372 1799 3372 1487 3372 1487 3373 1799 3373 1797 3373 1842 3374 1508 3374 1510 3374 1842 3375 1510 3375 1843 3375 1485 3376 1793 3376 1472 3376 1472 3377 1793 3377 1791 3377 1800 3378 1769 3378 1767 3378 1774 3379 1840 3379 1839 3379 1765 3380 1763 3380 1806 3380 1508 3381 1841 3381 1774 3381 1774 3382 1841 3382 1840 3382 1838 3383 1837 3383 1470 3383 1470 3384 1837 3384 1497 3384 1497 3385 1837 3385 1836 3385 1497 3386 1836 3386 1844 3386 1497 3387 1844 3387 1496 3387 1765 3388 1803 3388 1767 3388 1767 3389 1803 3389 1802 3389 1767 3390 1802 3390 1800 3390 1778 3391 1776 3391 1839 3391 1839 3392 1776 3392 1774 3392 1470 3393 1789 3393 1806 3393 1780 3394 1470 3394 1763 3394 1763 3395 1470 3395 1806 3395 1495 3396 1844 3396 1843 3396 1495 3397 1843 3397 1510 3397 1844 3398 1495 3398 1496 3398 1472 3399 1791 3399 1789 3399 1472 3400 1789 3400 1471 3400 1470 3401 1471 3401 1789 3401 1470 3402 1780 3402 1778 3402 1470 3403 1778 3403 1838 3403 1838 3404 1778 3404 1839 3404 1803 3405 1765 3405 1806 3405 1357 3406 1560 3406 1366 3406 1366 3407 1560 3407 1558 3407 1400 3408 1553 3408 1390 3408 1390 3409 1553 3409 1555 3409 1867 3410 1551 3410 1393 3410 1382 3411 1556 3411 1868 3411 69 3412 75 3412 782 3412 782 3413 75 3413 1867 3413 782 3414 1867 3414 1868 3414 1868 3415 1867 3415 1393 3415 1868 3416 1393 3416 1382 3416 1888 3417 1869 3417 1870 3417 1870 3418 1869 3418 1871 3418 1870 3419 1871 3419 1872 3419 1872 3420 1871 3420 1873 3420 1872 3421 1873 3421 1874 3421 1874 3422 1873 3422 1875 3422 1874 3423 1875 3423 1876 3423 1876 3424 1875 3424 1877 3424 1876 3425 1877 3425 1878 3425 1878 3426 1877 3426 1879 3426 1878 3427 1879 3427 1880 3427 1880 3428 1879 3428 1881 3428 1880 3429 1881 3429 1882 3429 1880 3430 1882 3430 1883 3430 1883 3431 1882 3431 1884 3431 1883 3432 1884 3432 1885 3432 1885 3433 1884 3433 1886 3433 1886 3434 1884 3434 1887 3434 1886 3435 1887 3435 1888 3435 1888 3436 1887 3436 1889 3436 1888 3437 1889 3437 1869 3437 1870 3438 1890 3438 1888 3438 1888 3439 1890 3439 1891 3439 1888 3440 1891 3440 1886 3440 1886 3441 1891 3441 1892 3441 1886 3442 1892 3442 1885 3442 1885 3443 1892 3443 1883 3443 1883 3444 1892 3444 1893 3444 1883 3445 1893 3445 1880 3445 1880 3446 1893 3446 1894 3446 1880 3447 1894 3447 1878 3447 1878 3448 1894 3448 1895 3448 1878 3449 1895 3449 1876 3449 1876 3450 1895 3450 1896 3450 1876 3451 1896 3451 1874 3451 1874 3452 1896 3452 1897 3452 1874 3453 1897 3453 1872 3453 1872 3454 1897 3454 1898 3454 1872 3455 1898 3455 1870 3455 1870 3456 1898 3456 1890 3456 1918 3457 1899 3457 1900 3457 1900 3458 1899 3458 1901 3458 1900 3459 1901 3459 1902 3459 1902 3460 1901 3460 1903 3460 1902 3461 1903 3461 1904 3461 1904 3462 1903 3462 1905 3462 1904 3463 1905 3463 1906 3463 1906 3464 1905 3464 1907 3464 1906 3465 1907 3465 1908 3465 1908 3466 1907 3466 1909 3466 1909 3467 1907 3467 1910 3467 1909 3468 1910 3468 1911 3468 1909 3469 1911 3469 1912 3469 1912 3470 1911 3470 1913 3470 1912 3471 1913 3471 1914 3471 1914 3472 1913 3472 1915 3472 1914 3473 1915 3473 1916 3473 1916 3474 1915 3474 1917 3474 1916 3475 1917 3475 1918 3475 1918 3476 1917 3476 1899 3476 1916 3477 1919 3477 1914 3477 1900 3478 1921 3478 1918 3478 1918 3479 1921 3479 1920 3479 1918 3480 1920 3480 1916 3480 1916 3481 1920 3481 1919 3481 1914 3482 1919 3482 1922 3482 1914 3483 1922 3483 1912 3483 1921 3484 1900 3484 1923 3484 1923 3485 1900 3485 1902 3485 1923 3486 1902 3486 1924 3486 1924 3487 1902 3487 1904 3487 1924 3488 1904 3488 1925 3488 1904 3489 1906 3489 1925 3489 1925 3490 1906 3490 1926 3490 1926 3491 1906 3491 1908 3491 1926 3492 1908 3492 1909 3492 1926 3493 1909 3493 1927 3493 1927 3494 1909 3494 1912 3494 1927 3495 1912 3495 1922 3495 1555 3496 1553 3496 1928 3496 752 3497 754 3497 753 3497 1867 3498 953 3498 1551 3498 1551 3499 953 3499 954 3499 1582 3500 1554 3500 1928 3500 753 3501 1928 3501 752 3501 752 3502 1928 3502 1553 3502 752 3503 1553 3503 954 3503 1553 3504 1552 3504 954 3504 954 3505 1552 3505 1551 3505 1928 3506 1554 3506 1555 3506 1929 3507 1947 3507 1932 3507 1930 3508 1931 3508 1932 3508 1938 3509 1933 3509 1937 3509 1937 3510 1933 3510 1934 3510 1934 3511 1933 3511 1935 3511 1932 3512 1931 3512 1929 3512 1932 3513 1936 3513 1930 3513 1930 3514 1936 3514 1937 3514 1937 3515 1936 3515 1938 3515 1935 3516 1933 3516 1939 3516 1935 3517 1939 3517 1940 3517 1940 3518 1939 3518 1941 3518 1940 3519 1941 3519 1942 3519 1942 3520 1941 3520 1943 3520 1942 3521 1943 3521 1944 3521 1942 3522 1944 3522 1945 3522 1945 3523 1944 3523 1946 3523 1946 3524 1944 3524 1947 3524 1946 3525 1947 3525 1929 3525 1929 3526 1948 3526 1946 3526 1946 3527 1948 3527 1945 3527 1945 3528 1948 3528 1949 3528 1945 3529 1949 3529 1942 3529 1942 3530 1949 3530 1950 3530 1942 3531 1950 3531 1940 3531 1940 3532 1950 3532 1951 3532 1940 3533 1951 3533 1935 3533 1935 3534 1951 3534 1952 3534 1935 3535 1952 3535 1934 3535 1934 3536 1952 3536 1953 3536 1934 3537 1953 3537 1937 3537 1937 3538 1953 3538 1954 3538 1937 3539 1954 3539 1930 3539 1930 3540 1954 3540 1955 3540 1930 3541 1955 3541 1931 3541 1931 3542 1955 3542 1929 3542 1929 3543 1955 3543 1956 3543 1929 3544 1956 3544 1948 3544 757 3545 756 3545 1957 3545 1957 3546 756 3546 755 3546 951 3547 1868 3547 950 3547 950 3548 1868 3548 1556 3548 950 3549 1558 3549 755 3549 755 3550 1558 3550 1560 3550 755 3551 1560 3551 1957 3551 950 3552 1556 3552 1557 3552 1560 3553 1559 3553 1957 3553 950 3554 1557 3554 1558 3554 1957 3555 1559 3555 1583 3555 1545 3556 1958 3556 13 3556 952 3557 1547 3557 13 3557 13 3558 1547 3558 1545 3558 1947 3559 1967 3559 1959 3559 1947 3560 1959 3560 1932 3560 1932 3561 1959 3561 1960 3561 1932 3562 1960 3562 1936 3562 1936 3563 1960 3563 1961 3563 1936 3564 1961 3564 1938 3564 1938 3565 1961 3565 1962 3565 1938 3566 1962 3566 1933 3566 1933 3567 1962 3567 1963 3567 1933 3568 1963 3568 1939 3568 1939 3569 1963 3569 1964 3569 1939 3570 1964 3570 1941 3570 1941 3571 1964 3571 1965 3571 1941 3572 1965 3572 1943 3572 1943 3573 1965 3573 1966 3573 1943 3574 1966 3574 1944 3574 1944 3575 1966 3575 1967 3575 1944 3576 1967 3576 1947 3576 1921 3577 1968 3577 1969 3577 1921 3578 1969 3578 1920 3578 1920 3579 1969 3579 1970 3579 1920 3580 1970 3580 1919 3580 1919 3581 1970 3581 1971 3581 1919 3582 1971 3582 1922 3582 1922 3583 1971 3583 1972 3583 1922 3584 1972 3584 1927 3584 1927 3585 1972 3585 1973 3585 1927 3586 1973 3586 1926 3586 1926 3587 1973 3587 1974 3587 1926 3588 1974 3588 1925 3588 1925 3589 1974 3589 1975 3589 1925 3590 1975 3590 1924 3590 1924 3591 1975 3591 1976 3591 1924 3592 1976 3592 1923 3592 1923 3593 1976 3593 1968 3593 1923 3594 1968 3594 1921 3594 1911 3595 1910 3595 1391 3595 1882 3596 1907 3596 1905 3596 1911 3597 1391 3597 1913 3597 1391 3598 1910 3598 1907 3598 1391 3599 1907 3599 1377 3599 1899 3600 1373 3600 1375 3600 1385 3601 1917 3601 1384 3601 1385 3602 1373 3602 1917 3602 1917 3603 1373 3603 1899 3603 1915 3604 1394 3604 1384 3604 1915 3605 1913 3605 1394 3605 1394 3606 1913 3606 1391 3606 1882 3607 1905 3607 1884 3607 1884 3608 1905 3608 1903 3608 1889 3609 1901 3609 1353 3609 1353 3610 1901 3610 1899 3610 1901 3611 1889 3611 1887 3611 1907 3612 1882 3612 1881 3612 1915 3613 1384 3613 1917 3613 1884 3614 1903 3614 1887 3614 1887 3615 1903 3615 1901 3615 1948 3616 1350 3616 1949 3616 1949 3617 1350 3617 1355 3617 1339 3618 1347 3618 1948 3618 1948 3619 1347 3619 1350 3619 1956 3620 1339 3620 1948 3620 1353 3621 1956 3621 1955 3621 1364 3622 1950 3622 1949 3622 1364 3623 1949 3623 1355 3623 1955 3624 1871 3624 1869 3624 1955 3625 1869 3625 1353 3625 1353 3626 1869 3626 1889 3626 1950 3627 1364 3627 1951 3627 1311 3628 1339 3628 1353 3628 1353 3629 1339 3629 1956 3629 1377 3630 1879 3630 1877 3630 1873 3631 1871 3631 1955 3631 1951 3632 1364 3632 1376 3632 1873 3633 1955 3633 1954 3633 1907 3634 1881 3634 1377 3634 1377 3635 1881 3635 1879 3635 1377 3636 1951 3636 1376 3636 1377 3637 1877 3637 1875 3637 1377 3638 1952 3638 1951 3638 1873 3639 1954 3639 1875 3639 1875 3640 1954 3640 1953 3640 1875 3641 1953 3641 1377 3641 1377 3642 1953 3642 1952 3642 88 3643 1817 3643 89 3643 89 3644 1817 3644 1577 3644 89 3645 1577 3645 818 3645 52 3646 818 3646 1577 3646 1564 3647 1283 3647 95 3647 95 3648 94 3648 1564 3648 1564 3649 94 3649 946 3649 1564 3650 946 3650 58 3650 1977 3651 1759 3651 1758 3651 1977 3652 1758 3652 1978 3652 1978 3653 1758 3653 1720 3653 1978 3654 1720 3654 1979 3654 1979 3655 1720 3655 1729 3655 1979 3656 1729 3656 1980 3656 1980 3657 1729 3657 1751 3657 1980 3658 1751 3658 1981 3658 1982 3659 1717 3659 1581 3659 1715 3660 1581 3660 1717 3660 1715 3661 1578 3661 1581 3661 1709 3662 1578 3662 1715 3662 1709 3663 1579 3663 1578 3663 1707 3664 1579 3664 1709 3664 1579 3665 1707 3665 1580 3665 1580 3666 1707 3666 1706 3666 1983 3667 1733 3667 1984 3667 1984 3668 1733 3668 1735 3668 1984 3669 1735 3669 1985 3669 1985 3670 1735 3670 1714 3670 1985 3671 1714 3671 1986 3671 1986 3672 1714 3672 1738 3672 1986 3673 1738 3673 1987 3673 1987 3674 1738 3674 1739 3674 1987 3675 1739 3675 1988 3675 1701 3676 1699 3676 1989 3676 1989 3677 1699 3677 1565 3677 1699 3678 1562 3678 1565 3678 1562 3679 1699 3679 1698 3679 1704 3680 1563 3680 1698 3680 1698 3681 1563 3681 1562 3681 1704 3682 1561 3682 1563 3682 1561 3683 1704 3683 1703 3683 1561 3684 1703 3684 1990 3684 1561 3685 1990 3685 1991 3685 1847 3686 1980 3686 1981 3686 1978 3687 1979 3687 1479 3687 1992 3688 1977 3688 1978 3688 1992 3689 1978 3689 1479 3689 1992 3690 1479 3690 1991 3690 1991 3691 1479 3691 1486 3691 1991 3692 1486 3692 1561 3692 1982 3693 1581 3693 1846 3693 1846 3694 1581 3694 1479 3694 1846 3695 1479 3695 1847 3695 1847 3696 1479 3696 1979 3696 1847 3697 1979 3697 1980 3697 1585 3698 1623 3698 1618 3698 1585 3699 1618 3699 1595 3699 1595 3700 1618 3700 1615 3700 1595 3701 1615 3701 1597 3701 1597 3702 1615 3702 1613 3702 1597 3703 1613 3703 1600 3703 1600 3704 1613 3704 1616 3704 1600 3705 1616 3705 1601 3705 1601 3706 1616 3706 1594 3706 1594 3707 1616 3707 1619 3707 1594 3708 1619 3708 1592 3708 1592 3709 1619 3709 1620 3709 1592 3710 1620 3710 1589 3710 1589 3711 1620 3711 1621 3711 1589 3712 1621 3712 1587 3712 1587 3713 1621 3713 1622 3713 1587 3714 1622 3714 1585 3714 1585 3715 1622 3715 1623 3715 1984 3716 1546 3716 1983 3716 1985 3717 1546 3717 1984 3717 1985 3718 1544 3718 1546 3718 1986 3719 1527 3719 1985 3719 1985 3720 1527 3720 1544 3720 1526 3721 1987 3721 1988 3721 1987 3722 1526 3722 1986 3722 1986 3723 1526 3723 1527 3723 1565 3724 1521 3724 1989 3724 1641 3725 1294 3725 1297 3725 1641 3726 1297 3726 1644 3726 1644 3727 1297 3727 1295 3727 1644 3728 1295 3728 1646 3728 1646 3729 1295 3729 1300 3729 1646 3730 1300 3730 1657 3730 1657 3731 1300 3731 1299 3731 1657 3732 1299 3732 1655 3732 1655 3733 1299 3733 1296 3733 1655 3734 1296 3734 1653 3734 1653 3735 1296 3735 1293 3735 1653 3736 1293 3736 1651 3736 1651 3737 1293 3737 1303 3737 1651 3738 1303 3738 1302 3738 1651 3739 1302 3739 1649 3739 1649 3740 1302 3740 1301 3740 1649 3741 1301 3741 1647 3741 1647 3742 1301 3742 1298 3742 1647 3743 1298 3743 1641 3743 1641 3744 1298 3744 1294 3744 1659 3745 1284 3745 1660 3745 1660 3746 1284 3746 1289 3746 1660 3747 1289 3747 1663 3747 1663 3748 1289 3748 1287 3748 1663 3749 1287 3749 1676 3749 1676 3750 1287 3750 1288 3750 1676 3751 1288 3751 1674 3751 1674 3752 1288 3752 1292 3752 1674 3753 1292 3753 1672 3753 1672 3754 1292 3754 1285 3754 1672 3755 1285 3755 1670 3755 1670 3756 1285 3756 1291 3756 1670 3757 1291 3757 1668 3757 1668 3758 1291 3758 1290 3758 1668 3759 1290 3759 1666 3759 1666 3760 1290 3760 1286 3760 1666 3761 1286 3761 1665 3761 1665 3762 1286 3762 1659 3762 1659 3763 1286 3763 1284 3763 1278 3764 1280 3764 1993 3764 1278 3765 1993 3765 1994 3765 1994 3766 1993 3766 1995 3766 1994 3767 1995 3767 1996 3767 1996 3768 1995 3768 1997 3768 1997 3769 1995 3769 1998 3769 1997 3770 1998 3770 1999 3770 1999 3771 1998 3771 2000 3771 1999 3772 2000 3772 2001 3772 1999 3773 2001 3773 2002 3773 2002 3774 2001 3774 1281 3774 2002 3775 1281 3775 1279 3775 2006 3776 2004 3776 2005 3776 2006 3777 2005 3777 2007 3777 2007 3778 2005 3778 2008 3778 2007 3779 2008 3779 2009 3779 2003 3780 2009 3780 2008 3780 1276 3781 1275 3781 2003 3781 1275 3782 2009 3782 2003 3782 1271 3783 1273 3783 2010 3783 2010 3784 1273 3784 2011 3784 2010 3785 2011 3785 2012 3785 2010 3786 2012 3786 2013 3786 2013 3787 2012 3787 2014 3787 2013 3788 2014 3788 2015 3788 2015 3789 2014 3789 2016 3789 2015 3790 2016 3790 2017 3790 2017 3791 2016 3791 2018 3791 2017 3792 2018 3792 2019 3792 2019 3793 2018 3793 1274 3793 2019 3794 1274 3794 1272 3794 1267 3795 1269 3795 2020 3795 2020 3796 1269 3796 2021 3796 2020 3797 2021 3797 2022 3797 2022 3798 2021 3798 2023 3798 2022 3799 2023 3799 2024 3799 2024 3800 2023 3800 2025 3800 2024 3801 2025 3801 2026 3801 2026 3802 2025 3802 2027 3802 2027 3803 2025 3803 2028 3803 2027 3804 2028 3804 1270 3804 2027 3805 1270 3805 1268 3805 1266 3806 1265 3806 2030 3806 2030 3807 1265 3807 2031 3807 2032 3808 2033 3808 2031 3808 2031 3809 2033 3809 2030 3809 2035 3810 2033 3810 2032 3810 2034 3811 2035 3811 2032 3811 2034 3812 2029 3812 2035 3812 1260 3813 1262 3813 2036 3813 2036 3814 1262 3814 2037 3814 2036 3815 2037 3815 2038 3815 2038 3816 2037 3816 2039 3816 2038 3817 2039 3817 2040 3817 2040 3818 2039 3818 2041 3818 2040 3819 2041 3819 2042 3819 2042 3820 2041 3820 2043 3820 2042 3821 2043 3821 2044 3821 2044 3822 2043 3822 2045 3822 2044 3823 2045 3823 1261 3823 1261 3824 2045 3824 1263 3824 1259 3825 1258 3825 2048 3825 2048 3826 1258 3826 2047 3826 2050 3827 2048 3827 2049 3827 2049 3828 2048 3828 2047 3828 2051 3829 2050 3829 2049 3829 2051 3830 2046 3830 2050 3830 2055 3831 2053 3831 2054 3831 2055 3832 2054 3832 2056 3832 2056 3833 2054 3833 2057 3833 1255 3834 2052 3834 2057 3834 2057 3835 2052 3835 2056 3835 1255 3836 1254 3836 2052 3836 1257 3837 1259 3837 2050 3837 1257 3838 2050 3838 2046 3838 2050 3839 1259 3839 2048 3839 1254 3840 2056 3840 2052 3840 1256 3841 2053 3841 2055 3841 2055 3842 2056 3842 1254 3842 2055 3843 1254 3843 1256 3843 1275 3844 2006 3844 2009 3844 2006 3845 2007 3845 2009 3845 2004 3846 2006 3846 1277 3846 1277 3847 2006 3847 1275 3847 1264 3848 1266 3848 2035 3848 2035 3849 2029 3849 1264 3849 1266 3850 2030 3850 2033 3850 1266 3851 2033 3851 2035 3851 11 3852 13 3852 1958 3852 31 3853 30 3853 1958 3853 1958 3854 30 3854 55 3854 1958 3855 55 3855 11 3855 11 3856 55 3856 1928 3856 11 3857 1928 3857 753 3857 25 3858 24 3858 88 3858 88 3859 24 3859 1845 3859 1845 3860 41 3860 88 3860 88 3861 41 3861 42 3861 88 3862 42 3862 1817 3862 1817 3863 42 3863 845 3863 49 3864 47 3864 59 3864 59 3865 47 3865 2058 3865 2058 3866 19 3866 59 3866 59 3867 19 3867 20 3867 59 3868 20 3868 1957 3868 1957 3869 20 3869 757 3869 93 3870 1761 3870 107 3870 107 3871 1761 3871 957 3871 919 3872 106 3872 959 3872 919 3873 959 3873 917 3873 917 3874 959 3874 1762 3874 819 3875 1403 3875 1582 3875 819 3876 1582 3876 72 3876 72 3877 1582 3877 1928 3877 72 3878 1928 3878 55 3878 819 3879 1550 3879 1402 3879 819 3880 1402 3880 1403 3880 832 3881 831 3881 1260 3881 831 3882 830 3882 1260 3882 1260 3883 830 3883 1261 3883 1260 3884 833 3884 832 3884 1260 3885 834 3885 833 3885 1261 3886 830 3886 839 3886 1261 3887 839 3887 2044 3887 2044 3888 839 3888 2042 3888 2042 3889 839 3889 838 3889 2042 3890 838 3890 2040 3890 2040 3891 838 3891 837 3891 2040 3892 837 3892 836 3892 2040 3893 836 3893 2038 3893 2038 3894 836 3894 835 3894 2038 3895 835 3895 2036 3895 2036 3896 835 3896 834 3896 2036 3897 834 3897 1260 3897 1271 3898 822 3898 821 3898 1271 3899 821 3899 1272 3899 1272 3900 821 3900 820 3900 1272 3901 820 3901 2019 3901 1271 3902 823 3902 822 3902 1271 3903 824 3903 823 3903 2019 3904 820 3904 2017 3904 2017 3905 820 3905 829 3905 2017 3906 829 3906 2015 3906 2015 3907 829 3907 828 3907 2015 3908 828 3908 827 3908 2015 3909 827 3909 2013 3909 2013 3910 827 3910 826 3910 2013 3911 826 3911 2010 3911 2010 3912 826 3912 825 3912 2010 3913 825 3913 1271 3913 1271 3914 825 3914 824 3914 59 3915 1957 3915 66 3915 66 3916 1957 3916 1583 3916 66 3917 1583 3917 947 3917 1519 3918 57 3918 947 3918 947 3919 1583 3919 1423 3919 947 3920 1423 3920 1519 3920 1270 3921 877 3921 1269 3921 1270 3922 878 3922 877 3922 1270 3923 881 3923 878 3923 1269 3924 877 3924 875 3924 1269 3925 875 3925 2021 3925 2021 3926 875 3926 893 3926 2021 3927 893 3927 890 3927 2021 3928 890 3928 2023 3928 2023 3929 890 3929 889 3929 2023 3930 889 3930 2025 3930 2025 3931 889 3931 887 3931 2025 3932 887 3932 885 3932 2025 3933 885 3933 2028 3933 2028 3934 885 3934 1270 3934 1270 3935 885 3935 883 3935 1270 3936 883 3936 881 3936 860 3937 1280 3937 862 3937 860 3938 858 3938 1280 3938 858 3939 857 3939 1280 3939 1280 3940 857 3940 855 3940 1280 3941 855 3941 1993 3941 1993 3942 855 3942 872 3942 1993 3943 872 3943 1995 3943 1995 3944 872 3944 870 3944 1995 3945 870 3945 1998 3945 1998 3946 870 3946 868 3946 1998 3947 868 3947 2000 3947 2000 3948 868 3948 866 3948 2000 3949 866 3949 2001 3949 2001 3950 866 3950 865 3950 2001 3951 865 3951 1281 3951 1281 3952 865 3952 862 3952 1281 3953 862 3953 1280 3953 1867 3954 75 3954 953 3954 953 3955 75 3955 74 3955 782 3956 1868 3956 780 3956 780 3957 1868 3957 951 3957 780 3958 951 3958 65 3958 1849 3959 1848 3959 2059 3959 2059 3960 1848 3960 1857 3960 2059 3961 1857 3961 2060 3961 2060 3962 1857 3962 1856 3962 2060 3963 1856 3963 2061 3963 2061 3964 1856 3964 1855 3964 2061 3965 1855 3965 2062 3965 2062 3966 1855 3966 1854 3966 2062 3967 1854 3967 2063 3967 2063 3968 1854 3968 1853 3968 2063 3969 1853 3969 2064 3969 2064 3970 1853 3970 1852 3970 2064 3971 1852 3971 2065 3971 2065 3972 1852 3972 1851 3972 2065 3973 1851 3973 2066 3973 2066 3974 1851 3974 1850 3974 2066 3975 1850 3975 2067 3975 2067 3976 1850 3976 1849 3976 2067 3977 1849 3977 2068 3977 2068 3978 1849 3978 2059 3978 1981 3979 1751 3979 1750 3979 2047 3980 1258 3980 958 3980 1750 3981 1 3981 2046 3981 2046 3982 1 3982 2 3982 958 3983 1258 3983 38 3983 38 3984 1258 3984 1257 3984 2 3985 38 3985 2046 3985 2046 3986 38 3986 1257 3986 1750 3987 2046 3987 1981 3987 1981 3988 2046 3988 2051 3988 1981 3989 2051 3989 1847 3989 2051 3990 2049 3990 1847 3990 1847 3991 2049 3991 2047 3991 1847 3992 2047 3992 958 3992 2004 3993 1702 3993 1977 3993 1977 3994 1702 3994 1759 3994 9 3995 1702 3995 7 3995 7 3996 1702 3996 2004 3996 843 3997 1277 3997 56 3997 56 3998 1277 3998 1276 3998 56 3999 1276 3999 2003 3999 1277 4000 843 4000 2004 4000 2004 4001 843 4001 7 4001 1992 4002 2008 4002 2005 4002 1992 4003 2005 4003 1977 4003 1977 4004 2005 4004 2004 4004 56 4005 2003 4005 1992 4005 1992 4006 2003 4006 2008 4006 56 4007 1992 4007 35 4007 35 4008 1992 4008 1991 4008 35 4009 1991 4009 1282 4009 1696 4010 2069 4010 1681 4010 1696 4011 2070 4011 2069 4011 1694 4012 2071 4012 1696 4012 1696 4013 2071 4013 2070 4013 1691 4014 2072 4014 1692 4014 1692 4015 2072 4015 2073 4015 1692 4016 2073 4016 1694 4016 1694 4017 2073 4017 2071 4017 2074 4018 2072 4018 1691 4018 2075 4019 2074 4019 1689 4019 1689 4020 2074 4020 1691 4020 1681 4021 2069 4021 2076 4021 1681 4022 2076 4022 1679 4022 1679 4023 2076 4023 2077 4023 1679 4024 2077 4024 1682 4024 1682 4025 2077 4025 1684 4025 1684 4026 2077 4026 2078 4026 1684 4027 2078 4027 1685 4027 1685 4028 2078 4028 2079 4028 1685 4029 2079 4029 1687 4029 1687 4030 2079 4030 2075 4030 1687 4031 2075 4031 1689 4031 1859 4032 1858 4032 2080 4032 2080 4033 1858 4033 2081 4033 2081 4034 1858 4034 1866 4034 2081 4035 1866 4035 2082 4035 2082 4036 1866 4036 1865 4036 2082 4037 1865 4037 2083 4037 2083 4038 1865 4038 1864 4038 2083 4039 1864 4039 1863 4039 2083 4040 1863 4040 2084 4040 2084 4041 1863 4041 1862 4041 2084 4042 1862 4042 2085 4042 2085 4043 1862 4043 1861 4043 2085 4044 1861 4044 2086 4044 2086 4045 1861 4045 1860 4045 2086 4046 1860 4046 2087 4046 2087 4047 1860 4047 1859 4047 2087 4048 1859 4048 2088 4048 2088 4049 1859 4049 2080 4049 2097 4050 1968 4050 2089 4050 2089 4051 1968 4051 1976 4051 2089 4052 1976 4052 2090 4052 2090 4053 1976 4053 1975 4053 2090 4054 1975 4054 2091 4054 2091 4055 1975 4055 1974 4055 2091 4056 1974 4056 2092 4056 2092 4057 1974 4057 1973 4057 2092 4058 1973 4058 2093 4058 2093 4059 1973 4059 1972 4059 2093 4060 1972 4060 2094 4060 2094 4061 1972 4061 2095 4061 2095 4062 1972 4062 1971 4062 2095 4063 1971 4063 1970 4063 2095 4064 1970 4064 2096 4064 2096 4065 1970 4065 1969 4065 2096 4066 1969 4066 2097 4066 2097 4067 1969 4067 1968 4067 5 4068 6 4068 1741 4068 1741 4069 1733 4069 1983 4069 1256 4070 16 4070 2053 4070 1255 4071 952 4071 1256 4071 1256 4072 952 4072 16 4072 2053 4073 16 4073 5 4073 2053 4074 5 4074 1741 4074 2053 4075 1741 4075 1983 4075 2053 4076 1983 4076 2054 4076 1547 4077 2057 4077 2054 4077 952 4078 1255 4078 2057 4078 952 4079 2057 4079 1547 4079 1546 4080 1547 4080 2054 4080 2054 4081 1983 4081 1546 4081 1723 4082 722 4082 2029 4082 2029 4083 722 4083 723 4083 50 4084 1265 4084 51 4084 51 4085 1265 4085 1264 4085 2029 4086 51 4086 1264 4086 2029 4087 723 4087 51 4087 1526 4088 2034 4088 1524 4088 1524 4089 2034 4089 2032 4089 1739 4090 1723 4090 1988 4090 1988 4091 1723 4091 2029 4091 1988 4092 2029 4092 1526 4092 1526 4093 2029 4093 2034 4093 1524 4094 2032 4094 2031 4094 1524 4095 2031 4095 50 4095 50 4096 2031 4096 1265 4096 19 4097 2058 4097 1525 4097 1524 4098 50 4098 1525 4098 1525 4099 50 4099 19 4099 2098 4100 1629 4100 1631 4100 2099 4101 2098 4101 1631 4101 1633 4102 2100 4102 1631 4102 1631 4103 2100 4103 2099 4103 2100 4104 1633 4104 1634 4104 2100 4105 1634 4105 2101 4105 2101 4106 1634 4106 1636 4106 2101 4107 1636 4107 2102 4107 1636 4108 2103 4108 2102 4108 2108 4109 2103 4109 1638 4109 1638 4110 2103 4110 1636 4110 1629 4111 2098 4111 2104 4111 1629 4112 2104 4112 2105 4112 1629 4113 2105 4113 1627 4113 1627 4114 2105 4114 2106 4114 1627 4115 2106 4115 1624 4115 1624 4116 2106 4116 2107 4116 1624 4117 2107 4117 1639 4117 1639 4118 2107 4118 2108 4118 1639 4119 2108 4119 1638 4119 2109 4120 1967 4120 2110 4120 2110 4121 1967 4121 1966 4121 2110 4122 1966 4122 2111 4122 2111 4123 1966 4123 1965 4123 2111 4124 1965 4124 2112 4124 2112 4125 1965 4125 1964 4125 2112 4126 1964 4126 2113 4126 2113 4127 1964 4127 1963 4127 2113 4128 1963 4128 2114 4128 2114 4129 1963 4129 1962 4129 2114 4130 1962 4130 2115 4130 2115 4131 1962 4131 1961 4131 2115 4132 1961 4132 2116 4132 2116 4133 1961 4133 1960 4133 2116 4134 1960 4134 2117 4134 2117 4135 1960 4135 1959 4135 2117 4136 1959 4136 2109 4136 2109 4137 1959 4137 1967 4137 722 4138 1723 4138 23 4138 23 4139 1723 4139 1700 4139 23 4140 1700 4140 48 4140 2027 4141 48 4141 1700 4141 1521 4142 1525 4142 2022 4142 1701 4143 1989 4143 1700 4143 1700 4144 1989 4144 2027 4144 2058 4145 47 4145 1267 4145 1267 4146 47 4146 1268 4146 1268 4147 47 4147 48 4147 1268 4148 48 4148 2027 4148 2026 4149 1989 4149 2024 4149 2024 4150 1989 4150 1521 4150 1267 4151 2020 4151 2058 4151 2058 4152 2020 4152 1525 4152 2024 4153 1521 4153 2022 4153 2020 4154 2022 4154 1525 4154 2026 4155 2027 4155 1989 4155 10 4156 43 4156 1705 4156 10 4157 1705 4157 9 4157 9 4158 1705 4158 1702 4158 1996 4159 1990 4159 1994 4159 44 4160 1282 4160 1279 4160 44 4161 1279 4161 1278 4161 44 4162 1278 4162 43 4162 1990 4163 1996 4163 1997 4163 2002 4164 1991 4164 1999 4164 43 4165 1278 4165 1994 4165 43 4166 1994 4166 1705 4166 1990 4167 1703 4167 1994 4167 1994 4168 1703 4168 1705 4168 1990 4169 1997 4169 1991 4169 1997 4170 1999 4170 1991 4170 1991 4171 2002 4171 1282 4171 1282 4172 2002 4172 1279 4172 1 4173 1750 4173 27 4173 27 4174 1750 4174 1716 4174 27 4175 1716 4175 28 4175 4 4176 29 4176 1708 4176 4 4177 1708 4177 6 4177 6 4178 1708 4178 1741 4178 1545 4179 2037 4179 1958 4179 1958 4180 2037 4180 1262 4180 31 4181 1958 4181 1262 4181 31 4182 1262 4182 29 4182 29 4183 1262 4183 1263 4183 29 4184 1263 4184 2045 4184 2039 4185 1548 4185 2041 4185 2041 4186 1548 4186 1580 4186 1545 4187 1548 4187 2037 4187 2037 4188 1548 4188 2039 4188 29 4189 2045 4189 1708 4189 2043 4190 2041 4190 1580 4190 1580 4191 1706 4191 2043 4191 2043 4192 1706 4192 1708 4192 2043 4193 1708 4193 2045 4193 1982 4194 2012 4194 1716 4194 1982 4195 1716 4195 1717 4195 2011 4196 28 4196 1716 4196 2011 4197 1716 4197 2012 4197 2011 4198 1273 4198 28 4198 28 4199 1273 4199 24 4199 24 4200 1273 4200 1274 4200 1274 4201 1845 4201 24 4201 2014 4202 2012 4202 1982 4202 1846 4203 2018 4203 2016 4203 1846 4204 2016 4204 1982 4204 1982 4205 2016 4205 2014 4205 1845 4206 1274 4206 2018 4206 1845 4207 2018 4207 1846 4207 2125 4208 2118 4208 2119 4208 2118 4209 2123 4209 2122 4209 2120 4210 2122 4210 2121 4210 2121 4211 2122 4211 2123 4211 2121 4212 2124 4212 2120 4212 2119 4213 2127 4213 2125 4213 2122 4214 2126 4214 2118 4214 2118 4215 2126 4215 2119 4215 2126 4216 1781 4216 1788 4216 2126 4217 1788 4217 2119 4217 2119 4218 1788 4218 1787 4218 2119 4219 1787 4219 2127 4219 2127 4220 1787 4220 2125 4220 2125 4221 1787 4221 1786 4221 2125 4222 1786 4222 2118 4222 2118 4223 1786 4223 1785 4223 2118 4224 1785 4224 2123 4224 2123 4225 1785 4225 2121 4225 2121 4226 1785 4226 1784 4226 2121 4227 1784 4227 2124 4227 2124 4228 1784 4228 1783 4228 2124 4229 1783 4229 2120 4229 2120 4230 1783 4230 1782 4230 2120 4231 1782 4231 2122 4231 2122 4232 1782 4232 1781 4232 2122 4233 1781 4233 2126 4233 2132 4234 2128 4234 2129 4234 2129 4235 2130 4235 2131 4235 2132 4236 2129 4236 2133 4236 2129 4237 2128 4237 2130 4237 2134 4238 2135 4238 2129 4238 2132 4239 2133 4239 2136 4239 2131 4240 2134 4240 2129 4240 2135 4241 1890 4241 2129 4241 2129 4242 1890 4242 1898 4242 2129 4243 1898 4243 1897 4243 2129 4244 1897 4244 2133 4244 2133 4245 1897 4245 1896 4245 2133 4246 1896 4246 2136 4246 2136 4247 1896 4247 1895 4247 2136 4248 1895 4248 2132 4248 2132 4249 1895 4249 1894 4249 2132 4250 1894 4250 2128 4250 2128 4251 1894 4251 1893 4251 2128 4252 1893 4252 2130 4252 2130 4253 1893 4253 1892 4253 2130 4254 1892 4254 2131 4254 2131 4255 1892 4255 1891 4255 2131 4256 1891 4256 2134 4256 2134 4257 1891 4257 1890 4257 2134 4258 1890 4258 2135 4258 2069 4259 2075 4259 2079 4259 2069 4260 2079 4260 2078 4260 2076 4261 2069 4261 2077 4261 2069 4262 2078 4262 2077 4262 2075 4263 2069 4263 2074 4263 2074 4264 2069 4264 2070 4264 2070 4265 2071 4265 2074 4265 2074 4266 2071 4266 2072 4266 2072 4267 2071 4267 2073 4267 2105 4268 2104 4268 2108 4268 2108 4269 2104 4269 2098 4269 2105 4270 2108 4270 2107 4270 2107 4271 2106 4271 2105 4271 2102 4272 2103 4272 2100 4272 2100 4273 2103 4273 2099 4273 2108 4274 2099 4274 2103 4274 2099 4275 2108 4275 2098 4275 2102 4276 2100 4276 2101 4276 2138 4277 2139 4277 2142 4277 2137 4278 2138 4278 2141 4278 2141 4279 2138 4279 2140 4279 2137 4280 2139 4280 2138 4280 2142 4281 2143 4281 2144 4281 2142 4282 2144 4282 2138 4282 2145 4283 2144 4283 2143 4283 2145 4284 2143 4284 2146 4284 2146 4285 2143 4285 2142 4285 2146 4286 2142 4286 2147 4286 2147 4287 2142 4287 2139 4287 2147 4288 2139 4288 2148 4288 2148 4289 2139 4289 2137 4289 2148 4290 2137 4290 2149 4290 2149 4291 2137 4291 2150 4291 2150 4292 2137 4292 2141 4292 2150 4293 2141 4293 2151 4293 2151 4294 2141 4294 2140 4294 2151 4295 2140 4295 2152 4295 2152 4296 2140 4296 2138 4296 2152 4297 2138 4297 2153 4297 2153 4298 2138 4298 2144 4298 2153 4299 2144 4299 2145 4299 2151 4300 2162 4300 2154 4300 2151 4301 2154 4301 2150 4301 2150 4302 2154 4302 2155 4302 2150 4303 2155 4303 2149 4303 2149 4304 2155 4304 2156 4304 2149 4305 2156 4305 2148 4305 2148 4306 2156 4306 2147 4306 2147 4307 2156 4307 2157 4307 2147 4308 2157 4308 2158 4308 2147 4309 2158 4309 2146 4309 2146 4310 2158 4310 2159 4310 2146 4311 2159 4311 2145 4311 2145 4312 2159 4312 2160 4312 2145 4313 2160 4313 2153 4313 2153 4314 2160 4314 2161 4314 2153 4315 2161 4315 2152 4315 2152 4316 2161 4316 2162 4316 2152 4317 2162 4317 2151 4317 2066 4318 2160 4318 2065 4318 2065 4319 2160 4319 2159 4319 2065 4320 2159 4320 2064 4320 2064 4321 2159 4321 2158 4321 2064 4322 2158 4322 2157 4322 2064 4323 2157 4323 2063 4323 2063 4324 2157 4324 2062 4324 2062 4325 2157 4325 2156 4325 2062 4326 2156 4326 2061 4326 2061 4327 2156 4327 2155 4327 2061 4328 2155 4328 2060 4328 2060 4329 2155 4329 2154 4329 2060 4330 2154 4330 2059 4330 2059 4331 2154 4331 2162 4331 2059 4332 2162 4332 2068 4332 2068 4333 2162 4333 2161 4333 2068 4334 2161 4334 2067 4334 2067 4335 2161 4335 2160 4335 2067 4336 2160 4336 2066 4336 2168 4337 2166 4337 2167 4337 2167 4338 2166 4338 2165 4338 2164 4339 2166 4339 2163 4339 2168 4340 2167 4340 2169 4340 2169 4341 2171 4341 2168 4341 2168 4342 2171 4342 2170 4342 2166 4343 2164 4343 2165 4343 2172 4344 2169 4344 2173 4344 2173 4345 2169 4345 2167 4345 2173 4346 2167 4346 2174 4346 2174 4347 2167 4347 2165 4347 2174 4348 2165 4348 2175 4348 2175 4349 2165 4349 2164 4349 2175 4350 2164 4350 2176 4350 2176 4351 2164 4351 2163 4351 2176 4352 2163 4352 2177 4352 2177 4353 2163 4353 2166 4353 2177 4354 2166 4354 2178 4354 2178 4355 2166 4355 2168 4355 2178 4356 2168 4356 2179 4356 2179 4357 2168 4357 2170 4357 2179 4358 2170 4358 2180 4358 2180 4359 2170 4359 2171 4359 2180 4360 2171 4360 2172 4360 2172 4361 2171 4361 2169 4361 2172 4362 2190 4362 2180 4362 2180 4363 2190 4363 2181 4363 2180 4364 2181 4364 2182 4364 2180 4365 2182 4365 2179 4365 2179 4366 2182 4366 2183 4366 2179 4367 2183 4367 2178 4367 2178 4368 2183 4368 2184 4368 2178 4369 2184 4369 2177 4369 2177 4370 2184 4370 2185 4370 2177 4371 2185 4371 2176 4371 2176 4372 2185 4372 2186 4372 2176 4373 2186 4373 2175 4373 2175 4374 2186 4374 2187 4374 2175 4375 2187 4375 2174 4375 2174 4376 2187 4376 2188 4376 2174 4377 2188 4377 2189 4377 2174 4378 2189 4378 2173 4378 2173 4379 2189 4379 2190 4379 2173 4380 2190 4380 2172 4380 2087 4381 2190 4381 2086 4381 2086 4382 2190 4382 2189 4382 2086 4383 2189 4383 2085 4383 2085 4384 2189 4384 2188 4384 2085 4385 2188 4385 2187 4385 2085 4386 2187 4386 2084 4386 2084 4387 2187 4387 2186 4387 2084 4388 2186 4388 2083 4388 2083 4389 2186 4389 2185 4389 2083 4390 2185 4390 2082 4390 2082 4391 2185 4391 2184 4391 2082 4392 2184 4392 2081 4392 2081 4393 2184 4393 2183 4393 2081 4394 2183 4394 2080 4394 2080 4395 2183 4395 2182 4395 2080 4396 2182 4396 2088 4396 2088 4397 2182 4397 2181 4397 2088 4398 2181 4398 2087 4398 2087 4399 2181 4399 2190 4399 2197 4400 2193 4400 2194 4400 2197 4401 2194 4401 2195 4401 2196 4402 2197 4402 2195 4402 2193 4403 2197 4403 2191 4403 2191 4404 2197 4404 2192 4404 2192 4405 2198 4405 2191 4405 2195 4406 2199 4406 2196 4406 2196 4407 2199 4407 2200 4407 2196 4408 2200 4408 2197 4408 2197 4409 2200 4409 2201 4409 2197 4410 2201 4410 2192 4410 2192 4411 2201 4411 2202 4411 2192 4412 2202 4412 2198 4412 2198 4413 2202 4413 2203 4413 2198 4414 2203 4414 2191 4414 2191 4415 2203 4415 2204 4415 2191 4416 2204 4416 2193 4416 2193 4417 2204 4417 2205 4417 2193 4418 2205 4418 2194 4418 2194 4419 2205 4419 2195 4419 2195 4420 2205 4420 2199 4420 2205 4421 2206 4421 2199 4421 2199 4422 2206 4422 2207 4422 2199 4423 2207 4423 2200 4423 2200 4424 2207 4424 2208 4424 2200 4425 2208 4425 2201 4425 2201 4426 2208 4426 2209 4426 2201 4427 2209 4427 2210 4427 2201 4428 2210 4428 2202 4428 2202 4429 2210 4429 2211 4429 2202 4430 2211 4430 2203 4430 2203 4431 2211 4431 2212 4431 2203 4432 2212 4432 2213 4432 2203 4433 2213 4433 2204 4433 2204 4434 2213 4434 2214 4434 2204 4435 2214 4435 2205 4435 2205 4436 2214 4436 2206 4436 2206 4437 2091 4437 2207 4437 2207 4438 2091 4438 2092 4438 2207 4439 2092 4439 2208 4439 2208 4440 2092 4440 2093 4440 2208 4441 2093 4441 2209 4441 2209 4442 2093 4442 2210 4442 2210 4443 2093 4443 2094 4443 2210 4444 2094 4444 2211 4444 2211 4445 2094 4445 2095 4445 2211 4446 2095 4446 2212 4446 2212 4447 2095 4447 2096 4447 2212 4448 2096 4448 2213 4448 2213 4449 2096 4449 2097 4449 2213 4450 2097 4450 2214 4450 2214 4451 2097 4451 2089 4451 2214 4452 2089 4452 2090 4452 2214 4453 2090 4453 2206 4453 2206 4454 2090 4454 2091 4454 2218 4455 2219 4455 2216 4455 2215 4456 2219 4456 2221 4456 2219 4457 2215 4457 2216 4457 2218 4458 2217 4458 2219 4458 2221 4459 2220 4459 2222 4459 2220 4460 2221 4460 2219 4460 2220 4461 2223 4461 2222 4461 2222 4462 2223 4462 2224 4462 2222 4463 2224 4463 2221 4463 2221 4464 2224 4464 2225 4464 2221 4465 2225 4465 2215 4465 2215 4466 2225 4466 2226 4466 2215 4467 2226 4467 2216 4467 2216 4468 2226 4468 2227 4468 2216 4469 2227 4469 2218 4469 2218 4470 2227 4470 2228 4470 2218 4471 2228 4471 2217 4471 2217 4472 2228 4472 2229 4472 2217 4473 2229 4473 2219 4473 2219 4474 2229 4474 2230 4474 2219 4475 2230 4475 2220 4475 2220 4476 2230 4476 2231 4476 2220 4477 2231 4477 2223 4477 2229 4478 2240 4478 2232 4478 2229 4479 2232 4479 2230 4479 2230 4480 2232 4480 2233 4480 2230 4481 2233 4481 2231 4481 2231 4482 2233 4482 2234 4482 2231 4483 2234 4483 2223 4483 2223 4484 2234 4484 2235 4484 2223 4485 2235 4485 2224 4485 2224 4486 2235 4486 2236 4486 2224 4487 2236 4487 2225 4487 2225 4488 2236 4488 2237 4488 2225 4489 2237 4489 2226 4489 2226 4490 2237 4490 2238 4490 2226 4491 2238 4491 2227 4491 2227 4492 2238 4492 2228 4492 2228 4493 2238 4493 2239 4493 2228 4494 2239 4494 2240 4494 2228 4495 2240 4495 2229 4495 2234 4496 2112 4496 2235 4496 2235 4497 2112 4497 2113 4497 2235 4498 2113 4498 2236 4498 2236 4499 2113 4499 2114 4499 2236 4500 2114 4500 2237 4500 2237 4501 2114 4501 2115 4501 2237 4502 2115 4502 2238 4502 2238 4503 2115 4503 2116 4503 2238 4504 2116 4504 2239 4504 2239 4505 2116 4505 2117 4505 2239 4506 2117 4506 2240 4506 2240 4507 2117 4507 2109 4507 2240 4508 2109 4508 2232 4508 2232 4509 2109 4509 2110 4509 2232 4510 2110 4510 2233 4510 2233 4511 2110 4511 2111 4511 2233 4512 2111 4512 2234 4512 2234 4513 2111 4513 2112 4513 2241 4514 2243 4514 2244 4514 2244 4515 2245 4515 2241 4515 2245 4516 2246 4516 2241 4516 2246 4517 2247 4517 2241 4517 2247 4518 2248 4518 2241 4518 2241 4519 2248 4519 2242 4519 2242 4520 2249 4520 2241 4520 2244 4521 2250 4521 2245 4521 2245 4522 2250 4522 2251 4522 2245 4523 2251 4523 2246 4523 2246 4524 2251 4524 2252 4524 2246 4525 2252 4525 2247 4525 2247 4526 2252 4526 2253 4526 2247 4527 2253 4527 2254 4527 2247 4528 2254 4528 2248 4528 2248 4529 2254 4529 2242 4529 2242 4530 2254 4530 2255 4530 2242 4531 2255 4531 2249 4531 2249 4532 2255 4532 2256 4532 2249 4533 2256 4533 2241 4533 2241 4534 2256 4534 2257 4534 2241 4535 2257 4535 2243 4535 2243 4536 2257 4536 2258 4536 2243 4537 2258 4537 2244 4537 2244 4538 2258 4538 2250 4538 2257 4539 2259 4539 2258 4539 2258 4540 2259 4540 2260 4540 2258 4541 2260 4541 2250 4541 2250 4542 2260 4542 2261 4542 2250 4543 2261 4543 2251 4543 2251 4544 2261 4544 2262 4544 2251 4545 2262 4545 2252 4545 2252 4546 2262 4546 2263 4546 2252 4547 2263 4547 2253 4547 2253 4548 2263 4548 2264 4548 2253 4549 2264 4549 2254 4549 2254 4550 2264 4550 2265 4550 2254 4551 2265 4551 2255 4551 2255 4552 2265 4552 2266 4552 2255 4553 2266 4553 2256 4553 2256 4554 2266 4554 2267 4554 2256 4555 2267 4555 2257 4555 2257 4556 2267 4556 2259 4556 2265 4557 2268 4557 2269 4557 2265 4558 2269 4558 2266 4558 2266 4559 2269 4559 2270 4559 2266 4560 2270 4560 2267 4560 2267 4561 2270 4561 2271 4561 2267 4562 2271 4562 2259 4562 2259 4563 2271 4563 2272 4563 2259 4564 2272 4564 2260 4564 2260 4565 2272 4565 2273 4565 2260 4566 2273 4566 2261 4566 2261 4567 2273 4567 2274 4567 2261 4568 2274 4568 2262 4568 2262 4569 2274 4569 2275 4569 2262 4570 2275 4570 2263 4570 2263 4571 2275 4571 2276 4571 2263 4572 2276 4572 2264 4572 2264 4573 2276 4573 2268 4573 2264 4574 2268 4574 2265 4574 2268 4575 2272 4575 2271 4575 2272 4576 2268 4576 2276 4576 2272 4577 2276 4577 2275 4577 2268 4578 2271 4578 2270 4578 2275 4579 2274 4579 2272 4579 2272 4580 2274 4580 2273 4580 2270 4581 2269 4581 2268 4581</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Camera_001" name="Camera_001" type="NODE"> + <matrix sid="transform">0.6858804 -0.3173701 0.6548619 7.481132 0.7276337 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953431 0.4452454 5.343665 0 0 0 1</matrix> + <instance_camera url="#Camera_001-camera"/> + </node> + <node id="Lamp_001" name="Lamp_001" type="NODE"> + <matrix sid="transform">-0.2908648 -0.7711007 0.5663931 4.076245 0.9551712 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1</matrix> + <instance_light url="#Lamp_001-light"/> + </node> + <node id="Link2" name="Link2" type="NODE"> + <matrix sid="transform">-7.58967e-10 -7.58967e-10 0.001 -0.015 -0.001 2.98027e-11 -7.58967e-10 0.015 -2.98021e-11 -0.001 -7.58967e-10 0.0091 0 0 0 1</matrix> + <instance_geometry url="#Link2-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="Material_002-material" target="#Material_002-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/arm/link2.stl b/kinton_description/meshes/arm/link2.stl new file mode 100644 index 0000000000000000000000000000000000000000..881ed7aa9d02d6c21eb63e8cd4feda568fcc7b90 Binary files /dev/null and b/kinton_description/meshes/arm/link2.stl differ diff --git a/kinton_description/meshes/arm/link3.dae b/kinton_description/meshes/arm/link3.dae new file mode 100644 index 0000000000000000000000000000000000000000..e7da9d83f98f768056f96c584471559116a38b5c --- /dev/null +++ b/kinton_description/meshes/arm/link3.dae @@ -0,0 +1,106 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2015-07-29T19:29:46</created> + <modified>2015-07-29T19:29:46</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_images/> + <library_effects> + <effect id="Material_001-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.03699346 0.03699346 0.03699346 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="Material_001-material" name="Material_001"> + <instance_effect url="#Material_001-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Link3-mesh" name="Link3"> + <mesh> + <source id="Link3-mesh-positions"> + <float_array id="Link3-mesh-positions-array" count="10998">18.98499 31.48527 11.74262 18.44672 31.43685 11.74262 18.98644 31.49595 12.29262 18.45 31.50078 12.29262 18.45 31.50078 24.69262 18.43377 31.41105 25.24262 18.97756 31.49279 24.69261 18.9908 31.49131 25.24262 11.55387 31.41926 11.74262 11.01356 31.49596 11.74262 11.55 31.50078 12.29262 10.98868 31.41356 12.29262 26.98095 29.92629 9.492624 26.91268 29.97578 11.74262 26.63668 30.40078 11.74262 26.63668 30.40078 15.49262 27 29.84132 15.49262 23.55 30.46745 11.74262 20.13377 30.04785 11.74262 18.8764 30.83289 11.74262 20.18025 30.5896 11.74262 20.15875 30.58331 12.29262 20.39227 30.02053 25.24262 26.91268 29.97578 25.24262 23.55 30.45078 25.24262 26.63668 30.40078 25.24262 19.34662 30.45593 25.24263 20.12445 30.60121 25.24262 26.98799 29.92118 27.49262 27 29.84132 21.49262 26.85821 30.37008 21.49262 22.25149 35.97222 9.489992 22.18439 35.97204 6.665726 7.562274 35.96385 9.492029 3.019055 29.92628 27.49262 3.087318 29.97578 25.24262 3.363317 30.40078 25.24262 3.363317 30.40078 21.49262 3 29.84132 21.49262 11.12366 30.83292 25.24262 11.55246 31.4221 25.24262 11.02245 31.49281 25.24262 6.449998 30.45078 25.24262 9.866227 30.04786 25.24262 9.785202 30.57299 25.24262 9.841233 30.58331 11.74262 9.636734 30.5558 12.29262 9.84195 30.05548 11.74262 3.087318 29.97578 11.74262 6.449998 30.43411 11.74262 3.363317 30.40078 11.74262 11.05753 30.77008 11.74262 3.012011 29.92118 9.492624 3 29.84132 15.49262 3.141792 30.37009 15.49262 23.55 30.50078 24.69262 20.2148 30.57299 24.69262 11.6113 31.35427 9.492625 11.04939 31.40077 9.492624 4.5 30.40078 9.492624 4.5 29.97578 9.492624 9.468079 30.43162 9.492623 9.866288 30.04788 9.492626 10.44885 30.81917 9.492624 6.449999 30.50078 24.69262 11.05753 30.77002 27.49259 11.05854 31.39135 27.49262 11.56722 31.40077 27.49262 4.5 29.97578 27.49262 4.5 30.40078 27.49262 9.841965 30.05548 27.49262 9.856507 30.48299 27.49262 25.5 12.00078 27.49262 25.48002 32.13657 30.34083 25.5 23.70078 27.49262 25.5 23.70078 21.49262 25.5 24.00078 21.49262 25.5 24.00078 27.49262 25.5 29.97578 27.49262 25.5 30.40078 27.49262 25.5 32.15111 27.49262 25.5 12.00078 9.492624 25.5 5.500775 9.492624 25.5 22.00078 21.49262 25.5 12.10078 21.49262 25.5 12.00078 15.49262 25.5 32.15111 9.492624 25.5 30.40078 9.492624 25.5 29.97578 9.492624 25.5 24.00078 9.492624 25.5 24.00078 15.49262 25.5 22.00078 15.49262 25.5 9.400303 20.50947 25.5 10.54405 19.79331 25.5 12.30078 27.49262 25.5 5.500775 15.49262 25.5 5.500775 21.49262 25.5 5.500775 27.49262 25.5 10.92801 19.05106 25.5 7.684387 16.94099 25.5 9.640503 16.59084 25.5 10.97891 18.01577 25.5 8.786538 16.48579 25.5 10.36571 17.00592 25.5 7.127861 17.77277 25.5 7.902618 20.20566 25.5 7.223 19.42299 25.5 6.986648 18.62149 4.5 32.15111 9.492624 4.517052 32.14197 6.662336 4.5 12.30078 21.49262 4.5 22.00078 21.49262 4.5 22.00078 15.49262 4.5 32.15111 27.49262 4.5 24.00078 27.49262 4.5 7.019165 18.87542 4.5 5.500775 21.49262 4.5 12.00078 15.49262 4.5 12.30078 27.49262 4.5 12.00078 9.492624 4.5 5.500775 9.492624 4.5 5.500775 15.49262 4.510668 3.856644 30.29801 4.5 24.00078 21.49262 4.5 23.70078 21.49262 4.5 23.70078 27.49262 4.5 24.00078 15.49262 4.5 24.00078 9.492624 4.5 12.00078 27.49262 4.5 5.500775 27.49262 4.5 7.045917 18.0403 4.5 7.404236 17.25798 4.5 10.03598 16.74083 4.5 10.82198 17.62283 4.5 8.048829 16.72635 4.5 11.0149 18.62151 4.5 12.00078 21.49262 4.5 10.69629 19.5874 4.5 7.557548 19.92703 4.5 8.872765 16.47844 4.5 9.793641 20.36659 4.5 8.617112 20.47407 9.596131 35.47342 30.49262 16.72632 34.86871 30.49262 19.9104 35.29906 30.49262 6.471644 33.27794 30.49263 4.727554 32.09275 30.48883 15.56537 35.44437 30.49264 7.20697 34.80479 30.49261 8.301941 35.40979 30.49262 21.1443 35.50474 30.49262 14.52151 35.47779 30.49262 22.18378 35.22861 30.49261 23.46534 32.53953 30.49262 23.45447 33.584 30.49263 22.97593 34.546 30.49666 9.799729 16.25909 30.49265 19.63159 30.88135 30.49264 8.075483 14.59193 30.49262 18.45404 17.23453 30.49264 20.83891 30.48312 30.49263 15.04621 30.4577 30.49262 13.53918 35.03961 30.49262 23.86794 8.246005 30.49262 23.37293 5.89917 30.49262 25.30634 3.910667 30.48269 7.837097 30.77853 30.49262 6.858734 31.62805 30.49262 4.686272 3.909325 30.48141 11.01714 34.55018 30.49262 12.82444 34.27807 30.49263 18.82445 34.27807 30.49263 17.51661 33.36964 30.49262 16.87617 0.3007753 30.49262 18.4812 0.7960205 30.49262 22.86002 13.237 30.49262 11.51772 33.16078 30.49262 12.47777 33.05487 30.49262 7.527557 4.11322 30.49262 6.326151 6.88179 30.49262 22.93958 31.35535 30.49263 23.80811 10.44188 30.49251 12.51485 17.57688 30.49262 20.99982 15.61353 30.49262 16.28256 30.84537 30.49261 6.920236 12.80119 30.49266 13.6315 30.88141 30.49262 10.28061 30.80318 30.49261 20.79709 2.209656 30.4926 22.37374 4.017 30.49262 15.51378 17.91491 30.49262 18.50441 33.25126 30.49262 8.838906 30.48312 30.49262 6.115704 9.89243 30.49262 21.89987 30.65965 30.49263 18.65753 32.00967 30.49262 17.18972 31.70675 30.4926 12.7717 31.8179 30.49261 11.27605 31.91258 30.49262 13.12423 0.3006592 30.49259 10.85985 1.089729 30.49264 9.119997 2.319792 30.49262 7.708405 0.2325592 30.48618 19.20004 8.051804 6.492623 23.02268 8.779019 6.492622 18.99373 9.031117 6.492622 19.17918 9.871384 6.492619 22.71301 10.09892 6.492619 19.97552 10.75886 6.492621 20.9451 11.00652 6.492622 22.43442 7.557556 6.492622 20.19567 7.131699 6.492621 21.79248 10.85692 6.492621 21.38278 7.01916 6.492621 14.78662 5.00771 6.492622 14.36779 1.084105 6.49262 15.38279 1.019163 6.492621 16.91694 3.632172 6.492621 16.98145 2.617165 6.492622 16.4344 1.557533 6.492623 13.97392 4.725079 6.492621 13.02771 3.369705 6.492622 13.6517 1.51474 6.492622 13.35246 4.166527 6.492617 15.61647 4.910217 6.492621 16.36556 4.486877 6.492623 13.06553 2.36969 6.492621 7.386291 7.761276 6.492623 10.3656 10.48686 6.492621 10.84065 9.79953 6.492622 6.985817 8.872767 6.492621 10.16989 7.335914 6.492622 8.367791 7.08411 6.492621 10.81568 8.146744 6.49263 9.224747 7.006901 6.492622 7.118437 9.697743 6.492622 7.693151 10.56045 6.492621 8.786601 11.00771 6.492622 9.616486 10.91022 6.492622 11.01778 8.957509 6.492621 15.87166 13.16213 6.492622 16.78264 15.94708 6.49262 14.13018 16.82197 6.492619 14.52312 13.02264 6.492621 17.01778 14.9575 6.492622 16.74044 13.9789 6.492623 15.30739 17.01223 6.492621 16.21735 16.5958 6.492621 12.98581 14.87278 6.492621 13.24819 16.03594 6.492621 13.38626 13.76132 6.49262 22.99607 8.702424 4.292622 22.67922 7.902405 4.292623 22.09481 7.305279 4.292622 21.28492 7.014605 4.292623 20.28737 7.094841 4.292622 19.35246 7.835052 4.292627 18.99315 8.786614 4.292623 19.20002 9.949723 4.292622 19.92223 10.69325 4.292623 20.86431 11.03105 4.292622 22.16991 10.66562 4.292623 22.88812 9.713776 4.29262 17.03106 2.87752 4.292622 16.59711 1.766861 4.292622 15.64291 1.070209 4.292622 14.45052 1.058765 4.292622 13.57317 1.573349 4.292625 13.11842 2.303864 4.292623 12.98581 3.128775 4.292622 13.38628 4.240257 4.292623 14.36776 4.917439 4.292621 15.3828 4.982386 4.292623 16.16861 4.631866 4.292617 16.74045 4.022583 4.292623 10.87397 8.207898 4.292623 10.21742 7.405805 4.292619 9.4674 7.037396 4.292623 8.287377 7.094841 4.292621 7.35247 7.835007 4.292622 6.965798 8.951369 4.292623 7.304016 10.09483 4.292624 8.195694 10.86987 4.292622 9.382843 10.98237 4.292621 10.43444 10.44395 4.292621 10.98145 9.3844 4.292621 16.99647 15.20117 4.292622 16.91694 14.3694 4.292622 16.46944 13.63445 4.292617 15.64291 13.07021 4.292623 14.28739 13.09484 4.292621 13.24818 13.96559 4.292621 12.9867 15.29587 4.292623 13.51333 16.36573 4.292624 14.52312 16.97891 4.292623 15.87166 16.83942 4.292621 16.74043 16.02264 4.292621 24.8 9.050177 22.45843 24.8 7.978943 26.23309 24.8 9.124054 26.52369 24.8 7.162149 25.36433 24.8 10.16649 22.84506 24.8 10.90672 23.78002 24.8 10.93134 25.13552 24.8 10.23474 26.08972 24.8 7.02264 24.01576 24.8 7.761291 22.87888 24.8 8.051819 10.69265 24.8 7.852219 14.13788 24.8 9.214985 10.48578 24.8 10.16648 10.84506 24.8 8.779019 14.5153 24.8 10.96416 12.96001 24.8 10.25079 14.12503 24.8 10.90672 11.78001 24.8 7.162144 13.36432 24.8 7.004829 12.19342 24.8 7.308289 11.41492 18.82912 10.2569 4.292621 19.54368 11.0608 4.292623 20.73328 11.50945 4.292622 22.20118 11.2424 4.292622 23.22833 10.18365 4.292623 23.52836 8.72361 4.292621 22.79302 7.196762 4.29262 21.26006 6.47096 4.292623 19.81619 6.772957 4.292623 18.88004 7.633179 4.292623 18.45726 9.062541 4.292623 16.36853 5.120148 4.292622 17.34247 3.991852 4.292623 17.47533 2.527542 4.292621 17.05658 1.565094 4.29262 16.27638 0.8246765 4.292623 15.28092 0.5084311 4.292621 13.99462 0.6644077 4.292623 12.88005 1.633207 4.292624 12.52462 2.576337 4.292621 12.62307 3.906082 4.292621 13.5437 5.06081 4.292624 14.95378 5.543856 4.292621 6.504263 9.491377 4.292623 7.366443 10.95036 4.292623 8.4709 11.45592 4.292622 9.803643 11.41398 4.292622 11.14127 10.3735 4.292622 11.52223 8.946688 4.292622 11.26958 7.933228 4.292621 10.62578 7.07168 4.292624 9.261711 6.470774 4.292622 8.026061 6.692163 4.292624 7.141632 7.294601 4.292622 6.62278 8.201096 4.292625 17.14127 16.37349 4.292622 17.50246 15.2138 4.292622 17.29158 13.89711 4.292623 16.27639 12.82468 4.292627 15.28094 12.50844 4.292621 14.2097 12.60494 4.292623 12.98284 13.45143 4.292623 12.45726 15.06253 4.292622 13.0149 16.60365 4.292623 14.31317 17.4283 4.292623 15.80366 17.41399 4.292621 12.85237 7.189086 3.983241 17.59194 7.909645 3.991733 16.68781 9.012175 3.648001 17.59247 10.09036 3.992238 17.81988 9.001044 3.992952 17.03305 10.95252 3.983537 15.83398 11.71156 3.98728 15.00711 10.3095 3.555026 13.15234 11.11009 3.983938 14.22821 11.71178 3.990588 13.31879 8.987289 3.644188 12.17153 9.171231 3.994139 12.55685 10.40082 3.993494 12.35689 8.067059 3.990644 14.81084 6.195604 3.993011 14.41102 7.279389 3.699854 13.72345 6.488767 3.990835 16.11395 6.393009 3.994101 15.58478 7.818085 3.576845 17.06612 7.094201 3.984292 14.40747 9.008075 3.49367 18.9209 4.010506 6.492621 19.22942 5.590767 6.492619 19.90572 4.28611 6.492624 19.46201 3.974333 6.492622 18.45037 4.501705 6.492622 19.84377 5.306885 6.492622 20.05506 4.807449 6.492621 18.57336 5.236069 6.492622 11.051 3.965977 6.492622 10.88503 5.581026 6.492622 10.25145 4.109737 6.492622 9.924919 4.780264 6.492622 11.44256 5.197421 6.49262 11.56983 4.620679 6.492622 10.23461 5.381995 6.492622 19.89559 13.74342 6.492619 19.81641 12.66612 6.492622 19.3656 14.04799 6.492622 18.63443 12.68983 6.492619 19.25902 12.42099 6.492621 18.42896 13.26315 6.492621 20.05171 13.15472 6.492621 18.70927 13.88292 6.492623 11.48482 13.62653 6.492622 10.95127 14.04264 6.492622 10.06437 12.80054 6.492622 11.52342 12.94789 6.492621 11.10762 12.5094 6.492621 10.56607 12.45366 6.492621 9.967082 13.47106 6.492622 10.34758 13.94665 6.492621 5.199998 9.95279 22.72633 5.199999 10.98238 24.87548 5.199998 8.536011 26.47363 5.199998 9.128769 22.47844 5.199998 9.713746 26.38075 5.199999 7.965561 22.74085 5.199999 10.54404 25.79324 5.199999 7.179565 23.62288 5.199999 10.59737 23.25804 5.199999 6.989326 24.80001 5.199999 10.95563 24.0403 5.199998 7.514709 25.85823 5.199999 7.902637 14.20566 5.199999 7.684448 10.94095 5.199999 10.66563 13.66254 5.199999 11.03105 12.35693 5.199998 10.59736 11.25802 5.199998 9.952736 10.72631 5.199999 8.95138 10.45843 5.199999 7.070206 13.13552 5.199998 7.058767 11.94313 5.199998 8.860886 14.49424 5.199998 9.713822 14.38074 26.2 9.384507 26.47407 26.2 8.369431 26.40958 26.2 7.278334 25.61533 26.2 7.00182 24.11237 26.2 7.684463 22.94098 26.2 9.122356 22.44019 26.2 10.49516 23.1116 26.2 11.05653 24.52699 26.2 10.44392 25.92708 26.2 8.207901 14.3666 26.2 7.305273 13.58742 26.2 7.014606 12.77755 26.2 7.058771 11.94312 26.2 7.573379 11.06581 26.2 8.303803 10.61108 26.2 9.295857 10.47933 26.2 10.36568 11.00589 26.2 10.85105 11.7164 26.2 11.01857 12.53503 26.2 10.66563 13.66252 26.2 9.561173 14.44873 21.01235 6.449021 3.492622 19.5437 6.940735 3.492618 18.8291 7.74469 3.492622 18.49145 8.732964 3.492622 18.62279 9.800507 3.492622 19.14164 10.70695 3.492624 20.40393 11.47345 3.492622 21.8985 11.35307 3.492623 22.78436 10.76343 3.492619 23.36013 9.891968 3.492622 23.49509 8.627839 3.492622 23.09894 7.627808 3.492617 22.36852 6.881405 3.492622 17.25276 1.854202 3.492621 16.19993 0.7580986 3.492621 14.93145 0.4935862 3.492622 13.9128 0.7242622 3.492621 12.87476 1.619964 3.492622 12.49136 2.787258 3.492622 12.62279 3.800476 3.492622 13.27373 4.868755 3.492622 14.43457 5.444335 3.492622 15.47849 5.477787 3.492621 16.62576 4.929886 3.492621 17.26955 4.06839 3.492622 17.52223 3.054867 3.492622 7.737424 6.831102 3.492617 6.810268 7.706764 3.492621 6.492162 8.962856 3.492622 6.67939 9.990387 3.49262 7.612154 11.13152 3.492622 9.261691 11.53078 3.492622 10.62579 10.92986 3.49262 11.36013 9.891983 3.492621 11.49509 8.627835 3.492622 10.87847 7.285917 3.492622 9.7706 6.613964 3.492622 8.733294 6.492106 3.492622 12.77867 16.17002 3.492624 13.6142 17.13361 3.492623 15.05296 17.52303 3.492622 16.46236 17.08186 3.492623 17.35263 15.90323 3.492621 17.50202 14.82586 3.492622 17.14127 13.62806 3.492622 15.99062 12.68059 3.49262 14.52467 12.50208 3.492621 13.06046 13.3553 3.492622 12.45725 14.939 3.492622 12.69444 10.68239 3.492622 13.27858 6.763893 3.492622 17.65693 8.040973 3.492622 17.03077 7.054418 3.492622 16.12164 6.411093 3.49262 14.59286 6.194846 3.492621 12.56863 7.593882 3.492622 12.14788 8.872307 3.492622 14.12144 11.6792 3.492621 15.5209 11.77444 3.492622 16.87517 11.1192 3.492622 17.72488 9.789613 3.492622 19.94472 4.310322 3.492622 19.36559 3.953556 3.492621 18.83285 4.054893 3.492622 18.45236 4.530495 3.492622 18.52267 5.137741 3.492622 18.9209 5.505767 3.492622 19.59765 5.511406 3.492622 20.02509 4.982269 3.492622 10.95765 3.93739 3.492621 10.07049 4.266254 3.492622 9.999484 5.077488 3.492621 10.56035 5.567233 3.492622 11.28463 5.389278 3.492623 11.59244 4.647443 3.492622 18.95449 12.48339 3.492621 18.43114 13.00847 3.492622 18.72205 13.9088 3.492622 19.66594 13.97455 3.492622 20.07888 13.12326 3.492622 19.57175 12.4924 3.492622 11.58752 13.20105 3.492622 11.25708 12.60096 3.492622 10.79192 12.43096 3.492622 10.27009 12.58458 3.492621 9.980648 13.02332 3.492622 9.999485 13.56278 3.492621 10.43565 13.99106 3.492622 11.18066 13.97455 3.492622 3.8 8.617066 26.47406 3.8 7.557556 25.92703 3.8 6.976775 24.702 3.8 7.294502 23.38402 3.8 8.209046 22.63617 3.8 9.031117 22.48636 3.8 10.03599 22.74082 3.8 10.90672 23.78002 3.8 10.98694 24.77762 3.8 10.69629 25.58734 3.8 9.79361 26.3666 3.799999 8.957508 14.5104 3.8 8.146759 14.3083 3.8 7.335896 13.66249 3.8 6.982973 12.53503 3.8 7.294495 11.384 3.8 8.369652 10.55818 3.8 9.369721 10.52033 3.8 10.31711 10.94095 3.8 10.99972 12.11233 3.8 10.85693 13.28509 3.8 10.09891 14.20565 26.2 6.470774 24.75433 26.2 6.86792 23.10687 26.20001 8.011139 22.17201 26.2 9.038712 21.98479 26.2 10.29477 22.30288 26.2 11.27727 23.40538 26.2 11.50796 24.42404 26.2 11.32096 25.48328 26.2 10.3735 26.6339 26.2 8.723572 27.02097 26.2 7.196739 26.28563 26.2 6.702486 13.58224 26.2 6.505847 12.11862 26.2 7.005066 10.94933 26.2 7.810822 10.28476 26.2 9.062535 9.949872 26.2 10.64624 10.55307 26.2 11.42829 11.8058 26.2 11.48348 12.84879 26.2 11.00841 14.05429 26.2 9.581734 14.96889 26.2 7.897163 14.78423 17.94458 11.85611 3.492622 12.14467 12.1641 3.492622 7.029304 12.60244 3.492526 10.92676 16.69788 3.492541 13.16712 17.50549 3.492616 22.67473 4.779802 3.492568 17.54759 0.6821339 3.492624 6.593668 6.642211 3.492554 6.300525 9.5914 3.492461 7.882675 3.982777 3.492474 12.61475 0.6253629 3.492563 9.941368 1.884822 3.492437 15.37055 0.2778726 3.492395 21.2811 2.980961 3.49264 19.36181 1.441684 3.492355 17.94458 6.17403 3.492622 23.55372 10.74318 3.492506 23.62826 7.728049 3.491641 20.86491 15.46477 3.49248 22.66047 13.20211 3.492561 18.91708 16.76917 3.492616 16.69103 17.55474 3.492458 14.63076 17.69294 3.492622 8.872291 15.2154 3.492496 10.78266 32.0545 7.292621 10.46234 30.91967 7.292623 10.09479 31.30527 7.292625 8.963058 30.96631 7.292622 9.2809 30.50843 7.292623 8.209656 30.60496 7.292622 7.834869 31.35275 7.292621 7.314636 31.14331 7.292628 7.098442 32.27653 7.292623 6.67939 32.01114 7.292624 6.491446 33.26857 7.292623 7.036424 33.46735 7.292623 6.829147 34.25702 7.292628 7.618942 34.49512 7.292619 7.543701 35.06079 7.292622 8.700776 34.99673 7.292624 8.733269 35.50943 7.292623 9.558472 34.92801 7.292619 9.990693 35.32094 7.292621 10.30063 34.54401 7.292625 10.83673 34.70874 7.292642 10.81564 33.8548 7.29263 11.47627 33.5817 7.292623 11.01778 33.04406 7.292623 11.36014 32.10956 7.292625 16.81564 33.85474 7.292626 17.2283 34.18368 7.292627 17.03106 32.87752 7.292623 17.52223 32.94668 7.292623 17.26953 31.93311 7.292621 16.5028 31.62891 7.292623 16.46234 30.91969 7.292624 15.3074 30.98933 7.292623 14.83038 30.46294 7.292623 14.28021 31.12787 7.292619 13.45673 31.00501 7.292622 13.44836 31.68445 7.292621 12.6794 32.01117 7.292624 12.9658 32.95138 7.292623 12.50427 33.49137 7.292623 13.4795 34.38474 7.292623 13.36645 34.95036 7.292629 14.70073 34.99671 7.292623 14.50864 35.4603 7.292623 15.58426 35.45499 7.292623 16.03258 34.77871 7.292623 16.52173 34.99451 7.292628 20.96307 30.96632 7.292623 20.62596 30.50585 7.292623 19.69321 31.4411 7.292621 19.45667 31.00507 7.292622 18.67938 32.01117 7.292622 19.0034 32.60833 7.292623 18.50427 33.49139 7.292623 19.14355 33.79255 7.292627 19.21649 34.78505 7.292617 19.6517 34.48678 7.292623 20.36789 34.91749 7.292625 20.31316 35.42827 7.292625 21.38284 34.98237 7.292624 21.80365 35.41399 7.292623 22.3006 34.54401 7.292623 22.83679 34.70862 7.292613 22.95611 33.56116 7.292623 23.47627 33.58169 7.292623 22.94917 32.52455 7.292623 23.29159 31.89715 7.292623 22.39763 31.49283 7.292623 22.08965 30.7025 7.292623 17.02269 32.77907 8.692624 16.54273 31.6995 8.692625 15.54841 31.04126 8.692624 14.19566 31.13169 8.692627 13.20001 32.05186 8.692624 12.99372 33.03112 8.692624 13.17915 33.87129 8.692618 13.8349 34.6488 8.692626 14.96303 35.03525 8.692624 16.24933 34.60687 8.692625 16.84064 33.79956 8.692621 11.03106 33.12406 8.692623 10.81564 32.14669 8.692621 10.16989 31.33592 8.692624 9.04245 30.98298 8.692625 8.223816 31.15045 8.692628 7.386291 31.76128 8.692625 6.985816 32.87277 8.692624 7.118431 33.69774 8.692614 7.820358 34.68473 8.692621 9.128899 35.0149 8.692624 10.09485 34.69623 8.692618 10.6792 34.09912 8.692628 22.88811 32.28776 8.692627 22.42745 31.59065 8.692646 21.54839 31.04127 8.692625 20.54773 31.04593 8.692626 19.76544 31.40418 8.692639 19.2338 32.04877 8.692623 18.98581 32.87283 8.692624 19.24821 34.03598 8.692625 20.13019 34.82197 8.692618 20.9451 35.00653 8.692625 21.95996 34.79489 8.692622 22.95559 33.63558 8.692623 15.69806 30.59175 9.492624 16.70703 34.8584 9.492622 12.82912 34.25694 9.492624 14.62598 30.50586 9.492625 13.54367 35.06077 9.492624 14.73329 35.50944 9.492625 15.77057 35.38757 9.492623 17.47626 33.58172 9.492624 13.65295 30.88507 9.492624 12.88004 31.63324 9.492624 12.45726 33.06254 9.492624 17.41738 32.33222 9.492628 16.79303 31.19676 9.492625 3.8 7.292877 26.32938 3.8 8.419808 26.96888 3.799999 9.89209 26.85277 3.8 10.76349 26.27692 3.8 11.45014 25.17817 3.8 11.39661 23.70235 3.8 10.55012 22.47547 3.799999 9.160786 21.9749 3.8 8.129578 22.14063 3.8 7.216492 22.70917 3.8 6.573269 23.80575 3.8 6.587561 25.29623 3.8 11.49571 12.11863 3.8 11.11639 11.14545 3.8 10.36833 10.37263 3.8 9.387223 10.01445 3.8 8.312851 10.06542 3.8 7.395782 10.56525 3.8 6.724251 11.40543 3.8 6.493586 12.42408 3.8 6.680588 13.48322 3.8 7.292831 14.32936 3.8 8.419804 14.96889 3.8 9.669373 14.91 3.8 10.62733 14.42101 3.8 11.3613 13.38287 16.46234 35.08186 27.49262 14.73329 30.4921 27.49262 15.28098 35.49311 27.49262 14.20969 35.39659 27.49262 13.31467 34.85828 27.49262 12.6794 33.9904 27.49262 15.77054 30.61392 27.4926 16.8785 31.28595 27.49262 17.26959 34.0683 27.49263 12.50427 32.51015 27.49262 13.36642 31.05121 27.49263 17.53883 32.84671 27.49262 27 8.211487 26.88879 27 7.143143 26.19962 27 6.546553 25.07687 27 6.573273 23.80576 27 7.216492 22.70911 27 8.510193 21.99688 27 9.800477 22.1154 27 10.70699 22.63428 27 11.39661 23.70235 27 11.47778 24.97115 27 10.92987 26.11841 27 9.701279 26.93776 27 9.27797 15.02097 27 7.62809 14.63392 27 6.680593 13.48323 27 6.492105 12.22591 27 6.940758 11.03632 27 7.744659 10.32172 27 8.939017 9.949872 27 10.55013 10.47548 27 11.31362 11.52234 27 11.53078 12.75432 27 10.80478 14.28564 6.608408 11.96577 3.692616 6.121622 9.817096 3.693676 7.613263 13.99343 3.708682 12.32774 17.50675 3.698947 9.119932 15.6817 3.692589 10.33366 16.57938 3.69259 15.16184 17.92628 3.695915 17.60613 17.51069 3.692574 19.72617 16.56098 3.693657 21.80244 14.78151 3.700947 23.10998 12.66668 3.692574 23.77308 10.5617 3.691122 23.89449 8.441905 3.689848 23.61282 6.758217 3.692575 22.75394 4.599903 3.693642 21.06422 2.449789 3.70085 19.00678 1.05373 3.692669 16.92836 0.3060709 3.683954 14.69767 0.1049249 3.697124 13.21607 0.2887358 3.68771 11.72731 0.7211339 3.69681 10.33372 1.422164 3.692644 8.39921 2.990995 3.692635 6.849355 5.386951 3.698969 6.228026 7.496659 3.692621 11.43648 32.40557 6.492621 10.87849 31.28594 6.492624 9.770569 30.61394 6.492622 8.524659 30.50209 6.492622 7.06041 31.35535 6.492625 6.457249 32.93902 6.492621 6.982834 34.55011 6.492621 8.403885 35.47343 6.492621 9.69806 35.40979 6.492619 10.62573 34.9299 6.492619 11.44515 33.70122 6.492622 17.34246 32.00967 6.492622 16.36852 30.88139 6.492626 15.16109 30.48312 6.492621 13.91275 30.72427 6.492621 12.81026 31.70677 6.492617 12.48339 33.36964 6.492622 13.02501 34.54678 6.49262 13.81625 35.22862 6.492626 14.85571 35.50474 6.492621 15.69806 35.40976 6.492624 16.62567 34.92987 6.492614 17.44514 33.70126 6.492621 23.52223 33.05487 6.492622 23.30082 32.0023 6.492622 22.707 31.14317 6.492621 21.7706 30.61397 6.49262 20.7333 30.49211 6.492621 19.36646 31.05124 6.492625 18.50427 32.51015 6.492622 18.67941 33.99042 6.492619 19.45674 34.9965 6.492625 20.83057 35.53868 6.491474 22.09522 35.2572 6.492622 23.07208 34.47589 6.492623 12.49145 32.73299 8.692622 12.82916 31.74457 8.692621 13.71939 30.80316 8.692622 15.16108 30.48312 8.692622 16.36839 30.88135 8.692617 17.09905 31.62792 8.692618 17.53883 32.84671 8.692624 17.26959 34.06836 8.692629 16.46231 35.08188 8.692627 14.83037 35.5386 8.692624 13.4567 34.99646 8.692625 12.67939 33.99039 8.692624 7.422975 35.8836 6.693169 6.893772 35.58732 6.634464 6.51197 35.22929 6.716881 6.627501 35.12732 6.511025 7.89698 35.97957 6.671989 7.58865 35.76534 6.5002 22.23261 35.80294 6.508675 23.1933 35.53615 6.683136 22.6183 35.86617 6.651283 23.16366 35.31966 6.497334 23.47868 35.22553 6.669922 9.80365 30.58757 8.692623 10.83679 31.29291 8.692612 11.39618 32.21158 8.692627 11.47681 33.48032 8.692625 11.05658 34.43634 8.692623 10.27634 35.17685 8.69262 9.053029 35.52302 8.692625 7.816254 35.22862 8.692632 6.750027 34.18695 8.692624 6.501854 32.5176 8.692638 7.36644 31.05121 8.692625 8.508728 30.54125 8.692623 21.35617 30.51806 8.692624 22.3685 30.88139 8.692624 23.22831 31.81792 8.692627 23.50202 32.82587 8.692625 23.36011 33.892 8.692626 22.62579 34.92987 8.692616 21.26174 35.53076 8.692623 19.81616 35.22858 8.692625 19.02501 34.54675 8.692614 18.55209 33.60437 8.692568 18.52908 32.55855 8.692585 19.06044 31.35535 8.692624 20.31308 30.57328 8.692622 11.00138 31.44179 24.69263 11.55 31.50078 24.69262 3 9.1549 27.03144 3 7.72348 26.66821 3 6.702482 25.58224 3 6.496805 24.34829 3 6.772964 23.30881 3 7.454773 22.51758 3 8.417557 22.03816 3 9.906113 22.1157 3 11.19837 23.212 3 11.51843 24.65367 3 11.22305 25.65558 3 10.54324 26.48898 3 9.581727 14.96889 3 7.897156 14.78423 3 6.824666 13.76898 3 6.462935 12.32301 3 6.885178 11.14545 3 7.814606 10.24263 3 9.491383 9.996886 3 10.95036 10.85907 3 11.50944 12.22591 3 11.32094 13.48328 3 10.70859 14.32947 6.525009 35.23021 30.31799 7.79776 35.98197 30.27396 7.897888 35.83197 30.47533 6.715118 35.19865 30.47845 7.378662 35.86349 30.3103 7.15844 35.58586 30.47537 6.860336 35.5729 30.30672 23.11454 35.6049 30.24201 23.482 35.2256 30.30542 23.15384 35.42468 30.45914 22.2094 35.9774 30.29652 22.38238 35.79119 30.48179 22.71203 35.82694 30.28656 25.30896 32.09169 6.504056 25.48763 32.14501 6.680572 26.57174 5.500775 21.49262 27 6.160235 21.49262 26.57174 5.500775 27.49262 27 6.160235 27.49262 27 12.00078 27.49262 27 12.00078 21.49262 26.57174 5.500775 9.492624 27 6.160235 9.492624 26.57174 5.500775 15.49262 27 6.160235 15.49262 27 12.00078 15.49262 27 12.00078 9.492624 24.7 7.699524 20.03536 24.7 10.00577 16.75595 24.7 9.215012 16.48578 24.7 8.360993 16.59086 24.7 7.506424 17.11156 24.7 7.19566 19.36875 24.7 9.793656 20.3666 24.7 10.64882 17.3276 24.7 8.617112 20.47406 24.7 6.970504 18.35693 24.7 11.00771 18.27923 24.7 10.79493 19.45255 26.2 23.70078 21.49262 26.2 23.70078 27.49262 26.2 22.00078 21.49262 26.2 12.30078 27.49262 26.2 12.30078 21.49262 23.12407 0.4187222 30.31507 22.60263 0.1210384 30.26341 22.09664 0.01093673 30.25777 22.5722 0.3114166 30.49059 23.30544 0.8166275 30.47614 23.46411 0.7526398 30.30547 22.30267 0.1056518 30.41164 23.38535 0.639534 6.707954 23.26632 0.5856133 6.591896 23.16794 0.7204857 6.496222 22.39049 0.2308692 6.505374 22.12103 0.03195714 6.639213 22.7259 0.1724483 6.670567 13.31005 0.2363424 6.494009 16.10705 0.1535348 6.524626 18.31842 0.7425631 6.492622 20.31125 1.819536 6.492619 22.40026 3.999192 6.492624 23.64376 6.750223 6.492618 23.9 9.000777 6.492622 23.64375 11.25135 6.492619 22.40014 14.00246 6.49263 20.88001 15.68176 6.492622 19.02112 16.97637 6.492618 16.13452 17.86038 6.492622 13.86954 17.82869 6.492622 11.66966 17.28864 6.492628 9.098863 15.70573 6.492632 7.20228 13.35683 6.492611 6.196533 10.51028 6.492621 6.196536 7.491256 6.492619 7.202295 4.644731 6.492631 9.098855 2.295817 6.492629 10.99319 1.053736 6.492622 7.277571 0.1868724 30.31474 6.86727 0.4092574 30.25665 6.580616 0.7121887 30.34503 7.740631 0.03737068 30.33196 6.910812 0.5680475 30.47831 7.882041 0.02974081 6.645524 7.63981 0.2521095 6.497309 6.693995 0.7730675 6.513912 6.516312 0.7667275 6.717525 7.421242 0.1232461 6.670181 6.898209 0.4047245 6.650299 4.723289 3.912426 6.497998 4.707903 32.09075 6.500954 6.654747 35.41624 9.492625 23.1482 35.63636 9.492633 20.3923 30.02054 9.492622 19.34662 30.45593 9.492628 18.39835 31.39288 9.492624 6.489514 33.25755 9.492634 6.622787 32.20099 9.492618 7.141602 31.29465 9.492626 8.209717 30.60496 9.492622 9.685517 30.5514 9.492626 10.92847 31.37424 9.49263 11.52835 32.7236 9.492623 11.30083 33.99927 9.492628 10.70694 34.85852 9.492627 9.77063 35.3876 9.492621 8.524674 35.49945 9.492624 7.060471 34.64625 9.492633 18.4829 32.84402 9.49264 18.88004 31.63318 9.492627 19.65283 30.88519 9.492637 20.62598 30.50585 9.492624 22.08965 30.7025 9.492624 23.17554 31.72346 9.492629 23.53883 33.15487 9.492624 22.87845 34.71561 9.492622 21.38425 35.51507 9.492623 19.71941 35.19839 9.492623 18.72393 34.08891 9.492621 9.687546 30.56362 24.69262 17.53883 33.15485 28.29262 17.07211 31.52573 28.29262 15.8903 30.64029 28.29263 14.85571 30.4968 28.29262 13.61423 30.86795 28.29262 12.58192 32.21191 28.29262 12.5728 33.68869 28.29263 13.21652 34.78503 28.29263 14.31311 35.42825 28.29262 15.35617 35.48347 28.29262 16.36847 35.12012 28.29261 17.099 34.37372 28.29261 20.13376 30.04786 27.49262 18.3887 31.35427 27.49262 11.47627 33.58171 28.29262 11.47627 32.41984 27.49262 11.29158 31.89713 28.29262 10.56166 30.99314 27.49263 10.27634 30.82462 28.29262 9.161103 30.48312 27.49262 9.280915 30.50843 28.29262 8.209717 30.60497 28.29261 8.100098 30.65962 27.4926 7.216492 31.21649 27.49262 7.314636 31.14331 28.29268 6.581928 32.21189 28.29262 6.504263 32.51016 27.49262 6.623072 33.90609 28.29262 6.750027 34.18695 27.49263 7.719421 35.19839 28.29262 7.994553 35.3371 27.49263 9.384255 35.51508 28.29262 9.685532 35.45014 27.49261 10.70703 34.85837 28.29262 10.7843 34.76343 27.49258 11.36014 33.89203 27.49263 23.53883 33.15486 28.29262 23.52836 33.27794 27.49262 23.30082 32.00233 27.49261 23.0721 31.52573 28.29262 22.70699 31.14317 27.49262 22.09515 30.74435 28.29262 21.58426 30.54657 27.49262 20.83039 30.46294 28.29262 20.5087 30.54123 27.49263 19.5437 30.94071 27.4926 19.27368 31.13281 28.29262 18.8291 31.74457 27.4926 18.54553 32.41757 28.29261 18.49145 32.73299 27.49262 18.62307 33.90608 28.29261 18.62277 33.80044 27.49264 19.27373 34.86876 27.49261 19.37161 34.90839 28.29268 20.3132 35.4283 28.29262 20.83038 35.53861 27.49262 21.3562 35.48348 28.29262 22.27631 35.17691 27.49263 22.36847 35.12015 28.29261 23.05646 34.43652 27.49258 23.099 34.37378 28.2926 3.428258 5.500775 27.49262 3 6.160235 27.49262 3.428258 5.500775 21.49262 3 6.160235 21.49262 3 12.00078 21.49262 3 12.00078 27.49262 3.428258 5.500775 15.49262 3 6.160235 15.49262 3.428258 5.500775 9.492624 3 6.160235 9.492624 3 12.00078 15.49262 3 12.00078 9.492624 5.299999 7.902618 20.20566 5.299999 9.044041 20.5104 5.299999 9.631867 16.55816 5.299999 8.450501 16.55086 5.299999 7.441116 17.18576 5.299999 6.993837 18.27926 5.299999 10.02258 20.23309 5.299999 10.83942 19.36429 5.299999 10.59737 17.25803 5.299999 10.99672 18.1934 5.299999 7.144635 19.28513 3.8 12.30078 21.49262 3.8 12.30078 27.49262 3.8 22.00078 21.49262 3.8 23.70078 27.49262 3.8 23.70078 21.49262 10.71302 31.9026 28.29262 9.642838 31.0702 28.29262 8.287369 31.09485 28.29262 7.352447 31.83505 28.29264 7.027714 32.63179 28.29262 7.065538 33.63187 28.29263 7.651794 34.48688 28.2926 8.523163 34.97892 28.29262 9.712128 34.88922 28.29261 10.65765 34.18085 28.29263 11.01778 33.04407 28.29262 17.02269 33.2225 28.29262 16.78265 32.05448 28.29261 16.21726 31.4057 28.29266 15.46736 31.03738 28.29263 14.28734 31.09483 28.29262 13.45813 31.71686 28.29256 13.05823 32.45047 28.29262 13.03641 33.46733 28.29262 13.41995 34.23749 28.29263 14.05295 34.78299 28.29263 15.20935 35.02478 28.29262 16.43442 34.444 28.29262 20.96307 30.96632 28.29262 19.97394 31.27643 28.2926 19.35248 31.83505 28.29261 19.0277 32.63187 28.29262 19.03643 33.46733 28.29262 19.61897 34.49515 28.29259 20.70076 34.99672 28.29261 21.8717 34.83942 28.29261 22.64526 34.14941 28.29258 22.98144 33.38444 28.29262 22.87397 32.2079 28.29261 22.0948 31.30527 28.29262 7.676711 35.97107 27.49415 6.740056 35.52019 27.49262 23.23783 35.53563 27.49263 22.32237 35.97102 27.49365 25.30106 3.907417 6.501658 25.4884 3.85871 6.679268 27 24.00078 27.49262 27 24.00078 21.49262 23.55 30.50078 12.29262 27 24.00078 15.49262 27 24.00078 9.492624 4.518375 3.860979 6.653831 20.33331 30.45033 9.492623 18.95012 31.34204 9.492624 3 24.00078 9.492624 3 24.00078 15.49262 6.449999 30.50078 12.29262 3 24.00078 21.49262 3 24.00078 27.49262 20.16521 30.48927 27.49262 18.92799 31.39285 27.49263 10.99607 33.29911 29.69262 10.83327 32.11787 29.69262 10.16864 31.36975 29.69262 9.382798 31.01916 29.69262 8.195679 31.13168 29.69262 7.304016 31.90677 29.69262 6.985817 32.87278 29.69262 7.248203 34.03597 29.69263 8.28743 34.90672 29.69262 9.467408 34.96414 29.69262 10.50279 34.37263 29.69263 16.95611 32.4404 29.69262 16.3006 31.45747 29.69263 15.20941 30.97678 29.69262 14.05295 31.21851 29.69262 13.41998 31.76404 29.69264 13.03642 32.53419 29.69262 13.09845 33.72502 29.69263 13.8349 34.64876 29.69263 14.60696 34.96842 29.69262 15.46741 34.96415 29.69262 16.21741 34.59576 29.69262 16.87396 33.79365 29.69262 22.99647 32.80044 29.69262 22.65769 31.82074 29.69264 21.87637 31.19571 29.69261 21.04244 30.98298 29.69262 19.89139 31.29446 29.69262 19.06554 32.36966 29.69261 19.09847 33.72507 29.69262 19.6973 34.52688 29.69262 20.45059 34.9428 29.69262 21.28507 34.98692 29.69262 22.09479 34.69632 29.69263 22.87398 33.79362 29.69261 11.45446 32.41756 29.69262 6.497978 33.17568 29.69262 6.77169 34.18364 29.69262 7.800079 35.24346 29.69262 9.790345 30.60496 29.69263 9.475342 35.49945 29.69262 10.78351 34.785 29.69261 11.4272 33.68867 29.69262 10.85835 31.29456 29.69263 6.63987 32.1095 29.6926 7.215759 31.2381 29.6927 8.314469 30.55139 29.69262 17.3772 32.20102 29.69262 15.56549 30.55725 29.69263 16.72627 31.13278 29.69262 14.52151 30.52375 29.69263 13.37421 31.07169 29.6926 12.63985 32.10956 29.69263 12.77169 34.18365 29.69264 13.6315 35.12018 29.69261 14.6438 35.48347 29.69261 15.6868 35.42827 29.69262 16.78348 34.78509 29.6926 17.49574 33.49136 29.69262 12.49798 33.17568 29.69262 23.51661 32.6319 29.69262 19.00364 34.54321 29.69266 22.97496 31.45474 29.69261 23.3519 33.87195 29.69264 22.78351 34.78503 29.6926 21.89978 35.34198 29.69261 20.83892 35.51843 29.69262 19.83716 35.22299 29.69256 22.0054 30.66441 29.69262 18.50491 33.37371 29.69262 18.63988 32.10953 29.69262 19.21564 31.23822 29.6926 20.31448 30.55139 29.69261 4.516617 32.13922 30.32975 25.26839 32.08628 30.48791 25.48761 3.856565 30.30467 14.12832 4.839412 32.29264 14.62597 5.495703 32.29262 17.52223 3.054872 32.29262 16.82085 2.130203 32.29262 17.30081 2.002319 32.29261 16.70696 1.143143 32.29258 16.16502 1.352737 32.29262 15.38423 0.4864631 32.29262 15.03696 0.9663098 32.29262 13.71941 0.8031616 32.29263 13.9052 1.30529 32.29262 15.29921 4.996717 32.29262 15.89025 5.361282 32.29261 16.38103 4.495163 32.29264 17.07211 4.47583 32.29263 17.01226 3.293671 32.29262 13.04442 2.365955 32.29262 12.62307 2.095459 32.29262 12.58193 3.789638 32.29261 13.16671 3.883659 32.29261 13.45671 4.996471 32.2926 17.43647 3.595978 33.49263 16.87849 4.715607 33.49261 15.58425 5.455 33.49262 14.10922 5.383194 33.49262 12.9406 4.458 33.49262 12.53465 3.461975 33.49261 12.54553 2.417541 33.49262 13.27372 1.13279 33.49261 14.83038 0.4629364 33.49262 16.46236 0.9196816 33.49262 17.44515 2.300285 33.49261 18.96894 8.877507 32.29262 19.25956 10.0226 32.29263 18.67941 9.990403 32.29262 19.61422 11.13361 32.29264 23.01226 9.293671 32.29262 23.49509 8.627823 32.29262 22.75182 7.965599 32.29261 23.099 7.627899 32.29263 22.36848 6.881374 32.29262 21.71263 7.094844 32.29262 20.95379 6.457693 32.29262 20.53262 7.037392 32.29261 19.54367 6.94075 32.2926 18.49217 8.962857 32.29262 18.72394 7.912598 32.29262 19.49719 7.628906 32.29263 21.63222 10.91745 32.29261 22.27631 11.17693 32.29261 22.48666 10.36569 32.29263 23.29158 10.10445 32.29262 20.28276 10.92765 32.29262 21.05297 11.52303 32.29262 23.52223 8.946681 33.49262 23.14124 10.3735 33.49262 21.99063 11.32094 33.49262 20.73327 11.50944 33.49261 19.54369 11.06081 33.49264 18.8291 10.25693 33.49261 18.49145 9.268574 33.49261 18.67938 8.011124 33.49263 19.31461 7.14328 33.49262 20.20972 6.604946 33.49262 21.68552 6.551397 33.49262 23.0721 7.525711 33.49264 11.01226 9.293625 32.29262 11.53883 8.846676 32.29262 10.7518 7.965584 32.29261 10.99633 7.458317 32.29262 9.869786 7.179568 32.29262 9.990612 6.680593 32.29261 8.87113 6.986648 32.29262 8.931452 6.493585 32.29261 7.912796 6.724266 32.29261 8.069642 7.222992 32.29262 7.286983 7.902611 32.29261 6.810261 7.706772 32.29262 6.982217 9.044045 32.29262 6.48227 9.160783 32.29261 7.342321 10.18083 32.29263 6.792114 10.19071 32.29258 7.456726 10.99648 32.2926 8.123826 10.80588 32.29265 8.434586 11.44434 32.2926 9.135691 11.03105 32.29262 9.478524 11.47778 32.29262 10.38103 10.49516 32.29261 10.46072 11.03961 32.29257 11.17557 10.27808 32.29262 11.52835 8.723603 33.49262 11.22831 10.18365 33.49261 10.52173 10.99451 33.49258 9.384236 11.51508 33.49262 8.100098 11.34189 33.49266 7.060451 10.64624 33.49261 6.534646 9.461998 33.49261 6.545526 8.417572 33.49263 7.141647 7.294556 33.4926 8.209717 6.604938 33.49259 9.68552 6.551396 33.49262 10.9284 7.374168 33.49261 15.97258 16.81223 32.29262 16.46236 17.08185 32.2926 17.44513 15.70129 32.29261 14.61716 16.98238 32.29262 14.83036 17.53861 32.29262 16.8565 15.79245 32.29261 17.00667 14.97454 32.29262 17.39617 14.21151 32.29261 16.56166 12.99313 32.29261 16.16502 13.35273 32.2926 16.82084 14.13022 32.29261 15.2134 12.99384 32.29262 15.16105 12.48311 32.29262 14.04008 13.20663 32.29262 13.71939 12.80318 32.29262 13.3208 13.90247 32.29266 12.82907 13.74466 32.2926 12.96894 14.87748 32.29262 12.49145 14.73299 32.29262 12.75001 16.18692 32.29263 13.43411 16.33317 32.29262 13.65282 17.11638 32.2926 17.34247 15.99185 33.49262 16.3685 17.12018 33.49264 15.16106 17.51843 33.49262 13.91275 17.27727 33.49261 13.07266 16.60577 33.49266 12.5728 15.6887 33.49261 12.54553 14.41756 33.49262 13.14168 13.29459 33.49261 14.20973 12.60493 33.49262 15.68555 12.55141 33.49262 16.78438 13.23819 33.49261 17.44514 14.30029 33.49263 13.12495 0.3005341 33.49262 15.09376 0.08025646 30.49262 15.44696 0.08674931 33.49269 17.60612 0.4908918 33.49262 19.79599 1.469223 33.49261 22.03107 3.497131 33.49257 23.10993 5.334854 33.49262 23.86507 7.826681 33.49258 23.74001 10.7886 33.49261 22.72833 13.47284 33.49261 20.79712 15.79193 33.4926 18.20361 17.33521 33.49261 16.13046 17.82869 33.49262 13.7321 17.83923 33.49262 10.86002 16.91191 33.49259 8.460999 15.08084 33.49258 6.809017 12.55515 33.49261 6.092806 9.623394 33.49261 6.394188 6.620514 33.49264 7.230174 4.66029 33.49262 8.647873 2.725723 33.49259 11.10104 0.9680941 33.49261 17.01226 14.70788 30.49262 16.381 13.50637 30.49262 15.45229 13.04591 30.49262 14.61716 13.01917 30.49261 13.83142 13.36972 30.49259 13.16672 14.11787 30.49262 13 15.00078 30.49262 13.12603 15.79365 30.49262 13.90517 16.69625 30.49261 14.8711 17.0149 30.49262 16.02446 16.75887 30.49262 16.82085 15.87134 30.49263 10.97854 9.45324 30.49263 10.93915 8.462265 30.49261 10.38103 7.506399 30.49263 9.135694 6.970503 30.49262 7.978912 7.259888 30.49263 7.079685 8.266152 30.49262 7.12603 9.793653 30.49263 8.184552 10.88819 30.49263 9.712609 10.90672 30.49263 10.54196 10.2847 30.49258 23.02858 9.052578 30.49262 22.76633 8.048798 30.49268 22.23464 7.404205 30.49261 20.96566 6.945026 30.49262 19.69937 7.457504 30.49262 19.1843 8.146729 30.49259 18.98222 8.957509 30.49262 19.15932 9.79953 30.49259 19.75065 10.60686 30.49262 20.8711 11.0149 30.49262 22.02446 10.75888 30.49261 22.73666 10.00574 30.49258 17.00768 3.206028 30.49262 16.8 2.051865 30.49262 15.80432 1.131691 30.49262 14.6172 1.019164 30.49262 13.83136 1.369705 30.49263 13.16673 2.117859 30.49262 13 3.000775 30.49262 13.12602 3.793632 30.49262 14.04007 4.794922 30.49262 15.38026 4.999727 30.49262 16.55164 4.317154 30.49262 18.52319 9.480332 30.49262 19.20699 10.80481 30.49261 20.3019 11.40979 30.49263 21.59606 11.47345 30.49262 23.01715 10.55009 30.49262 23.53839 8.937213 30.49265 23.05939 7.543564 30.49261 21.89076 6.618354 30.49261 20.64384 6.518066 30.49263 19.63152 6.881393 30.49261 18.65753 8.009705 30.49262 7.72364 11.17689 30.49263 8.947035 11.52303 30.49262 10.38578 11.13361 30.49261 11.37827 9.875618 30.49262 11.48786 8.62697 30.4926 11.17088 7.744614 30.49259 10.28059 6.803168 30.49263 9.068549 6.493587 30.49263 7.80011 6.758083 30.49263 6.657534 8.009697 30.49263 6.523191 9.480343 30.49262 6.943467 10.43652 30.49261 22.85111 9.8956 27.49262 19.08307 9.632187 27.49263 21.1357 6.970503 27.49262 22.38104 7.506409 27.49262 22.96357 8.534195 27.49263 21.86981 10.82198 27.49262 19.8773 10.72322 27.49262 19.07969 8.266137 27.49262 19.9789 7.259903 27.49264 21.05489 11.00652 27.49262 18.98222 9.044057 29.69262 19.15935 8.202057 29.69263 19.63437 7.514664 29.6926 20.69263 6.989325 29.69262 21.86976 7.179552 29.69261 22.75181 7.965607 29.6926 23.01417 9.128823 29.69262 22.61372 10.24026 29.69263 21.63222 10.91743 29.69262 20.77519 10.99464 29.69262 19.83009 10.66562 29.69263 19.18436 9.854889 29.69263 23.18976 10.29475 29.69264 22.08722 11.27727 29.69261 20.83895 11.51843 29.69262 19.43833 11.00841 29.69262 18.60382 9.790009 29.69261 18.5232 8.52121 29.69262 18.94345 7.565002 29.69264 19.7236 6.824676 29.69262 21.16963 6.462937 29.69262 22.72628 7.132797 29.69263 23.51609 8.632654 29.69267 11.03419 9.050181 27.49262 7.083059 9.632166 27.49263 10.16502 10.64882 27.4926 7.634405 10.48687 27.49264 10.73669 10.00577 27.49262 9.213414 11.00771 27.49262 8.383576 10.91024 27.49262 7.043884 8.440392 27.49262 9.135697 6.970505 27.49262 10.23461 7.404195 27.49262 10.7663 8.048798 27.49262 7.830109 7.335907 27.49262 6.998382 8.860871 29.69262 7.217339 8.054505 29.69261 8.040085 7.206623 29.69261 9.054839 6.995024 29.69262 9.869788 7.17957 29.69262 10.64754 7.835037 29.69262 11.00684 8.786568 29.69262 10.90176 9.640625 29.69261 10.38102 10.49516 29.69262 9.135697 11.03105 29.69262 7.830091 10.66562 29.6926 7.111892 9.713772 29.69262 10.92737 10.60577 29.69264 10.08726 11.27727 29.69262 8.838952 11.51843 29.69262 7.438337 11.00842 29.69262 6.699163 9.999188 29.69264 6.47777 8.946684 29.69262 6.82444 7.72348 29.69262 7.910393 6.702476 29.69261 9.596081 6.528107 29.69261 10.85835 7.294586 29.69264 11.4479 8.397183 29.69257 11.44002 9.657325 29.69255 27 30.40078 15.49262 23.55 30.40078 11.29262 27 30.40078 9.492624 18.45 31.40077 11.29262 18.92799 31.39285 11.29262 9.666657 30.45032 11.29262 6.449999 30.40078 11.29262 3 30.40078 9.492624 11.0499 31.34207 11.29262 9.64853 30.45565 25.69262 11.08065 31.35231 25.69262 18.95009 31.34209 25.69263 20.33331 30.45032 25.69262 20.16522 30.48927 11.29262 25.13443 41.57873 0.9053955 26.03455 40.9624 1.507446 25.6964 41.70605 1.055115 25.08131 43.00143 0.6448517 25.47614 42.47308 0.8582764 24.99477 42.47558 0.6810837 25.17786 39.55664 1.823975 25.61792 39.70068 1.705322 25.52426 40.65442 1.242004 26.43311 39.43384 2.238403 26.41205 38.59888 2.461975 26.8059 36.22812 3.781433 26.93147 35.72089 3.984009 27.94423 36.52834 3.348186 27.27875 35.95283 3.474426 27.61088 36.33552 3.306076 26.41284 36.98877 3.540649 27.42682 37.49798 3.116211 26.86086 36.78332 3.351074 26.49359 37.61645 2.980225 27.00906 37.46783 3.02977 26.91422 38.30401 2.770172 29.1526 35.93234 3.854767 29.19804 36.15698 3.664246 28.22463 36.09366 3.6586 28.03284 35.89447 3.838623 27.68988 35.57922 4.417725 28.58064 36.47341 3.493092 29.17558 36.49321 3.516375 29.25673 35.69079 4.359131 29.65263 36.12407 3.965702 29.79284 36.16894 4.186638 29.97722 36.54483 4.299973 29.78951 36.53715 3.878693 29.4901 36.50944 3.629684 4.483566 40.46301 1.315613 5.279587 43.93318 0.5333405 5.543327 43.36703 0.5050783 4.672615 42.62794 0.7519493 5.005829 41.84381 0.8165894 4.104919 41.40933 1.273682 4.356476 41.32129 1.093811 3.556457 39.44696 2.253357 3.630859 38.61426 2.437256 4.395508 39.42334 1.858887 2.654419 36.01906 3.428856 3.028175 36.22058 3.599518 3.074242 35.71188 3.998535 3.320932 36.40716 3.877869 2.538116 37.35547 3.137985 2.324738 36.42742 3.284019 3.873291 37.54272 3.213867 4.76416 39.23047 2.047852 3.002869 38.12524 2.840454 3.100052 37.20117 3.138 3.434051 37.13159 3.303955 1.747665 36.50989 3.444168 0.9441834 36.32907 3.565475 1.8172 36.21149 3.562683 2.053955 35.91791 3.762207 0.9890747 36.06464 3.727478 0.8429566 35.90637 3.89386 0.5326996 35.93921 4.028564 0.05177116 36.56864 4.129906 0.1172163 36.3075 4.202026 0.6063538 36.27493 3.667908 0.2844963 36.04016 4.243042 0.3514404 36.41913 3.7547 0.7621384 36.5762 3.514265 29.14295 36.48669 33.47165 29.96858 36.51273 32.71643 29.75613 36.1382 32.81686 29.53424 36.53683 33.33496 29.25882 36.31232 33.38266 29.13061 36.07992 33.27352 29.82208 36.55846 33.06158 29.17642 35.85791 32.99975 29.62573 36.26169 33.15179 28.55358 36.00794 33.22264 28.32752 36.53229 33.52209 27.14296 35.86484 33.34863 27.87012 35.87755 33.16644 27.41145 36.10354 33.59627 27.69904 36.43636 33.69726 27.16184 36.81152 33.74499 26.92653 35.71382 32.979 26.701 36.43378 33.20846 27.25391 37.59302 33.95117 25.98865 37.71387 33.83533 26.79761 38.5542 34.33154 26.3877 39.5957 34.81787 26.67969 37.47815 33.96924 26.22632 38.00928 34.23035 26.25342 38.94336 34.72363 25.61389 39.28662 35.04834 25.33801 40.55517 35.70489 25.55048 41.14368 35.89136 25.88617 41.43396 35.72461 24.72119 43.82959 36.45056 25.06946 42.82153 36.33743 25.51758 42.24121 36.08783 24.8385 41.77014 36.15576 0.7857361 36.625 33.47225 0.2531128 36.17556 32.90858 0.4909287 35.94183 32.89526 0.8595886 45.9064 33.4707 0.8042288 36.08999 33.26879 0.4461975 36.5611 33.32681 0.09563446 36.43022 32.9013 0.4686356 36.31319 33.2664 0.01479196 36.62274 32.68473 0.9402924 36.3688 33.43997 0.8495979 35.90878 33.09805 2.657989 36.03265 33.54559 1.549103 36.45976 33.4897 2.337547 36.39044 33.69393 2.061279 35.57153 32.51391 1.565506 36.00621 33.25019 3.533813 39.48572 34.7135 3.657471 38.9834 34.70532 3.074245 35.6864 32.9169 2.873888 35.86245 33.35492 2.603516 37.29639 33.86011 3.407525 36.61891 33.25947 3.860802 37.49968 33.73227 3.033691 38.20239 34.1676 4.540162 38.67972 34.53056 4.264404 39.04492 34.9032 3.152435 37.10834 33.81412 3.618957 37.9956 34.24432 4.236786 41.4743 35.85095 3.907471 41.09082 35.39429 4.555176 40.349 35.62488 5.243774 42.75378 36.37094 4.870239 43.06103 36.31723 4.73407 42.38232 36.24036 4.789124 41.70557 36.11029 5.252624 40.74316 35.79742 25.12982 39.44495 35.08032 25.45146 38.65002 34.50134 25.20981 37.75598 33.50622 26.04154 36.60895 32.27612 26.85108 34.87345 30.09192 26.91531 35.44739 32.43359 26.51909 35.79294 31.40369 27.01025 34.13745 31.08405 26.99413 34.6641 31.47853 26.96369 34.40301 27.49282 25.35949 36.06008 29.60657 25.36147 35.96042 27.49404 25.94071 35.75627 27.49565 25.38055 36.62964 31.66357 25.19357 36.28564 30.63538 25.91616 36.0932 30.67847 26.316 35.56382 29.27515 25.34483 37.13702 32.63281 26.60101 35.20123 27.49351 4.688002 35.96152 27.49488 4.049499 35.77826 27.49263 3.960991 35.75631 29.38269 3.564369 35.44334 29.34528 3.341874 35.12194 27.49361 3.015393 34.32165 27.4929 4.61618 37.75586 33.52722 3.00776 34.61116 31.43174 3.188521 35.04751 30.32532 3.068214 35.27161 32.17578 3.575409 35.87863 31.31329 4.923614 39.4837 35.1037 4.08535 36.67697 32.22797 4.834076 36.86429 32.14184 4.498276 36.24475 30.58948 4.641047 36.05209 29.55274 25.53244 35.95965 9.492626 25.38138 36.00893 7.674194 26.05193 35.74045 7.668457 26.58723 35.26389 9.492494 26.71473 35.13003 7.513428 26.9826 34.33382 9.492438 25.52942 37.7793 3.400391 26.99549 34.66388 5.506348 26.93121 35.26501 4.825317 26.71338 35.53931 5.486084 25.50354 38.82324 2.297852 25.51007 37.13647 4.314697 25.37897 36.63037 5.321777 26.20114 36.08331 5.681885 25.50163 36.24475 6.395752 24.87631 40.6477 1.239136 5.171143 40.51343 1.289734 4.768677 38.4873 2.68335 4.581039 37.71387 3.499023 4.049665 36.92895 4.309326 3.175785 35.08328 6.453125 3.051445 35.1344 5.00415 3.544739 35.88269 5.578247 3.00951 34.11129 9.491402 2.998436 34.3728 5.72583 3.143671 34.74499 9.492202 3.293026 35.09057 7.589691 4.512299 36.04698 7.39917 4.458773 35.95352 8.434998 4.515648 36.63135 5.309326 4.619202 36.26922 6.345337 3.568426 35.38972 9.490637 4.790161 37.13721 4.366699 3.8237 35.793 6.768616 4.361465 35.94103 9.492624 24.58488 43.85748 0.5073724 26.02258 46.47888 1.444397 26.34796 46.30406 2.121338 25.86075 72.98036 1.220402 25.90864 47.65008 1.285263 25.64801 73.88135 0.9972229 25.22583 74.76673 0.7025604 24.53764 75.51442 0.499732 4.138833 72.96737 1.219731 5.134857 75.39543 0.5810013 4.547485 74.4442 0.836606 4.06695 47.12376 1.312386 3.758003 46.11345 1.894012 25.86235 72.91782 35.76758 24.27289 43.47494 36.48942 24.45477 75.81893 36.48619 25.26648 74.74762 36.26349 25.65442 73.8479 35.98059 25.93565 47.09369 35.66882 26.3523 45.91748 34.88367 5.427643 43.88019 36.4811 4.139503 72.98667 35.76373 4.072451 47.19018 35.6815 4.404724 74.08118 36.03989 4.820923 74.82556 36.30292 5.485443 75.59777 36.48612 29.98559 41.7082 10.0058 29.46011 42.31375 10.47168 29.50693 42.4137 10.24853 29.04834 42.40631 10.57898 29.86112 42.01651 10.22058 29.85715 41.73797 10.42334 28.73364 41.37805 11.27145 29.13507 41.45618 11.15683 29.51038 41.5758 10.91354 29.0047 41.86413 11.07971 29.18543 42.06836 10.89453 29.53705 42.01282 10.70764 17.26685 42.07727 10.95398 17.24886 41.61185 11.22731 28.85963 36.00052 15.69952 28.89486 36.22589 14.70166 28.78425 36.54101 13.99219 28.79396 37.17889 13.01355 28.90555 38.05566 12.20703 28.78313 39.06659 11.64658 29.00771 40.26044 11.29333 29.51044 35.66109 15.69867 29.48352 36.05224 14.23047 29.489 36.66699 13.16553 29.38943 37.26221 12.56812 29.2804 39.00452 11.4585 29.57806 38.12915 11.6499 29.63965 39.72058 10.90832 29.84809 35.80469 13.68311 29.84261 36.92322 12.10474 29.88762 35.15657 15.14453 29.88565 39.19397 10.6106 29.9832 35.90942 12.63818 29.99217 34.6297 15.60645 29.99159 38.64392 10.32269 17.20575 41.20966 11.31882 16.65588 41.99278 11.18262 16.76453 42.3612 10.68555 29.79901 35.32672 21.36969 29.28886 35.80896 21.29346 28.78632 36.00875 21.27063 16.49921 40.70877 12.14426 16.34996 41.22199 12.37958 15.84649 41.78197 12.52747 15.25512 42.02557 12.52161 15.81787 41.97543 11.8252 16.55042 40.89432 11.92123 15.54663 42.22406 11.32153 16.44092 41.27254 11.94031 16.78076 41.26576 11.54541 16.17002 41.60724 12.00058 16.73853 41.64928 11.39813 28.72076 41.2984 25.70727 28.77382 39.81183 25.58211 28.78428 38.70059 25.15231 28.85807 37.73056 24.52887 28.89496 36.9068 23.62024 28.78305 36.35461 22.62665 29.18391 41.38718 25.84794 29.18702 40.19955 25.78281 29.28032 38.99354 25.52173 29.3778 36.9884 24.13855 29.48972 36.24744 23.13501 29.38947 35.98456 22.33081 29.56128 38.12683 25.31531 29.64606 41.74019 26.23398 29.72168 39.68051 26.16171 29.80951 37.66431 25.40161 29.78003 36.63708 24.40064 29.78717 35.65314 22.77441 29.97969 39.78204 26.81375 29.9851 37.79101 26.07593 29.97817 35.92346 24.33838 29.98011 34.85818 21.91516 29.97255 41.8352 26.95258 14.75076 42.01059 12.68347 14.11428 41.77101 12.38815 13.71772 41.35625 12.22127 13.50514 40.85633 12.11431 15.12927 42.03438 24.28034 15.71878 41.85971 24.55927 16.01151 41.69581 24.78696 16.48006 40.9252 24.81575 28.84917 41.66678 25.79749 29.0842 42.18907 26.14813 29.2182 41.80379 25.95659 29.67105 42.08829 26.48267 29.18558 42.43078 26.50012 29.87308 41.71314 26.59808 29.61676 42.3136 26.69898 29.86043 42.68994 28.26025 13.02234 42.23859 10.81421 13.30929 41.13818 11.6608 14.67614 42.08758 11.9989 13.97217 42.25751 11.09497 14.0899 41.94357 11.82373 13.548 41.5614 11.70642 13.20935 41.61249 11.38721 13.01343 42.46863 10.43774 13.36551 41.92035 11.23981 14.66104 42.00199 24.41492 14.22225 41.8188 24.40671 13.78755 41.46358 24.70379 13.5084 40.82423 24.78398 15.36287 42.06567 24.95007 17.31271 41.24461 25.68764 17.23122 41.73793 25.80849 12.63635 41.25609 11.29193 12.98323 41.21589 11.39451 12.70819 41.78116 11.15585 16.32988 41.39014 24.95026 16.58158 40.91589 25.12914 14.71863 42.10818 25.00562 15.78592 42.27289 25.88721 15.98694 42.08203 25.53394 16.69873 41.7493 25.62592 16.74887 41.26391 25.40961 16.36749 42.01849 25.68457 16.9942 41.30426 25.5818 17.09613 42.09579 26.02835 17.08862 42.41608 26.42517 1.351532 41.35316 11.27789 0.8122559 42.39957 10.55695 13.37201 41.73196 25.57984 13.41246 41.03693 25.17268 13.55265 41.50772 25.26749 14.0531 41.866 25.06479 13.67129 42.12421 25.81397 13.07391 41.19543 25.53488 14.30493 42.20203 25.61377 13.60889 42.35553 26.21387 0.1657257 42.00044 10.29327 0.3998413 42.26578 10.36414 0.3162842 41.80325 10.69775 0.4672546 41.57045 10.8811 1.071411 41.5408 11.21974 0.7889404 41.60208 11.10074 0.9049378 42.05109 10.94543 12.70654 41.24774 25.68504 12.76469 42.02771 25.98866 12.872 41.61752 25.74768 12.98352 42.38463 26.36563 0.04089164 41.74391 10.15974 0.1456756 40.25165 10.50777 1.023537 42.0592 26.0228 1.264221 41.30838 25.70999 1.136642 39.83182 11.38728 1.104935 38.68225 11.82544 1.113693 38.01648 12.24451 0.9929962 37.39294 12.75391 1.10572 36.90686 13.36523 1.136749 36.34515 14.35522 1.213615 36.00876 15.71469 0.5935364 39.72076 11.14145 0.4878235 36.02661 14.23437 0.7113342 35.80901 15.69174 0.5297241 38.19012 11.72119 0.4381714 36.83868 12.78223 0.2010302 35.32677 15.61578 0.2199401 38.79437 11.00769 0.1482238 37.74341 11.45837 0.1565704 36.54034 12.53613 0.1188659 35.61229 13.79559 0.01886558 37.99745 10.67789 0.007296919 34.86933 14.24092 0.5754395 42.37619 26.58936 0.2837982 42.19095 26.68399 0.05057716 41.81424 26.80373 0.2588348 41.75209 26.36697 0.5692139 41.60336 26.01465 0.8282471 41.27331 25.84174 1.121246 41.58121 25.77116 0.6749363 41.99723 26.10387 1.131676 35.99506 21.21756 0.731247 35.85049 21.38428 0.2854004 35.42766 21.35297 0.1153278 35.19416 21.95035 0.007959604 34.92872 22.91898 0.3563233 40.4155 26.19461 0.8683319 42.42633 26.46887 1.216923 36.3477 22.61005 1.206402 37.1788 23.97165 1.244025 38.33711 24.95712 1.104935 39.48163 25.49072 0.9923477 40.26041 25.69186 0.8130608 38.65692 25.28157 0.7196865 36.17206 22.70007 0.5104694 36.66803 23.81836 0.6383991 37.56344 24.69461 0.4388428 38.94961 25.73465 0.3605156 35.8931 22.82202 0.2634776 37.36601 25.01733 0.1562442 38.80775 26.09491 0.1114306 35.94775 23.81226 0.02642583 39.38876 26.66851 0.01919376 36.95166 25.42625 17.29876 36.04019 21.25742 17.25742 36.35998 22.54273 17.16148 36.96478 23.58362 17.1742 37.48724 24.20917 17.18153 38.4373 24.96518 17.24955 39.86606 25.55947 16.8806 39.83377 25.35828 16.67864 39.20398 24.92224 16.52289 38.96069 24.46362 16.84023 38.20563 24.55963 16.68269 37.51227 23.69714 16.50924 37.85974 23.47168 16.81873 36.6344 22.59705 16.51863 36.9237 22.0318 16.77434 36.30453 21.26044 16.52453 36.74585 15.86609 16.87516 36.20647 15.86609 17.27012 36.04904 15.65289 17.26277 39.90845 11.41559 16.89911 39.82239 11.61536 16.61475 39.91333 11.93182 17.16156 38.77734 11.85425 17.1676 38.10693 12.25525 17.26392 37.25024 12.98901 17.23628 36.5769 14.01074 17.1613 36.28992 14.72595 16.9068 37.10205 13.46851 16.66958 37.62463 13.16516 16.72609 36.70636 14.47119 16.68265 38.57776 12.37634 16.51502 37.22504 14.33362 16.51082 38.73511 12.75745 12.85983 40.26007 25.59566 13.32919 39.81555 25.14609 13.48456 36.82263 21.71467 13.48189 37.87558 23.61755 13.45283 39.30701 24.68726 13.37239 36.86741 22.53718 13.23032 38.36066 24.60721 13.21227 36.31064 21.22579 13.15972 36.45917 22.15552 13.17956 37.41778 23.8344 12.8385 36.59265 22.97607 12.83834 38.77771 25.13147 12.75661 36.04725 21.28119 12.76303 36.98791 23.63861 12.76337 39.4862 25.43483 12.68922 36.26193 22.25 12.69233 37.77602 24.51722 13.48079 36.77735 15.69276 13.12188 36.20912 15.8078 12.67266 36.04034 15.69177 13.47657 37.87804 13.29491 12.91829 40.17184 11.41795 13.48302 39.23035 12.40077 13.35332 36.79097 14.5415 13.31965 39.43318 11.93106 13.16083 37.14783 13.47888 12.83843 39.43445 11.58173 12.8387 36.26904 14.79077 12.83903 36.56219 14.06885 13.19844 37.96051 12.65686 12.7729 38.38251 12.04468 12.72138 37.23004 13.0025 18.45 39.01733 11.68762 18.45 40.52414 11.29763 23.55 37.99981 12.29235 18.45 37.99903 12.29252 23.55 39.14691 11.63397 23.55 40.582 11.29675 6.449998 39.01745 11.68765 6.449999 40.52591 11.2973 11.54997 37.99951 12.29239 6.449999 37.99942 12.29251 11.55 39.14691 11.63397 11.55 40.58012 11.29704 11.55 39.01767 25.29771 11.55 40.52408 25.68761 6.450004 37.99981 24.69289 11.55 37.99902 24.69271 6.449999 39.14697 25.35127 6.449999 40.58194 25.6885 23.55 39.01752 25.29764 23.55 40.52589 25.68795 18.45003 37.9995 24.69285 23.55 37.9994 24.69273 18.45 39.14697 25.35127 18.45 40.58009 25.6882 0.01838302 44.49341 5.789307 0.01003432 45.8659 4.58989 0.2838593 44.66296 6.244751 0.7366943 43.66846 7.92334 0.7780762 42.98901 9.138428 0.7392273 44.41479 6.943359 0.7468872 45.31177 6.034424 0.4243622 46.30597 5.042908 0.2898712 43.09314 8.315674 0.02574396 43.00458 7.557129 0.8179932 46.44574 5.126648 0.5722294 46.55437 4.770874 1.008207 46.65781 4.732391 0.1704101 46.21754 4.747803 0.7749443 46.65852 4.368103 0.04146575 45.93163 4.254219 0.2878647 46.37147 4.293594 0.8675804 46.51446 3.942444 0.2120361 45.93801 3.896332 0.5042191 46.43614 4.018799 0.840992 46.15536 3.611206 0.5293884 45.92267 3.62323 0.8132305 45.81724 3.511209 0.7595062 35.41382 4.815796 0.8701782 34.61725 5.648437 1.648499 34.84778 5.415039 0.9002228 33.66797 6.195038 0.7588348 33.19635 6.366211 0.7677994 32.54774 6.484474 0.4375153 35.37756 5.114502 0.5352173 34.51294 5.841919 0.4720154 33.7138 6.315765 0.2575379 32.80803 6.771782 0.1910858 34.49512 6.220093 0.1221313 35.66431 5.319031 0.01787757 35.66986 5.741882 0.01543903 33.53996 7.152008 0.6789703 25.56089 6.538006 0.1342487 25.61989 6.977993 0.003669023 24.97286 7.486675 0.003834843 23.29137 8.831238 0.04091173 22.72159 9.964417 0.1173992 24.82941 7.186142 0.1149978 23.51083 8.018616 0.2267818 22.61768 9.071961 0.3195458 24.10275 7.245056 0.3389411 22.25114 10.0437 0.4063377 22.91626 8.245972 0.6615448 24.74347 6.732773 0.6614952 23.17371 7.713257 0.7573261 23.86524 7.118622 0.7577591 22.56613 8.455994 0.7366467 22.20963 9.286988 0.8095715 22.031 10.05511 0.6940045 22.04443 26.91618 0.2657709 22.36408 27.23128 0.01563835 22.78639 27.08237 0.005239963 24.40849 29.34263 0.1335091 22.96892 28.31999 0.1211547 25.48241 29.97635 0.226715 23.60411 29.27087 0.3391571 24.54199 29.98218 0.5171852 22.70653 28.57087 0.6773377 25.61221 30.45143 0.7364693 22.22513 27.74603 0.7357178 23.42857 29.543 0.8324967 22.58255 28.57641 0.8092346 24.49359 30.19789 0.689621 33.25561 30.62555 0.8065071 34.04648 30.95975 0.7853766 34.82042 31.51317 0.9040833 35.33346 32.06821 0.5365296 35.26555 31.80966 0.0100733 35.48766 30.8789 0.153553 35.48499 31.53441 0.4243088 34.15314 30.83582 0.1327991 34.08172 30.44824 0.3426819 32.65379 30.2878 0.02649688 32.85661 29.8051 0.007982254 45.8194 32.65545 0.2982483 45.83907 33.21994 0.6330567 45.96344 33.40033 0.07828807 46.11032 32.36108 0.283659 46.22807 32.02388 0.9029541 46.45129 33.13135 0.7635803 46.58929 32.875 0.6303101 46.26623 33.22229 0.9305287 46.68226 32.52156 0.3561554 46.40751 32.81067 0.1676025 46.11154 32.87439 0.7599945 46.56875 32.0639 0.7463913 46.42966 31.84737 0.4904251 46.54942 32.35016 0.8540192 42.97558 27.7981 0.8264923 45.34582 30.97302 0.5871267 44.38159 30.05029 1.227356 46.33743 31.73792 0.8197479 43.68494 29.06421 0.4015408 45.16998 31.05371 0.102169 44.49457 30.92712 0.00573796 43.34352 30.24709 0.3405228 43.48767 29.16382 0.07461524 42.83063 28.87512 0.3397179 42.85535 28.07617 29.94323 46.08856 32.44365 29.89476 44.94287 31.31885 29.79173 46.11603 32.05298 29.70825 44.65967 30.73071 29.48761 46.27551 31.84674 29.2518 45.31055 30.94983 29.18152 43.06177 27.99732 29.2522 43.68542 29.07764 29.26361 44.41406 30.04126 29.5813 43.16406 28.58814 29.96784 43.6438 30.2085 29.11133 45.86212 33.47615 29.39807 45.85333 33.41012 29.82153 45.8223 33.07635 29.13437 46.51559 33.04816 29.98539 45.84842 32.67883 29.25836 46.64981 32.65027 29.17851 46.66928 32.37637 29.55078 46.01904 33.27313 29.75513 46.32846 32.71496 29.56958 46.30969 33.06012 29.14781 46.44842 31.853 28.66203 46.60365 32.07672 29.6001 46.4451 32.1962 29.18182 46.25439 33.30621 29.44734 35.95445 32.98552 29.23335 35.41444 32.17444 29.21945 34.82516 31.51115 29.18239 34.11084 30.99455 29.21948 33.1991 30.62302 29.38202 32.50992 30.44751 28.99814 32.58288 30.51223 29.45471 33.6991 30.69873 29.67478 35.22552 31.57513 29.58798 34.54614 31.07275 29.86142 34.54175 30.71167 29.80978 32.95911 30.14295 29.92269 35.74585 31.61145 29.9881 33.12793 29.76248 29.99297 35.3374 30.7016 29.70453 25.62048 30.21738 29.16435 25.55432 30.46844 29.98389 25.23004 29.66544 29.99201 23.68854 28.78406 29.99487 22.88004 27.17987 29.83759 22.79379 28.11206 29.86565 22.5137 27.03717 29.76981 24.19739 29.70252 29.73129 23.14795 28.85388 29.61411 24.60651 30.03632 29.62186 22.24455 27.17135 29.31439 23.37122 29.48169 29.24257 24.41925 30.15915 29.26334 22.7675 28.81049 29.2644 22.30491 27.99656 29.19046 22.03101 26.93016 29.98206 22.75899 10.17505 29.72497 22.31514 10.13005 29.302 22.05081 9.998169 29.99175 23.04349 9.154908 29.98567 24.68466 7.468842 29.81911 23.51955 7.840485 29.77445 24.47861 7.150024 29.786 25.65306 6.865723 29.67824 22.54509 9.001576 29.59274 22.91089 8.254273 29.29703 25.57545 6.53241 29.26337 22.22507 9.239136 29.26474 23.42856 7.442383 29.26434 24.49701 6.796722 29.19124 22.60361 8.381104 29.96625 32.60974 7.172516 29.70778 32.47854 6.763763 29.21541 32.62901 6.477406 29.19034 34.10351 5.994141 29.64971 35.49603 5.06189 29.14663 34.98541 5.317627 29.97676 35.57544 5.753906 29.51164 34.54961 5.88652 29.85655 34.6037 6.215027 29.75882 33.58227 6.586914 29.22331 33.32587 6.321304 29.98951 34.3612 6.836914 29.99364 45.83098 4.38205 29.97651 45.99655 4.437019 29.78356 46.19488 4.898804 29.56213 46.34296 5.010986 29.26172 46.45312 5.108398 29.22762 46.65649 4.672119 28.58847 46.67538 4.702148 29.67025 46.45001 4.494531 29.2919 46.63102 4.255371 29.26785 46.40683 3.842834 28.64447 46.58044 4.023804 29.70078 46.19391 3.965088 29.81136 45.80239 3.882843 29.18166 46.19067 3.64267 29.11865 45.86451 3.510109 29.42307 45.89622 3.594986 29.1754 43.06201 8.9917 29.32452 44.38281 6.97168 29.24094 45.25732 6.089844 29.19034 43.67602 7.930176 29.7194 44.71411 6.189697 29.97532 43.87158 6.394287 29.65972 43.48926 7.821777 29.92728 42.71985 8.274415 29.6595 42.85791 8.907715 25.1872 49.2439 3.858948 25.89533 49.11016 3.008514 28.81177 46.39343 5.201843 28.60828 46.54852 5.013306 28.15372 46.77464 4.506256 27.75464 46.82952 4.062988 27.20807 47.08104 3.923218 26.59261 47.58881 3.756134 27.48282 46.96586 4.420105 26.55139 47.50769 4.268433 28.21045 46.49805 5.121338 27.79102 46.80029 4.739746 26.99878 46.99463 4.753906 26.59082 47.05493 4.784424 25.7655 48.01037 4.278748 26.27918 47.93713 3.883423 26.11025 48.32576 3.410801 25.85127 48.62762 3.700806 25.47208 49.04968 3.808044 25.78453 49.28973 3.424988 25.23407 51.1132 3.500401 25.53748 51.04834 3.35852 25.79993 51.06207 3.050293 24.96058 72.62744 3.492622 25.69533 71.97376 3.186356 25.83888 73.08075 2.811127 25.54392 74.71248 2.810974 25.07452 76.06185 2.950027 24.534 77.24297 2.829071 23.76086 78.48751 2.767242 22.91733 79.47002 2.818909 21.92951 80.37424 2.897827 20.84995 81.18009 2.817383 19.63742 81.85326 2.761719 18.43961 82.29169 2.967895 17.7023 82.58073 1.234802 17.03854 82.68857 2.829834 15.72098 82.85152 2.884705 14.29083 82.86228 2.818329 12.97168 82.66122 2.96582 11.67502 82.35524 2.884491 10.33157 81.84585 2.838959 9.123925 81.13668 2.948456 8.087052 80.36469 2.966705 7.078461 79.46588 2.818085 6.193527 78.40877 2.755157 5.450406 77.2378 2.753723 4.883572 76.00579 2.829559 4.460424 74.69978 2.874458 4.156929 73.02079 2.831692 5.870182 77.45548 3.275009 6.723 78.79108 3.191589 19.55826 81.6261 3.246155 4.387161 73.04917 3.219482 4.958435 75.39569 3.294312 14.37978 82.5239 3.338837 16.48901 82.48468 3.304871 20.69405 80.935 3.287994 23.23026 78.77545 3.235107 24.45264 76.66495 3.349701 25.30948 74.64057 3.235107 25.455 73.18077 3.357803 10.91019 81.62799 3.390076 12.19371 81.96299 3.471085 21.89484 79.78803 3.427719 4.747006 72.73471 3.470176 8.862915 80.50989 3.365234 18.98847 81.49706 3.475784 5.76479 76.46547 3.485804 8.301659 79.7842 3.4758 23.75523 77.30539 3.48247 25.0331 74.04831 3.476955 16.17468 82.11591 3.486877 4.797037 51.14987 3.500184 4.408577 51.07659 3.321747 4.120903 51.06044 2.865708 4.808212 49.27966 3.848389 4.113185 49.17104 3.207348 4.42263 49.32223 3.665283 3.843654 48.1484 3.244965 3.438738 47.59864 3.633865 4.322754 48.01807 4.293213 2.931564 47.21279 4.008354 2.224426 46.82088 4.070862 1.755096 46.74055 4.540802 1.306396 46.43628 5.158142 1.37677 46.60916 4.894897 0.848999 45.98437 5.508789 2.218018 46.8573 4.531433 2.685791 46.91394 4.733643 3.068848 46.91992 4.853394 3.253723 47.35052 4.341858 3.757568 47.44092 4.544312 3.848 48.01257 3.967133 3.973474 48.47071 3.458862 4.327698 48.38769 4.063293 4.216495 48.69534 3.755432 4.468878 74.74506 1.15844 11.63643 82.36097 1.237854 21.87412 80.41098 1.033142 5.628328 75.80254 0.4945173 24.80106 75.86832 0.660492 25.52897 74.74394 1.161194 7.259411 78.69151 0.5059834 5.911102 77.34101 0.641037 8.732636 80.08135 0.5015068 4.904949 76.04523 1.102226 25.12778 75.96305 1.101852 23.80153 78.39678 1.158478 24.54998 77.22274 1.167603 19.61575 81.858 1.165405 20.82878 81.188 1.156067 22.92154 79.46457 1.165894 23.15888 78.78745 0.696167 24.21796 77.11366 0.6462555 22.75755 78.6083 0.4971466 21.09177 80.46683 0.5832214 20.03008 81.36518 0.7145386 18.33936 82.30658 1.04834 15.72718 82.85147 1.101807 14.25345 82.83678 1.034088 19.19239 81.24832 0.495801 17.93866 82.10416 0.6229248 16.9859 82.45502 0.7510986 10.38453 81.83737 1.118225 15.14926 82.18506 0.4992218 15.11581 82.52747 0.6421509 12.6498 81.95729 0.5072937 12.9837 82.50379 0.7991943 11.68706 82.12436 0.7399902 10.0237 81.2887 0.6337738 9.171929 81.17392 1.088959 7.745544 79.85971 0.7801209 8.066674 80.40132 1.231842 7.066188 79.45618 1.173309 6.217396 78.37509 1.01944 5.465247 77.24323 1.156189 12.95772 82.6968 1.221374 25.89554 49.08471 33.7665 26.06733 48.40451 33.55549 26.41028 47.72174 33.58911 25.77571 47.79782 32.58751 26.98436 47.23673 33.13779 28.7879 46.35751 31.75537 28.68359 46.48572 31.88879 28.52818 46.67175 32.23981 27.75153 46.80835 32.24646 27.66943 46.55798 31.89429 28.19605 46.75469 32.56889 27.44223 47.00024 32.58922 26.8385 46.98849 32.17238 27.68875 46.80653 33.06854 26.74951 47.36412 32.65945 26.27072 47.94774 33.13949 25.96779 48.01227 32.83087 25.8187 48.54758 33.1655 25.18884 49.09927 33.08526 25.62506 49.26716 33.35137 25.86514 50.8725 34.04261 25.28227 51.103 33.48987 25.62426 51.02081 33.69893 25.23828 72.76056 33.5243 25.55908 72.92076 33.69926 25.88044 72.00131 34.15546 4.159895 73.12773 34.19031 4.870503 76.00248 34.23027 4.473062 74.70226 34.08805 5.452076 77.22669 34.16499 6.217809 78.37593 34.0193 7.052574 79.43737 34.16543 8.066052 80.39403 34.17418 9.165253 81.19396 34.22058 10.37265 81.83429 34.08761 11.64318 82.34975 34.11056 13.0292 82.68244 34.03529 14.28632 82.80365 33.98099 14.34571 82.88514 35.8212 15.67635 82.83142 34.01944 17.15653 82.70168 34.50116 18.38876 82.35668 34.14752 19.59403 81.85721 34.10123 20.86513 81.15849 34.10254 21.92778 80.34919 34.05102 21.93171 80.41397 35.76358 22.94122 79.44815 34.17615 23.77268 78.38912 34.02019 24.50697 77.23186 34.01807 25.12409 76.00415 34.17386 25.52631 74.70494 34.0881 25.78411 73.40155 34.10066 17.02228 82.61847 33.98083 9.257828 81.02375 33.79776 5.08699 75.89727 33.74032 4.301117 72.8963 33.85132 25.04114 75.39723 33.69084 22.75052 79.29295 33.7511 8.473748 80.25067 33.6222 7.003937 78.86971 33.63604 5.707443 77.08567 33.69759 21.14867 80.59342 33.66867 18.81635 81.85477 33.66943 16.39882 82.39397 33.61098 11.0741 81.84955 33.70184 4.928635 74.43914 33.53365 23.65867 77.61674 33.52227 14.44418 82.25196 33.50464 13.02409 82.22292 33.58393 4.739609 72.86307 33.51479 24.59514 75.47455 33.49795 21.99828 79.55553 33.52887 18.72503 81.56298 33.50107 11.15409 81.48226 33.49956 7.5448 78.99515 33.50635 5.849625 76.46677 33.49834 4.715271 51.09738 33.48993 4.354462 51.04144 33.71982 4.120628 51.01019 34.11755 4.827965 49.41138 33.16717 4.100779 49.15177 33.85237 1.353485 46.51889 31.92239 1.607544 46.6983 32.28039 1.368713 46.67508 32.28339 2.505951 46.96965 32.83288 1.777908 46.64517 32.98178 2.846985 46.94844 33.43866 3.256744 47.44533 33.20495 1.871094 46.69446 32.15271 2.768524 47.09097 32.61096 3.348846 47.39746 32.60528 2.76001 46.84912 32.11053 3.569006 47.16957 32.26356 4.549713 48.2507 32.78665 4.071562 47.99019 32.78639 3.670822 47.85531 33.05249 3.6791 47.90048 33.56421 4.028853 48.38679 33.21897 4.447693 49.12186 33.25397 4.230041 49.12071 33.49734 3.992037 48.61474 33.66046 25.54891 74.70298 35.7684 9.4516 81.3821 35.81622 8.087784 80.36717 35.96472 24.6077 76.62853 36.24771 5.469452 76.47641 36.35058 4.472519 74.76255 35.81392 23.41164 78.11249 36.43082 20.88931 80.31281 36.48601 25.12091 76.01334 35.81177 4.902763 76.03891 35.88428 6.251053 78.43758 35.95151 5.476379 77.2365 35.89714 10.36023 81.85968 35.68872 6.732391 78.12383 36.4696 9.213685 80.80632 36.34799 7.543549 79.56555 36.26721 10.48752 81.65073 36.24426 11.73209 82.13886 36.24567 12.95581 82.6944 35.81131 15.6832 82.87429 35.69714 7.884018 79.34027 36.48135 11.71829 81.68625 36.48498 14.33213 82.61619 36.22902 16.05451 82.72931 36.08581 15.74582 82.26102 36.47845 16.99561 82.39575 36.27856 19.06165 81.60559 36.41348 18.32566 82.30442 36.00366 19.58901 81.86082 35.88275 20.82689 81.17447 35.89508 22.84315 79.34467 36.13324 22.94479 79.45447 35.68835 23.77179 78.42932 35.88364 20.64102 80.82324 36.37051 21.99976 79.87207 36.35165 24.54249 77.24469 35.76312 7.078003 79.46504 35.81756 11.63635 82.35733 35.76263 17.0136 82.69783 35.81805 13.35939 82.46454 36.29663 2.999734 32.81195 6.433914 2.997713 33.82593 6.058838 2.127136 35.57483 4.452393 27.00696 33.57373 6.184875 27.00042 32.5021 6.468948 2.99976 33.50909 30.76616 2.999855 32.53989 30.52438 0.8400421 32.47586 30.50026 27.00205 32.51327 30.51931 27.0003 33.24872 30.6868 27.91009 35.39863 32.22195 3 25.33623 6.52231 3 23.95288 7.04364 3 22.98731 7.845337 3 22.10471 9.374451 3 24.9359 30.4104 3 23.35338 29.50603 3 22.55176 28.54044 3 22.05192 27.24011 27 22.09178 9.457047 27 22.91455 7.93042 27 23.85748 7.102081 27 25.26643 6.527343 27 22.1047 27.61079 27 23.20727 29.39908 27 25.07811 30.44331 1.371071 46.59598 4.049469 4.081412 48.80001 2.579971 2.866211 46.88019 3.451904 3.410614 46.19529 2.450348 2.724829 45.84237 3.031532 3.871597 47.49187 2.292084 3.386703 47.09445 3.010376 2.237091 46.36539 3.467102 1.566803 46.19388 3.583435 3.051941 46.38129 2.927887 1.842773 45.7854 3.413245 26.63788 47.18368 3.128784 26.14163 47.71655 2.518433 28.60639 46.35254 3.739441 28.20607 45.96051 3.44117 27.30847 45.94658 3.059601 26.80676 46.18318 2.679321 27.74182 46.47314 3.551392 27.15234 46.67054 3.270874 25.94526 48.3363 34.67139 26.96741 45.96582 34.17651 27.56567 45.92978 33.79065 28.20142 45.93521 33.54816 28.24814 46.62555 32.97717 28.25223 46.35559 33.31897 26.12451 47.26007 34.8977 27.32489 46.55664 33.63989 26.61939 46.67297 34.29126 4.054573 48.01276 35.01761 2.421875 46.68172 33.35046 3.155884 46.94296 33.8291 3.644501 46.13554 34.86279 1.598145 46.2359 33.35742 1.815063 45.86511 33.5594 3.021423 45.9752 34.16095 2.650635 46.10126 33.8706 3.664459 47.03796 34.50989 9.481583 69.4494 35.29262 9.160477 69.43485 36.49261 10.21374 69.74878 36.49264 10.98862 70.3346 35.29264 11.03561 70.42667 36.49263 11.54483 71.6193 36.49261 11.59394 71.95363 35.29262 11.45718 72.71283 36.49262 11.04776 73.59369 35.29262 10.84012 73.82965 36.49263 10.01855 74.3476 35.29263 9.489197 74.52714 36.49262 8.944886 74.57346 35.29262 8.392945 74.48592 36.49261 7.495483 74.11432 35.29261 7.250885 73.91681 36.49263 6.698456 73.1178 35.29262 6.4354 72.39269 36.49262 6.427303 72.05484 35.29262 6.677978 70.89176 36.4926 6.824554 70.58725 35.29263 7.680237 69.76721 36.49262 7.990601 69.63373 35.2926 7.378967 73.26552 35.29262 8.707777 74.01403 35.29262 10.03516 73.75263 35.29262 10.82123 72.87055 35.29261 9.464692 70.01974 35.29262 11.01413 71.87191 35.29262 10.60608 70.75144 35.29261 6.976001 71.79141 35.29262 7.368896 70.83216 35.2926 8.117127 70.16751 35.29263 14.83965 75.43484 35.29262 15.16034 75.43483 36.49262 16.31998 75.76731 35.29262 16.3949 75.83841 36.49264 17.38311 76.97534 36.49262 17.43009 77.09223 35.29261 17.49838 78.70001 36.49261 17.5033 78.59674 35.29262 16.89484 79.74195 35.29261 16.7981 79.82056 36.49261 15.90912 80.40811 36.49261 15.80505 80.44483 35.29261 14.61963 80.5458 36.49261 14.5108 80.52714 35.29262 13.59961 80.14173 36.4926 13.53589 80.09851 35.29261 12.83817 79.39655 36.4926 12.65574 79.11219 35.29263 12.46764 78.36411 36.49263 12.44596 77.85353 35.29262 12.56992 77.09221 36.49261 12.82443 76.58734 35.29264 13.68011 75.76725 36.49262 13.78625 75.74884 35.2926 14.46497 76.06693 35.29264 15.6348 76.0452 35.29262 15.20538 80.00918 35.29262 16.6955 76.90601 35.29259 17.04543 78.20937 35.29262 16.31641 79.55237 35.29259 13.55673 76.56647 35.29262 12.976 77.79142 35.29262 13.29375 79.10947 35.29262 14.20825 79.85724 35.29262 21.69293 69.52017 35.29262 20.73831 69.441 36.49262 22.20993 69.70578 36.49263 22.63721 70.03485 35.29259 23.15793 70.62671 36.49258 23.43009 71.09223 35.29261 23.54483 71.61927 36.49263 23.53236 72.36408 35.29262 23.3443 73.11206 36.49261 23.1618 73.39649 35.29261 22.30298 74.21991 36.49264 22.40039 74.14173 35.29255 21.38046 74.54578 35.29262 21.25543 74.54627 36.49261 20.19501 74.44492 36.49262 20.31775 74.4664 35.29262 19.34088 73.96768 35.29264 19.25781 73.87409 36.49261 18.53854 72.8205 36.49263 18.50164 72.70003 35.29262 18.52393 71.3003 36.49262 18.55628 71.19474 35.29262 19.32172 70.02237 36.4926 19.41968 69.9433 35.29263 20.64905 69.46427 35.29261 21.02577 74.0083 35.29262 21.87061 73.82166 35.29263 22.52612 73.30347 35.29264 19.89295 73.73334 35.29263 22.99896 72.38106 35.29262 22.79416 71.04087 35.29262 22.09802 70.32147 35.29258 21.2984 70.00471 35.29262 19.25909 70.97974 35.29262 20.11713 70.16748 35.29261 19.00612 71.77603 35.29262 19.08333 72.63301 35.29264 15.0335 63.44227 35.29262 14.63519 63.4599 36.49261 16.09976 63.63415 36.49261 16.31982 63.76723 35.29261 17.27236 64.79329 36.49262 17.43009 65.09223 35.29261 17.55405 65.85354 36.49262 17.53235 66.36408 35.29262 17.40775 66.90872 36.49262 17.16168 67.39673 35.29264 16.65906 67.96784 36.4926 16.40027 68.14173 35.29262 15.68213 68.46646 36.49265 15.38037 68.54578 35.29261 14.4075 68.5266 36.49263 14.09088 68.40811 35.29262 13.10513 67.74179 36.49262 13.20184 67.82074 35.29257 12.59228 66.90888 35.29264 12.43541 66.39273 36.49261 12.47788 65.39276 35.29262 12.67795 64.89188 36.49261 13.10522 64.28174 35.29264 13.51373 63.90002 36.49262 13.99054 63.63379 35.29263 15.47626 64.05161 35.29262 16.23395 64.40363 35.29263 16.93058 65.35791 35.29261 16.90594 66.71341 35.29262 16.28394 67.54273 35.2926 15.37971 68.00164 35.29262 14.36011 67.90253 35.29262 13.50568 67.38184 35.29262 12.94425 65.96641 35.29262 13.45673 64.70014 35.29265 14.43967 64.04464 35.29262 14.20712 64.12682 33.49261 13.20586 65.04084 33.49261 19.71594 73.54261 33.49261 15.56027 64.04464 33.49262 6.994248 72.05562 33.49262 7.205856 71.04084 33.49262 8.207184 70.12677 33.49262 9.20044 70.00429 33.49261 10.18005 70.34308 33.49261 10.49438 73.38178 33.49262 15.22179 75.97811 33.49261 15.79169 67.85727 33.49263 18.98587 71.87191 33.49261 20.20715 70.1268 33.49261 16.54334 64.70017 33.49262 16.92721 65.44229 33.49261 12.99306 66.21411 33.49261 14.61347 67.99929 33.49262 11.03028 72.13648 33.49262 9.48298 73.9591 33.49259 12.99306 78.21413 33.49262 13.20581 77.0409 33.49261 21.64602 73.92871 33.4926 13.44025 67.30753 33.49261 10.8051 71.12461 33.49261 20.47471 73.95281 33.49259 19.1788 72.87059 33.49263 16.99594 66.29998 33.49261 21.38373 70.01936 33.49261 22.30133 70.45822 33.49262 7.316025 73.18044 33.49262 19.30451 70.90607 33.49261 8.474674 73.95278 33.4926 22.59656 73.2356 33.49263 22.99595 72.30001 33.49262 16.30127 76.45813 33.49261 14.05383 76.21808 33.49261 16.59644 67.23548 33.49262 15.29446 80.01366 33.49263 22.88841 71.28859 33.49261 16.23718 79.58057 33.49259 16.80516 77.1247 33.49267 14.12946 79.8216 33.49262 16.78226 78.94782 33.4926 17.0178 77.95838 33.49262 13.35193 79.1659 33.49257 6.92041 70.51087 1.692622 7.217743 71.05371 1.692623 6.4194 71.73384 1.692623 6.996821 71.88533 1.692623 8.799683 73.99726 1.692623 7.820007 73.65854 1.692622 8.184327 74.4256 1.692624 7.259766 73.8963 1.692624 7.11158 72.71294 1.692623 6.64093 72.99054 1.692624 9.500489 74.54643 1.692623 9.956147 73.82094 1.692623 10.63721 73.96668 1.692624 11.43006 72.9094 1.692623 10.85612 72.79334 1.692623 10.99895 71.62053 1.692623 11.46148 71.18109 1.692623 10.19482 70.32756 1.692624 10.40021 69.81668 1.692623 7.763428 70.42078 1.692621 7.874329 69.66335 1.692623 8.70723 69.98851 1.692623 9.178498 69.44871 1.692623 8.619538 69.4558 0.492623 7.250885 70.08466 0.492623 6.4354 71.60887 0.492623 6.677948 73.10977 0.492623 7.680054 74.23426 0.4926229 9.163208 74.56887 0.4926231 10.39502 74.16315 0.4926233 11.15784 73.37512 0.4926242 11.58859 72.1738 0.492623 11.12271 70.50922 0.4926231 9.909119 69.59345 0.4926231 12.87732 76.50916 1.692623 13.13092 77.19644 1.692623 12.4114 78.17382 1.692623 13.01838 78.38355 1.692623 13.90601 76.30487 1.692623 14.28549 75.50675 1.692623 15.0518 75.97221 1.692623 14.77824 80.02347 1.692623 14.40527 80.5044 1.692623 13.55679 79.43524 1.692623 13.09467 79.7616 1.692622 15.9234 80.42525 1.692623 15.79834 79.84156 1.692624 16.48602 79.36634 1.692624 17.10138 79.48621 1.692624 16.96339 78.46817 1.692623 17.59394 78.04794 1.692623 16.942 77.45127 1.692623 17.1618 76.60498 1.692623 16.31638 76.4491 1.692623 16.01096 75.61151 1.692623 14.61957 75.4558 0.492623 13.42694 75.96436 0.4926231 12.63338 76.99048 0.4926229 12.45134 78.48567 0.492623 13.17999 79.82001 0.4926231 14.49954 80.54642 0.492623 15.8158 80.42554 0.4926231 16.90527 79.76166 0.492623 17.49243 78.57752 0.4926231 17.49838 77.30158 0.4926231 16.79797 76.18079 0.4926231 15.90912 75.59348 0.4926229 19.34076 70.03382 1.692622 18.59229 71.09272 1.692623 19.13092 71.19647 1.692623 18.44595 72.14803 1.692623 19.0405 72.54922 1.692623 20.46484 73.93451 1.692623 19.6051 74.16315 1.692624 19.69867 73.54349 1.692623 18.72762 73.20824 1.692623 20.60577 74.5285 1.692623 21.46475 73.98179 1.692623 21.70154 74.47657 1.692623 22.82007 73.81989 1.692625 22.48602 73.36634 1.692623 23.47605 72.70145 1.692623 22.96339 72.46814 1.692623 23.46149 71.18112 1.692623 22.90593 71.28816 1.692623 22.74201 70.12726 1.692625 22.03525 70.24901 1.692624 21.59259 69.47499 1.692623 19.90595 70.30487 1.692623 20.31836 69.53498 1.692623 20.87425 69.98828 1.692623 20.4075 69.47498 0.492623 18.95218 70.40793 0.4926231 18.40606 72.04795 0.4926231 18.8988 73.48624 0.492623 20.07663 74.42528 0.4926232 21.59479 74.50437 0.4926233 22.74036 73.8963 0.4926232 23.35907 72.99048 0.4926231 23.5806 71.73383 0.4926231 23.07956 70.51068 0.4926231 22.12564 69.66335 0.492623 12.99682 65.88534 1.692623 12.47346 65.51268 1.692623 12.92041 64.51087 1.692623 13.29373 64.89212 1.692623 13.58984 67.42823 1.692624 13.2597 67.89633 1.692623 12.55625 66.80686 1.692622 16.36621 67.47046 1.692626 15.92343 68.42523 1.692623 15.46472 67.9818 1.692623 14.40521 68.50438 1.692623 14.28699 67.8889 1.692623 13.11158 66.71294 1.692623 16.20648 63.72784 1.692623 15.87048 64.1799 1.692623 16.75813 64.97638 1.692623 17.16177 64.60495 1.692623 17.56801 65.83647 1.692623 16.99807 66.48558 1.692623 17.24158 67.30698 1.692623 13.69727 63.78155 1.692622 14.04797 64.23456 1.692623 14.87414 63.98827 1.692623 14.94483 63.42809 1.692623 15.25555 63.45529 0.4926231 14.19489 63.55669 0.4926229 13.25806 64.1272 0.4926231 12.53852 65.18106 0.4926231 12.52394 66.7014 0.492623 13.0542 67.66168 0.492623 13.89001 68.32236 0.492623 15.37627 68.56771 0.492623 16.74036 67.8963 0.4926231 17.52213 66.60877 0.4926231 17.40776 65.09281 0.492623 16.50446 63.88719 0.4926231 20.20129 73.84149 3.492622 21.04328 74.01856 3.492622 17.0178 78.04322 3.492622 16.94978 65.34835 3.492622 16.85031 77.22464 3.492622 16.36481 76.5141 3.492622 22.98161 72.38356 3.492622 14.45654 64.05518 3.492622 16.02179 67.7414 3.492626 19.1788 71.13105 3.492622 14.12952 76.17993 3.492623 10.97814 71.52394 3.492622 16.83865 66.8725 3.492622 19.83423 70.35321 3.492619 20.62695 70.02873 3.492622 14.87677 68.03186 3.492622 18.98587 72.12963 3.492622 15.22174 80.02347 3.492622 19.3938 73.24999 3.492622 15.29288 75.98851 3.492622 22.33237 73.56668 3.492621 22.91667 71.36856 3.492622 10.83861 72.8725 3.492623 16.09399 64.30481 3.492622 22.36499 70.51416 3.492626 13.40491 79.21802 3.492622 7.766052 73.5979 3.492621 8.70163 73.99684 3.492621 21.43512 70.02667 3.492622 14.05377 79.78357 3.492623 16.57785 79.31897 3.492621 13.09407 65.28818 3.492622 9.292832 69.98851 3.492622 8.129273 70.17993 3.492622 7.241913 70.97632 3.49262 13.03237 77.60782 3.492622 9.882874 73.83408 3.492623 10.36499 70.51416 3.492623 13.90173 67.67993 3.492622 6.98587 72.12965 3.492621 7.222198 72.93122 3.492625 15.27533 64.0114 3.492622 13.01383 66.28569 3.492622 13.30444 67.09552 3.492622 13.71594 64.45886 3.492622 13.35199 76.83576 3.492622 13.03661 78.46815 3.492621 3 22.00078 15.49262 3 22.00078 21.49262 1.2 29.54577 18.87299 0 29.44485 17.68761 1.2 29.3382 17.36691 0 28.74183 16.59779 1.2 28.11221 16.14838 0 27.59669 15.98931 1.2 26.85355 15.93857 0 26.09219 16.06256 1.2 25.79321 16.22026 0 25.03491 16.85553 1.2 24.98627 16.91565 0 24.45513 17.9922 1.2 24.49721 17.89774 1.2 24.48611 18.96301 0 24.57602 19.30835 1.2 25.02243 20.171 0 25.10526 20.23295 0 26.3928 21.01475 1.2 26.30023 20.96869 1.2 27.59676 20.99592 0 27.90878 20.90038 1.2 28.91681 20.24176 0 28.82074 20.29047 0 29.49482 19.20709 1.199998 29.00814 18.28186 1.2 28.72324 19.61533 1.2 27.46555 20.47362 1.2 26.11787 20.32589 1.2 25.2599 19.51375 1.2 24.98298 18.53507 1.2 25.15042 17.71655 1.2 25.76128 16.87892 1.2 27.05019 16.45843 1.2 28.00573 16.75592 1.2 28.64879 17.32758 1.2 29.54577 12.87305 0 29.59039 12.33546 1.2 29.4081 11.58356 0 28.91684 10.74349 1.2 28.82077 10.69476 1.2 27.90884 10.0849 0 27.3927 9.928023 1.2 26.85355 9.938573 0 25.89175 10.17059 1.2 25.79334 10.22025 0 24.76721 11.17278 1.2 24.98627 10.91577 1.2 24.49722 11.89778 0 24.43269 12.6558 1.2 24.57632 13.41607 0 24.7487 13.70627 0 25.42659 14.52821 1.2 25.51531 14.59382 0 26.82774 15.08122 1.2 26.49969 15.00136 1.2 27.59673 14.99593 0 28.3027 14.71223 1.2 28.91683 14.24176 0 29.21985 13.79547 1.2 25.34309 11.31261 1.2 26.28854 10.6042 1.2 27.47763 10.51448 1.2 24.98299 12.44932 1.2 25.28775 13.59078 1.2 26.35787 14.42319 1.2 27.55023 14.43463 1.2 28.55241 13.80905 1.2 28.61453 11.25316 1.2 29.02936 12.54443 1.2 27.80508 22.62353 1.2 28.65898 22.52487 1.2 27.71283 22.03545 1.2 26.39276 21.97051 1.2 26.45238 22.53312 1.2 25.28186 22.5979 1.2 25.34308 23.31262 1.2 24.63377 23.48322 1.2 24.98299 24.44933 1.2 24.44278 24.53131 1.2 24.67922 25.60259 1.2 25.21811 25.43889 1.2 25.51542 26.59391 1.2 25.78333 26.08759 1.2 26.69339 26.50407 1.2 26.95366 27.08657 1.2 28.02527 26.25072 1.2 28.18689 26.75928 1.2 29.03702 26.06592 1.2 28.82156 25.36325 1.2 29.59039 24.6498 1.2 28.80075 23.54367 1.2 29.31577 23.40378 1.2 29.00745 24.51886 0 29.54577 24.11224 0 28.91681 22.74346 0 27.7868 22.05808 0 26.72878 21.93378 0 25.51535 22.39139 0 24.6792 23.38266 0 24.43383 24.86885 0 24.98625 26.06949 0 25.79332 26.765 0 27.26772 27.07323 0 28.49072 26.57221 0 29.33817 25.61838 3 30.40078 21.49262 3 30.40078 27.49262 10.97813 32.52392 11.29262 11.55 31.40077 11.29262 7.834259 31.3533 11.29262 7.205841 33.96067 11.29262 8.860016 35.00238 11.29262 9.882905 34.83403 11.29262 10.36491 31.51408 11.29263 9.121562 30.94833 11.29262 7.275757 31.97473 11.29262 6.993064 32.7874 11.29262 8.053772 34.78343 11.29263 10.83864 33.87245 11.29262 9.631287 34.91774 25.69262 7.456757 34.30142 25.69264 6.944252 33.03513 25.69262 8.439621 34.9569 25.69262 6.449999 30.40078 25.69262 7.505661 31.61969 25.69262 8.704934 30.98749 25.69262 9.870545 31.17995 25.69263 10.64799 31.83571 25.69259 11.55 31.40077 25.69262 11.03447 32.9638 25.69262 10.60611 34.25009 25.69262 9.383667 34.98223 27.49262 8.207154 34.87476 27.49262 7.304504 34.09558 27.49264 7.01383 33.28569 27.49262 7.094063 32.28815 27.49263 8.105149 31.14967 27.49261 9.631089 31.06632 27.49262 10.48599 31.65247 27.49258 10.97813 32.52392 27.49262 10.9272 33.55929 27.49261 10.44322 34.43516 27.49261 7.011626 33.39388 24.69262 7.176437 32.06923 24.69263 7.217728 32.0538 12.29263 8.051011 31.20082 12.29262 8.275727 31.09926 24.69262 9.392457 31.00418 12.29262 9.631089 31.06632 24.69262 10.42737 31.57391 12.29262 10.70627 31.89216 24.69261 10.942 32.45128 12.29262 11.00318 32.88533 24.69262 10.98617 33.28567 12.29262 10.88841 33.713 24.69262 10.60611 34.25011 12.29262 10.18008 34.65845 24.69262 9.798707 34.8414 12.29262 9.20047 34.99724 24.69262 8.778222 35.02346 12.29262 8.368622 34.91772 24.69262 7.851257 34.64584 12.29262 7.513885 34.36629 24.69261 7.259109 34.02183 12.29262 6.985322 33.04037 12.29262 9.123295 35.03184 9.492625 7.978149 34.74123 9.492622 7.259117 34.02188 9.492629 6.982198 33.04317 9.492622 7.149719 32.22458 9.49262 7.760529 31.38704 9.492622 8.871987 30.9866 9.492623 10.03525 31.24902 9.492628 10.90593 32.28815 9.492626 10.96337 33.4682 9.492623 10.37192 34.50354 9.492626 3 29.02936 24.44083 3 28.6145 25.73209 3 27.63306 26.40927 3 26.45236 26.45212 3 25.23223 25.54119 3 25.0452 23.85779 3 25.78339 22.89764 3 26.53345 22.52924 3 27.71338 22.58668 3 28.64832 23.32687 3 29.00745 12.46639 3 28.80075 13.44162 3 27.94779 14.27487 3 26.79138 14.51661 3 25.70017 14.03591 3 25.11267 13.20561 3 25.01977 12.02782 3 25.63519 11.00656 3 26.69339 10.48117 3 28.02525 10.73454 3 28.82159 11.62198 27 22.00078 15.49262 27 22.00078 21.49262 28.8 29.54577 18.11225 30 29.57971 18.20992 28.8 29.40813 19.40164 30 29.34763 19.51093 30 28.74194 20.38745 28.8 28.49237 20.61534 30 27.59674 20.99592 28.8 27.05483 21.06532 30 26.4997 21.00136 28.8 25.58728 20.66812 30 25.5153 20.59382 30 24.78648 19.77396 28.8 24.63377 19.50206 30 24.44205 18.76574 28.8 24.44278 18.45394 30 24.70578 17.28273 28.8 24.76726 17.17273 30 25.79321 16.22026 28.8 26.09218 16.06255 30 26.85353 15.93857 28.8 27.59669 15.98932 30 28.1122 16.14838 28.8 28.91684 16.74348 30 29.09836 17.02808 28.8 28.92801 19.05109 28.8 28.98796 18.03793 28.8 28.36567 17.00589 28.8 27.29585 16.47933 28.8 26.13019 16.67181 28.8 25.47455 17.18988 28.8 25.05875 17.94312 28.8 25.01461 18.77759 28.8 25.30526 19.58742 28.8 25.9024 20.17179 28.8 26.70239 20.48869 28.8 27.53577 20.4265 28.8 28.44397 19.927 28.8 29.52658 11.90009 30 29.5797 12.20991 28.8 29.40811 13.40167 30 29.34766 13.51086 30 28.74191 14.38739 28.8 28.49243 14.61533 30 27.3927 15.05722 28.8 27.05484 15.06532 30 25.89184 14.81468 28.8 25.5873 14.66813 30 24.76724 13.81252 28.8 24.53433 13.29727 30 24.43269 12.32944 28.8 24.52505 11.79089 30 24.94328 10.91231 28.8 25.03491 10.85559 28.8 25.89179 10.17058 30 26.19469 10.04887 28.8 27.39269 9.928022 30 27.70003 9.99426 28.8 28.74187 10.59781 30 28.96771 10.83345 28.8 28.82163 11.62207 28.8 24.96605 12.19741 28.8 25.18509 13.34671 28.8 25.75145 10.8865 28.8 27.03775 10.45815 28.8 28.16581 10.84459 28.8 28.76715 13.44452 28.8 29.01328 12.6184 28.8 28.23541 14.08917 28.8 27.1365 14.52289 28.8 25.83089 14.15749 28.8 25.08385 23.86121 28.8 25.01934 24.87633 28.8 24.43269 24.6558 28.8 24.74874 25.70635 28.8 25.4581 25.79394 28.8 25.58731 26.66814 28.8 26.45235 26.45212 28.8 27.05486 27.06532 28.8 27.633 26.40929 28.8 28.11792 26.79416 28.8 28.48746 25.85767 28.8 28.96771 26.15173 28.8 28.93995 25.0311 28.8 29.52711 24.98177 28.8 28.99362 24.20647 28.8 29.44487 23.68759 28.8 28.55246 23.1763 28.8 28.8743 22.75053 28.8 28.01124 22.12606 28.8 27.20935 22.4472 28.8 26.51598 21.94396 28.8 25.7515 22.88652 28.8 25.18161 22.67267 28.8 24.60187 23.60376 30 29.55284 24.67104 30 29.18483 25.89282 30 27.82048 26.9541 30 26.09216 26.92268 30 24.90019 25.97899 30 24.4861 24.96303 30 24.53435 23.68794 30 25.42664 22.457 30 26.82778 21.90403 30 28.49241 22.36994 30 29.40811 23.58354 27 30.40078 27.49262 19.62814 34.50358 11.29262 19.31604 31.82114 11.29262 22.33241 34.56663 11.29262 20.8767 35.03184 11.29262 22.98162 33.38359 11.29262 22.8691 32.19649 11.29262 21.94897 31.20081 11.29262 20.60758 31.00417 11.29262 18.98855 33.30816 11.29262 21.1233 35.03184 25.69262 19.82001 34.65847 25.69263 19.0405 33.54921 25.69262 18.45 31.40077 25.69262 19.04516 32.54843 25.69262 19.40341 31.76618 25.69264 20.04797 31.2345 25.69261 21.04942 30.96657 25.69262 22.8729 32.28082 25.69262 23.55 30.40078 25.69262 22.31638 31.44915 25.69262 23.01413 33.12963 25.69262 22.50792 34.39844 25.69263 20.36865 34.91772 27.49262 19.39389 34.25011 27.49262 18.96553 32.96379 27.49262 19.35199 31.83569 27.49262 20.1294 31.17992 27.49263 20.96967 30.99451 27.49262 21.94896 31.2008 27.49261 22.8691 32.19649 27.49261 22.98161 33.38356 27.49262 22.54324 34.30145 27.49263 21.56035 34.95691 27.49262 23.01468 33.04036 24.69262 23.00675 32.7902 12.29262 22.79416 33.96066 12.29262 22.66487 34.17065 24.69262 21.94635 34.78345 12.29262 21.85413 34.81637 24.69262 21.04328 35.01856 24.69262 20.95672 35.01856 12.29262 19.90184 34.71379 24.69262 19.6676 34.56665 12.29262 19.14386 33.79328 24.69261 18.976 33.21014 12.29262 19.00104 32.62054 24.69262 19.29373 31.89215 12.29262 19.5726 31.57394 24.69262 20.20828 31.14432 12.29263 20.3031 31.11911 24.69261 21.12802 30.98659 24.69262 21.21425 30.99394 12.29262 22.09409 31.30482 24.69263 22.16577 31.35327 12.29262 22.78228 32.05378 24.69261 22.72435 31.97479 12.29262 20.95672 35.01855 9.492623 20.146 34.81644 9.492618 19.33514 34.17067 9.49263 18.9822 33.04317 9.492625 19.21773 32.05377 9.492615 20.05106 31.20082 9.492626 21.21426 30.99393 9.492625 22.00488 31.26401 9.492617 22.64804 31.83575 9.49263 22.96763 32.60774 9.49262 22.93058 33.64368 9.492628 22.09818 34.7138 9.492622 27 29.02936 24.5444 27 28.61451 23.25316 27 27.47766 22.5145 27 26.44241 22.56542 27 25.56635 23.04941 27 25.06688 23.9577 27 25.00472 24.79105 27 25.40369 25.72657 27 26.35787 26.42318 27 27.39383 26.46026 27 28.16583 26.14063 27 28.73743 25.49744 27 28.97485 12.05739 27 28.58069 11.25574 27 27.80508 10.62353 27 26.618 10.511 27 25.70017 10.94937 27 25.18509 11.63849 27 24.983 12.44933 27 25.28775 13.59076 27 26.35786 14.42318 27 27.71341 14.39855 27 28.54273 13.77655 27 28.94636 13.03613 3 29.45499 25.07694 3 29.38319 23.60185 3 28.29475 22.30287 3 26.63192 21.97601 3 25.29459 22.63428 3 24.5281 23.89655 3 24.59177 25.19077 3 25.07171 26.11844 3 26.30028 26.93776 3 27.79007 26.8888 3 28.8584 26.19965 3 29.50945 12.22591 3 28.95037 10.85907 3 27.68869 10.06541 3 26.21193 10.07455 3 24.86794 11.10684 3 24.47077 12.75431 3 25.07166 14.11839 3 25.93328 14.76224 3 27.15489 15.03145 3 28.71567 14.37108 3 29.38756 13.26324 27 29.49571 12.11864 27 29.40978 13.1908 27 28.92987 14.11838 27 27.70127 14.93777 27 26.00967 14.83508 27 24.88134 13.86105 27 24.48312 12.65367 27 24.72427 11.4054 27 25.70679 10.30288 27 27.36964 9.97601 27 28.86877 10.76635 27 29.47778 24.97113 27 29.03967 25.95349 27 28.10437 26.78424 27 26.8259 26.99464 27 25.81795 26.72098 27 24.88138 25.86111 27 24.51807 24.84882 27 24.57327 23.80579 27 25.35532 22.55307 27 26.73299 21.98407 27 28.18693 22.24264 27 29.33715 23.48723 5.299999 25.5733 17.06589 5.299999 28.36572 17.00593 5.299999 28.444 19.92703 5.3 25.20662 19.45254 5.299999 25.00183 18.11234 5.299999 26.05451 20.2753 5.299999 27.22255 20.5153 5.299999 28.92801 19.05103 5.299996 28.98378 18.02776 5.299999 26.60831 16.49603 5.299999 27.64047 16.59082 24.7 25.05102 17.84015 24.70001 28.69632 19.58743 24.7 25.90674 16.79663 24.7 27.05018 16.45842 24.7 25.16214 19.36431 24.7 27.94705 20.2753 24.7 28.82198 17.62285 24.70001 29.01401 18.62135 24.7 26.95753 20.5104 24.7 25.97895 20.23308 24.7 28.16653 16.84509 5.199999 27.29586 22.47934 5.199998 28.44397 25.92703 5.199999 25.27649 23.46661 5.199998 24.99385 24.27921 5.199998 28.98237 24.87541 5.199999 25.09129 25.10898 5.199999 25.96561 22.7408 5.199999 25.6289 25.99542 5.199999 28.91744 23.8604 5.199999 27.0537 26.54798 5.199999 28.36568 23.00591 3.8 26.61709 26.47407 3.8 25.55757 25.92706 3.8 25.01916 24.87541 3.8 25.13168 23.68834 3.8 26.05185 22.69264 3.8 27.03112 22.48635 3.8 27.87138 22.6718 3.8 28.64877 23.32756 3.8 29.00771 24.27924 3.799999 28.85693 25.28516 3.799999 27.95693 26.3128 3.8 29.47345 23.89657 3.8 28.70693 22.63425 3.8 27.36965 21.97601 3.8 25.91257 22.2166 3.8 25.09308 22.86426 3.799999 24.57326 23.80582 3.8 24.54656 25.07691 3.8 25.00707 26.0144 3.8 25.81793 26.72095 3.8 27.05486 27.01485 3.8 28.4758 26.56474 3.8 29.36128 25.38287 5.199998 25.44112 11.18581 5.199999 24.96632 12.45568 5.199998 27.94972 10.69264 5.199999 25.39469 13.74196 5.199998 28.86985 11.68829 5.199999 26.60827 10.49604 5.199999 26.2021 14.33331 5.199999 27.04405 14.5104 5.199999 28.66562 13.66254 5.199999 28.99464 12.71744 5.199999 27.8548 14.30832 3.8 26.61709 14.47406 3.8 25.69947 14.03533 3.8 25.19568 13.36877 3.8 24.9705 12.35692 3.8 25.40427 11.25806 3.8 26.36965 10.55817 3.799999 27.5511 10.55086 3.8 28.28467 10.95068 3.8 28.82198 11.62286 3.8 29.0149 12.62152 3.799999 28.69629 13.5874 3.8 27.79363 14.36659 3.8 28.47582 14.56474 3.8 29.45014 13.17815 3.8 29.33714 11.48721 3.8 28.36833 10.37265 3.8 27.38723 10.01445 3.799999 26.31285 10.06541 3.8 25.21649 10.70908 3.8 24.57326 11.80586 3.8 24.58757 13.29629 3.8 25.4584 14.48902 3.8 26.84666 15.03145 24.8 28.1665 10.84508 24.8 25.02264 12.01575 24.8 28.98153 11.94136 24.8 25.51483 11.14429 24.8 28.91026 13.10901 24.8 28.37271 13.99539 24.8 26.94784 14.54797 24.8 25.55755 13.92704 24.8 25.07353 13.05099 24.8 26.36967 10.55817 24.8 27.36971 10.52033 26.2 27.05371 14.54797 26.2 25.7668 14.08969 26.2 25.14462 13.28508 26.2 25.00183 12.11233 26.2 25.47467 11.18988 26.2 26.13025 10.67175 26.2 27.29586 10.47933 26.2 28.62183 11.22792 26.2 29.02478 12.70197 26.2 28.44405 13.927 26.2 27.58175 14.96889 26.2 25.89715 14.78422 26.2 24.70249 13.58224 26.2 24.5281 11.89656 26.2 25.14319 10.80725 26.2 26.0112 10.172 26.2 27.49139 9.996888 26.2 28.60574 10.56531 26.20001 29.27725 11.4053 26.2 29.51509 12.87685 26.2 28.8584 14.19962 24.8 25.01916 24.87544 24.8 25.13168 23.68836 24.8 28.85689 25.2851 24.8 26.05182 22.69264 24.8 27.215 22.48579 24.8 28.46115 23.04535 24.8 29.0077 24.27922 24.8 25.97885 26.23302 24.8 27.12408 26.52369 24.8 28.23468 26.08972 24.8 25.36964 25.66116 26.2 26.36942 26.40958 26.2 25.27834 25.61534 26.2 25.00183 24.11234 26.2 25.57336 23.06577 26.2 26.77371 22.44917 26.2 28.24022 22.87887 26.2 28.97891 24.01575 26.2 28.88922 25.20474 26.2 28.302 26.03531 26.2 27.38445 26.47406 26.2 29.3832 23.60187 26.2 29.41397 25.29625 26.2 28.54315 26.48901 26.2 27.1549 27.03145 26.2 25.72347 26.66819 26.2 24.96188 25.95332 26.2 24.52378 24.97115 26.2 24.66442 23.48727 26.2 25.81464 22.24262 26.20001 27.49139 21.99689 26.2 28.60573 22.56524 14.69261 11.01223 27.49262 13.63439 10.48686 27.4926 13.01899 9.465554 27.49262 13.23146 7.952179 27.49263 14.28783 7.112362 27.49262 15.2992 7.00483 27.49262 16.23463 7.404209 27.49262 16.7663 8.048798 27.49262 17.0342 9.0502 27.49262 16.64754 10.16647 27.49263 15.86984 10.82198 27.49262 12.99838 8.860901 29.69262 13.21732 8.054505 29.69261 14.04006 7.206634 29.69262 15.21336 6.993838 29.69262 16.16504 7.352745 29.69261 16.73671 7.99588 29.69261 17.0342 8.951358 29.69262 16.7663 9.95279 29.69264 16.23462 10.59737 29.69262 15.13568 11.03105 29.69262 13.97888 10.74164 29.69259 13.16672 9.883679 29.69261 13.12149 10.71561 29.69262 12.46117 9.154862 29.69262 12.82443 7.72348 29.69263 13.91038 6.702476 29.69261 15.14433 6.496807 29.69262 16.1838 6.772957 29.69263 16.97502 7.454819 29.69264 17.51609 8.632643 29.69266 17.35198 9.871949 29.69262 16.63355 10.95035 29.69263 15.26673 11.50944 29.69262 14.22936 11.38758 29.69262 17.37827 9.875641 30.49262 16.6853 10.85828 30.49266 15.79028 11.3966 30.49262 14.31445 11.45015 30.49263 13.0716 10.62739 30.4926 12.58263 9.669388 30.49262 12.50491 8.627846 30.49262 12.90097 7.627869 30.49262 13.63153 6.881363 30.49259 15.04621 6.457694 30.49262 16.45631 6.940746 30.49262 17.43513 8.208235 30.49255</float_array> + <technique_common> + <accessor source="#Link3-mesh-positions-array" count="3666" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Link3-mesh-normals"> + <float_array id="Link3-mesh-normals-array" count="22188">-0.08957082 0.9957974 -0.01909434 0.008952796 0.9932667 -0.1155047 0.01493918 0.9867722 0.1614233 -0.1426048 0.9897609 0.006102383 0.1390774 0.9797221 -0.1442297 -0.1520364 0.9784501 0.1397157 0.8386694 0.5446409 0 0.8386691 0.5446411 0 0.7333598 0.6798016 0.007298409 -3.1336e-7 -2.03499e-7 -1 4.77379e-7 5.20463e-6 -1 -4.0938e-6 -2.91247e-6 -1 -3.36155e-6 -2.02309e-6 -1 6.91495e-7 3.46138e-6 -1 3.22854e-6 3.24372e-6 -1 0.5993467 0.7998267 0.03257077 0.6142026 0.7889664 -0.01694369 -3.07457e-7 -2.17659e-6 1 0 0 1 -2.60871e-7 1.8106e-6 1 1.44773e-6 5.37761e-6 1 2.73857e-7 -6.443e-6 1 3.38732e-6 -5.00702e-6 1 0.7271539 0.6864315 -0.007680654 0.8386694 0.5446409 0 0.9644201 0.2586212 0.05485445 -5.69515e-4 0.9999998 -4.9951e-5 5.3005e-4 0.999984 0.005638659 -0.8386694 0.5446409 0 -0.8386709 0.5446387 -3.57407e-7 -0.7333984 0.6797599 -0.007296502 0 0 1 3.04267e-7 -2.15401e-6 1 6.34397e-6 -6.39633e-6 1 -1.01891e-5 1.38902e-5 1 1.00499e-6 3.78715e-6 1 -5.18831e-6 2.83158e-6 1 -0.6117977 0.7858708 0.09005886 -0.5292516 0.8341739 -0.1550694 0 2.27794e-6 -1 3.11146e-7 -2.02062e-7 -1 0 0 -1 2.50918e-7 1.76758e-6 -1 2.8756e-6 -3.60967e-6 -1 -6.84637e-7 -3.61451e-6 -1 -0.7271656 0.6864191 0.007680416 -0.8386694 0.5446409 4.74402e-7 -0.9644212 0.2586169 -0.05485463 0.02155816 0.9956616 0.0905165 0.04383003 0.9980694 -0.04400503 1.9196e-7 0 1 -4.49336e-7 6.98936e-6 1 -2.77895e-6 4.57191e-6 1 -3.00275e-6 4.74095e-6 1 -1.56358e-6 1.61448e-6 1 -0.0364691 0.9952306 0.09047728 -0.01940351 0.9997192 -0.01359832 2.78361e-6 5.21814e-5 -1 -3.5705e-7 0 -1 -9.31775e-7 -8.89122e-6 -1 -2.18669e-5 -8.17913e-6 -1 -3.63074e-5 5.22451e-5 -1 0.9999867 2.61827e-4 0.005162954 1 0 0 0.9999753 0 0.007013857 0.9999754 0 0.007013857 0.9999754 0 0.007013857 0.9999915 0 -0.004123985 1 0 0 0.9999904 0 -0.00440061 0.9999904 0 -0.00440061 0.9999904 0 -0.00440061 1 0 0 1 -4.46621e-7 -7.13276e-7 1 0 0 0.9999754 0 0.007013857 0.9999755 0 0.007013857 0.9999753 0 0.007013857 1 0 0 1 0 0 1 0 0 1 0 0 0.9999915 0 -0.004123985 0.9999907 2.75082e-5 -0.004320919 0.999975 -0.007065534 0 0.999975 -0.007065534 0 0.9999728 -0.007358789 3.25123e-5 0.9999716 -0.007533073 0 0.9999903 0 0.004404664 1 -2.57581e-6 1.23725e-6 1 1.17934e-6 2.53463e-6 1 1.76649e-6 3.79652e-6 1 0 -1.92048e-6 1 -1.06649e-6 1.60787e-6 1 3.47937e-6 -1.67127e-6 1 -1.79275e-6 0 1 -7.46813e-7 4.53483e-7 1 0 0 1 2.11151e-6 1.75707e-6 1 0 0 1 2.55385e-6 -1.8224e-6 1 -1.28366e-6 0 1 0 0 1 3.76474e-6 -1.22809e-5 -0.9999819 0 -0.006024599 -1 0 0 -0.9999828 0 0.005856812 -0.9999829 0 0.005856812 -0.9999829 0 0.005856812 -1 0 0 -1 0 0 -0.9999372 -0.01120519 0 -0.9999554 -0.009438991 -3.27699e-4 -1 0 0 -1 0 0 -0.9999829 0 0.005856812 -0.9999829 0 0.005856812 -1 0 0 -1 0 0 -1 0 0 -0.9999791 0 -0.006472826 -0.9999791 0 -0.006472826 -0.9999811 -4.49539e-5 -0.006153881 -0.9999818 0 -0.006024599 -0.9999819 0 -0.006024599 -0.9999928 0 0.003802537 -0.9999789 -0.006488263 0 -0.9999789 -0.006488263 0 -1 -3.14041e-7 0 -1 8.94212e-7 -5.42331e-7 -1 -5.7258e-7 3.47264e-7 -1 1.54961e-7 -1.38094e-7 -1 2.73638e-7 -5.65152e-7 -1 9.39409e-7 2.95997e-7 -0.9999903 2.05404e-4 0.004398822 -0.9999828 0 0.005856752 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.48365e-7 3.26285e-7 -1 -2.68152e-7 -3.5228e-7 -1 -3.56929e-7 7.37176e-7 -1 0 -4.83695e-7 -1 0 -2.81919e-7 -1 0 0 -1 0 4.68152e-7 -1 3.43742e-7 -6.73772e-7 -3.14005e-4 0.04666692 0.9989104 4.57929e-6 -2.0585e-5 1 -0.001872658 -4.45142e-4 0.9999982 -0.003243386 0.001571953 0.9999935 -0.01726329 0.01438963 0.9997474 -0.001923382 0.03905957 0.999235 -3.13393e-5 0.03530895 0.9993764 6.03227e-4 0.01940727 0.9998115 -4.25123e-4 0.03960138 0.9992155 3.87085e-6 -4.17699e-5 1 -0.01170068 0.02133458 0.999704 -0.01478958 0.02675801 0.9995325 -0.007143676 0.02161854 0.9997407 0.002616941 1.62832e-5 0.9999966 0.004675447 0.01757967 0.9998345 0.008788704 0.01612752 0.9998313 -0.001451909 -0.004911601 0.9999869 -4.49851e-5 3.05085e-5 1 0 4.12624e-6 1 -1.56546e-7 4.70381e-6 1 0.004219532 -8.9084e-4 0.9999908 -3.32364e-4 -3.78283e-4 0.9999998 -0.001832425 -2.60711e-4 0.9999983 -1.45243e-6 1.13816e-5 1 -5.11115e-6 -5.23921e-6 1 0 1.30402e-5 1 3.58786e-4 -0.001158893 0.9999994 -3.5662e-6 -2.65764e-6 1 -6.67219e-7 -6.04812e-6 1 -0.003825247 -0.0016613 0.9999914 0.002353072 -0.001033425 0.9999967 0.002085924 -1.82404e-4 0.9999978 0.007684707 2.58904e-4 0.9999705 1.6497e-5 -1.08315e-5 1 7.3797e-6 -1.76688e-7 1 7.07375e-7 -2.48889e-7 1 -9.74104e-6 5.50543e-6 1 7.11315e-6 -3.00499e-6 1 9.77662e-5 -4.2834e-5 1 5.68689e-7 1.89878e-6 1 0.004418075 -0.003864705 0.9999828 0.003233909 -0.004209458 0.9999859 0.00332266 -0.001762866 0.9999929 -4.36072e-7 -1.7738e-6 1 1.37293e-5 -6.27236e-6 1 -6.5945e-6 2.3388e-6 1 -1.77224e-6 2.76772e-6 1 4.16652e-4 -6.70436e-4 0.9999997 -2.93433e-6 -8.37309e-6 1 4.95633e-6 1.51172e-6 1 -9.02198e-5 1.18393e-5 1 2.2746e-4 -3.42677e-4 0.9999999 0.0110957 0.001041352 0.999938 -4.35171e-6 -6.25982e-6 1 1.70636e-4 1.96653e-5 1 -0.006067752 -4.24145e-4 0.9999815 0.01243072 0.0105645 0.9998669 -9.86283e-6 1.6842e-5 1 -1.903e-5 3.55414e-5 1 -1.90454e-6 8.43489e-6 1 7.93215e-6 -1.57136e-5 1 -0.001141428 -0.003331124 0.9999939 -0.001481056 -0.002082467 0.9999967 -0.008698701 0.002798855 0.9999583 -0.01756513 0.002322971 0.999843 -1.2077e-4 -4.03096e-4 1 -1.04811e-6 -9.50077e-6 1 8.91432e-6 -1.97897e-7 1 -0.003701031 -0.003392219 0.9999874 -0.003803849 -0.003374338 0.9999871 -2.33359e-6 -3.36024e-6 1 -9.7223e-6 -9.55891e-6 1 0 -1.48024e-6 -1 1.85332e-7 -2.87832e-6 -1 0 -1.83324e-6 -1 -1.46868e-7 2.28096e-6 -1 -1.19661e-7 2.39382e-6 -1 -1.50795e-7 2.33318e-6 -1 1.46888e-6 -1.09781e-6 -1 0 2.48959e-7 -1 -6.37372e-7 1.38327e-6 -1 1.4307e-6 3.33399e-7 -1 8.78469e-7 -1.35353e-6 -1 4.33779e-7 4.39817e-7 -1 -8.04386e-6 -2.70588e-6 -1 -2.5962e-6 0 -1 7.73702e-6 -9.25092e-7 -1 -5.7058e-7 0 -1 1.84699e-6 0 -1 -1.95911e-6 9.67742e-7 -1 2.72678e-6 -1.78343e-6 -1 1.59706e-6 5.37237e-7 -1 3.85434e-7 -1.12111e-6 -1 6.99215e-7 -1.4641e-6 -1 1.46973e-6 4.24275e-6 -1 -3.55069e-6 1.16493e-5 -1 1.02996e-6 5.25581e-6 -1 3.15895e-6 -1.07857e-5 -1 -5.97985e-7 1.25213e-6 -1 -1.90158e-7 -4.26044e-7 -1 -5.42845e-7 4.52106e-7 -1 -1.39669e-7 1.40758e-6 -1 3.3404e-7 2.84368e-6 -1 7.63928e-7 -5.48519e-7 -1 0 -1.45297e-6 -1 3.07522e-6 -1.51958e-6 -1 2.39366e-6 2.26968e-7 -1 0 -1.32755e-7 -1 -1.65519e-6 0 -1 -2.19687e-6 4.95548e-7 -1 4.62183e-7 -5.79727e-7 -1 -3.60905e-6 4.09825e-7 -1 -0.9297329 0.3682313 -0.001574218 -0.9004898 0.4336819 -0.03221923 -0.7143552 0.6991356 0.03010183 -0.4554818 0.8896802 -0.03170961 -0.3377765 0.9411354 0.01307743 0.08017301 0.996765 -0.005630373 0.09436923 0.9954557 -0.01274389 0.6206926 0.7839505 0.01273703 0.678483 0.7341794 -0.02532482 0.9351038 0.3531017 0.03000026 0.9782593 0.2060883 -0.02316117 0.9843661 -0.1750846 0.0191999 0.9764967 -0.2155269 0.00157535 0.7441867 -0.6677622 -0.01672863 0.7173141 -0.6967417 0.003402292 0.337456 -0.9411311 0.01989352 0.2474368 -0.9686999 -0.01988452 -0.1738607 -0.9847595 -0.004592061 -0.2693458 -0.9623144 0.03746908 -0.6351045 -0.7712895 -0.0418899 -0.797555 -0.601791 0.0418747 -0.9728805 -0.2282525 -0.03747397 -0.9942281 -0.106128 0.0157212 -0.9975373 -0.06340003 -0.03000009 -0.9312014 0.3638371 0.02205651 -0.8883551 0.4586266 -0.02206492 -0.5893346 0.8072059 0.03321754 -0.455453 0.8896402 -0.03320842 -0.009594798 0.9997106 0.02206182 0.06384837 0.9979181 -0.009092688 0.5058982 0.8625453 0.009090185 0.5153575 0.8569639 0.00443232 0.824681 0.5654154 -0.01437705 0.8489394 0.5284703 0.004593431 0.9871473 0.1586818 0.01898002 0.9990173 0.0377869 -0.02316343 0.940623 -0.3389095 0.01920205 0.9260417 -0.3774178 0.00158751 0.668389 -0.7436677 -0.0146479 0.5676524 -0.8227331 0.02968358 0.328381 -0.9442461 -0.02377516 0.06382745 -0.9975458 0.02877974 -0.1166565 -0.9929673 -0.0201826 -0.4073354 -0.9131817 0.01330858 -0.4919644 -0.8705132 -0.01332938 -0.7290098 -0.6842063 0.02016925 -0.8399679 -0.5418726 -0.02877718 -0.9687073 -0.2458546 0.03408175 -0.9952743 0.09092628 0.03408044 -0.9701337 0.2418268 -0.01897966 -0.7822148 0.6229997 -0.00340569 -0.7738164 0.6334009 0.003404557 -0.4408029 0.8974031 0.01898604 -0.3286703 0.9441606 -0.02316403 0.04861468 0.998633 0.01920431 0.08973318 0.9959647 0.001577973 0.5678069 0.8229915 -0.01674008 0.6206324 0.783923 0.01673108 0.9449176 0.3272893 -0.003557682 0.9407903 0.3389706 0.003550171 0.9872179 -0.1587012 -0.01465314 0.9585096 -0.2835111 0.02968174 0.8318673 -0.5541712 -0.02985405 0.6553931 -0.7540252 0.04365831 0.3782297 -0.9246817 -0.04365611 0.09427851 -0.9948578 0.0370081 -0.1166416 -0.9929691 -0.02017706 -0.4556554 -0.8899491 0.01920509 -0.4920125 -0.8705866 0.001583933 -0.8225482 -0.5685069 -0.0146504 -0.8881807 -0.4585344 0.0296812 -0.9783055 -0.2057986 -0.02377671 -0.9952578 0.09515571 0.02018177 -0.9617086 0.2725585 -0.02877932 -0.8538814 0.5199243 0.02377849 -0.684666 0.7282522 -0.02968323 -0.5636498 0.8256618 0.02411162 -0.10284 0.9942196 -0.03084528 0.01815468 0.9993591 0.0308513 0.5445851 0.8381382 -0.03084731 0.6419432 0.7661314 0.03084534 0.9404423 0.3388339 -0.02756357 0.9805354 0.1927351 0.03746283 0.9746345 -0.2198485 -0.04188466 0.8964086 -0.4412446 0.0418896 0.6649917 -0.7461772 -0.03171241 0.5187738 -0.8543232 0.03171247 0.1594094 -0.9863234 -0.04188925 -0.1027471 -0.9933645 0.05167275 -0.4158747 -0.9087371 -0.03528738 -0.6847203 -0.728308 0.0269373 -0.7538928 -0.6569476 -0.008100569 -0.9546718 -0.2975503 0.008095145 -0.972783 -0.2311528 -0.01617723 1 -4.18908e-6 -2.70475e-6 1 2.8623e-6 1.84809e-6 1 9.32977e-7 1.30137e-6 1 -5.55214e-7 -1.67348e-6 1 1.06592e-6 1.38775e-6 1 -3.49526e-6 -4.55056e-6 1 3.62081e-6 1.03978e-6 1 3.06121e-6 3.11217e-7 1 -2.23081e-6 4.24377e-7 1 1.38334e-6 -1.44194e-6 1 -4.04843e-6 0 1 -1.23372e-6 2.34695e-7 1 2.56602e-6 0 1 2.01266e-6 6.70224e-7 1 -3.8303e-6 -3.94306e-6 1 7.66627e-6 -1.98956e-6 1 3.48548e-6 1.16068e-6 3.63621e-6 -2.66354e-7 -1 -3.27809e-7 9.59726e-7 -1 -7.09368e-7 5.66753e-7 -1 -7.49214e-7 -1.20195e-6 -1 1.51038e-7 -9.55365e-7 -1 1.31831e-7 -8.33871e-7 -1 -3.67387e-7 -8.06806e-7 -1 1.73761e-6 3.81592e-6 -1 4.40461e-6 1.88487e-6 -1 -8.3598e-7 -1.50369e-6 -1 -8.61973e-7 -8.50671e-7 -1 -4.84942e-6 3.27242e-6 -1 -2.15567e-6 3.70685e-6 -1 -2.51791e-6 1.37615e-6 -1 -2.11581e-6 9.73851e-7 -1 1.49906e-6 8.08571e-7 -1 -1.45455e-6 -3.7964e-6 -1 -5.00796e-6 1.40511e-6 -1 5.5116e-6 5.99813e-6 -1 8.7966e-6 -1.68945e-6 -1 -4.05258e-7 -7.87071e-7 -1 -1.9338e-7 -3.75572e-7 -1 2.01473e-6 -2.22425e-6 -1 1.53729e-5 3.4714e-6 -1 -1.70228e-6 -2.31463e-6 -1 -1.54031e-6 8.58361e-7 -1 -1.48305e-6 8.42362e-7 -1 -1.64142e-6 6.41332e-7 -1 -3.80861e-6 3.14339e-6 -1 -5.0942e-6 2.15799e-7 -1 2.14009e-6 -2.24679e-6 -1 2.67247e-6 -8.73247e-7 -1 -4.10586e-7 1.11337e-6 -1 -1.10397e-6 0 -1 -2.36593e-6 1.52602e-6 -1 1.6693e-6 3.39705e-6 -1 1.15623e-6 -2.54395e-6 -1 1.22977e-6 -2.57008e-6 -1 2.02821e-6 -8.30062e-7 -1 1.13454e-6 0 -1 1.77935e-6 2.16913e-7 -1 1.21288e-6 1.51067e-6 -1 -3.0662e-6 2.33158e-6 -1 -2.98587e-6 2.79331e-6 -1 2.49842e-6 -2.3373e-6 -1 -1.21208e-6 -5.17246e-6 -1 -3.50005e-6 1.11987e-5 -1 1.08741e-6 9.29393e-7 -1 3.22809e-6 -1.90762e-6 -1 -7.32137e-7 -1.61865e-6 -1 -5.49953e-7 2.58257e-7 -1 -8.40746e-7 3.94812e-7 -1 0 2.14383e-6 -1 7.54624e-7 1.47387e-6 -1 1.54751e-6 1.98948e-6 -1 1.42241e-6 7.34338e-7 -1 2.2497e-6 6.00661e-7 -1 7.25696e-7 -1.2822e-6 -1 -3.27447e-6 2.2278e-6 -1 -4.94532e-6 -1.78797e-7 -1 9.03244e-6 -3.23199e-6 -1 1.59945e-6 -1.23164e-5 -1 1.22316e-6 3.97525e-7 -1 1.23148e-6 3.94505e-7 -1 -3.05898e-6 -6.30405e-6 -1 -1.6722e-6 -7.204e-6 -1 -3.89675e-7 1.52031e-7 -1 -3.82554e-6 1.49253e-6 -1 -5.01771e-6 -8.83704e-7 -1 -2.42231e-6 -2.0703e-6 -1 1.10366e-6 9.6052e-7 -1 8.80685e-7 3.52946e-7 -1 1.33382e-6 -1.64746e-7 -1 0 0 -1 0 -5.7465e-7 -1 2.99278e-7 -7.72231e-7 -1 5.81008e-6 3.59912e-6 -1 1.18101e-5 -1.51814e-5 -1 1.81399e-6 -1.27984e-5 -1 6.2105e-6 -1.45524e-6 -1 1.08884e-6 1.84483e-6 -1 -1.57592e-6 -2.6701e-6 -1 -2.16634e-6 -2.57647e-6 -1 -2.39214e-6 -3.40253e-6 -1 -4.80246e-6 -2.15864e-6 -1 2.47297e-7 1.48241e-6 -1 7.47034e-7 3.48508e-7 -1 2.06614e-6 3.20064e-7 -1 4.4779e-7 -3.07038e-6 -1 -2.83236e-7 -1.32323e-7 -1 -9.64081e-7 -4.50402e-7 -1 -1.345e-6 6.70748e-7 -1 0.2904221 -0.05958741 -0.9550415 0.2914889 0.06022727 -0.9546763 0.2143153 0.1292886 -0.9681701 -0.001926124 0.2956529 -0.9552935 -0.1233557 0.2312341 -0.9650463 -0.2779376 0.08659654 -0.956688 -0.1838718 0.1412684 -0.9727458 -0.2983343 -0.04706346 -0.9533005 -0.230838 -0.1221325 -0.9652966 -0.07523185 -0.2861381 -0.9552304 0.04119819 -0.2666397 -0.9629154 0.2122205 -0.1280071 -0.9688017 -0.1628213 -0.212971 -0.9633963 -0.1710858 -0.1170328 -0.9782807 -0.1325804 -0.1503355 -0.9797049 -0.1381837 0.1100721 -0.984271 -0.1638207 0.1433643 -0.9760171 0.0159915 -0.2555754 -0.9666568 -0.04959821 -0.1183872 -0.991728 0.08044683 0.009923994 -0.9967095 0.1551251 -0.2241085 -0.9621391 0.2033747 -0.1300369 -0.9704273 0.05904084 0.004947245 -0.9982434 0.1621458 0.1400593 -0.9767764 0.1351481 0.2182632 -0.9664865 7.70312e-7 -1.65912e-6 -1 -1.14099e-6 -4.24634e-6 -1 5.03343e-6 -1.04571e-6 -1 -2.992e-6 -9.24584e-7 -1 6.3371e-6 3.63579e-6 -1 -4.40905e-6 0 -1 -6.07604e-7 0 -1 -3.53197e-7 -1.71997e-7 -1 -2.76105e-6 -2.8374e-7 -1 3.98304e-6 -2.42812e-6 -1 2.87817e-7 -9.40572e-7 -1 -1.93409e-6 -9.76024e-7 -1 2.3896e-6 -1.54304e-6 -1 2.50527e-6 4.22466e-6 -1 -5.78048e-6 -2.23084e-6 -1 1.72477e-6 -2.78251e-6 -1 1.68392e-6 2.31592e-6 -1 1.46355e-6 7.30686e-7 -1 -8.61564e-7 2.05892e-6 -1 -7.22852e-7 6.85448e-7 -1 0 7.00724e-7 -1 3.356e-7 -3.27636e-6 -1 -8.89565e-7 0 -1 -1 0 0 -1 4.06976e-7 0 -1 -4.51986e-7 -1.86413e-7 -1 6.02172e-7 0 -1 -2.44732e-7 -2.18086e-7 -1 1.00692e-6 0 -1 6.17911e-7 1.47724e-7 -1 -1.34036e-6 6.13866e-7 -1 -6.84713e-7 0 -1 -3.71959e-7 -1.57549e-7 -1 6.35113e-7 1.77759e-7 -1 6.40382e-7 1.81188e-7 -1 0 0 -1 -4.68006e-7 0 -1 -6.26666e-7 0 -1 2.01227e-6 7.80498e-7 -1 -5.07834e-7 0 -1 0 -1.28533e-7 -1 0 0 -0.04711318 0.06332772 -0.9968801 0.05350816 0.2456205 -0.9678881 -0.06211024 0.5873888 -0.806918 0.06222337 0.7271504 -0.6836524 -0.04911893 0.9823064 -0.1807248 0.02188861 0.9944533 -0.102876 -0.02189111 0.8637867 0.5033819 0.0218442 0.8383532 0.5446898 -0.02383542 0.3288088 0.9440957 -0.003605365 0.310125 0.9506889 0.02916884 -0.3271313 0.9445286 -0.0677278 -0.4383351 0.8962563 0.06574308 -0.7823298 0.6193851 -0.09678053 -0.9251947 0.3669444 0.09683996 -0.9951357 0.01807969 -0.09192818 -0.9122631 -0.3991556 0.05210864 -0.8065754 -0.58883 -0.03465807 -0.4584952 -0.8880208 0.03467053 -0.3637071 -0.9308679 -0.08104288 0.06037944 -0.9948801 0.055399 0.3765789 -0.9247266 -0.04230761 0.6528574 -0.7562985 0.02978157 0.7458965 -0.6653956 -0.04235398 0.9403713 -0.3375024 0.04857915 0.9899249 -0.133 -0.02901422 0.9981818 0.05283164 0.02901989 0.9313259 0.363029 -0.03713482 0.8619647 0.5056062 0.04687732 0.6960101 0.7165002 -0.04561388 0.5279607 0.848043 0.03404581 0.1315656 0.9907226 -0.005582392 0.1751011 0.9845346 0.02470463 -0.3531415 0.9352437 -0.04020887 -0.441244 0.896486 0.04020708 -0.7833861 0.6202337 -0.007205367 -0.8257009 0.5640622 -0.02983617 -0.9792599 0.2003998 0.05350518 -0.9973868 0.04854756 -0.05351388 -0.9529664 -0.298314 0.07992762 -0.8500955 -0.5205279 -0.0968436 -0.5771974 -0.8108418 0.09677535 -0.2551092 -0.9620571 0.2038996 0.9748581 -0.08986979 0.3161866 0.944384 0.09036028 0.6746647 0.7342202 -0.07581746 0.7466658 0.6636775 0.04497104 0.9461854 0.3232687 -0.01518088 0.9561851 0.2828232 -0.07563966 0.9882771 -0.1215826 0.09233582 0.9519988 -0.2964047 -0.0764364 0.8663435 -0.4958963 0.05946284 0.7449297 -0.6621466 -0.08149623 0.5154979 -0.8489444 0.1164271 0.3510177 -0.9307281 -0.102625 -0.08003914 -0.9937613 0.0776689 -0.1785702 -0.9815586 -0.06822979 -0.5516372 -0.828764 0.0940569 -0.7137097 -0.6924169 -0.1057233 -0.8326648 -0.5501356 0.06340497 -0.9757636 -0.2005079 -0.08764731 -0.9928998 -0.1060033 0.05397516 -0.9296952 0.3682898 -0.005432784 -0.8954837 0.431271 -0.1100646 -0.7109191 0.6956924 0.102985 -0.4243969 0.8963618 -0.1281517 -0.3030627 0.9505577 0.06777179 -0.9139986 0.3976656 -0.08042746 -0.719258 0.6908668 0.07328718 -0.688363 0.7253461 0.005423486 -0.3023918 0.9518548 -0.05031514 -0.2036243 0.9764837 0.07083082 0.1200755 0.9902349 -0.07082825 0.2205797 0.9740701 0.05031782 0.65326 0.7570654 -0.01017105 0.6559363 0.7546287 -0.01682788 0.9356873 0.3526256 -0.01202231 0.9491969 0.3117677 0.0427348 0.9954246 -0.07369774 -0.06081575 0.9915551 -0.1286159 0.01662606 0.8519662 -0.5191328 0.06822687 0.7768589 -0.6193658 -0.1134739 0.4432825 -0.8940199 0.06503248 0.3226953 -0.9419966 -0.09225106 0.03185784 -0.9941711 0.1029999 -0.2852124 -0.9523128 -0.108417 -0.4297058 -0.8997797 0.07582414 -0.7540746 -0.6509125 -0.08766096 -0.8009432 -0.5985333 0.01574444 -0.9682372 -0.2413933 0.06516212 -0.9890528 -0.08973628 -0.1171403 -0.9720449 0.2181585 0.08680766 0.5619698 0.8250171 -0.05947136 0.6838565 0.7240709 0.0897873 0.8632736 0.4941144 -0.1030024 0.966646 0.2448042 0.07527542 0.9929826 0.09120881 -0.0752775 0.9785697 -0.1783066 0.1029962 0.8538516 -0.5045781 -0.127821 0.77082 -0.630069 0.09407281 0.4149464 -0.906511 -0.0778287 0.2329255 -0.9623363 0.1401951 -0.03121244 -0.9918334 -0.1236622 -0.3992754 -0.9063618 0.1381571 -0.6068844 -0.7802094 -0.1515411 -0.8100929 -0.5731735 0.1233761 -0.9604623 -0.2564392 -0.1084032 -0.9914872 -0.1058509 0.0758208 -0.9683551 0.2413986 -0.06336581 -0.9035606 0.4151929 0.1057972 -0.7976293 0.5960403 -0.09232276 -0.5174957 0.8532112 0.06502974 -0.4014214 0.9112359 -0.09224903 -0.1160523 0.9878883 0.1029973 0.175646 0.9803421 -0.08987665 0.3218709 0.9455615 0.04808932 0.7490257 -0.6494891 0.1308605 0.5296408 -0.8338278 -0.1556018 0.259175 -0.9575397 0.1262772 -0.009522914 -0.9919501 -0.1262705 -0.2954088 -0.9437479 0.1485714 -0.6045059 -0.7771168 -0.1751061 -0.7898604 -0.5966161 0.1420204 -0.951912 -0.29648 -0.0772221 -0.9882974 -0.1370396 0.06699627 -0.9845654 0.157689 -0.07592797 -0.95424 0.2873985 0.08263301 -0.722984 0.6843941 -0.09433382 -0.633207 0.7689995 0.08768498 -0.3021678 0.9511457 -0.06337374 -0.1201994 0.9870975 0.1057865 0.0893383 0.9917123 -0.09233242 0.501571 0.8607502 0.08680742 0.5673626 0.8223041 -0.04376643 0.9334403 0.3555286 0.04783838 0.9496018 0.3097878 -0.04783266 0.9668285 -0.2524356 0.03897511 0.9362716 -0.3387859 -0.09284251 -0.8400996 0.5414229 0.03307223 -0.8441714 0.535793 0.01733845 -0.5929756 0.8049061 -0.02249664 -0.5775102 0.8161242 0.02057331 -0.1399779 0.9895865 0.03353816 -0.1495276 0.9867072 0.06364178 0.2588178 0.9591517 -0.1141988 0.3928174 0.907259 0.1502519 0.6220272 0.7723057 -0.128942 0.7563821 0.6469908 0.09637957 0.8664335 0.4897852 -0.0969718 0.9445035 0.3108524 0.1062269 0.9758569 0.164269 -0.1439406 0.9496645 -0.2867578 0.1261243 0.9500634 -0.2976758 0.09364223 0.756166 -0.6368843 -0.1503046 0.5636051 -0.8068352 0.177105 0.4877855 -0.8716679 -0.04754352 0.06781244 -0.9964109 0.05066573 -3.98267e-4 -0.9920485 -0.1258562 -0.4299782 -0.888697 0.1591745 -0.531633 -0.83927 -0.1139839 -0.9762193 0.2039646 -0.07344514 -0.9691975 0.03765827 0.2433887 -0.969903 -0.2025718 -0.1351032 -0.8347954 -0.5406119 0.1041892 -0.8393691 -0.5364213 0.08781677 -0.9927815 0.1187497 0.01683849 -0.9612824 0.2753735 -0.01027405 -0.5749225 0.8182075 -8.7046e-4 -0.5244745 0.8513556 0.0109592 0.066697 0.9977322 -0.009053707 0.18686 0.9823449 0.009050309 0.7220926 0.6917095 -0.01095908 0.7808425 0.624694 0.006512165 0.9933623 -0.1150267 -4.45767e-4 0.9862015 -0.1651669 -0.01124864 0.6786518 -0.7343521 0.01260298 0.4754512 -0.8794152 -0.02397853 0.008329153 -0.9995881 0.0274651 -0.4193127 -0.9074265 -0.02746319 -0.7777289 -0.6282498 0.02097284 -0.9208856 -0.389599 -0.01350289 -0.783739 0.6210901 -3.65671e-4 -0.7454071 0.6663965 0.01684409 0.1769434 0.9841085 -0.01488339 0.3474429 0.9372846 0.02794259 0.8986208 0.4376031 -0.03137391 0.9956364 0.08714276 0.03338015 0.8889098 -0.4574928 -0.0232321 0.6575289 -0.7530178 0.02489894 0.2925005 -0.9558767 -0.02726155 -0.2384914 -0.9706726 0.03027397 -0.5666881 -0.8236157 -0.02284139 -0.923377 -0.3831371 0.02410477 -0.9764621 -0.215489 -0.009281635 -0.01457989 0.9996456 0.02227509 0.395273 0.9183232 -0.02102011 0.7080104 0.7056866 0.02697682 0.9410035 0.3372409 -0.02794635 0.9512172 -0.3073573 0.02678328 0.9111432 -0.4120898 3.2824e-4 0.2439015 -0.9697723 -0.007324695 0.06946241 -0.9970914 0.03136271 -0.4980469 -0.8666768 -0.02864474 -0.8991733 -0.4361723 0.03522962 -0.96657 -0.2563313 -0.00606513 -0.9008867 0.4338686 -0.01270854 -0.779103 0.6263027 0.02726942 -0.4025002 0.9151976 -0.02017295 -0.9980458 -0.05676901 -0.02611458 -0.8757612 0.4822438 0.0219835 -0.7255482 0.6880047 -0.01514804 -0.3432409 0.9391762 0.01156306 -0.1023743 0.9946293 -0.01523393 0.2823762 0.9592015 0.01399981 0.568592 0.8223713 -0.02020972 0.83459 0.5505905 0.01759451 0.9894946 0.1435721 -0.01695352 0.9993437 -0.03489518 0.00972712 0.7808065 -0.6246818 -0.01066362 0.7005959 -0.7134881 0.01000672 0.1570148 -0.9875455 -0.01000827 -0.0221529 -0.9995342 0.02099198 -0.6147155 -0.7882114 -0.02911412 -0.8844695 -0.4652301 0.03570342 -0.005572557 -0.09095525 -0.9958394 0.02627837 0.4586115 -0.8882483 -0.02628397 0.5159307 -0.856227 0.005560696 0.8956716 -0.4446814 0.02188485 0.9033771 -0.4282882 -0.02001613 0.9869933 0.1595102 0.0397948 0.9713804 0.2341722 -0.05214589 0.7455642 0.6643905 0.05213928 0.6321668 0.7730761 -0.03464698 0.2199302 0.9749001 -0.006944477 0.1792832 0.9837729 0.02259677 -0.2454218 0.9691529 -0.007209658 -0.2880719 0.9575815 -0.02981936 -0.6360513 0.7710704 0.06991231 -0.7646262 0.6406708 -0.04560202 -0.9082385 0.4159606 0.02895414 -0.9990684 0.03199958 -0.00884813 -0.9967436 0.0801503 0.02054667 -0.9410043 -0.3377706 -0.03472596 -0.9018152 -0.4307243 0.04023057 -0.6529332 -0.7563463 -0.0246911 -0.5774391 -0.8160604 0.005592823 -0.07861495 -0.9968894 0.008844375 0.2883481 -0.9574848 -0.02895355 0.2417705 -0.9699014 0.05121588 0.6221842 -0.7811939 -0.08104658 0.7867195 -0.6119672 0.06850683 0.9520952 -0.2980297 -0.05809366 0.9982652 -0.009576499 0.05809468 0.9636415 0.2608064 -0.06851518 0.8462646 0.5283387 0.0810393 0.607142 0.79045 -0.08103877 0.3547483 0.9314432 0.05540162 0.03775787 0.99775 -0.03448796 -0.2582832 0.9654535 0.03449171 -0.4055428 0.913425 -0.04728496 -0.6355953 0.770573 0.05882072 -0.8625035 0.5026212 -0.04328781 -0.9293099 0.3667552 0.04328668 -0.9917382 -0.1207549 -0.05881875 -0.9613254 -0.269061 0.06574994 -0.7702951 -0.634289 -0.06570523 -0.601029 -0.7965219 0.04981231 -0.2576411 -0.9649559 -0.02054524 -0.1318777 -0.9910531 1 -2.09055e-6 -2.54479e-7 1 -2.93821e-6 5.40573e-7 1 -5.0688e-6 -1.22192e-6 1 -2.64958e-6 -1.54408e-6 1 -2.005e-6 1.62862e-6 1 2.57071e-6 3.57247e-6 1 3.59213e-6 -6.59763e-7 1 -1.5926e-6 2.9251e-7 1 -1.58097e-6 3.91751e-7 1 2.689e-6 -6.6631e-7 1 2.27084e-6 4.46933e-7 1 8.84719e-6 1.74125e-6 1 7.52105e-6 -4.07426e-6 1 -8.85391e-7 -1.7497e-6 1 0 0 1 0 0 1 -4.71524e-7 2.91773e-6 1 -2.05755e-7 3.23892e-6 1 -3.51267e-7 3.32321e-6 1 0 0 1 -9.46107e-6 -3.66975e-6 1 7.48622e-6 2.90375e-6 1 2.21376e-6 6.97463e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 1.08517e-6 -1.63942e-6 1 -4.51946e-7 -3.40327e-6 1 2.01563e-7 -3.69125e-6 1 0 0 1 4.12138e-6 2.55353e-6 1 2.87476e-6 2.773e-6 1 3.03972e-6 1.70788e-6 1 0 0 1 2.82768e-6 -4.18984e-6 1 3.74026e-6 -3.27264e-6 1 -1.06415e-6 9.31107e-7 1 6.73571e-7 7.30706e-6 1 9.66671e-7 7.29548e-6 1 3.14059e-6 2.33674e-6 1 0 0 1 -9.53323e-6 4.71474e-6 3.92312e-5 -1.58368e-5 -1 1.44627e-5 -5.97529e-5 -1 1.36336e-4 -1.14608e-5 -1 0.00301975 -0.002467095 -0.9999925 5.2356e-4 -9.6791e-5 -0.9999998 0.001094341 7.72527e-5 -0.9999994 1.38434e-4 3.54383e-5 -1 2.78589e-5 7.58789e-5 -1 -1.19779e-5 1.17156e-5 -1 1.35214e-5 -1.35377e-5 -1 6.68126e-5 4.96607e-6 -1 4.30938e-5 5.08304e-5 -1 5.78349e-5 7.42536e-5 -1 -1.45755e-4 -6.01269e-4 -0.9999998 7.22926e-5 5.38785e-5 -1 4.12935e-5 4.86537e-5 -1 -1.54002e-4 7.37617e-4 -0.9999997 2.58393e-5 4.27022e-4 -1 5.11034e-6 5.23553e-4 -0.9999999 4.42431e-4 0.001951634 -0.999998 1.64336e-6 -2.23104e-6 -1 -4.72674e-4 7.74927e-4 -0.9999996 -9.63094e-7 -2.692e-7 -1 -5.3012e-7 -4.34193e-7 -1 7.47746e-6 -4.88418e-6 -1 5.6445e-6 -8.49418e-6 -1 -1.46761e-5 -2.89221e-5 -1 0 0 -1 -2.01248e-5 2.76201e-6 -1 -2.17104e-5 -1.79882e-5 -1 0 0 -1 -9.10981e-7 -2.81452e-7 -1 -8.11289e-6 2.43433e-5 -1 -7.24624e-4 -8.00532e-5 -0.9999998 -4.07896e-4 -4.33589e-5 -0.9999999 -0.006512999 1.25849e-4 -0.9999788 -0.002260804 0.002205669 -0.999995 -0.001993596 7.9476e-4 -0.9999977 -1.49269e-4 -1.02177e-4 -1 -1.52414e-4 -2.21705e-4 -1 -7.20838e-5 -3.69093e-6 -1 -7.36898e-5 -3.57456e-5 -1 -1.45419e-6 8.20896e-7 -1 -2.39417e-5 1.88683e-5 -1 -2.17411e-5 -5.31844e-5 -1 -8.67777e-5 -2.52155e-5 -1 -6.09699e-7 -2.12559e-6 -1 9.5395e-6 -2.81759e-6 -1 6.11519e-6 -2.37512e-6 -1 -9.41489e-5 -3.0186e-4 -0.9999999 -9.53773e-5 -2.38398e-4 -1 3.2256e-6 6.6118e-6 -1 3.42761e-6 -1.51125e-5 -1 -2.70203e-6 -6.24974e-7 -1 -4.41546e-5 -3.26037e-4 -0.9999999 3.00461e-5 9.89595e-5 -1 3.30531e-5 -2.92198e-6 -1 4.05075e-5 -2.59018e-5 -1 -2.34073e-6 -1.05613e-4 -1 2.96175e-5 2.11693e-5 -1 -6.71536e-5 -3.59392e-5 -1 4.54381e-5 -4.46042e-5 -1 4.63327e-5 -4.3994e-5 -1 -3.46735e-7 -2.22845e-6 -1 2.62345e-6 8.65561e-7 -1 0 0 -1 -1.83137e-6 -3.26413e-5 -1 0 0 -1 0 0 -1 -3.06358e-6 1.72527e-6 -1 6.09853e-7 -5.93646e-6 -1 -8.28036e-7 -2.71972e-7 -1 8.66736e-5 3.67903e-5 -1 -4.70734e-7 9.49385e-7 -1 2.16478e-5 1.05893e-5 -1 -9.26353e-7 1.20159e-7 -1 -6.20271e-7 3.77953e-7 -1 7.22446e-6 -8.27116e-7 -1 6.71338e-6 -8.3258e-7 -1 -4.12774e-7 1.32328e-7 -1 -5.76414e-7 3.06896e-6 -1 -1.76922e-7 -1.58604e-5 -1 5.18322e-7 -1.66165e-7 -1 2.59488e-7 0 -1 4.65067e-5 5.41424e-5 -1 3.88208e-5 1.00681e-4 -1 4.04876e-7 -6.67531e-7 -1 3.77837e-5 8.58974e-5 -1 3.20514e-7 -7.71824e-7 -1 8.55873e-7 -5.7095e-7 -1 1.60815e-6 -2.40481e-7 -1 4.90921e-6 -8.34356e-7 -1 1.5308e-6 -2.13773e-7 -1 -5.23412e-7 2.38264e-6 -1 9.05532e-6 -8.34683e-6 -1 5.61496e-5 -2.20453e-5 -1 -7.62009e-6 3.53899e-6 -1 -4.85955e-7 0 -1 1.05616e-6 4.78809e-7 -1 1.30946e-7 0 -1 -3.37358e-7 2.59359e-7 -1 0 -1.5403e-6 -1 -3.1357e-7 -2.76736e-6 -1 2.63803e-7 1.19595e-7 -1 -3.58811e-6 -4.54422e-7 -1 -2.2619e-6 -1.42012e-6 -1 -7.06719e-7 0 -1 1.0852e-6 0 -1 0 0 -1 1.20957e-6 1.25549e-6 -1 1.24389e-7 -2.87854e-6 -1 0 -7.30042e-6 -1 -4.513e-7 -3.86031e-7 -1 8.69619e-7 0 -1 -1.65065e-6 0 -1 -7.1185e-7 -2.34282e-7 -1 -4.84907e-7 -5.01732e-7 -1 3.2151e-7 2.7857e-6 -1 0 0 -1 -5.66921e-7 1.75646e-7 -1 0 -6.8035e-7 -1 -4.53059e-6 -2.91179e-5 -1 -4.7542e-5 1.21579e-4 -1 1.60489e-6 -4.10416e-6 -1 2.94142e-7 5.97637e-7 -1 1.53847e-7 3.12585e-7 -1 1.35459e-5 -6.16627e-5 -1 3.31552e-5 1.67178e-4 -1 -2.59681e-6 2.98368e-5 -1 -4.26395e-5 -1.06015e-4 -1 -3.48062e-7 -5.08515e-7 -1 -4.99611e-7 -3.15953e-7 -1 7.84278e-6 -4.3146e-6 -1 -5.70424e-6 -4.90841e-7 -1 1.46962e-6 6.34733e-6 -1 1.16781e-6 -3.35496e-6 -1 1.4989e-6 -3.12514e-6 -1 4.93133e-7 -1.02816e-6 -1 -1.10131e-5 -6.79498e-6 -1 -1.10376e-5 -6.73429e-6 -1 -1.44553e-6 -4.90435e-6 -1 -3.28039e-6 -2.00717e-6 -1 1.43065e-6 8.75367e-7 -1 -2.11997e-7 5.37895e-6 -1 -1.15888e-5 2.39271e-6 -1 -1.16701e-5 2.66251e-6 -1 2.31091e-6 4.52215e-6 -1 2.00201e-6 -1.05693e-6 -1 -6.1587e-6 -5.39725e-7 -1 -8.46873e-7 6.99928e-6 -1 7.73318e-6 -2.43875e-6 -1 2.92434e-5 6.1422e-6 -1 2.70464e-5 1.3292e-5 -1 -5.00501e-6 1.40835e-5 -1 -7.73388e-6 7.48221e-6 -1 3.23873e-6 -1.87502e-6 -1 7.46265e-6 -3.27561e-7 -1 9.63454e-7 3.1401e-6 -1 -4.72686e-7 3.35697e-6 -1 -3.43266e-7 2.43784e-6 -1 -4.30207e-6 1.43823e-6 -1 -3.27203e-6 -1.15801e-6 -1 7.42088e-7 -1.38701e-6 -1 8.86539e-7 1.00834e-6 -1 3.94069e-6 -1.75929e-6 -1 -2.42585e-6 -7.02704e-6 -1 -3.25888e-6 -1.44372e-6 -1 -4.33967e-6 -1.45702e-6 -1 -3.48504e-6 5.54422e-7 -1 1.08593e-6 -8.37946e-7 -1 9.07391e-7 -9.90537e-7 -1 -8.48592e-6 9.2635e-6 -1 -4.63701e-6 1.00327e-5 -1 -4.19243e-6 -2.76578e-6 -1 8.83359e-7 -6.62554e-7 -1 1.29458e-7 7.90903e-7 -1 7.30176e-6 5.54552e-6 -1 6.85387e-6 6.56075e-6 -1 3.54199e-6 0 -1 1.778e-6 -2.6614e-7 -1 0 -2.13509e-6 -1 -1.66317e-6 -1.28491e-6 -1 3.11332e-7 2.22659e-6 -1 3.13718e-6 6.93281e-7 -1 6.29219e-6 2.47661e-6 -1 1.26498e-5 -1.10189e-5 -1 4.89128e-6 -1.04487e-5 -1 7.40599e-6 -6.77936e-6 -1 6.54553e-6 7.01383e-7 -1 -9.33231e-7 0 -1 -9.61362e-7 -1.67486e-7 -1 -1.06901e-6 0 -1 -1.52755e-5 -8.17753e-6 -1 -1.47632e-5 -9.84633e-6 -1 -5.8615e-7 -8.37212e-6 -1 -9.35135e-7 4.66262e-7 -1 1.45544e-6 -7.2569e-7 -1 1.40697e-6 -7.52144e-7 -1 1.95756e-6 -1.96951e-6 -1 -2.58951e-7 -1.10577e-6 -1 2.07014e-7 8.83988e-7 -1 -0.9207456 0.3895493 0.02188539 -0.9137489 0.4062409 0.005574345 -0.5518126 0.8335536 -0.02629309 -0.4711979 0.8806958 0.04845035 0.06662005 0.9966021 -0.04843521 0.1336563 0.9910132 0.005366027 0.5558202 0.8307132 0.03129893 0.676954 0.7324811 -0.07214462 0.9320684 0.3550212 0.07217162 0.9780455 0.2060361 -0.03124451 0.9764763 -0.2155039 -0.007203936 0.938503 -0.3363479 0.07798796 0.7624233 -0.6430309 -0.07226324 0.4473319 -0.8926868 0.05481427 0.323872 -0.9454661 -0.03465515 -0.1612687 -0.9852437 0.05733448 -0.31525 -0.9466136 -0.06738013 -0.762308 -0.6460548 0.03872501 -0.8067162 -0.5908722 -0.008884906 -0.9765151 -0.2152628 0.008949756 -0.9842942 -0.1755913 -0.0182361 -0.9729057 0.2311676 -0.003979921 -0.9765213 0.2152399 0.008829772 -0.7820181 0.6228461 -0.02259159 -0.7364054 0.6760895 0.02470099 -0.2869083 0.9579418 -0.005584061 -0.2987469 0.9543161 0.005578219 0.2003716 0.9794494 -0.02302539 0.3236993 0.9450106 0.04662466 0.5886054 0.8070586 -0.04690492 0.7801046 0.6218892 0.06848639 0.9385855 0.3381752 -0.06851667 0.9969602 0.05192184 0.05808991 0.9868283 -0.158635 -0.03169953 0.8695839 -0.4928628 0.03017026 0.8143185 -0.5791254 -0.03871917 0.4198336 -0.905465 0.0622335 0.2441791 -0.9677391 -0.06210851 -0.07980734 -0.9961109 0.03733569 -0.3130803 -0.9489993 -0.03716498 -0.4593509 -0.887781 0.02901035 -0.7143992 -0.6991376 -0.02898955 -0.8007755 -0.5983831 0.02638435 -0.9401345 -0.3392583 -0.03241926 -0.9700384 -0.2418583 0.02302092 -0.9999772 0.006697416 -7.32051e-4 -0.9981346 0.04996842 -0.03508007 -0.8811445 0.4710453 0.04123979 -0.8341152 0.5511999 -0.0207495 -0.5293743 0.8470344 -0.047912 -0.3430399 0.9346675 0.09338223 0.004651188 0.9984536 -0.05539691 0.3497587 0.9354741 0.05056875 0.4163628 0.9091951 0.002497911 0.7712526 0.636113 -0.02301555 0.8592687 0.507807 0.06155776 0.956721 0.2879056 -0.04237145 0.9924728 -0.1174573 0.03466343 0.9748997 -0.2199336 -0.03463757 0.8062115 -0.5901103 0.04233908 0.6645305 -0.7456799 -0.04858851 0.5151496 -0.8566087 0.02902519 0.2207824 -0.9748912 -0.02902436 0.06375402 -0.9972743 0.0371406 -0.2039199 -0.977864 -0.04688936 -0.4303125 -0.9008947 0.05674326 -0.7568928 -0.6500258 -0.06767439 -0.8315864 -0.5546287 0.02917164 -8.70224e-7 -2.41247e-7 -1 1.85855e-7 -1.65211e-7 -1 8.082e-7 0 -1 -1.83418e-6 0 -1 -1.09419e-6 -1.34163e-7 -1 1.24786e-6 -7.4213e-7 -1 1.64069e-6 1.69497e-6 -1 6.75183e-7 1.99715e-7 -1 3.21673e-7 0 -1 5.57522e-6 -3.31571e-6 -1 -7.48755e-7 2.93142e-6 -1 -1 4.42039e-7 -3.01776e-7 -1 2.44859e-7 -4.31488e-7 -1 -1.86617e-7 0 -1 2.103e-7 0 -1 -2.35528e-7 -9.33098e-7 -1 0 -9.62774e-7 -1 0 3.42659e-7 -1 1.78235e-7 3.28378e-7 -1 0 0 -1 2.22109e-7 -2.56852e-7 -1 -4.83892e-7 0 -1 -4.38687e-7 3.02673e-7 -1 0 1.60164e-7 -1 0 1.95807e-7 -1 -4.44798e-7 8.19541e-7 -1 4.82206e-7 1.05456e-6 -1 -5.26168e-7 -3.96746e-7 -1 0 -4.75516e-7 -1 0 3.50313e-7 -1 1.93502e-7 3.30923e-7 -1 -1.23134e-7 -2.10581e-7 -1 -2.40697e-7 -1.57652e-7 -1 1.72373e-7 0 -1 -4.79962e-7 0 -1 0 0 -1 0 4.1006e-7 -1 0 4.25182e-7 -1 0 0 -1 -2.38715e-7 0 -1 0 4.81212e-7 -1 0 4.83439e-7 -1 0 0 -1 4.20052e-7 0 -1 4.14532e-7 0 -1 -5.13861e-7 0 -1 -4.54329e-7 -1.44889e-7 -1 3.34632e-7 0 -1 4.53617e-7 -3.28225e-7 -1 2.70818e-7 -3.40029e-7 -1 2.76385e-7 0 -1 -6.55705e-7 2.71028e-7 -1 -1.50081e-7 8.64016e-7 -1 2.49509e-7 1.52159e-7 -1 0 0 -1 0 -1.93919e-7 -1 0 -2.01978e-7 -1 0 0 -1 -4.82442e-7 1.37294e-7 -1.27891e-7 -3.67387e-7 1 -1.76346e-6 -1.88268e-7 1 0 0 1 -2.07943e-6 -6.75633e-7 1 2.12149e-5 -8.4076e-6 1 2.8803e-6 2.23628e-6 1 1.96585e-5 2.07685e-5 1 -1.72542e-5 -2.45116e-6 1 -1.75195e-5 -2.33606e-6 1 1.26594e-5 -6.57804e-6 1 -0.1426251 0.03251373 -0.9892426 0.1278392 0.4303488 -0.8935643 -0.05395352 0.5412953 -0.8390998 0.008710741 0.8830392 -0.4692184 0.08679288 0.9001881 -0.4267651 -0.102631 0.9944999 0.02090519 0.1515479 0.9609231 0.2316458 -0.1233389 0.8559913 0.5020622 0.1084321 0.629305 0.7695568 -0.1084461 0.4794328 0.8708523 0.1029921 0.1782923 0.9785726 -0.07526952 -0.09120595 0.9929834 0.07528215 -0.2447987 0.9666469 -0.1029995 -0.4941298 0.8632652 0.108434 -0.7421643 0.661388 -0.07582414 -0.837683 0.5408678 0.06336551 -0.9733437 0.2204243 -0.08104807 -0.994677 0.0636326 0.08146739 -0.9814976 -0.1732789 -0.09851574 -0.8979846 -0.4288572 0.1262573 -0.7657897 -0.6305754 -0.14855 -0.5486801 -0.822729 0.1751239 -0.2248671 -0.958523 0.1055017 0.1083568 -0.988498 -0.1055077 0.2271181 -0.9681351 0.1055153 0.7053025 -0.7010099 -0.05744367 0.7706985 -0.6346054 0.008715689 0.9889115 -0.1482504 0.03486084 0.9904928 -0.1330743 -0.03123992 0.9352107 0.3527112 0.03121811 0.9192394 0.3924597 -0.0278542 0.6641167 0.74711 0.0169813 0.6361873 0.7713477 -0.01951986 0.2972043 0.9546144 0.03987282 0.2582478 0.9652556 -0.04783147 -0.3097941 0.9495998 0.04782909 -0.3555289 0.9334407 -0.03987252 -0.8073109 0.5887779 0.06589627 -0.8464264 0.5284128 -0.07941091 -0.9817076 0.1730436 0.06513959 -0.9964824 0.05272281 0.01170927 -0.9303005 -0.3666112 -0.1055262 -0.8985486 -0.4259984 0.1054932 -0.5366789 -0.8371661 -0.1055067 -0.4314887 -0.8959274 -0.6447404 0.1560665 -0.7483002 -0.5803763 0.1310888 -0.8037282 -0.812833 0.406127 -0.4175685 -0.4530194 0.3195166 -0.8322756 -0.6374251 0.5638559 -0.5251246 -0.3925749 0.5307888 -0.7510981 -0.3647377 0.50549 -0.7819503 -0.3427924 0.7410468 -0.5773587 -0.1984774 0.5506588 -0.8107907 -0.1258676 0.8465523 -0.5172102 -0.09887021 0.772028 -0.6278514 0.04035705 0.6025615 -0.7970515 0.1464697 0.865319 -0.4793432 0.2015252 0.5708996 -0.7959027 0.3349177 0.7469769 -0.5743306 0.3266791 0.4879056 -0.8094621 0.5954522 0.6931081 -0.4062486 0.4374071 0.3470799 -0.8295845 0.7605814 0.4720092 -0.445784 0.6022263 0.2187868 -0.7677602 0.7525866 0.2374992 -0.6141722 0.6787847 0.01699256 -0.7341408 0.5411568 0.03150147 -0.8403316 0.7979251 -0.1344392 -0.5875726 0.5492795 -0.1779071 -0.8164809 0.762131 -0.3035655 -0.571843 0.5939939 -0.4689975 -0.653615 0.6357348 -0.4925499 -0.5943365 0.3746081 -0.4669433 -0.8010198 0.4823637 -0.7078589 -0.5160049 0.2593774 -0.6197949 -0.7406604 0.2739033 -0.7544699 -0.5964496 0.1092168 -0.5877052 -0.8016696 0.07560217 -0.8702868 -0.4867086 -0.07325887 -0.6300916 -0.7730574 -0.07538634 -0.5974709 -0.7983391 -0.2232544 -0.7557135 -0.6156741 -0.2445138 -0.5190976 -0.8189937 -0.286908 -0.5749019 -0.7662712 -0.5494593 -0.6775374 -0.4889147 -0.3735184 -0.3665133 -0.8521456 -0.7461072 -0.481413 -0.4599626 -0.4906498 -0.237789 -0.8382835 -0.8438823 -0.2499595 -0.4747453 -0.579479 -0.05762463 -0.8129473 -0.7659552 -0.03483128 -0.6419498 -0.9991825 0.006686747 0.03986984 -0.9947374 0.07846844 -0.06588196 -0.8921844 0.4446394 0.0793901 -0.7906097 0.5965339 -0.1381436 -0.5148085 0.8487519 0.1207987 -0.3277764 0.9416581 -0.07643604 -0.08914875 0.9930833 0.07640677 0.0893625 0.9917104 -0.0923289 0.5015778 0.8607449 0.08682191 0.5144097 0.8552126 0.06319892 0.8029252 0.5877372 -0.099379 0.9237218 0.3518095 0.1515528 0.9837918 0.1470437 -0.1026255 0.947102 -0.3089739 0.08679205 0.944403 -0.3226551 0.06321793 0.7436702 -0.6611241 -0.09934586 0.5385445 -0.8288584 0.1515379 0.3510185 -0.9307262 -0.1026381 -0.0490083 -0.996679 0.06503242 -0.1480183 -0.9874248 -0.05552428 -0.4583635 -0.8860624 0.06925475 -0.5848208 -0.8082069 -0.06918227 -0.8301503 -0.5536319 0.06589657 -0.869038 -0.4931369 -0.03986316 -0.9866312 0.05989009 0.1515656 -0.9682357 0.2413995 -0.06516158 -0.7821496 0.6229813 -0.01167607 -0.7557338 0.6523576 0.0574097 -0.3132421 0.9496333 -0.008716166 -0.2685026 0.9593607 -0.08679604 0.1886746 0.9766623 0.1026277 0.3645746 0.9238727 -0.1163812 0.6607825 0.7414861 0.116468 0.7871677 0.6081392 -0.1026338 0.9775211 0.192148 0.08678472 0.9921225 0.1173831 -0.04374945 0.9077303 -0.4176552 0.03987085 0.8556762 -0.5056609 -0.1101146 0.6493206 -0.7535091 0.1029903 0.4060877 -0.9095821 -0.08805215 0.2563112 -0.9648772 0.05758976 -0.004921317 -0.9983274 -0.05760312 -0.1119629 -0.9928984 0.04021507 -0.459438 -0.8880809 -0.01513999 -0.4408343 -0.8974593 0.01523321 -0.7531514 -0.6563181 -0.04482769 -0.8270172 -0.551612 0.1084745 -0.9654818 -0.2294114 -0.1233501 -0.9858905 0.108083 -0.1278198 -0.9784625 0.2058217 0.01576417 -0.820881 0.5673758 0.06510871 -0.6968089 0.7010632 -0.151551 -0.4895704 0.8662818 0.0993815 -0.1164391 0.991182 -0.06324672 -0.1330738 0.9904928 -0.03486239 0.3783817 0.924992 0.03488534 0.3926352 0.9196522 0.0088045 0.7901972 0.6104806 -0.05387002 0.8538379 0.504597 0.1278388 0.9829231 0.1162837 -0.1426196 0.9829186 -0.1162919 0.1426436 0.8708485 -0.4794452 -0.1084212 0.7890442 -0.6096398 0.0758199 0.5044701 -0.8600918 -0.07584196 0.3650134 -0.9246808 0.1083086 -0.009489119 -0.9897453 -0.142528 -0.2160069 -0.9700185 0.111379 -0.6228753 -0.7787768 -0.07438588 -0.5623015 -0.8235957 0.07421183 -0.8643032 -0.4904503 -0.1115279 -0.9435666 -0.2988989 0.1426238 1.24196e-5 4.06956e-6 1 -3.17911e-6 -1.04171e-6 1 -3.37537e-6 -7.11058e-7 1 -5.38943e-6 -2.80627e-6 1 -4.79608e-6 -3.52232e-6 1 -8.51699e-6 -5.06997e-6 1 -2.92508e-6 -1.31766e-5 1 2.47664e-6 -5.13598e-6 1 6.58379e-6 -7.98615e-6 1 5.85214e-6 -1.17378e-5 1 1.20341e-5 -1.3055e-5 1 1.3187e-5 -4.09598e-6 1 6.4581e-7 -4.92787e-6 1 -3.59022e-7 2.73952e-6 1 -1.50023e-5 -7.99023e-6 1 -1.16851e-5 -1.32838e-5 1 -6.34998e-6 -3.17594e-6 1 -2.39035e-6 -4.95135e-6 1 -2.52366e-6 -6.65122e-7 1 2.32607e-6 6.13047e-7 1 -1.02915e-6 4.36672e-6 1 -8.55679e-6 -3.82236e-6 1 9.47866e-6 -8.27126e-6 1 -0.1819199 0.7610868 -0.6226171 -0.3028863 0.6744211 -0.6733618 -0.2704031 0.392432 -0.8791356 -0.6126598 0.5154165 -0.599161 3.77997e-5 0.6805222 -0.7327275 4.16452e-4 0.06275337 -0.998029 -0.001157581 0.6266014 -0.7793391 0.5253682 0.5115893 -0.6799005 0.3705248 0.5751838 -0.7292976 0.2358569 0.4742896 -0.8481867 0.1462132 0.6952676 -0.703722 1.47003e-6 -1.99379e-6 1 1.65553e-5 -9.3765e-6 1 1.65381e-5 -9.64318e-6 1 -1.03467e-5 -1.03094e-5 1 -1.15658e-5 5.97756e-7 1 -6.40666e-6 2.66215e-6 1 3.19262e-7 -5.75317e-6 1 9.60645e-6 6.21779e-6 1 -2.86222e-7 1.72886e-5 1 -5.47213e-6 -1.90217e-6 1 4.10334e-6 -5.51797e-6 1 3.51535e-6 -1.35198e-6 1 -1.65066e-6 -2.12335e-6 1 1.11573e-5 -2.09569e-5 1 1.24151e-5 -2.09474e-5 1 8.69422e-6 -1.29468e-5 1 3.39833e-5 6.09727e-6 1 2.61192e-5 4.6863e-6 1 2.23811e-5 9.77999e-6 1 1.36904e-5 -3.82748e-7 1 -3.34779e-6 0 1 -2.1342e-6 -1.03907e-5 1 3.02804e-6 -7.97647e-6 1 1.6145e-7 -4.51293e-6 1 1.50712e-6 -4.19922e-6 1 -3.90197e-6 -3.19463e-5 1 3.37701e-5 -3.50771e-5 1 1.97565e-5 1.43052e-5 1 2.85095e-6 2.0643e-6 1 1.63092e-6 3.4562e-6 1 -7.65059e-6 -2.80741e-6 1 -1.09336e-5 2.37188e-6 1 7.17746e-6 6.98669e-6 1 7.42781e-6 5.75175e-6 1 3.1776e-6 1.71902e-6 1 -1.04447e-5 9.94699e-6 1 4.09109e-6 -1.32587e-5 1 1.31499e-5 -6.26241e-6 1 -2.249e-5 1.07104e-5 1 -7.36175e-5 -1.16317e-5 1 -9.33832e-5 2.0247e-5 1 -9.62747e-5 1.85326e-5 1 -6.85344e-5 -2.17813e-5 1 -4.38523e-5 1.23384e-5 1 -2.21219e-5 6.9058e-6 1 -1.93303e-5 -3.34003e-5 1 9.1482e-6 -1.46303e-5 1 9.03954e-7 -1.05374e-5 1 -1.98297e-6 -2.91698e-6 1 -0.1065006 0.990429 -0.08779627 0.1309472 0.9814788 0.1398295 0.1485385 0.2432311 -0.9585275 -0.1021763 0.4909619 -0.8651684 0.1015089 0.7248038 -0.6814363 -0.08264619 0.8230664 -0.5618998 0.08263474 0.9830178 -0.1638518 -0.1015506 0.9947847 -0.00953865 0.08148354 0.9632604 0.2559099 -0.0984928 0.8583668 0.5034934 0.06913745 0.7557325 0.6512207 -0.04581421 0.528015 0.8479983 0.04575097 0.4452822 0.8942207 -0.06917983 0.1582958 0.9849654 0.1262751 -0.05160468 0.990652 -0.1485554 -0.3352053 0.9303596 0.1751023 -0.6369305 0.750772 -0.1426411 -0.814682 0.5620915 0.1084281 -0.9704748 0.2154573 -0.1084304 -0.9934507 0.03603613 0.1029712 -0.9540844 -0.2812824 -0.07532596 -0.8456106 -0.5284589 0.0457313 -0.7740875 -0.6314246 -0.06920546 -0.5500059 -0.8322886 0.1263101 -0.3610158 -0.9239661 -0.1485364 -0.07775014 -0.9858458 0.1563155 0.1076295 -0.9818255 -0.1207909 0.4899291 -0.8633534 0.1057963 0.6836005 -0.7221478 -0.06336092 0.8085321 -0.585031 0.087686 0.9663681 -0.2417515 -0.01576328 0.9846462 -0.1738487 -0.0651291 0.9732371 0.2203809 0.07941377 0.9383422 0.3364632 -0.04571485 0.7803296 0.6236953 0.07529699 0.6947839 0.7152662 -0.1029961 0.4760186 0.8733831 0.1278074 0.1438217 0.9813157 -0.01575303 0.04738521 0.9987524 -0.06513208 -0.3422186 0.9373603 0.1515567 -0.5028773 0.8509672 -0.09936618 -0.7149643 0.6920639 0.06323522 -0.9298622 0.3624329 0.03485548 -0.9250042 0.3783548 -0.03123688 -0.9939107 -0.1056687 0.03126877 -0.9884641 -0.1481917 -0.03124344 -0.8161377 -0.5770124 -0.01519978 -0.8100344 -0.5861853 0.04933148 -0.492919 -0.8686757 -0.01575851 -0.454587 -0.8905629 -0.06822037 -0.04696661 -0.9965642 -0.1574226 0.752869 0.6390669 -0.2046782 0.6150856 0.7614306 -0.38423 0.6776176 0.627058 -0.4402709 0.5099433 0.738999 -0.5018555 0.5139654 0.6956872 0.04522591 0.03347939 0.9984157 0.6073527 0.661851 0.4394041 0.3311595 0.6550762 0.6791235 0.4564406 0.7235017 0.5178872 0.247369 0.7891433 0.5621933 0.5956594 0.8012305 0.05674082 0.6175022 0.7864661 -0.01273947 0.528355 0.3495311 -0.773737 0.5893607 0.3818883 -0.7119095 0.8386692 -0.5446412 0 0.8386692 -0.5446412 0 1 1.32275e-6 -1.03081e-6 1 -3.64692e-6 0 1 4.45562e-6 1.21823e-6 1 0 0 1 3.77285e-6 1.39289e-6 1 -4.93725e-6 0 1 7.51841e-6 -1.3425e-6 1 0 0 1 -5.59415e-7 -1.90038e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.8386691 -0.5446412 0 0.8386691 -0.5446412 0 1 -4.05815e-6 0 1 3.00727e-6 1.01811e-6 1 0 0 1 -5.52195e-7 3.35579e-6 1 8.50204e-7 -8.42473e-7 1 1.53141e-6 3.9658e-7 1 -4.53224e-7 -2.99595e-6 1 0 0 1 0 0 1 7.57748e-7 8.52442e-7 1 3.71016e-6 9.60797e-7 1 -5.74727e-6 0 1 0 0 1 0 0 1 5.03223e-6 -1.30882e-6 1 -1.34752e-6 -1.52925e-6 1 4.04978e-6 2.26639e-6 1 3.20218e-6 4.40867e-7 1 0 5.67137e-7 1 3.82109e-7 6.27115e-7 1 -8.45661e-6 -4.96795e-7 1 3.25978e-6 1.915e-7 1 1.84398e-7 1.93476e-6 1 3.55683e-6 3.89623e-6 1 -5.23334e-6 -7.20512e-7 1 0 0 1 0 0 1 0 0 0.5237122 -0.5137704 0.6795333 0.3492877 -0.4839802 0.8023474 0.3421863 -0.7068278 0.6191147 0.3379226 -0.6887621 0.6414166 0.1991316 -0.9308555 0.306357 0.5721416 -0.7901836 -0.2196905 0.2583644 -0.4264564 -0.8668234 0.295576 -0.5370478 -0.7900725 0.2016484 -0.7199798 -0.6640534 -0.1230152 -0.9923003 -0.01440656 -0.02992856 -0.9990367 0.03209322 0.08961224 -0.9955955 -0.02755129 0.2576287 -0.9659793 0.0226171 0.3384932 -0.9407271 -0.0213285 0.4753507 -0.8795888 0.01911181 0.5612309 -0.8269058 -0.03530812 0.7214244 -0.6914231 0.03848326 0.7857668 -0.6176279 -0.03326427 0.9109088 -0.4117406 0.02673566 0.9290736 -0.3697218 -0.01131999 0.9862269 -0.1650074 -0.01136702 0.9933698 -0.113102 0.02060079 0.998274 0.05718719 -0.01336437 0.9934192 0.1131096 0.01801419 0.9533616 0.3003435 -0.02992665 0.9106823 0.4116659 0.03447902 0.849969 0.5256495 -0.03528845 0.7410668 0.6708247 0.02854049 0.6505209 0.7589043 -0.02978122 0.5713628 0.8203982 0.02216726 0.4086231 0.9121266 -0.03243964 0.2926458 0.9555996 0.03446477 0.1674692 0.9852548 -0.03502726 -0.01398283 0.9994984 0.02841639 -0.1463876 0.988672 -0.0331428 -0.2383672 0.9709761 0.01965886 -0.4214445 0.906406 -0.0285083 -0.5239973 0.8510227 0.03445196 -0.5946007 0.8039406 -0.01137387 -0.7460992 0.6657385 -0.01132768 -0.7777168 0.6279554 0.02878314 -0.8954901 0.444024 -0.03066313 -0.9423179 0.3329411 0.03445565 -0.9748886 0.2208484 -0.02860319 -0.999642 -1.11762e-6 0.02675455 -0.9988865 -0.04579907 -0.01132237 -0.9591929 -0.2825252 -0.01133269 -0.9424342 -0.332989 0.03059506 -0.8390793 -0.5426684 -0.03816992 -0.7774707 -0.627745 0.03841394 -0.6294806 -0.7762084 -0.03542506 -0.5482242 -0.8361133 0.01910275 -0.2789546 -0.9602659 -0.008586287 -0.3326148 -0.9427363 0.02481424 -0.449326 -0.8932911 -0.0117138 -0.2067766 -0.5470408 0.8111658 -0.269721 -0.6240165 0.7333852 -0.4509103 -0.6813007 0.5766362 -0.5108785 -0.648176 0.5646867 -0.1746773 -0.6707356 -0.720834 -0.2694081 -0.4621921 -0.8448656 -0.2768442 -0.5691117 -0.7742539 -0.6203337 -0.55071 -0.5584841 -0.003652036 4.69869e-7 -0.9999934 5.03848e-6 0 -1 -0.004019618 -0.001532971 -0.9999908 -0.00350821 1.02967e-4 -0.9999938 -2.64894e-6 1.94995e-7 -1 -4.56388e-7 -3.85182e-7 -1 -1.54397e-6 -2.03608e-7 -1 1.97794e-5 -7.03838e-6 -1 -1.22658e-5 -1.73147e-6 -1 3.21318e-6 2.80711e-5 -1 -0.02288544 0.01778268 -0.9995799 -0.00565803 0.001845777 -0.9999823 -1.10568e-4 -1.86389e-4 -1 -0.007628679 8.8844e-4 -0.9999705 -1.50527e-5 1.80065e-6 -1 -0.001959383 -6.9633e-4 -0.9999977 -5.63196e-4 -0.005422592 -0.9999851 -0.005856454 -0.004727602 -0.9999717 0 6.44126e-7 -1 2.30212e-6 0 -1 -1.507e-6 4.73148e-7 -1 -2.15236e-6 7.08102e-7 -1 2.08713e-7 1.29608e-7 -1 0.005747556 -0.001208961 -0.9999827 -9.19403e-4 0.003443777 -0.9999936 -0.001025259 -0.001558244 -0.9999983 -5.91313e-4 -0.003373563 -0.9999941 3.29596e-6 -6.69474e-7 -1 -1.89878e-6 9.18108e-7 -1 -6.35737e-6 1.33195e-5 -1 4.52119e-6 -5.36808e-7 -1 2.90049e-5 6.19842e-4 -0.9999998 0.001344621 0.02970784 -0.9995578 -0.02301096 0.01770532 -0.9995784 -5.01228e-7 4.24747e-7 -1 -3.72121e-7 -1.85413e-6 -1 0.004364132 8.38602e-5 -0.9999904 0.005874395 -0.004059135 -0.9999745 0.007056236 0.02762645 -0.9995934 0.002729833 0.02871537 -0.9995839 -3.08305e-4 0.02047908 -0.9997902 -1.82589e-4 -0.001659512 -0.9999986 -1.27481e-4 -0.001160621 -0.9999992 3.8093e-6 2.74424e-6 -1 4.46597e-6 -4.35515e-6 -1 -0.005993604 0.009224057 -0.9999395 -0.003681123 -0.01284611 -0.9999107 0.00771743 0.00244534 -0.9999673 0.009914755 0.004507005 -0.9999406 3.26184e-6 -6.61926e-6 -1 5.46135e-7 -3.15038e-7 -1 -1.44341e-6 -2.08414e-6 -1 -4.12436e-7 -6.48488e-6 -1 -3.91289e-6 2.09842e-6 -1 2.00371e-6 6.06686e-6 -1 3.45453e-7 -3.25846e-7 -1 1.89511e-7 -1.30243e-6 -1 -0.00250864 -0.04486018 -0.9989901 0.002540409 -0.004703938 -0.9999858 0.004109799 0.005137264 -0.9999784 0 3.67245e-7 -1 -7.87424e-7 -2.46558e-6 -1 -0.01350343 0.007350385 -0.9998818 9.22207e-4 -8.8123e-4 -0.9999992 0.003102421 -3.70739e-4 -0.9999951 0.003070175 -0.00138998 -0.9999943 0.004565715 -5.18144e-4 -0.9999895 0.01099574 0.001250684 -0.9999388 -1.3693e-6 0 -1 0.00954616 9.23555e-4 -0.9999541 1.78906e-4 -3.14767e-4 -1 -0.6698651 0.4433649 -0.5955739 -0.5485864 0.3493139 -0.7596266 -0.9916139 0.04673004 -0.1204915 -0.9379684 0.3384535 0.0752623 -0.8737788 0.480459 -0.07529729 -0.7108802 0.6957259 0.1030289 -0.481744 0.8718779 -0.08804488 -0.3122161 0.9465488 0.0810346 -0.07959884 0.9934915 -0.08147656 0.2152411 0.9695972 0.1164153 0.362356 0.9297633 -0.06510281 0.6954225 0.7184273 -0.01580512 0.7256953 0.6862441 0.04934996 0.9461804 0.3232836 -0.01518028 0.9561817 0.2828328 -0.0756452 0.9837911 -0.147049 0.1026238 0.9517788 -0.2963312 -0.07940346 0.7901085 -0.6104479 0.0555157 0.7471069 -0.664121 -0.0278328 0.3668883 -0.9296121 0.03484827 0.3528758 -0.9356297 0.008716702 -0.1165419 -0.9919115 -0.05029636 -0.2670903 -0.9543478 0.1337275 -0.4898648 -0.8668967 -0.09231853 -0.7805386 -0.6217092 0.06509298 -0.8528831 -0.5138854 -0.09226238 -0.969451 -0.213658 0.1204786 -0.7938395 0.6069517 -0.03779435 -0.5982147 0.7990689 0.0602343 -0.5067697 0.8620406 -0.008392989 -0.0117979 0.9999243 -0.003504633 -0.01343357 0.9998741 -0.008434414 -0.03666049 0.9990626 -0.02301764 -0.1991948 0.9797914 -0.01817893 -0.4884511 0.872591 -7.08963e-4 -0.5166206 0.8561766 0.008043885 -0.6855463 0.727899 -0.01376152 0.7360839 0.6767781 -0.01232349 0.4986079 0.8665249 -0.02290439 0.3507003 0.9364308 0.01033347 0.2368509 0.9715294 -0.005689024 0.008761167 0.9998996 -0.01113128 0.01063024 0.9999212 -0.006674289 0.03339177 0.9992224 -0.02096527 0.3841783 0.922671 0.03294241 0.5293405 0.8478276 -0.03141677 0.7025792 0.7110663 0.02769982 0.8144923 0.5794575 -0.02883404 0.9871701 0.1245218 -0.09994733 0.8660181 0.4957324 0.0652849 0.8581383 0.5059565 0.08721607 0.5395856 0.8356512 -0.1026379 0.4063734 0.9102512 0.07939422 0.03618854 0.9971705 -0.06589007 -0.03572356 0.998566 0.03987348 -0.5514764 0.8330414 -0.04376977 -0.5637348 0.8257293 -0.01934427 -0.8532519 0.5195577 0.04495704 -0.9083853 0.4038395 -0.1083956 -0.9903669 0.06293851 0.1233385 -0.979316 -0.1746709 -0.102128 -0.9138365 -0.4016935 0.05954074 -0.8211798 -0.5675725 -0.05937385 -0.686099 -0.722913 0.08163952 -0.4903307 -0.867731 -0.08135664 -0.2713882 -0.9590471 0.08110052 -0.08906441 -0.992127 -0.0880444 0.2297977 -0.9653921 0.1233336 0.4976496 -0.8540346 -0.1515576 0.6921206 -0.708437 0.1381532 0.9158741 -0.3765549 -0.1392158 0.9780037 -0.145393 0.1495649 0.948693 0.3111526 -0.05626481 0.9127827 0.4031034 0.06584376 0.6925092 0.7154785 -0.09231334 0.5266233 0.843495 0.1057544 0.3624633 0.9298398 -0.06339013 0.05275624 0.9965949 0.06336921 -0.1324087 0.9855317 -0.1058076 -0.3363646 0.9371946 0.09233164 -0.6830259 0.7264684 -0.07562637 -0.736273 0.6759627 0.03125005 -0.9686815 0.2458463 -0.034868 -0.9631201 0.2615339 -0.06324344 -0.9863501 -0.1312929 0.09937667 -0.9103171 -0.3851736 -0.1515385 -0.8120322 -0.5745269 0.1025788 -0.4699828 -0.8783943 -0.08683019 -0.4027528 -0.914263 0.04374331 0.1866568 -0.9812602 -0.04782778 0.2046051 -0.9787687 -0.01218974 0.6520003 -0.7565481 0.05030649 0.7404626 -0.6643813 -0.1015507 0.8909475 -0.4471059 0.07942944 0.977299 -0.1892187 -0.09530472 0.9976167 -0.0219506 0.06541424 -0.5958303 0.801456 -0.05152171 -0.5537257 0.8284317 0.08419501 -0.9559632 0.2738725 -0.1054909 -0.9158262 0.3874695 0.1054984 -0.5969317 0.7967258 -0.09434282 -0.5179688 0.8539721 0.04939603 -0.1166291 0.9930582 -0.01526927 -0.1373579 0.9904049 0.01520115 0.2860785 0.956932 -0.04939925 0.3769062 0.9214357 0.09432888 0.7886286 0.6057476 -0.1055216 0.8561078 0.505914 0.1055015 0.9955207 0.006152749 -0.09434407 0.9892489 -0.1170431 0.08767926 0.8598586 -0.5048698 -0.07582658 0.8061128 -0.5900583 0.04487216 0.5153532 -0.8568427 -0.01522213 0.5057011 -0.8621424 -0.03125572 0.08969479 -0.995581 0.02780687 0.05285286 -0.9984577 -0.016999 -0.3286958 -0.9442342 0.01951783 -0.3378275 -0.9411928 0.005364537 -0.7137568 -0.6985816 -0.05034857 -0.7802565 -0.6214323 0.07086598 -0.9382701 -0.338576 -0.07082027 -0.9732236 -0.2144997 0.0826174 -0.8084837 0.588418 0.01087892 -0.7777845 0.6285088 -0.005291163 -0.529577 0.8482227 0.008146166 -0.5067425 0.8620567 -0.008384287 -0.01491719 0.9998825 -0.003547847 -0.01063138 0.9999212 0.006675004 -0.03339701 0.9992221 0.02096855 0.006861865 0.999912 -0.0113582 0.01343017 0.9998743 0.008432209 0.03666174 0.9990626 0.02301836 0.3841937 0.9226649 0.03293377 0.5980577 0.7988665 -0.06433737 0.7225535 0.6905786 0.03190147 -0.9818213 0.1076428 -0.1563329 -0.8315134 0.5330548 0.1563267 -0.7215413 0.6830114 -0.1134622 -0.341193 0.9369412 0.07568639 -0.3026988 0.9529653 0.0151835 0.08966463 0.9949591 -0.04490697 0.1639328 0.9854509 0.04486376 0.5331109 0.8459078 -0.01525521 0.5153501 0.8568457 0.01515662 0.8237357 0.5648191 -0.0493853 0.8721051 0.4801365 0.09434831 0.9941248 -0.02414196 -0.1055124 0.9839057 -0.1442102 0.1055125 0.7582941 -0.6433164 -0.1055181 0.6749273 -0.7303054 0.1054855 0.1858334 -0.976903 -0.1054827 0.06632673 -0.9922026 0.1055215 -0.4426972 -0.8916953 -0.09433269 -0.5293419 -0.8469702 0.04938393 -0.8341993 -0.5512549 -0.01515275 -0.8540778 -0.5146162 -0.07563889 -0.990464 -0.07813131 0.1134746 -0.9836783 0.1754629 0.0398736 -0.9554843 0.2737342 -0.1100883 -0.8182547 0.5655542 0.1029943 -0.6221808 0.7779077 -0.08803832 -0.4677052 0.880158 0.08107954 -0.2160605 0.9710278 -0.1020926 -0.004936814 0.9950384 0.09936928 0.3817234 0.9221099 -0.06325089 0.3937807 0.9150938 -0.086833 0.7441928 0.6615546 0.09231787 0.8651029 0.4903043 -0.1058235 0.9444074 0.3226159 0.06335282 0.9947996 -0.05181837 -0.08768552 0.9923939 -0.1220909 0.01575583 0.8519681 -0.5191279 0.06823807 0.7993536 -0.5969745 -0.06823009 0.4833123 -0.8753057 -0.01577782 0.3920314 -0.91103 0.1278114 0.05255293 -0.9932928 -0.1029927 -0.2416394 -0.9659704 0.09225809 -0.3376979 -0.9408424 -0.02785229 -0.688112 -0.7250708 0.02782744 -0.7145476 -0.6993839 -0.01685488 -0.9259468 -0.3771418 0.01965904 -0.9398878 -0.3391482 -0.03986823 -0.8386708 -0.5446386 0 -0.8386708 -0.5446386 0 -1 0 0 -1 -5.9803e-7 0 -1 -1.32169e-7 0 -1 0 0 -1 -1.26139e-7 1.83186e-7 -1 -7.05883e-7 0 -1 1.41819e-7 -1.7912e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 1.46772e-7 -1 -2.40129e-7 0 -1 4.9429e-7 0 -1 1.80713e-7 0 -1 2.04177e-7 -8.44849e-7 -1 0 3.82648e-7 -0.8386709 -0.5446386 0 -0.8386709 -0.5446386 0 -1 0 0 -1 0 5.3877e-7 -1 -1.62871e-7 0 -1 0 0 -1 1.48105e-7 0 -1 2.53979e-7 0 -1 2.59397e-7 0 -1 -7.8764e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -4.85246e-7 0 -1 3.88352e-7 -1.31395e-7 -1 0 0 -1 0 0 -1 0 0 -1 -4.03258e-7 0 -1 0 0 -1 -4.73041e-7 0 -1 9.08259e-7 1.22012e-7 -1 0 0 -1 0 0 -1 0 0 -1 7.34741e-7 1.41953e-7 -1 0 0 -1 0 0 -1 0 0 9.86915e-6 -2.22856e-6 -1 -2.00935e-6 2.58335e-6 -1 -5.56865e-6 -6.59814e-6 -1 1.20776e-6 -1.09639e-5 -1 9.12343e-6 2.44731e-6 -1 -6.2062e-5 1.3731e-5 -1 -6.50416e-5 -4.60764e-5 -1 7.70103e-6 -5.00526e-5 -1 1.97198e-5 -2.54779e-5 -1 -1.93392e-5 1.5989e-5 -1 2.26088e-5 1.70257e-6 -1 -3.97962e-7 -3.54199e-5 -1 -3.43457e-5 2.47101e-5 -1 8.0208e-6 2.06833e-5 -1 1.64965e-6 -2.64939e-6 -1 -2.86169e-6 4.59594e-6 -1 7.98725e-6 1.02794e-5 -1 7.47697e-6 -6.1753e-6 -1 -1.27601e-5 -4.70043e-6 -1 -7.33704e-6 2.7092e-6 -1 -2.03049e-7 -3.37445e-6 -1 9.88106e-6 -9.67192e-7 -1 -2.11681e-5 -1.01944e-5 -1 -5.17062e-6 -1.12549e-5 -1 -2.13946e-6 1.18705e-5 -1 2.59538e-5 -7.43547e-6 -1 -3.44727e-5 -4.05159e-5 -1 -4.83074e-5 5.80137e-5 -1 2.82675e-5 2.53043e-5 -1 8.61192e-6 4.36924e-6 -1 3.71519e-6 9.90973e-6 -1 -3.77452e-6 2.79142e-6 -1 2.0865e-5 -7.03086e-5 -1 -1.17196e-4 -9.56953e-5 -1 -2.9664e-5 5.92284e-5 -1 -1.85889e-6 3.71154e-6 -1 -1.98096e-5 1.02101e-5 -1 -1.42107e-5 2.19365e-5 -1 -1.81886e-6 2.80769e-6 -1 -4.55633e-6 1.79063e-6 -1 -4.60675e-6 -1.88341e-5 -1 -7.88395e-6 -1.75127e-5 -1 0 0 -1 -3.38002e-6 1.0819e-6 -1 -1.88375e-6 -1.71099e-5 -1 -2.21081e-5 -1.90826e-5 -1 2.11031e-5 5.80497e-6 -1 -2.18728e-5 -3.94403e-5 -1 -2.78166e-5 -1.04592e-5 -1 -9.0689e-6 -1.25629e-5 -1 1.2242e-5 1.69585e-5 -1 2.29296e-5 -7.08856e-6 -1 8.74503e-6 -4.55523e-7 -1 -1.02261e-5 -1.83287e-5 -1 -1.02257e-4 1.37263e-4 -1 -1.23473e-4 1.24564e-4 -1 6.45961e-6 2.7898e-5 -1 -6.35342e-6 1.63919e-5 -1 8.91524e-7 6.6364e-6 -1 -4.94841e-6 1.96219e-6 -1 -2.05198e-5 2.95164e-5 -1 2.51987e-5 4.25525e-5 -1 5.92551e-5 -2.63201e-5 -1 -1.04572e-6 -1.91549e-5 -1 9.81329e-6 7.20932e-6 -1 3.67408e-5 -1.16966e-5 -1 4.73559e-6 -2.09925e-5 -1 -2.30094e-6 1.01999e-5 -1 -1.36969e-6 1.02004e-5 -1 -1.08486e-6 1.16532e-5 -1 -0.2713952 0.9624343 0.008044779 -0.4336904 0.9009888 -0.01147925 -0.4890398 0.8722495 0.004566669 -0.7143476 0.699574 0.01743078 0.7169358 0.6969865 0.01458847 0.4829876 0.8756271 -4.03194e-4 0.4294465 0.9029939 -0.01333266 0.2869282 0.9579061 0.009383738 0.6880034 -1.30967e-4 -0.7257075 0.7028047 5.20036e-5 -0.7113829 0 0 1 0 0 1 0 -1 0 0 -1 0 0.03622287 0.9992613 0.0128377 0.02428525 0.9978741 -0.06047636 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0.8374475 0.5462028 0.01854866 0.828921 0.5593446 -0.004861056 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0.06651926 0.9977852 0 0 0.9998611 0.01666438 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0.1319573 -0.09016245 -0.9871464 -0.1495522 0.1965681 -0.9690176 0.08226597 0.4298762 -0.8991323 -0.05204838 0.7540419 -0.6547609 0.01361626 0.7976766 -0.6029317 -0.01360207 0.9590766 -0.2828198 0.05206423 0.9748007 -0.216917 -0.07398021 0.9837361 0.1636772 0.1073351 0.9132523 0.3930004 -0.06618046 0.8292993 0.5548719 0.06617325 0.5191903 0.8520931 -0.0813933 0.3804749 0.9212024 0.06526261 0.1218557 0.9903999 -0.06525623 -0.1218351 0.9904029 0.04763847 -0.3229416 0.9452192 -0.04762667 -0.4961907 0.8669062 0.0652582 -0.6629766 0.7457904 -0.09338283 -0.8510217 0.5167608 0.08224809 -0.9325023 0.3516741 -0.05205386 -0.9974393 -0.04904234 0.07392573 -0.9812589 -0.1779491 -0.08254885 -0.8851689 -0.4578883 0.1026069 -0.6706498 -0.7346433 -0.1089279 -0.5275444 -0.842515 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0.2745797 -0.9610307 0.03203427 0 -1 0 0.715681 -0.4721319 -0.5146768 0.5837163 -0.3770856 -0.7190839 0.4338532 -0.2889367 -0.8533974 0.7006673 -0.7134874 0.001081168 0.578045 -0.816004 -0.001234829 0.495735 -0.8684737 6.97714e-4 0.2262884 -0.9740599 -9.40191e-4 0.2126269 -0.9771333 -6.50097e-4 -0.005251169 -0.4979875 -0.8671684 0.004387378 -0.5623277 -0.8269029 -2.12603e-4 -0.691424 -0.7224493 -0.002030074 -0.556149 -0.8310801 -0.1989117 -0.980017 -8.71836e-4 -0.3072636 -0.9516242 6.93757e-4 -0.4738825 -0.8805879 -5.09818e-4 -0.4764626 -0.8791946 -4.5563e-4 -0.6880213 -0.7256901 -7.62377e-4 -0.726295 -0.687383 3.90009e-4 -0.5178707 -0.3290917 -0.7896257 -0.6682955 -0.4438029 -0.5970093 -0.6456608 1.99409e-4 -0.7636243 -0.6052865 -2.47025e-4 -0.7960076 -0.8398385 0.5427937 -0.006813347 -0.8346232 0.5507904 0.005834817 -3.73426e-7 0 1 -2.06131e-7 -2.24722e-6 1 4.82383e-6 -1.55684e-6 1 4.86952e-6 6.48393e-6 1 4.13739e-7 4.49013e-6 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 -0.01724672 0.9989029 0.04353988 -0.04363244 0.991788 -0.1202186 0 -1 0 0 -1 0 0 3.21888e-7 1 -1.28793e-6 0 1 1.07259e-6 0 -1 -1.73954e-7 -1.29508e-5 -1 -7.13798e-6 -1.24547e-5 -1 1.52809e-5 3.35883e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0.09336215 -0.09057492 -0.9915037 -0.0933727 0.2568215 -0.9619377 0.1109104 0.4559276 -0.8830793 -0.1108976 0.7672093 -0.6317369 0.09337055 0.8862376 -0.4537234 -0.0789287 0.985863 -0.1477983 0.05541765 0.9979513 0.03196907 -0.05275648 0.9242762 0.3780612 -0.004321098 0.9091637 0.4164164 0.04027867 0.6357547 0.7708396 -0.08137494 0.5306637 0.8436671 0.06525528 0.2875065 0.9555531 -0.09337264 -0.006151676 0.9956123 0.1108962 -0.2186809 0.9694744 -0.1109105 -0.5832812 0.8046627 0.09335863 -0.743308 0.6624028 -0.0789209 -0.9168183 0.3914279 0.07893335 -0.9787848 0.1890764 -0.09336745 -0.9867677 -0.1325591 0.08226746 -0.946448 -0.3121989 -0.06057238 -0.727221 -0.6837255 0.06057006 -0.6522422 -0.7555868 -0.08224558 -0.2717261 -0.9588538 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 -0.9898346 0.1364231 -0.04020237 -0.9652518 0.2577127 0.04327875 -0.7470558 0.6636807 -0.03788828 -0.6127908 0.7878426 0.06157594 -0.4070634 0.9124178 -0.04234457 0.0181685 0.9990426 0.0397973 0.09434098 0.9953389 -0.02000379 0.6206087 0.7838647 0.02002584 0.6559671 0.7546207 -0.01596403 0.925962 0.3774033 0.01269996 0.9494926 0.3127581 -0.02542191 0.9986238 -0.03777009 0.0363866 0.9735128 -0.2195987 -0.06363302 0.8234725 -0.5646317 0.05553531 0.6410198 -0.7650477 -0.06160855 0.4913482 -0.87014 0.0378611 0.04855793 -0.9978821 -0.04328387 -0.07516807 -0.996361 0.0401805 -0.4956477 -0.8675923 -0.0402103 -0.5990212 -0.7995631 0.04327201 -0.9078134 -0.4171357 -0.04327392 -0.9525358 -0.3017607 0.0402013 -0.9948781 -0.06039994 -0.08105152 -0.9774107 0.2008666 0.06573414 -0.8309283 0.5541464 -0.04979914 -0.7537326 0.656859 0.02057975 -0.4408429 0.8975574 -0.00694859 -0.4028981 0.914589 -0.03464269 0.04856103 0.9974591 0.05212616 0.2043216 0.977514 -0.05214333 0.5998053 0.7995913 0.02978652 0.6528326 0.7574627 -0.007737874 0.8779986 0.4785998 0.00779426 0.8950597 0.4457651 -0.01271295 0.9996678 0.02145099 0.01429224 0.9980463 -0.05198603 -0.03465563 0.8943383 -0.4453824 0.04234981 0.7809926 -0.622649 -0.04856723 0.6525381 -0.7571997 0.02903187 0.3823839 -0.9235486 -0.02899378 0.2044215 -0.9776757 0.04860037 -0.004960715 -0.9990904 -0.04235374 -0.4280394 -0.9028834 0.03979688 -0.4406846 -0.8971951 0.02894908 -0.7728108 -0.6325662 -0.05121964 -0.8979988 -0.4324715 0.08103466 -0.9916712 -0.1223032 -0.04037499 -0.994678 0.09086197 0.04857867 -0.9436308 0.3263074 -0.05553668 -0.7554491 0.6521103 0.06363064 -0.6242711 0.7803624 -0.03633195 -0.2867761 0.9575219 0.03018879 -0.2471772 0.9689671 0.002480447 0.2611231 0.9649474 -0.02629107 0.2991594 0.9541881 0.005347073 0.6682116 0.7433733 0.0298236 0.7911226 0.6076507 -0.06989616 0.9250657 0.3770585 0.04561054 0.9995254 -0.01044666 -0.0289793 0.9989128 -0.02426755 -0.03980296 0.8687987 -0.492412 0.05214649 0.8008257 -0.5980818 -0.03124755 0.4833365 -0.8754051 -0.00719726 0.4202945 -0.9064972 0.04019159 0.05277645 -0.9981849 -0.02901124 -0.1329852 -0.9899269 0.04857587 -0.3374933 -0.9403753 -0.04233932 -0.665357 -0.7459312 0.02977806 -0.7563142 -0.6528363 -0.0423507 -0.914473 -0.4018774 0.04726248 -0.8385241 0.5448071 -0.007905244 -0.8327126 0.5536588 0.007197499 3.23264e-4 0.9999921 -0.003934681 3.56733e-6 0.9999974 -0.002276778 0.839587 0.5431563 0.00866127 0.8313397 0.5556575 -0.01091974 0.8371836 -0.5469219 -2.18731e-5 0.8377091 -0.5461168 -1.78437e-4 1.55259e-4 -0.9999996 -8.89835e-4 -0.001839697 -0.9999983 3.11136e-4 -0.8401024 -0.542427 0.001034319 -0.8352647 -0.549848 -3.73092e-4 -1.62022e-6 -3.00611e-6 1 6.07559e-7 -1.16153e-5 1 -2.47625e-5 1.05089e-5 1 -2.23991e-5 1.81354e-5 1 -5.71079e-6 1.28005e-5 1 1.30706e-5 1.92414e-6 1 3.99101e-6 -1.12165e-5 1 -1.61759e-6 0 1 -1.27869e-5 1.89532e-7 1 2.16034e-5 3.15472e-5 1 3.23646e-5 2.42216e-5 1 1.39161e-5 -7.12501e-7 1 1.03597e-5 3.22327e-6 1 -7.43171e-6 9.04022e-6 1 -1.00849e-5 8.95939e-6 1 -9.46375e-6 1.46569e-5 1 1.94261e-5 1.20091e-4 1 9.56464e-5 1.10031e-4 1 8.59648e-5 2.08847e-5 1 -2.37346e-6 -1.64164e-5 1 -1.98276e-5 -8.50556e-6 1 -6.88443e-6 1.16457e-5 1 -2.95928e-6 2.68113e-6 1 -1.38355e-5 1.55354e-5 1 -4.11808e-6 7.23833e-7 1 1.58042e-5 -2.77789e-6 1 1.30358e-5 -6.4073e-6 1 -7.96632e-6 2.05169e-5 1 0 8.29281e-6 1 -2.11736e-5 -6.04416e-6 1 -1.31342e-5 -4.32097e-5 1 -2.84683e-5 -4.21959e-5 1 1.10381e-5 -1.29299e-5 1 -1.33396e-5 4.2796e-5 1 -4.47928e-6 4.66189e-5 1 -8.75395e-6 1.91421e-5 1 -4.33993e-6 1.88264e-5 1 -1.44849e-5 2.73739e-6 1 4.25753e-7 -4.3108e-6 1 3.18145e-5 1.56951e-5 1 2.97223e-5 2.19506e-5 1 1.57348e-7 1.92525e-5 1 -8.07036e-6 2.32894e-6 1 -4.30475e-6 3.95457e-7 1 -1.28896e-6 1.91706e-5 1 6.77853e-6 1.16364e-5 1 -1.20608e-5 -4.17686e-6 1 1.90203e-6 -1.94392e-5 1 6.2401e-6 1.92579e-5 1 5.40233e-5 -3.13392e-5 1 1.94454e-6 6.00112e-6 1 -5.1969e-5 -2.38222e-5 1 -5.78456e-5 1.20363e-5 1 4.43285e-5 2.136e-5 1 4.23867e-5 3.64348e-5 1 -3.69685e-6 2.25163e-5 1 9.06092e-6 4.28548e-7 1 6.92904e-6 -1.36093e-6 1 -8.20344e-5 5.86551e-5 1 -6.29955e-5 1.00338e-4 1 5.67892e-5 7.62707e-5 1 5.3989e-5 -4.26994e-5 1 4.07947e-5 -4.28062e-5 1 -3.78754e-5 1.57172e-6 1 3.61401e-5 -4.47683e-5 1 1.23162e-5 -4.52085e-6 1 2.18976e-5 8.29117e-7 1 2.64419e-5 -6.60694e-6 1 -2.70847e-5 -1.37076e-5 1 -2.63366e-5 -2.26962e-5 1 -5.0452e-7 -7.98779e-6 1 3.87417e-6 1.17108e-5 1 -1.87679e-6 -5.67317e-6 1 -0.5192155 0.3348909 0.7862973 -0.5630596 0.3686653 0.7396281 -6.81524e-4 0.8018056 0.5975846 0.001672148 0.7060902 0.7081199 0.5706234 0.3774474 0.72933 0.4893202 0.3169376 0.8124755 0.04072099 0.03439843 0.9985783 0.5705857 6.16395e-4 0.8212379 0.7005488 -7.24286e-4 0.7136041 0.5872865 -0.3813075 0.7139322 0.5972989 -0.3892101 0.7012485 0.001133918 -0.8522704 0.5231004 0.001633882 -0.3601022 0.9329115 -0.001385033 -0.6201114 0.7845126 -4.70411e-6 -0.09332227 0.995636 6.99067e-4 -0.1866576 0.9824247 -0.6069393 -0.3891783 0.6929392 -0.4699541 -0.3136498 0.8250859 -0.7221972 -6.24339e-4 0.691687 -0.6020289 6.71528e-4 0.7984741 0.9911372 0.131904 0.01576471 0.9655773 0.2265405 -0.1278278 0.8298279 0.5484272 0.103021 0.653778 0.7529353 -0.07525104 0.5285063 0.8455849 0.07528179 0.2813373 0.9540644 -0.1030074 -0.03605735 0.9934511 0.1084199 -0.2154468 0.9704771 -0.1084284 -0.5382975 0.833683 0.1233225 -0.738341 0.6624967 -0.1262958 -0.8789786 0.4665806 0.098486 -0.9769943 0.1891633 -0.09848517 -0.9949087 -0.02133977 0.09849554 -0.9344037 -0.3366554 -0.1164162 -0.8577916 -0.5036382 0.1026742 -0.5427638 -0.8353983 -0.08670091 -0.4788587 -0.8767999 0.04377436 0.04906988 -0.9979988 -0.03987824 0.150134 -0.9825168 0.1100933 0.4800882 -0.8689019 -0.1205194 0.709706 -0.6886574 0.1485542 0.8905553 -0.4288884 -0.1515449 0.9630026 -0.2615048 0.06512439 0.9902608 0.1317806 0.04491192 0.9701087 0.2305154 -0.07584083 0.8139748 0.5759306 0.07582235 0.734504 0.6743537 -0.0758351 0.4297145 0.8997774 0.07580387 0.2852187 0.9523086 -0.1084368 -0.03189951 0.9941686 0.1030105 -0.2983476 0.9514859 -0.07525473 -0.4429489 0.8933801 0.07528775 -0.6835573 0.7198817 -0.1204977 -0.8477297 0.5165624 0.1204892 -0.9752548 0.1917149 -0.1101068 -0.9950153 0.09140741 0.03986406 -0.8835892 -0.4658137 -0.04782921 -0.8759482 -0.4822516 -0.01217925 -0.5051577 -0.8613401 0.05393493 -0.4436937 -0.8948189 -0.04934841 -0.03200393 -0.9993715 0.01524227 -0.05284273 -0.9984876 -0.0151664 0.3374476 -0.9402728 0.04490387 0.4069625 -0.9123398 -0.04491782 0.72907 -0.6842699 0.01521897 0.7362766 -0.6759594 0.03123652 0.9616372 -0.2725393 -0.03124278 0.9649409 -0.2620268 -0.0151959 0.992295 0.1223775 0.01934981 0.9943114 0.1061567 -0.008692383 0.8332453 0.5506073 0.05033725 0.753046 0.6500859 -0.1015381 0.5272529 0.8435457 0.1021506 0.3108502 0.9424214 -0.1233459 -0.066145 0.9895905 0.1278097 -0.1641128 0.9863154 -0.01577866 -0.5548177 0.8291677 -0.06825166 -0.6303535 0.7733072 0.06819498 -0.9083812 0.4179779 0.0117557 -0.9139033 0.4057625 -0.01171886 -0.9978219 -0.01038563 -0.06514149 -0.9881594 -0.1312545 0.07945615 -0.8944933 -0.4447704 -0.0454002 -0.8480552 -0.5279065 0.04601246 -0.6510282 -0.7559183 -0.06891983 -0.5318931 -0.8439781 0.06921446 -0.2564713 -0.9654673 -0.04577583 -0.1639038 -0.9854173 0.04569786 0.1638979 -0.983277 -0.07939672 0.2822702 -0.9571192 0.06516593 0.6319389 -0.7748568 0.01582491 0.6823402 -0.7257552 -0.08769971 0.9172026 -0.3911425 0.07580918 0.9537386 -0.2972639 -0.04490864 1.41377e-5 -6.59825e-6 1 5.43146e-6 -3.92737e-5 1 4.6337e-5 -4.39936e-5 1 4.8239e-5 -3.90756e-5 1 7.60198e-6 -2.4483e-6 1 6.2178e-6 -3.45003e-6 1 3.11096e-6 2.16401e-5 1 1.10321e-5 1.48846e-5 1 7.04522e-6 9.50543e-6 1 -2.51328e-6 2.5002e-5 1 6.35994e-6 3.00299e-5 1 5.24162e-6 -9.94607e-6 1 2.87891e-6 -9.82643e-6 1 6.94518e-6 -1.1426e-6 1 1.92894e-5 1.56542e-5 1 3.40756e-6 8.79462e-6 1 4.64457e-6 6.86772e-6 1 -8.1883e-7 5.09291e-6 1 -2.30099e-6 1.43116e-5 1 -5.05142e-5 2.68759e-5 1 -4.3626e-5 5.63307e-5 1 -0.9976437 -0.006675601 -0.0682829 -0.9511147 -0.3012843 0.06788641 -0.8936482 -0.4453601 -0.05520093 -0.5983987 -0.7987143 0.06304407 -0.4951993 -0.8668022 -0.0585798 -0.1055904 -0.9931198 0.05063474 0.04849547 -0.9961875 -0.07251685 0.3913268 -0.916539 0.08258193 0.6184959 -0.7812263 -0.08454751 0.8067651 -0.5847891 0.0845685 0.9239919 -0.3765987 -0.06642502 0.9990546 0.01041424 0.04220741 0.9980236 0.02423417 0.05797797 0.8674648 0.4916718 -0.07591938 0.7583416 0.6433557 0.1049358 0.3930904 0.9134929 -0.1049312 0.1858483 0.9769595 0.1049308 -0.2680277 0.9576799 -0.1049304 -0.4433888 0.8931072 0.07593321 -0.8132998 0.5789504 -0.05796402 -0.8218876 0.5680843 -0.0422036 -0.9764202 0.2054008 0.06643921 -1.94452e-5 -5.05891e-6 1 -1.96937e-5 -5.80383e-7 1 9.75467e-6 1.34438e-6 1 0 -5.74139e-6 1 -2.36905e-5 2.08292e-5 1 -2.76107e-5 1.6799e-5 1 -3.16219e-6 8.15478e-6 1 -1.38291e-6 1.36213e-5 1 -4.05065e-6 1.67986e-5 1 -1.62077e-5 7.9662e-6 1 0 0 1 6.76955e-7 3.78154e-6 1 -7.69897e-6 5.90828e-6 1 -2.68007e-5 -4.6157e-5 1 -1.10229e-5 -4.50914e-5 1 -4.92873e-6 2.6936e-5 1 3.06978e-5 3.61742e-5 1 1.88542e-5 -1.28857e-5 1 1.63198e-5 -2.1112e-5 1 5.59894e-6 -7.24302e-6 1 7.93885e-6 -5.00482e-6 1 1.8424e-5 -1.64231e-6 1 -0.9889349 -0.1362938 0.05858284 -0.9642255 -0.2574689 -0.06307679 -0.7247654 -0.6861065 0.06303149 -0.6345666 -0.7706449 -0.05858051 -0.2718795 -0.9609998 0.05060511 -0.1480737 -0.9876796 -0.05062818 0.2608116 -0.963611 0.05857723 0.3526476 -0.9350633 -0.03600656 0.7473908 -0.6643747 0.003617823 0.7733873 -0.6324061 0.04398256 0.9452911 -0.3229407 -0.04619574 0.9827491 -0.1790776 0.0462085 0.9883365 0.1477121 -0.03704279 0.9763363 0.2154601 0.01856064 0.8067961 0.5905394 -0.01853001 0.7638688 0.6443061 0.03706961 0.5148373 0.856042 -0.04620164 0.3229154 0.9426433 0.08455401 0.03607982 0.9943684 -0.09964841 -0.2854689 0.953194 0.09964215 -0.5719503 0.8139608 -0.1016892 -0.7140496 0.6987427 0.04349499 -0.9296646 0.3682569 0.01051849 -0.9516751 0.3014681 -0.05857938 -4.18028e-6 -4.92499e-6 1 -1.72318e-5 6.73328e-6 1 -3.32489e-6 1.34374e-5 1 3.56946e-6 -1.44258e-5 1 -8.27377e-7 -1.54905e-5 1 1.33713e-6 -7.57316e-6 1 -1.80196e-6 -7.9572e-6 1 2.27394e-7 -1.53693e-5 1 -2.57483e-5 -7.20013e-6 1 3.06604e-5 2.27583e-5 1 3.97665e-5 5.91712e-7 1 -6.11444e-6 6.49143e-6 1 -9.29347e-6 -7.12315e-6 1 -8.90513e-5 6.01247e-5 1 -8.92345e-5 4.99312e-5 1 -6.66939e-5 4.67696e-5 1 -5.07996e-5 1.02399e-4 1 1.44392e-5 7.06451e-5 1 -2.2197e-5 8.49533e-6 1 6.44867e-6 -1.34878e-5 1 8.40269e-5 5.77646e-5 1 0 7.0073e-5 1 -1.83719e-5 3.04768e-6 1 0 0 1 -0.9791133 -0.2012102 -0.02918487 -0.9690121 -0.2459174 0.02323997 -0.7537879 -0.6568557 -0.01855427 -0.7290587 -0.6843572 0.0113399 -0.4161094 -0.9092214 -0.01302134 -0.4074072 -0.9132395 -0.003623247 0.03200429 -0.998924 0.03356629 0.1335099 -0.9899185 -0.04729223 0.4160946 -0.9085093 0.03842109 0.5551538 -0.829665 -0.05882436 0.7696086 -0.6347908 0.06887096 0.9128061 -0.4052879 -0.05026614 0.9571594 -0.2879504 0.03050249 0.9988775 0.01040542 -0.04620933 0.9719953 0.2192598 0.08455872 0.8802551 0.4672599 -0.08257895 0.6635469 0.7446094 0.07254278 0.5417315 0.8390265 -0.05061107 0.2206661 0.9744318 0.04229742 0.0361669 0.9968382 -0.0707497 -0.1735417 0.9828918 0.06169992 -0.551293 0.8327817 -0.05050176 -0.611598 0.7908944 0.02083599 -0.9135127 0.4061461 -0.02323669 -0.9310224 0.3637939 0.02918249 2.47005e-5 2.5873e-5 1 -4.76575e-6 8.68466e-6 1 8.21363e-7 6.54324e-6 1 1.93244e-5 3.56391e-5 1 -1.33832e-6 -8.64141e-6 1 7.43462e-7 4.80046e-6 1 1.369e-5 -3.01054e-6 1 -7.9705e-6 1.81676e-6 1 -6.85116e-6 1.56162e-6 1 -4.8667e-6 -1.24831e-5 1 1.41605e-5 2.62274e-5 1 1.4142e-5 -8.91862e-6 1 -1.32984e-6 -7.33285e-6 1 2.24914e-6 -1.78779e-6 1 2.99805e-5 -2.38309e-5 1 -1.08159e-4 -7.39188e-5 1 -1.31696e-4 -5.76963e-7 1 1.35918e-5 -1.85154e-5 1 1.01216e-5 -7.04742e-6 1 1.25715e-5 -6.63782e-6 1 5.21643e-6 2.77669e-5 1 -2.96448e-5 3.75017e-5 1 -0.9987258 0.03282564 0.03832983 -0.9956758 -0.06043469 -0.07055032 -0.8126347 -0.5784874 0.07054919 -0.756432 -0.6529496 -0.03830611 -0.3132299 -0.9496595 0.005834579 -0.269069 -0.9613739 0.05798441 0.1892362 -0.9795309 -0.06862276 0.337054 -0.9399912 0.05302083 0.6240768 -0.7807675 -0.03049856 0.7164107 -0.6958659 0.05026406 0.875959 -0.4774441 -0.06886976 0.9819609 -0.1746284 0.07251143 0.9984878 -0.02141946 -0.05062949 0.9454619 0.3229763 0.04228627 0.881961 0.4682011 -0.05415141 0.7248772 0.6854874 0.06826448 0.5406011 0.8372155 -0.08258718 0.2161615 0.9736603 0.07252627 0.03614646 0.9967116 -0.07252341 -0.3405909 0.935335 0.09563648 -0.5285294 0.8456314 -0.0745936 -0.8480458 0.5275914 0.0496546 -0.8250022 0.5650711 -0.008136332 -0.09167379 -0.9957049 0.01294779 0.1227739 -0.9923583 -0.01230669 0.1839532 -0.9827789 0.01752191 0.2948228 -0.9554864 -0.01118403 0.4077588 -0.9127163 0.0261088 0.5206601 -0.8529716 -0.03677856 0.6713746 -0.7399606 0.04140692 0.7532709 -0.6571213 -0.02783101 0.8830849 -0.4688023 0.01963132 0.862209 -0.5061724 -0.01962816 0.956609 -0.2898947 0.02933031 0.9780894 -0.2063077 -0.02789908 0.9996177 0.02723789 0.00476557 0.9989517 0.04217517 0.01779931 0.9468888 0.3211814 -0.01562684 0.9356609 0.352648 0.0133475 0.7873794 0.6163123 -0.01388871 0.7683694 0.6398563 0.01386427 0.5370508 0.8434359 -0.01387166 0.5113176 0.8592803 0.01384598 0.2254235 0.9741621 -0.01387476 0.2315211 0.9726317 -0.01963764 0.004392087 0.9996031 0.0278263 -0.1119113 0.9928548 -0.04141569 -0.3069908 0.950811 0.04141473 -0.4362658 0.8988645 -0.04140961 -0.6062032 0.7942304 0.04142165 -0.6948373 0.7186284 -0.02782505 -0.8401489 0.5420003 0.019634 -0.8368031 0.5473282 0.01386684 -0.9637201 0.2665545 -0.01386642 -0.9713392 0.2372927 0.01386636 -0.9974699 -0.06972432 -0.01386588 -0.9949057 -0.09985274 0.01386696 -0.9172627 -0.3980414 -0.0138635 -0.9196645 -0.3922135 -0.01964157 -0.806288 -0.5908684 0.02782309 -0.7474756 -0.6637061 -0.02782738 -0.5771771 -0.816383 0.01963239 -0.5823596 -0.8128131 0.01386427 -0.3290407 -0.9442418 -0.01183062 -0.3132373 -0.9496748 3.56835e-5 -0.1112121 -0.9937967 -1.47075e-5 7.62736e-6 -6.16505e-5 -1 8.1765e-7 2.18102e-6 1 4.12028e-6 2.47484e-6 1 2.35681e-5 6.28659e-5 1 -3.89111e-5 1.39032e-4 1 -6.79298e-6 6.94031e-6 1 -1.90432e-6 -7.634e-6 1 7.49729e-5 -7.4113e-6 1 -7.5468e-6 -8.83627e-6 1 4.01779e-6 1.09992e-5 1 0 1.21288e-5 1 8.96505e-6 2.99325e-5 1 -4.22636e-6 2.55006e-5 1 -2.33058e-5 4.3387e-5 1 1.31255e-5 -5.57432e-6 1 5.48207e-6 -6.74549e-7 1 4.40548e-5 7.37378e-6 1 -4.51967e-6 -8.24116e-6 1 2.91031e-6 1.19252e-5 1 4.86225e-6 1.87858e-6 1 5.05105e-6 1.90373e-6 1 5.3757e-6 1.43543e-6 1 8.51457e-5 -7.99639e-6 1 7.62307e-5 -1.07253e-5 1 -1.65562e-6 -6.78403e-6 1 2.69951e-6 3.16075e-6 1 -1.67054e-5 1.75428e-4 1 -3.42107e-5 -3.54285e-5 1 5.80249e-6 4.86246e-6 1 3.67608e-6 9.64088e-6 1 -1.52021e-6 -9.90393e-6 1 -1.8323e-7 -3.30547e-5 1 -1.33211e-6 1.39888e-5 1 2.50309e-6 1.33033e-5 1 -2.34117e-6 -1.35468e-5 1 -5.5881e-6 3.59416e-6 1 -5.63625e-6 2.98517e-6 1 4.01426e-6 -6.63238e-6 1 4.36079e-7 -1.10462e-5 1 2.31022e-6 -7.57114e-6 1 -5.62062e-6 1.84917e-5 1 4.27816e-5 -4.54145e-5 1 -8.15121e-6 6.33977e-6 1 4.90151e-5 2.24045e-6 1 -2.59626e-7 5.3332e-6 1 6.26348e-7 7.48255e-6 1 3.51995e-7 -9.70232e-6 1 -1.55109e-6 9.44832e-6 1 1.17252e-5 -3.38685e-5 1 1.22656e-5 -8.75033e-6 1 7.12087e-6 1.09627e-5 1 0 0 1 -1.8542e-6 1.75414e-6 1 -2.34063e-7 5.92898e-6 1 1.27797e-6 -5.62796e-6 1 -2.44947e-5 1.62916e-5 1 -9.65881e-6 7.16684e-6 1 2.31137e-5 1.27166e-7 1 2.33758e-5 3.06725e-5 1 -4.16932e-5 -3.49329e-6 1 -1.58776e-5 2.39783e-5 1 2.70309e-5 1.98366e-5 1 -1.34926e-5 9.34431e-6 1 -4.07461e-6 6.76894e-6 1 -1.12427e-5 1.22453e-5 1 2.46183e-5 -2.68135e-5 1 1.18462e-6 -1.29589e-5 1 3.78959e-7 9.15767e-6 1 4.74599e-7 7.93567e-6 1 -5.0354e-7 1.72025e-7 1 -1.02301e-6 -3.41296e-6 1 5.13172e-6 6.15721e-6 1 -3.45056e-6 2.35294e-7 1 2.03705e-7 -2.28166e-6 1 -1.73497e-5 2.05091e-5 1 -0.9760329 0.214814 -0.03485381 -0.8839144 0.4643985 0.05504018 -0.7638688 0.6443298 -0.0366562 -0.444083 0.8956861 0.02316761 -0.3528017 0.9354894 -0.01976168 -0.03199452 0.9991838 0.02465665 0.1782606 0.9829438 -0.04521638 0.4071733 0.9126611 0.03549182 0.7473066 0.6639519 -0.02647143 0.6950532 0.7184705 0.0264818 0.9398761 0.3391812 -0.03986388 0.9822028 0.1854676 0.02965444 0.9875817 -0.1569802 0.006289064 0.950102 -0.3036082 -0.07161325 0.7553228 -0.6520059 0.06615 0.4804578 -0.8755412 -0.05087023 0.3131721 -0.9493117 0.02702623 -0.1244725 -0.9915887 -0.03547775 -0.216654 -0.9759849 0.02268803 -0.744291 -0.6678534 -0.001653909 -0.7555786 -0.6549139 -0.01373714 -0.9866594 -0.1623235 0.01242846 -0.9832838 -0.180532 0.02369195 -0.9989638 0.03971159 0.02223324 -0.9801276 0.1922276 -0.04897326 -0.8625259 0.5036163 0.04918944 -0.6643648 0.7455031 -0.05333429 -0.3946912 0.9171998 0.05443578 -0.189546 0.9811872 -0.03665989 0.2425972 0.9697524 0.02695882 0.2828366 0.9591529 0.005403995 0.655554 0.7549439 -0.01756858 0.7447684 0.6655476 0.04864716 0.9644671 0.2575162 -0.05906414 0.9972888 -0.03025829 0.06707859 0.9521425 -0.301614 -0.04953473 0.7174045 -0.6937997 0.06302976 0.624535 -0.7808597 -0.01463681 0.2170634 -0.9754453 -0.03728121 0.01209473 -0.9972761 0.07275933 -0.3944873 -0.9167312 -0.06311762 -0.5995253 -0.7993627 0.03985881 -0.8850968 -0.4647461 -0.024796 -0.884999 -0.4649399 -0.02465134 -0.9807206 0.1923183 -0.03465169 -0.9675168 0.2527768 0.00388807 -0.7712237 0.6361418 0.02319008 -0.6413033 0.7653539 -0.05443865 -0.3395856 0.9384754 0.06281304 -0.04853397 0.9968434 -0.0628283 0.3748103 0.9261202 0.0426464 0.4958571 0.8679857 -0.02695679 0.8005909 0.5983044 0.03295093 0.9199082 0.3891913 -0.04794579 0.9701601 0.2418033 0.01790308 0.978587 -0.2058247 -0.001929759 0.9690031 -0.2459297 -0.02348631 0.8064237 -0.5906611 0.02828806 0.6612521 -0.7475765 -0.06225115 0.341435 -0.9375745 0.06615281 -0.007547795 -0.9986765 -0.05087596 -0.2165398 -0.9755045 0.03874939 -0.5419454 -0.8392525 -0.0441634 -0.7260947 -0.6866272 0.03646063 -0.8972872 -0.4399234 -0.03664851 -0.9557178 -0.2926962 0.03053802 -0.9841753 0.1770921 -0.006121873 -0.9867264 0.1623331 0.004361033 -0.7642299 0.6446579 -0.01920682 -0.6779999 0.7336356 0.04577153 -0.3236483 0.9447929 -0.05116796 -0.09424328 0.9942332 0.05117154 0.2867056 0.9572347 -0.03875231 0.4073271 0.9131427 0.01596903 0.7475873 0.6641277 -0.006900012 0.7760255 0.6297805 -0.03407227 0.9818003 0.1854021 0.04115939 0.984478 -0.1564798 -0.0794807 0.9965984 -0.08030515 -0.01851302 0.7384408 -0.6741034 0.01702183 0.7048425 -0.7091596 -0.01702761 0.1510432 -0.9883805 0.01702409 0.1331502 -0.9910864 0.004338264 -0.4205265 -0.9070498 -0.0204522 -0.5031108 -0.8633993 0.03769844 -0.8846273 -0.4647572 -0.03788518 -0.9249092 -0.3796169 0.02083384 -3.66546e-5 -2.85337e-5 -1 -6.19674e-5 2.19118e-5 -1 1.71372e-5 1.81608e-5 -1 1.18799e-5 3.7213e-6 -1 1.04198e-6 1.11622e-5 -1 -7.32485e-6 -8.98106e-7 -1 -6.94693e-6 -1.4956e-6 -1 9.4369e-6 8.32688e-6 -1 2.08967e-5 6.28136e-5 -1 1.43155e-4 -1.81321e-7 -1 4.84317e-5 -9.04112e-7 -1 3.3336e-5 -6.76146e-5 -1 -1.23061e-4 6.83002e-5 -1 -1.93891e-5 1.28435e-4 -1 2.49727e-6 -1.09275e-6 -1 -1.25007e-5 5.47002e-6 -1 -1.26443e-5 5.06329e-6 -1 7.63582e-6 -1.02227e-5 -1 6.71222e-6 9.14161e-6 -1 4.95498e-6 9.34859e-6 -1 -3.64328e-5 -6.8738e-5 -1 -6.02011e-5 2.26352e-5 -1 -1.34021e-6 2.4715e-6 -1 -3.22186e-6 -5.14372e-6 -1 -1.15574e-6 -7.62527e-6 -1 -1.05126e-5 -1.92483e-5 -1 -2.9556e-5 3.72517e-5 -1 7.80834e-5 5.70549e-5 -1 2.97681e-5 -4.17189e-5 -1 -2.6394e-5 1.14313e-5 -1 -1.58166e-5 1.79512e-5 -1 -1.60523e-5 1.87365e-5 -1 -4.83838e-5 8.29638e-6 -1 -4.70922e-5 4.01401e-6 -1 1.10349e-5 -4.2884e-6 -1 8.56284e-6 -2.12022e-5 -1 -4.05082e-6 -1.94264e-5 -1 -8.21033e-6 6.72648e-6 -1 9.10668e-6 5.56096e-7 -1 -8.71912e-6 -7.95953e-6 -1 -9.10952e-6 -7.31688e-6 -1 1.66504e-5 4.48951e-6 -1 2.86352e-5 -1.85705e-5 -1 2.13435e-5 -2.06412e-5 -1 8.74855e-6 1.39671e-5 -1 -6.55713e-6 -9.20127e-6 1 2.9825e-7 -6.01551e-7 1 0 -4.89876e-6 1 -5.61428e-5 -4.96675e-5 1 6.55908e-5 1.23854e-5 1 4.57821e-7 -2.40534e-7 1 -2.04852e-6 4.60898e-6 1 1.74277e-7 7.85086e-7 1 -2.03808e-5 1.98806e-5 1 1.75881e-5 -3.90073e-7 1 -2.72861e-6 -5.1144e-6 1 0 0 1 -1.78252e-7 1.16643e-6 1 2.52663e-6 -4.016e-7 1 2.85067e-5 2.03768e-5 1 -1.82225e-5 -3.44111e-6 1 3.9516e-7 -4.27586e-7 1 0 -1.66795e-6 1 -6.33043e-7 1.70797e-6 1 3.53939e-6 7.29747e-6 1 1.62074e-6 -3.76629e-6 1 -5.39326e-7 -7.11745e-6 1 -2.5346e-6 -6.80273e-6 1 -7.95427e-6 -1.11503e-5 1 -2.35611e-6 -1.0404e-5 1 3.10778e-6 1.34715e-5 1 2.7954e-5 4.58316e-5 1 0.9989778 -0.002474904 0.0451349 0.9781574 0.2057725 -0.02942383 0.8226049 0.5684596 -0.01322764 0.7450637 0.665818 0.03957843 0.4443877 0.8951865 -0.03407061 0.2424944 0.9693053 0.04054474 -0.1594017 0.986381 -0.04054141 -0.3948901 0.9176468 0.04456418 -0.6646799 0.7458516 -0.04365849 -0.869147 0.4926232 0.04365706 -0.974826 0.2198742 -0.03700786 -0.9955897 -0.08224761 0.04512906 -0.9396981 -0.3385701 -0.04835104 -0.6859222 -0.7265844 0.03981959 -0.5676993 -0.8228377 -0.02560687 -0.2208319 -0.9751371 0.01846235 -0.0897119 -0.9958263 -0.01678425 0.2338368 -0.9719677 0.02447903 0.3287263 -0.94426 -0.01766681 0.7822088 -0.6230162 4.73345e-4 0.8082706 -0.5883868 0.02235001 0.9701051 -0.241845 -0.02018034 -8.50724e-6 -1.50778e-5 1 -1.14704e-5 1.62476e-5 1 -4.90448e-7 2.18223e-5 1 9.43199e-6 9.27585e-6 1 2.20141e-6 -2.67943e-7 1 1.47521e-5 -1.79555e-6 1 -2.83806e-6 1.90131e-5 1 -1.14764e-5 9.14074e-6 1 -3.781e-5 1.49386e-5 1 -3.52832e-5 -7.6703e-6 1 -4.75006e-6 7.81818e-6 1 -9.13687e-6 1.16695e-5 1 -6.39386e-6 1.71369e-5 1 5.22519e-5 -2.73802e-6 1 5.45769e-5 2.91728e-5 1 -1.75073e-6 2.18882e-5 1 1.17217e-6 4.68566e-6 1 9.02598e-7 4.44138e-6 1 -1.87511e-5 2.36431e-5 1 -1.81361e-5 3.49098e-5 1 -1.15427e-4 3.7892e-5 1 -8.82861e-5 6.79531e-6 1 -9.67691e-5 -1.78596e-6 1 -0.9763281 -0.1916866 0.1001979 -0.9461266 -0.3057657 -0.1065447 -0.6623392 -0.7432432 0.09432125 -0.5403707 -0.8316615 -0.1278231 -0.1882372 -0.9743462 0.1233541 0.04887115 -0.9935702 -0.102126 0.3403917 -0.9347832 0.1015574 0.4819723 -0.8722815 -0.08263051 0.8213547 -0.5625618 0.09434258 0.8851444 -0.4569808 -0.08768135 0.9951147 -0.06323075 0.07581907 0.989984 0.09043562 -0.1084112 0.9106157 0.4002165 0.1029843 0.7537466 0.6506516 -0.09229671 0.688084 0.7250984 0.02779775 0.3376762 0.9408508 -0.02783346 0.2416486 0.9659687 0.09225213 -0.0795865 0.9895185 -0.1204955 -0.3891693 0.9043681 0.1751155 -0.6143764 0.776013 -0.1426375 -0.8775269 0.4620935 0.1281254 -0.9412463 0.3235146 -0.0969215 1.25146e-6 -1.4445e-5 1 3.84968e-6 3.1945e-6 1 7.70059e-7 3.33116e-5 1 1.67302e-5 -1.40997e-5 1 -3.10984e-6 4.60489e-5 1 1.68073e-5 -1.53051e-5 1 -6.55864e-7 1.66187e-6 1 -1.85059e-7 3.1116e-6 1 -6.93258e-7 -1.71926e-6 1 1.20714e-6 4.31312e-6 1 0.9990974 -0.03284186 0.02694123 0.9646175 0.2619283 -0.03011018 0.8141 0.579515 0.03746294 0.7173916 0.6961248 -0.02756255 0.2693905 0.9625367 0.03085237 0.204131 0.9789376 -0.003407657 -0.2208195 0.9751299 -0.01898378 -0.3668874 0.929641 0.03407853 -0.6441678 0.7643426 -0.02877914 -0.7712744 0.6361829 0.02017676 -0.9354028 0.3532137 -0.01617801 -0.9658563 0.258384 0.0189526 -0.9921544 -0.1220763 -0.02696257 -0.9545617 -0.2971783 0.02229517 -0.8537275 -0.5202425 -0.02229315 -0.747098 -0.6641669 0.0269618 -0.3951466 -0.9182686 -0.02533942 -0.352874 -0.9356673 -0.002538442 0.1166325 -0.993067 0.01465618 0.2693247 -0.9622498 -0.03923738 0.4918172 -0.8702808 0.02696478 0.798066 -0.6021661 -0.02206069 0.840296 -0.5420517 0.009094059 0.9912274 -0.1319195 -0.00809735 -2.27107e-5 -8.52993e-6 1 -5.48063e-6 -2.05848e-6 1 -3.44522e-6 -9.92446e-6 1 -6.86562e-6 -1.2007e-5 1 1.52687e-5 -3.81915e-5 1 3.98868e-5 -1.00575e-5 1 2.7546e-5 -6.94574e-6 1 1.73006e-5 -2.17612e-5 1 -1.07551e-5 1.43136e-6 1 -1.43631e-5 -2.04576e-5 1 2.42502e-5 1.15507e-5 1 1.86966e-5 1.81424e-5 1 8.4502e-6 -5.95714e-6 1 -7.88444e-6 -1.75504e-6 1 -3.20616e-6 -2.00565e-5 1 -7.76792e-7 -1.72404e-5 1 -1.20511e-5 -1.25036e-5 1 -1.64546e-5 2.53441e-5 1 2.92538e-5 4.31737e-5 1 8.49133e-5 -3.60728e-5 1 1.29501e-4 1.44322e-5 1 1.09085e-4 2.45884e-5 1 1.08218e-4 5.25534e-5 1 -5.87995e-6 -9.1663e-5 1 -0.9947727 -0.08730471 -0.05296349 -0.8780345 -0.4746011 0.06171864 -0.7792291 -0.6147692 -0.1219054 -0.6217004 -0.7777965 0.09231078 -0.2605122 -0.9625032 -0.07563567 -0.1895876 -0.9813664 0.03124713 0.2721124 -0.961758 -0.03124326 0.3411791 -0.9369504 0.07563585 0.6854186 -0.7222708 -0.09233814 0.8043995 -0.5891524 0.0764271 0.91385 -0.4016701 -0.05949211 0.9753304 -0.2051617 0.08148193 0.989081 0.09035086 -0.1164281 0.9570267 0.271233 0.1026278 0.7357575 0.6716601 -0.08679705 0.6843287 0.7278603 0.04374378 0.2039685 0.9781651 -0.03987216 0.1022667 0.9886459 0.1100945 -0.2456728 0.9618347 -0.120495 -0.5132717 0.8452736 0.1485427 -0.7227721 0.6834974 -0.102136 -0.8790951 0.4700517 0.07901418 -0.9399372 0.3376587 -0.05004525 -0.9986451 -0.006244242 0.05166298 0 -1 0 -0.02136033 -0.9889776 0.1465167 -0.02612847 -0.9994745 0.0191822 -0.00958836 -0.9999001 -0.01038742 0 -1 0 0 -1 0 0 -1 0 -0.9030365 -0.4286638 0.0277909 -0.01656162 -0.9998511 0.004856169 -0.09172201 -0.9954193 0.02697163 0.00620681 -0.9999337 0.009703278 0.01539635 -0.9997424 -0.0166794 -0.06802976 -0.9949576 0.07369899 0.01079809 -0.9999269 0.005455136 0 -1 0 0.03708738 -0.9992941 -0.005988657 0.3673219 -0.9295817 -0.0308662 0.5407643 -0.8388037 0.06310588 0.6954973 -0.7181406 -0.02361452 0.5300531 -0.846583 -0.0483818 0.6027162 -0.7975732 0.02470463 -0.5897182 -0.8074597 0.01553261 -0.5415707 -0.8400306 -0.03240209 -0.5897127 -0.8074636 0.01554256 -0.5415561 -0.84004 -0.03239947 0.34237 -0.1205525 -0.9317992 0.2925422 -0.1888993 -0.9374093 0.341373 -0.1404706 -0.929372 0.2964479 -0.2139352 -0.9307793 0.5556825 -0.2327951 -0.7981374 0.5558885 -0.2334164 -0.7978125 -0.09555697 -0.4425382 -0.8916439 0.5775434 -0.2247121 -0.7848237 -0.6529412 -0.414753 -0.6337569 -0.5206047 -0.4902826 -0.6989948 -0.2543944 -0.6256832 -0.7374308 -0.04215174 -0.5553622 -0.8305397 -0.5247257 -0.5284011 -0.6674243 -0.0959714 -0.5484334 -0.8306685 -0.6536149 -0.4221865 -0.6281291 0.2173631 -0.4412515 -0.8706609 -0.05056113 -0.4692651 -0.8816087 0.2819708 -0.3966863 -0.8735745 -0.2016769 -0.2424318 -0.9489749 -0.2690438 -0.360895 -0.892956 -0.03349983 -0.4187201 -0.9074972 0.4085185 -0.2280437 -0.8838035 0.2137175 -0.2674535 -0.9395709 0.3975726 -0.2466734 -0.883792 0.1986914 -0.1313921 -0.9712147 0.2094761 -0.120373 -0.9703763 0.2378585 -0.5566053 -0.7959986 0.1299933 -0.9011436 -0.4135723 0.3360294 -0.3941144 -0.8554286 0.1490561 -0.5091754 -0.8476572 0.04970103 -0.4378325 -0.8976818 0.2309238 -0.7653279 -0.6007891 0.03371673 -0.6878072 -0.7251101 0.03137296 -0.4006259 -0.9157044 0.04677945 -0.6515938 -0.7571243 0.4050281 -0.7892297 -0.4615938 0.3919968 -0.639881 -0.6609772 0.4670228 -0.4609701 -0.7545835 0.6174143 -0.352688 -0.7031435 0.3325267 -0.3609684 -0.8712794 0.8373253 -0.2668579 -0.4771512 0.8540073 -0.3617361 -0.3739233 -0.1533907 -0.1457511 -0.9773577 -0.5954449 -0.06542998 -0.8007274 -0.2549437 -0.1865505 -0.9487901 -0.1848044 -0.2714599 -0.9445405 -0.2270567 -0.05724173 -0.9721978 -0.6213388 -0.2810223 -0.7314127 -0.5296414 -0.2478671 -0.8111978 -0.5870863 -0.2242404 -0.777847 0.564715 -0.4770822 -0.6734164 -0.277886 -0.08665037 -0.956698 0.1833419 -0.1938076 -0.9637553 -0.2313157 -0.2260826 -0.946245 -0.3914064 -0.2316536 -0.8905827 0.3315523 -0.4215437 -0.8440225 0.2947083 -0.5110995 -0.8074184 -0.1384013 -0.4860442 -0.8629056 0.753077 -0.3624881 -0.5490695 0.7453066 -0.4816267 -0.4610357 0.4247922 -0.6019886 -0.676137 0.4966788 -0.6553311 -0.5690794 0.1221866 -0.5655484 -0.8156136 0.1489647 -0.2888486 -0.9457145 -0.3221614 -0.3206866 -0.8907144 0.5478531 -0.3887895 -0.7407428 -0.1957604 -0.4410901 -0.8758524 -0.2469115 -0.4948489 -0.8331623 -0.08374196 -0.9015776 -0.4244352 -0.2654768 -0.6791594 -0.6842986 -0.05524039 -0.5913309 -0.8045348 -0.07167088 -0.6905105 -0.7197629 -0.07409644 -0.530077 -0.8447059 -0.297856 -0.4115022 -0.861364 -0.05405825 -0.379427 -0.923641 -0.08602106 -0.2625212 -0.9610844 -0.5332307 -0.5621476 -0.6321829 -0.6833844 -0.5390591 -0.4923424 -0.6728764 -0.5040932 -0.5414125 -0.4262126 -0.2262849 -0.8758642 -0.796442 -0.3380714 -0.5013861 -0.1653128 -0.5354632 -0.8282214 -0.2198445 -0.3505889 -0.9103603 -0.2142969 -0.606817 -0.7654083 -0.3608146 -0.6447571 -0.6738703 0.03005522 -0.4384335 0.8982609 0.6267533 -0.619632 0.4724791 0.2894711 -0.7191751 0.6316595 0.3922226 -0.6034721 0.6942498 0.3854882 -0.5578447 0.7349886 0.7998867 -0.3907659 0.4555034 0.8378632 -0.366864 0.4042226 0.4529407 -0.3847723 0.8042357 0.3471741 -0.2328913 0.9084227 0.6782832 -0.2373877 0.6953984 0.04054152 -0.772728 0.6334413 0.1613329 -0.7921256 0.5886499 0.0783798 -0.7117 0.6980973 0.2397039 -0.4656428 0.8518913 0.08289641 0.7183106 0.6907663 0.1119565 -0.8253405 0.5534246 0.1446163 -0.5908537 0.7937116 -0.02474039 -0.4371545 0.899046 -0.9183391 -0.3478553 0.1888116 -0.08513206 -0.2447801 0.965834 0.4622561 -0.2192721 0.8592084 -0.4310294 -0.5788385 0.6922137 -0.3095585 -0.6627393 0.6818726 -0.2283577 -0.6003203 0.7664648 -0.07448029 -0.2300975 0.9703132 0.0829187 -0.2633389 0.9611333 0.094994 -0.3269883 0.9402419 0.3833762 -0.3321762 0.8617898 -0.03654837 -0.4658383 0.8841149 -0.1016941 -0.3824724 0.9183535 -0.4603689 -0.3350154 0.8220859 0.1911709 -0.462698 0.8656583 -0.2233362 -0.5768946 0.7856929 -0.7170168 -0.4199209 0.5563752 -0.7065315 -0.4060545 0.5795973 0.3024703 -0.3854111 0.8717626 0.2386855 -0.3946393 0.887293 0.5837001 -0.2272246 0.7795275 0.5729214 -0.2315094 0.7862343 0.3164438 -0.1579571 0.9353678 0.5312715 -0.1338308 0.8365644 0.06632828 -0.323062 0.9440507 0.1769278 -0.2051935 0.9625967 -0.7167 -0.2256603 0.6598625 -0.408084 -0.6781149 0.6112509 -0.05683678 -0.1584871 0.9857238 -0.3406842 -0.2515792 0.905893 -0.2991905 -0.2948372 0.9074999 -0.5600187 -0.6022331 0.5689414 -0.4361365 -0.6490924 0.6232687 -0.2739529 -0.4025617 0.873438 -0.6994289 -0.4158852 0.5812391 0.3235582 -0.6047105 0.7277606 -0.03669953 -0.9329323 0.3581766 -0.1327044 -0.8900557 0.4361083 -0.1346854 -0.8100926 0.5706224 -0.2604246 -0.4581992 0.8498426 -0.002449929 -0.467032 0.884237 -0.09243518 -0.5821789 0.8077892 -0.2096016 -0.5287384 0.8224979 0.007984757 -0.858738 0.5123528 -0.2577657 -0.1005874 0.9609574 0.5154689 -0.2606294 0.8163112 0.6003016 -0.4422761 0.6663557 0.4045757 -0.5853717 0.7026084 0.3937621 -0.560347 0.7286718 0.2178536 -0.6115868 0.7605928 0.2449902 -0.6360494 0.7317246 0.7298476 -0.4499218 0.5146774 -0.24675 -0.4019138 0.8818048 0.1156346 -0.290284 0.9499283 0.01869672 -0.1856903 0.9824304 -0.06352812 -0.4081629 0.9106961 -0.2047064 -0.2260344 0.9523674 -0.2568022 -0.4004846 0.8795822 -0.5353093 -0.1453259 0.8320603 -0.6389451 -0.1695078 0.750344 -0.7537755 -0.1216963 0.645765 -0.4292584 -0.2930833 0.8543064 -0.2405433 -0.4283767 0.870995 -0.1935384 -0.064152 0.9789931 -0.1988099 -0.07082599 0.9774755 -0.344729 -0.2041348 0.9162374 -0.04719853 -0.3293041 0.9430435 -0.3135513 -0.2715193 0.9099246 -0.09723532 -0.4740663 0.8751037 -0.9914932 -0.09610849 0.08777511 -0.9796022 -0.1873037 0.07277947 -0.9764745 -0.2156077 -0.003283798 -0.8420187 -0.5181471 0.1500939 -0.9016954 -0.3707174 0.2225177 -0.6330523 -0.7071629 0.3149052 -0.7091917 -0.5863509 0.3914584 -0.8543022 -0.5017976 0.1355249 -0.3321864 -0.9421804 0.04413795 -0.260568 -0.9003242 0.3485978 -0.2630158 -0.9504107 0.1659583 -0.385131 -0.8943444 0.2276445 -0.4602436 -0.887792 0.001051127 -0.4071305 -0.8152793 0.4117817 -0.3187509 -0.8944072 0.3137413 -0.3211024 -0.6643943 0.6748878 -0.2672138 -0.8052343 0.5293341 -0.3135668 -0.7797411 0.5419223 -0.6725542 -0.6872085 0.2746188 -0.5724639 -0.8076187 0.141553 -0.7895745 -0.6136531 -0.001423716 -0.1524758 -0.6214249 0.7684934 -0.9098481 -0.413428 0.03540891 -0.6424514 -0.7645045 0.05281227 0.2758788 -0.9611908 0.001758337 0.6181918 -0.7857772 0.0198251 0.6793568 -0.7323967 0.04549181 0.9786184 -0.1867322 0.0862382 0.8869061 -0.4011415 0.2290918 0.39697 -0.6600117 0.6378083 0.1884317 -0.628083 0.754987 0.693269 -0.583692 0.4227077 0.3960948 -0.7794235 0.4853945 0.2616243 -0.7923731 0.5510877 0.5726364 -0.7486183 0.3341534 0.982908 -0.163941 0.08375698 0.7937492 -0.5815075 0.1783571 0.5652304 -0.7513186 0.3406391 0.2640828 -0.9141056 0.307687 0.8436618 -0.5251839 0.11143 0.6006066 -0.7813802 0.1694601 0.4626922 -0.8741131 0.147791 0.343182 -0.9138397 0.2170782 0.9449965 -0.3260615 0.02579694 0.9251549 -0.3774572 0.04018074 0.7534124 -0.6571272 0.02352869 0.3879537 -0.9203563 0.04935812 0.06535178 -0.4942835 0.8668408 -0.1068665 -0.1960318 0.974757 -0.3716538 -0.9283539 0.005719602 -0.5497525 -0.8334209 -0.05640709 -0.6766443 -0.7362838 0.006210148 -0.9311506 -0.3204741 -0.1739392 -0.9378477 -0.3011001 -0.1725695 -0.4801765 -0.6425476 -0.5971291 -0.5352164 -0.6856487 -0.4933855 -0.8259599 -0.5056766 -0.2491617 -0.7444405 -0.5853852 -0.3211426 -0.4602091 -0.8004724 -0.3839939 -0.3453188 -0.8197465 -0.4569141 -0.9347792 -0.305433 -0.1813791 -0.4561623 -0.8528414 -0.2541207 -0.9495863 -0.3074282 -0.06143265 -0.7449103 -0.6540672 -0.1315479 -0.6888196 -0.7039312 -0.1732297 -0.3963176 -0.8992865 -0.1849765 -0.3655296 -0.9086195 -0.2019869 -0.9999033 -0.01321381 -0.004326105 -0.9168267 -0.3976689 -0.03589147 -0.9198015 -0.3910098 -0.03280967 0.00878185 -0.4705301 -0.8823401 0.007680356 -0.3393148 -0.9406416 0.1217637 -0.08815968 -0.9886362 -0.01078873 -0.336255 -0.9417092 6.03276e-4 -0.4631661 -0.8862712 0.1449874 -0.537043 -0.8310014 -0.5196351 -0.5570948 -0.6477846 0.3879973 -0.7760111 -0.4972571 0.9762985 -0.1965013 -0.09071069 0.4132516 -0.6551092 -0.632499 0.8928409 -0.4408403 -0.0921688 0.9969769 -0.07725423 -0.008296966 0.9782391 -0.2070903 -0.01271522 0.8045189 -0.5665125 -0.1783614 0.9038484 -0.3606437 -0.2302049 0.7175126 -0.693063 -0.06956642 0.6661306 -0.6834971 -0.2984992 0.6802119 -0.5873265 -0.4385879 0.8653948 -0.4936381 -0.08610075 0.4883125 -0.8710362 -0.05335479 0.3430461 -0.8755054 -0.3403084 0.4527919 -0.8805918 -0.139777 0.4194675 -0.9028465 -0.0944209 0.2622172 -0.7733707 -0.5771826 0.2771519 -0.8779264 -0.3904253 0.7879464 -0.6155009 -0.01729357 0.4663552 -0.7645976 -0.4448632 0.5651102 -0.8021537 -0.1928729 0.6487058 -0.7322903 -0.2071994 0.834537 -0.5498787 -0.03437024 0.5702103 -0.8203846 0.04277163 0.9009836 -0.00300461 -0.4338427 0.7954858 -0.004942715 -0.6059522 0.7968214 -0.005177497 -0.6041927 0.7220342 -8.90482e-4 -0.6918569 0.6671826 4.30609e-4 -0.744894 0.7393072 -3.26444e-4 -0.6733682 0.4749483 -5.62034e-4 -0.8800135 0.5730264 4.89772e-4 -0.8195368 0.2677395 5.32318e-4 -0.9634912 0.2828935 1.90668e-4 -0.9591514 -0.1043701 0.001026451 -0.9945381 -0.1727309 1.31956e-4 -0.984969 -0.3984186 -4.43334e-4 -0.9172036 -0.341062 0.001159846 -0.9400401 -0.6825301 -7.39648e-4 -0.7308571 -0.739615 -3.55763e-4 -0.6730302 -0.676051 -5.33183e-4 -0.7368547 -0.8812218 -0.002653539 -0.4726952 0.08666366 -3.87711e-4 0.9962376 0.2659817 0.001141607 0.9639775 0.3097046 2.90985e-4 0.9508328 0.4856458 -9.72373e-4 0.8741551 0.5894921 1.88508e-4 0.8077741 0.7140195 -7.15875e-4 0.7001255 0.7632321 -3.04466e-4 0.6461243 0.7014065 -4.42209e-4 0.7127614 0.8814322 -0.003051221 0.4723007 0.04086983 -0.1788365 0.9830295 0.1362315 -0.06388115 0.9886152 0.06497794 -0.4944146 0.8667941 -0.8874411 0.002300083 0.4609155 -0.8087615 -0.005817353 0.588108 -0.7206387 -3.05683e-4 0.6933107 -0.7232586 -3.21337e-4 0.6905773 -0.6149409 -0.00140202 0.788572 -0.4902204 -3.68365e-4 0.8715984 -0.533981 -2.00882e-4 0.8454964 -0.2820471 -5.60051e-6 0.9594005 -0.2661329 3.32533e-4 0.9639363 -0.001320123 -0.5084212 -0.8611075 9.54508e-4 -0.4722297 -0.8814751 0.001087009 -0.2424771 -0.9701566 -2.56307e-4 -0.3351129 -0.9421779 -1.17964e-4 -0.3374096 -0.941358 0.003307163 -0.123757 -0.9923071 -3.12381e-4 -0.2002558 -0.9797435 0.03331905 -0.9955542 -0.08810085 5.63423e-4 -0.999179 -0.04050916 0.002048969 -0.6498982 -0.7600185 -0.006762981 -0.5448109 -0.8385317 -0.001040101 -0.7255246 -0.6881955 -9.69138e-4 -0.7261496 -0.687536 -4.84491e-6 -0.8328431 -0.5535091 -0.001472413 -0.8180345 -0.5751672 -0.001218557 -0.8809885 -0.4731361 2.26143e-4 -0.8935273 -0.4490087 1.57635e-4 -0.9411637 -0.3379511 -3.09883e-4 -0.9440049 -0.3299313 -6.48467e-4 -0.9784643 -0.2064154 5.96607e-4 -0.9834189 -0.1813477 -0.001522123 -0.999738 -0.02283471 -0.003490447 -0.9988831 0.0471211 -0.00252366 -0.09692597 0.9952884 0.001154363 -0.1917045 0.9814521 -0.001425862 -0.2407295 0.9705911 -0.001004219 -0.3482737 0.9373924 0.001494526 -0.308511 0.9512196 6.78264e-5 -0.4903119 0.8715471 -4.79298e-4 -0.4823684 0.8759683 -2.17883e-6 -0.9991127 0.0421167 0.003202259 -0.9990246 0.04404121 2.81982e-4 -0.99921 0.03974211 -1.79777e-4 -0.9768046 0.2141323 0.001536965 -0.9831292 0.182906 0.001013696 -0.9288423 0.370474 -0.00342977 -0.9481403 0.3178336 6.7841e-4 -0.8859379 0.4638035 -0.001765966 -0.841035 0.5409778 5.94395e-4 -0.8158532 0.5782587 6.94998e-4 -0.7356154 0.6773992 -1.22619e-4 -0.7438598 0.6683356 3.13076e-4 -0.5805767 0.8142054 -1.94253e-4 -0.5887912 0.8082852 0.6947825 0.5906867 0.4103248 0.7307066 0.6337331 0.2538703 0.9424675 0.1878662 0.2765166 -0.01533412 0.6790585 0.733924 0.4487502 0.302374 0.8409479 0.4614469 0.3361207 0.8210297 0.4822037 0.3491372 0.8034817 0.442173 0.6207125 0.6474558 0.3225321 0.7125859 0.6230525 0.7736088 0.3656908 0.5174937 0.7523265 0.2426552 0.6124731 0.6963706 0.544564 0.4674593 0.2208448 0.2488395 0.9430304 0.3047912 0.8437278 0.4418433 0.09128743 -0.9421707 -0.3224607 0.003740012 0.6904715 0.7233499 0.004445075 0.6782726 0.7347969 -4.1414e-5 0.5064047 0.8622959 0.003853619 0.3650828 0.9309671 7.66758e-4 0.2217771 0.9750971 0.4521797 0.8664504 0.2116534 0.4786716 0.8276639 0.2929947 0.3692175 0.7768801 0.510035 0.4663822 0.7650622 0.4440357 0.3704122 0.6881548 0.6238892 0.4348655 0.5790375 0.6896431 0.3616748 0.4851654 0.7961193 0.3683402 0.1993904 0.9080578 0.3917001 0.1139286 0.9130123 0.4364516 0.8713603 0.2241458 0.4768928 0.5880981 0.6532334 0.5727211 0.3561939 0.7383201 0.5129456 0.3461878 0.7855194 0.6444539 0.2355895 0.7274453 0.5418425 0.03539359 0.8397344 0.8023794 0.515082 0.3014597 0.7709996 0.5107558 0.380379 0.7849318 0.361872 0.5029221 0.8536283 0.507007 0.1194254 0.7672797 0.5936833 0.2425323 0.7500609 0.5408356 0.3806647 0.7051377 0.3803812 0.5984069 0.8850608 0.1680281 0.4340899 0.8154738 0.0552017 0.5761556 0.8070191 0.05233746 0.5882014 0.966521 0.2109208 0.1461148 0.9570929 0.2736101 0.09545063 0.9172352 0.3667983 0.1553662 0.8660063 0.32158 0.3829091 0.9797152 0.09686076 0.1754311 0.9563214 0.03210109 0.2905491 0.9559496 0.032045 0.2917764 0.2999649 0.557731 0.7739233 0.3240549 0.1767264 0.9293848 0.1189191 0.7850733 0.60788 0.24735 0.4835408 0.8396465 0.981692 0.190409 -0.005018532 0.9314409 0.3638777 0.003312706 0.7982133 0.6023534 -0.005101859 0.6863009 0.7272742 0.007958114 0.4624266 0.8866428 -0.005120337 0.3692977 0.9293046 0.003486573 0.368422 0.9000087 0.2329152 0.9388297 0.1260604 0.3204803 0.7465932 0.1839182 0.6393533 0.7764674 0.587327 0.2283537 0.6816383 0.4474438 0.5789329 0.6755346 0.3279864 0.660362 0.4875319 0.7089999 0.5095409 0.6698067 0.7224096 0.1717078 0.5039508 0.5427833 0.6718779 0.2319722 0.9160197 0.3272566 0.234167 0.7558646 0.6114201 0.4754505 0.3605259 0.8024762 0.9390158 0.2605559 0.2244105 0.3760055 0.8951599 0.2393923 0.2735242 0.09038662 -0.9576089 0.3969967 0.0512883 -0.916386 0.2483465 0.2232725 -0.9425887 0.4313454 0.3289803 -0.8400675 0.2789089 0.5341316 -0.7980685 0.5016211 0.6509431 -0.5697802 0.4537931 0.7562232 -0.4713791 0.3691712 0.8687943 -0.3300137 0.4264138 0.8767144 -0.2225826 0.370153 0.9093686 -0.1898304 0.5958397 0.363686 -0.716036 0.3948218 0.628795 -0.6698751 0.4189018 0.7521867 -0.5086615 0.6201785 0.04456818 -0.7831937 0.6094175 0.05013734 -0.7912626 0.6899943 0.2037418 -0.6945483 0.5444347 0.3572377 -0.7589283 0.8132669 0.3496839 -0.4651004 0.6895315 0.700128 -0.1853841 0.7312965 0.4651275 -0.4988605 0.735006 0.5820668 -0.3477995 0.7794853 0.5602129 -0.2802931 0.7262085 0.6709576 -0.1497901 0.7245204 0.2705519 -0.6339336 0.7369738 0.5797334 -0.3475325 0.9262859 0.04712653 -0.3738631 0.9036013 0.1850182 -0.3863587 0.9231831 0.2543277 -0.2881849 0.9107996 0.2794011 -0.3039395 0.9468078 0.2771499 -0.1635324 0.8933404 0.4116466 -0.1802499 0.9528512 0.2972357 -0.06103813 0.9578188 0.1021429 -0.2686073 0.7511883 0.6067035 0.2600519 0.8480929 -0.01233774 -0.529704 0.9605721 0.02207708 -0.2771531 -0.4070587 0.9016928 0.1457852 -0.03003931 0.9995481 -0.001069903 0.2830778 0.9590942 0.002311468 0.3808866 0.9246197 -0.001930892 0.488798 0.8723969 -4.48068e-4 0.7429264 0.6693521 -0.005295574 0.8543909 0.5196194 0.003463089 0.9598078 0.2806381 -0.003342807 0.4512445 0.6696771 -0.5898397 0.2626041 0.1422148 -0.9543658 0.3183932 0.2146055 -0.9233474 0.8213105 0.2914073 -0.4904394 0.186132 0.4885361 -0.8524596 0.4950298 0.4812728 -0.72341 0.5181138 0.5184111 -0.6802999 0.5537195 0.1671763 -0.8157491 0.4528954 0.6718275 -0.5861176 0.8353921 0.4718878 -0.2818545 0.8623375 0.3525874 -0.3633955 -0.006420671 0.9818465 0.1895689 -0.3325607 0.8454268 0.4179198 -0.3091974 0.9056257 0.2902397 -0.3632346 0.8329244 0.4174896 -0.2180023 0.6891279 0.69107 -0.5315257 0.5580866 0.6371967 -0.5171898 0.5686103 0.6396853 -0.5762003 0.6760346 0.4593154 -0.7478439 0.6251457 0.2234332 -0.8709481 0.2846584 0.4005235 -0.635509 0.2809309 0.7191703 -0.5496109 0.3275115 0.7685468 -0.7510285 0.3642506 0.5507066 -0.06894624 0.9976204 2.03932e-4 -0.3514744 0.9361954 -0.002001643 -0.3852551 0.9228102 -2.08854e-4 -0.6317002 0.7752084 0.002592027 -0.7223932 0.69148 -0.00190407 -0.9203931 0.3909906 0.001787364 -0.9163943 0.4002748 0.001249849 0.3513861 0.9214652 -0.1656197 5.49006e-4 0.2380325 -0.971257 5.36293e-4 0.2377179 -0.9713341 0.004423499 0.524671 -0.8512935 0.002621948 0.5565714 -0.8307956 2.20737e-4 0.7781603 -0.6280657 0.002508461 0.8240064 -0.566575 -0.1694759 0.8391689 0.5167917 -0.3485557 0.2155233 0.9121725 -0.2433154 0.274394 0.9303254 -0.2141399 0.5080604 0.8342773 -0.2327542 0.6795064 0.6957704 0.6913175 0.3977998 -0.6031877 0.05990362 0.9959239 -0.06743186 0.2090157 0.9307107 -0.30015 0.6943809 0.5288006 -0.4880626 0.1801192 0.415861 -0.8914127 0.2803966 0.9021611 -0.3278458 0.6184702 0.7409158 -0.2617983 0.03846466 0.8881501 -0.4579409 0.3112007 0.84832 -0.4283775 0.724947 0.5045697 -0.4688938 0.4824176 0.3976513 -0.7804785 0.7507468 0.156367 -0.6418167 0.8881038 0.3669416 -0.2768129 0.3083875 0.5487657 -0.7770158 0.3152382 0.2985852 -0.9008173 0.2759769 0.5766182 -0.7689917 0.2077823 0.7630925 -0.6119773 0.1500774 0.802772 -0.5770909 0.3493053 0.2769935 -0.8951315 9.52822e-4 0.250751 0.9680511 -8.44449e-4 0.2948724 0.9555363 -0.004914462 0.4722324 0.8814604 -0.004273235 0.7438843 0.6682949 -5.88936e-4 0.598659 0.8010038 2.6414e-4 0.8533051 0.5214119 -0.3775534 0.9116314 -0.1624245 -0.1151477 0.9795693 -0.1648784 -0.6337346 0.7045956 -0.3192578 -0.593088 0.4511452 -0.6668693 -0.7050743 0.6710195 -0.2293536 -0.5163062 0.6936928 -0.5022135 -0.7002665 0.1144887 -0.7046411 -0.8604373 0.3266284 -0.3911029 -0.8605757 0.3337402 -0.3847426 -0.6145098 0.3275224 -0.7177094 -0.6331923 0.4069807 -0.6583572 -0.3620089 0.2757567 -0.8904536 -0.3398094 0.8222376 -0.4565688 -0.3493379 0.9275529 -0.1326976 -0.2047176 0.936773 -0.2838082 -0.2625744 0.8169153 -0.5135213 -0.8801579 0.2055926 0.4278478 -0.7099686 0.4918219 0.5040394 -0.4926486 0.3954057 0.7752107 -0.5104479 0.5617954 0.6510214 -0.2883583 0.3786863 0.8794579 -0.49128 0.586853 0.6436207 -0.562205 0.2550013 0.7867019 -0.1880691 0.8371614 -0.5136054 -0.2118133 0.6149751 -0.7595662 -0.3723613 0.3957541 -0.8394795 -0.324663 0.2973607 -0.89787 -0.1212598 0.7549894 -0.6444277 -0.8912529 0.04271566 0.4514906 -0.4199799 -0.579343 0.6985546 -0.002764105 0.7716385 -0.6360553 -5.22168e-5 0.7261763 -0.6875085 -0.001325249 0.4656311 -0.884978 -0.003287255 0.5058907 -0.8625913 -0.002489447 0.1680932 -0.985768 -9.70469e-4 0.2183135 -0.9758782 -0.1435282 0.09113001 0.9854415 -0.4444388 0.3297252 0.8329198 -0.463324 0.8537814 0.2374622 -0.3701998 0.9087951 0.1924673 -0.4853466 0.06693768 0.8717557 -0.4268683 0.09739965 0.8990533 -0.4374001 0.3344131 0.8347749 -0.5175737 0.4509135 0.7271826 -0.4109923 0.623158 0.6654018 -0.5631268 0.5931023 0.5754285 -0.4682995 0.762108 0.4470871 -0.4600088 0.7681745 0.4453085 -0.5161961 0.5502572 0.656322 -0.6879051 0.6949775 0.2092677 -0.7437007 0.04312402 0.6671203 -0.8096631 0.01719558 0.5866429 -0.7178398 0.1929038 0.66895 -0.7981272 0.2422178 0.5516554 -0.7545522 0.301455 0.5829029 -0.7917507 0.4094967 0.4532586 -0.8056669 0.5048557 0.3098737 -0.804891 0.3928555 0.444764 -0.8475659 0.439031 0.2981338 -0.8039062 0.5809477 0.1274161 -0.9252811 0.08003103 0.3707423 -0.9649648 0.1562401 0.2107889 -0.777 0.0907216 0.6229292 -0.9564336 0.1910955 0.2207201 0.3414964 0.7517381 0.5641543 -0.9238886 0.2890453 0.2507642 -0.9786931 0.191449 0.07420933 -0.2746732 0.4033644 -0.8728412 -0.5630113 0.5915524 -0.5771344 -0.3749622 0.2993924 -0.8773641 -0.6354628 0.3288241 -0.698614 -0.6525318 0.467761 -0.5961558 -0.3725433 0.692966 -0.6172598 -0.2779345 0.6919987 -0.666251 -0.2931877 0.06030535 -0.9541511 -0.3923713 0.1660264 -0.9046989 -0.8186277 0.3661775 -0.4424508 -0.3694007 0.9292648 -0.003187239 -0.3416504 0.9398101 -0.005653202 -0.6866074 0.7270226 -0.002895951 -0.688035 0.7256727 -0.002642154 -0.806526 0.5911969 0.001464903 -0.9164205 0.4001966 -0.004020392 -0.9300975 0.3673046 -0.002442896 -0.5736536 -0.02124106 -0.8188225 -0.7432472 0.03196501 -0.6682527 -0.4056 0.8916805 -0.2009842 -0.3821229 0.3519387 -0.8544714 -0.3604497 0.9053769 -0.2244294 -0.3679909 0.792396 -0.4865092 -0.4708078 0.7704666 -0.4297922 -0.3569398 0.6788967 -0.6416333 -0.4568269 0.5849881 -0.6701478 -0.2636184 0.4885751 -0.8317449 -0.2948634 0.09294939 -0.951008 -0.573107 0.3861383 -0.7228039 -0.4506 0.1616107 -0.877976 -0.6699153 0.7198339 -0.181804 -0.6425675 0.739294 -0.201374 -0.6423993 0.6487827 -0.4079267 -0.7090036 0.4180908 -0.5679031 -0.5698474 0.3905918 -0.7229884 -0.5725417 0.2159447 -0.7909261 -0.6175915 0.01629716 -0.7863302 -0.6913156 0.553401 -0.4645751 -0.8047987 0.1359836 -0.5777609 -0.8998321 0.4270034 -0.08927702 -0.7920771 0.5652531 -0.2304399 -0.8484186 0.4720602 -0.2394682 -0.7920459 0.4423648 -0.4206861 -0.8027853 0.3175104 -0.5047009 -0.9271965 0.1370059 -0.3486203 -0.8316317 0.01094204 -0.5552198 -0.9213087 0.3043696 -0.2419698 -0.9161609 0.1939999 -0.3507325 -0.9002992 0.03316032 -0.4340067 -0.9852572 0.1578561 -0.06595331 -0.9201182 0.3068068 -0.2434178 -0.8822845 0.2158444 -0.4183124 0.7987291 0.09489637 -0.5941604 0.5635889 0.08141636 -0.8220334 0.4699325 0.09706014 -0.8773499 0.3267188 0.07264202 -0.9423258 0.8291167 0.1131735 -0.547501 0.9257205 0.09667193 -0.3656448 0.949268 0.07542157 -0.3052901 0.4296796 0.3292768 -0.8408045 0.5732702 0.334135 -0.7481411 0.6044369 0.3565803 -0.7123949 0.8443986 0.2982943 -0.4449849 0.4550508 0.5523099 -0.6984859 0.6121332 0.5579464 -0.560347 0.8597802 0.3097126 -0.4060247 0.9166333 0.261232 -0.3025579 0.5818222 0.6183733 -0.5282967 0.4435556 0.7920872 -0.4193522 0.6314268 0.6422967 -0.4344598 0.8685946 0.4340873 -0.2389803 0.9223866 0.3265739 -0.2062823 0.4397611 0.8747562 -0.2034986 0.4968821 0.8385566 -0.2234523 0.8252046 0.5413963 -0.1610203 0.9195693 0.3927891 -0.01045137 0.838401 0.5450235 0.005761861 0.4500651 0.8929615 -0.007821798 0.3700634 0.9290065 -4.24519e-4 0.4772722 0.08153414 0.8749648 0.4040808 0.299088 0.864445 0.3751098 0.7693212 0.5171436 0.46399 0.08590233 0.8816655 0.5448343 0.5799805 0.6056221 0.5480132 0.5918712 0.5910754 0.5418252 0.743893 0.3912142 0.5238728 0.7701305 0.3639456 0.4449725 0.8780906 0.1759444 0.6340054 0.3201428 0.7039502 0.582463 0.4211137 0.6952698 0.6276981 0.4912008 0.603918 0.6094827 0.7647719 0.2089371 0.753767 0.09332633 0.650481 0.7553066 0.241216 0.6093658 0.7576102 0.5489131 0.3531591 0.8235113 0.0600869 0.5641086 0.8686104 0.4222377 0.25929 0.8337683 0.5420119 0.1051363 0.959167 0.06586164 0.2750653 0.9229076 0.1630156 0.3488087 0.9176446 0.2458303 0.3122435 0.9080665 0.4013102 0.1198558 0.9691287 0.07833433 0.2337806 0.9574339 0.2097041 0.1983548 -0.3751052 0.02564382 -0.9266275 -0.6595426 0.06127738 -0.7491654 -0.9956805 0.04175436 -0.0829268 -0.9471737 0.05483645 -0.3159982 -0.958608 0.07135492 -0.2756434 -0.9551929 0.2584105 -0.1443271 -0.90527 0.2423658 -0.3489195 -0.8116164 0.5667862 -0.1415354 -0.8214586 0.5540741 -0.1349366 -0.8547211 0.4198889 -0.3051967 -0.8415496 0.3687984 -0.3946921 -0.8382692 0.2385705 -0.4902945 -0.6442217 0.6738482 -0.3618108 -0.6495721 0.6603956 -0.3767408 -0.6285676 0.3073447 -0.7144522 -0.5085508 0.8453125 -0.1637766 -0.5084702 0.7127603 -0.4831468 -0.5593413 0.2755527 -0.781798 -0.5469003 0.2351588 -0.8034926 -0.4147211 0.8818796 -0.2242645 -0.4195634 0.8555144 -0.3034166 -0.3931695 0.6685079 -0.6312804 -0.5032013 0.5638425 -0.6548817 -0.4370675 0.5156201 -0.7369586 -0.8457808 0.5335192 -0.003482937 -0.8852752 0.4650282 0.006055772 -0.5011572 0.8653206 -0.007853984 -0.3526452 0.9357479 0.004139542 -0.7022671 0.1072907 0.7037825 -0.6234611 0.05629426 0.7798253 -0.9015702 0.0623824 0.4281117 -0.8322147 0.5456166 0.09859675 -0.8677029 0.2753738 0.4138367 -0.8613954 0.2829921 0.4217978 -0.6394535 0.7362541 0.2214252 -0.6039216 0.7385752 0.2996422 -0.6287937 0.6955986 0.3475071 -0.570398 0.2364677 0.7865933 -0.9312481 0.07547372 0.3564838 -0.5214009 0.6186267 0.5877432 -0.4078096 0.5943231 0.6931604 -0.3831754 0.9096618 0.1602869 -0.4181039 0.748409 0.5148524 -0.9657128 0.2352945 0.1097055 -0.8452058 0.4413865 0.3013389 -0.7974371 0.4469447 0.405382 -0.6073711 0.3908507 0.6916185 -0.5461444 0.365698 0.753652 -0.2792122 0.0389136 0.9594406 0.01534271 0.5133647 0.8580334 0.05414217 0.3568316 0.9325985 -0.03373628 0.2504207 0.9675491 0.05915719 0.076613 0.9953044 0.03287357 0.6522929 0.7572538 0.01797908 0.510634 0.8596101 0.004672646 0.676677 0.7362653 0.008860349 0.4856709 0.8740969 0.005551457 0.4977796 0.8672857 0.00203967 0.2833719 0.959008 0.01408499 0.228733 0.9733873 0.001804113 0.02001684 0.9997981 0.003196656 0.9754024 0.2204084 0.005801379 0.9680048 0.2508651 0.005827367 0.9142267 0.4051611 0.003482699 0.9279401 0.3727132 0.003480851 0.8377321 0.5460703 0.003995537 0.834929 0.5503432 0.002559661 0.6691803 0.7430957 -7.95261e-5 0.6811417 0.7321515 -0.01158165 0.5325573 0.8463147 0.001755416 0.3561129 0.9344413 -0.01632887 0.2504914 0.9679812 0.007664918 0.07063913 0.9974724 4.2206e-6 0.6781972 0.7348801 -0.04492443 0.639716 0.7672973 0.01980936 0.4976132 0.8671728 -0.05337512 0.4050191 0.9127489 -0.009015679 0.2177343 0.9759663 -0.01773458 0.2288138 0.9733086 -0.05780982 0.1004156 0.9932647 -0.002180278 0.9693558 0.2456513 -0.002632021 0.9706849 0.2403414 -0.00797683 0.9264964 0.3762192 -0.002721369 0.8473665 0.5310016 -0.008778393 0.8696021 0.4936751 -0.002328455 0.7825143 0.6226283 -0.007213652 0.6457708 0.7634973 -0.004936873 0.6332332 0.7739453 -0.0060997 0.510775 0.8596929 -0.01228582 0.5240145 -0.8516207 -0.0462538 0.3890492 -0.9200551 0.01264691 0.2505517 -0.9680206 -0.02701193 0.2066286 -0.9780465 -0.05338096 0.08178418 -0.9952195 -0.03237938 0.5103799 -0.8593392 0.00331968 0.6479282 -0.7616942 -0.01176887 0.4977371 -0.8672481 0.002831697 0.4228388 -0.9062005 -0.009694755 0.2487371 -0.9685225 -0.01407539 0.2287515 -0.9733831 -0.001659452 0.01772898 -0.9998415 -0.003009676 0.969437 -0.2453221 5.10595e-4 0.9763248 -0.2163091 -0.006168723 0.9105032 -0.4134562 -0.001581013 0.8535514 -0.5210063 -5.81539e-4 0.8587523 -0.5123906 -0.006959974 0.7441116 -0.6680191 0.002067625 0.6524953 -0.75779 6.85817e-5 0.6186296 -0.7856828 0.009417712 0.5411445 -0.8408769 -0.004056453 0.3606991 -0.9326735 0.01462686 0.2504829 -0.9680106 -0.00876379 0.08358317 -0.9964622 -4.3234e-6 0.6865468 -0.7270856 0.04675292 0.6217632 -0.7818086 -0.01443594 0.4976314 -0.8672685 0.06790447 0.3804075 -0.9223226 -0.0317232 0.2287517 -0.9729677 0.05309957 0.09003192 -0.9945223 0.002933919 0.9704329 -0.2413531 0.002251088 0.9689772 -0.24714 0.004059016 0.8647972 -0.5021048 0.005835652 0.8737922 -0.4862644 0.005793333 0.767444 -0.6410897 0.002946972 0.7409156 -0.6715918 0.008058726 0.6316267 -0.7752307 -6.68984e-4 0.5107891 -0.8597058 -0.3263405 0.612311 0.720123 -0.4540241 0.5510039 0.7001834 -0.4343682 0.8280246 0.3545413 -0.426715 0.8303847 0.3582955 -0.55516 0.7177605 0.4202586 -0.4431779 0.7137137 0.5424078 -0.4428901 0.7138776 0.5424272 -0.5643664 0.5899608 0.57744 -0.7426963 0.4355598 0.5086156 -0.7557446 0.5921184 0.2797248 -0.8668251 0.3115808 0.3892707 -0.8477309 0.4039692 0.343746 -0.8954726 0.3534659 0.2705378 -0.8294494 0.5093248 0.2293514 -0.908506 0.2718262 0.3173755 -0.9180987 0.3545853 0.177099 -0.3822788 0.7763656 0.5011182 -0.3613174 0.5802714 0.7298867 -0.1783766 0.8998857 0.3979794 -0.2167788 0.9660282 0.1407006 -0.7957262 0.4789547 -0.3707051 -0.6196627 0.7174381 0.3182778 -0.6427875 0.7605572 0.09152597 -0.5040184 0.8631553 -0.03046917 -0.4797869 0.8596667 -0.1754354 -0.2683369 0.8932484 -0.3606972 -0.2880754 0.6607102 -0.6931629 -0.8687422 0.4918612 -0.05796247 -0.5546504 0.4905734 -0.6720868 -0.4295966 0.5377882 -0.7254177 -0.2546712 0.2934171 -0.9214385 -0.7215809 0.5321389 -0.4428874 -0.9092186 0.4163037 -0.00362122 -0.3665513 0.001718878 -0.9303963 -0.5045069 -0.002497494 -0.863404 -0.6522359 0.001726508 -0.7580142 -0.7817919 -0.002171695 -0.6235356 -0.9027383 0.004717707 -0.4301642 -0.9956471 1.41596e-4 -0.09320241 -0.2925986 -0.8321527 -0.471071 -0.4625648 -0.6705402 -0.5800085 -0.2235714 -0.6421536 -0.7332493 -0.2850098 -0.485058 -0.8267335 -0.2874241 -0.2494668 -0.9247452 -0.584616 -0.7424583 -0.3270777 -0.3315001 -0.4616555 -0.8227892 -0.3898136 -0.7647577 -0.5130216 -0.4322947 -0.3217374 -0.8423813 -0.5443626 -0.1577464 -0.8238843 -0.6035341 -0.5521426 -0.5752261 -0.6911175 -0.327399 -0.6443341 -0.7423784 -0.5896975 -0.3180114 -0.734919 -0.4406262 -0.5155023 -0.51614 -0.284509 -0.8078701 -0.7850773 -0.5382566 -0.3064857 -0.944929 -0.2329154 -0.2299122 -0.8199095 -0.3153859 -0.4777867 -0.9359393 -0.1422165 -0.3221682 -0.9467617 -0.2807726 -0.1575092 -0.9074376 -0.358592 -0.2190179 -0.4908003 -4.35575e-4 -0.8712719 -0.6290666 -0.01150834 -0.7772663 -0.8443005 -8.91628e-4 -0.5358694 -0.9658073 -0.008795082 -0.2591117 -0.9432224 -0.06563478 -0.3256126 -0.9456947 -0.1722984 -0.2756351 -0.9759222 -0.1362776 -0.1703066 -0.8982493 -0.377607 -0.2248578 -0.9213555 -0.3585555 -0.1501401 -0.8571833 -0.2738224 -0.4361858 -0.8312045 -0.5450467 -0.1096501 -0.7780601 -0.5174484 -0.3561877 -0.6295416 -0.1852697 -0.7545546 -0.6466096 -0.1637368 -0.7450411 -0.6436295 -0.2380234 -0.727383 -0.6381197 -0.5206975 -0.567166 -0.6385117 -0.5272478 -0.5606358 -0.4876978 -0.5293584 -0.6942121 -0.523725 -0.7583984 -0.3879999 -0.4885836 -0.7972756 -0.3544539 -0.5424622 -0.8047847 -0.2409487 -0.4479885 -0.4001184 -0.7995071 -0.4032967 -0.7332042 -0.5475065 -0.4142732 -0.8943889 -0.1686607 -0.4236576 -0.9058198 -0.002182185 -0.5968859 -0.8023215 0.002731204 -0.8603528 -0.5096988 -3.13303e-4 -0.8448147 -0.5350583 7.78165e-4 -0.9977288 -0.06734752 -0.00121808 -0.9780834 -0.1712651 0.1184107 -0.9201306 -0.2779532 0.2758654 -0.8729739 -0.4636361 0.1515196 -0.8286324 -0.2718066 0.4893767 -0.8522621 -0.1945575 0.4855892 -0.6642758 -0.6847662 0.2997217 -0.6855683 -0.5725406 0.4496591 -0.6240248 -0.1398934 0.7687801 -0.4809225 -0.8512498 0.2099698 -0.5586015 -0.7723898 0.3022884 -0.5249798 -0.622528 0.5803923 -0.5367354 -0.4680702 0.7020152 -0.3407784 -0.8485934 0.4046721 -0.4093821 -0.4572286 0.7895241 -0.4250323 -0.2474594 0.870696 -0.2988478 -0.7327193 0.611402 -0.3920006 0.002747833 0.9199608 -0.6476683 -0.01307797 0.7618101 -0.8361242 0.002005696 0.5485367 -0.9811263 -0.008107423 0.1931985 -0.2071638 -0.1557397 -0.9658303 -0.1733484 -0.8636698 0.4733127 -0.348182 -0.8021597 0.4850867 -0.7183589 -0.5860564 0.3748313 -0.9173507 -0.3445453 0.1993897 -0.9604525 -0.2346035 0.1499735 -0.6505492 -0.6565784 0.3816946 -0.3547466 -0.6475443 0.6744191 -0.392255 -0.5421041 0.7431415 -0.2356619 -0.6265716 0.7428806 -0.6731377 -0.4475055 0.5887481 -0.6766125 -0.4444228 0.587098 -0.9661062 -0.1489216 0.2108584 -0.3710644 -0.3143897 0.8737679 -0.7154209 -0.3527719 0.6030961 -0.7573639 -0.2507925 0.6029121 -0.5194864 -0.170438 0.8373079 -0.8558183 -0.18027 0.4848482 -0.4498551 -0.2256322 0.8641299 -0.9367323 4.20773e-4 0.3500461 -0.8893606 0.003668487 0.4571918 -0.7710472 -0.004960536 0.6367587 -0.3944216 0.004295408 0.9189195 -0.4740408 -9.68953e-4 0.8805024 -0.2960917 0.002515375 0.9551562 -0.05607897 0.5056849 0.8608936 -0.108397 0.5317389 0.8399429 -0.1263142 0.5316418 0.8374974 -0.3177496 0.751966 0.5775659 -0.4139426 0.7402672 0.5297698 -0.2307204 0.9610162 -0.1523675 -0.3216463 0.9419969 0.09584003 -0.4226516 0.8934383 0.1520974 -0.6371549 0.4920353 0.593241 -0.5464479 0.4208034 0.7240988 -0.09590327 0.9738845 -0.2057951 -0.5899272 0.5105141 0.6255887 -0.7164285 0.667384 -0.2032948 -0.4935251 0.7553315 -0.4311699 -0.9115062 0.3798523 0.1576979 -0.8818672 0.1458062 0.448387 -0.8208163 0.5533863 0.1415068 -0.7291576 0.6843437 -0.001705825 -0.5186019 0.7338225 -0.4388127 -0.05759662 0.6242526 -0.7790966 -0.3736175 0.5655248 -0.7352495 -0.4964906 0.5559428 -0.6666517 -0.7214623 0.4225917 -0.5485512 -0.8509615 0.3415417 -0.3990162 -0.9171693 0.2568442 -0.3046829 -0.9858764 0.1172326 -0.1196004 -0.3989465 0.683746 -0.6110098 -0.7658233 0.429193 -0.4788613 -0.4092785 0.6969076 -0.5889065 -0.6525175 0.6166931 -0.4403527 -0.7849712 0.486322 -0.3838114 -0.9843047 0.1433082 -0.1029897 -0.4269846 0.783907 -0.4507481 -0.4181618 0.785438 -0.4563199 -0.8469089 0.4599684 -0.2667847 -0.3015739 0.8800265 -0.3668876 -0.3835921 0.859502 -0.3378069 -0.5801454 0.743906 -0.3317156 -0.8606166 0.4721718 -0.1907687 -0.8083332 0.5321833 -0.2517505 -0.8634404 0.456761 -0.2141028 0.2969642 0.6101527 -0.7345243 0.05392581 0.6238099 -0.7797136 0.3944153 0.8471844 -0.3559708 0.4898123 0.7407875 -0.4596931 0.3422738 0.8591721 -0.380358 0.4437702 0.5495162 -0.7078841 0.5659049 0.5905446 -0.5753336 0.4486827 0.7102805 -0.5423886 0.3759129 0.7492426 -0.5452752 0.6504984 0.4897647 -0.5805019 0.7398674 0.6185461 -0.2645696 0.8355131 0.342332 -0.4297986 0.8650572 0.3858617 -0.3206037 0.6791961 0.6437093 -0.3526061 0.7781251 0.4328249 -0.4551746 0.8356794 0.4897901 -0.2484865 0.9002715 0.2849903 -0.3290772 0.6868927 0.4941421 -0.5329184 0.7135848 0.6128652 -0.339401 0.9922245 0.08927488 -0.08672106 0.6206678 0.07337725 0.7806327 0.8794671 0.4027712 0.2536 0.8468925 0.3780889 0.3739275 0.709264 0.3862933 0.5896797 0.1113353 0.9132477 -0.391897 0.7798117 0.5683459 -0.2624434 0.7885341 0.4225145 0.446873 0.3319097 0.4002783 0.8541741 0.4017412 0.5242818 0.7508213 0.7433269 0.6649742 -0.07262599 0.6420077 0.5880077 -0.4920093 0.2201364 0.3541874 0.9088957 0.3114438 0.695889 0.6471023 0.3829127 0.8326056 0.4001821 0.4461014 0.8924985 -0.06663322 0.2991778 0.872721 -0.3858117 0.3853481 0.7753659 -0.5003145 0.5404071 0.8409515 0.02758091 0.4884164 0.8168315 0.3069781 0.9245395 -1.30316e-4 0.3810862 0.9204903 -5.68463e-4 0.3907648 0.6886961 -0.001115143 0.7250493 0.6191461 0.002713859 0.7852712 0.3300971 -0.002790927 0.9439429 0.2243945 2.88835e-4 0.9744983 0.1218563 -0.21786 0.9683429 0.3186773 -0.8256202 0.4656135 0.4232755 -0.3270757 0.844902 0.495292 -0.6545729 0.5711569 0.383476 -0.5541934 0.7387936 0.4725518 -0.562227 0.6786721 0.2900953 -0.4243924 0.8577504 0.6079115 -0.7254958 0.3226445 0.393943 -0.7527325 0.5274495 0.1413077 -0.2128812 0.9668059 0.7398219 -0.3657516 0.5647029 0.5808231 -0.2920064 0.7598533 0.6935943 -0.1892351 0.6950661 0.6953926 -0.4825919 0.5324795 0.868446 -0.4234673 0.257831 0.8646904 -0.4300992 0.2594708 0.7749067 -0.4031863 0.486786 0.9312428 -0.1497626 0.3322017 0.9191948 -0.1557612 0.3616896 0.8698235 -0.4214996 0.2564082 0.9761824 -0.1595366 0.1470243 0.8904743 -0.006065547 0.4549931 0.9069337 -0.008735895 0.4211828 0.5800406 -5.7306e-5 0.8145877 0.4225099 -0.01049512 0.9062976 0.1658465 -0.002222895 0.9861491 0.9540157 -0.2669939 0.136265 0.9283541 -0.1807972 0.3247632 0.9204265 -0.3717482 0.1209062 0.8335342 -0.1537476 0.5306435 0.8442766 -0.3553661 0.4011383 0.8721688 -0.380995 0.3068624 0.792554 -0.1749874 0.5841554 0.7719334 -0.6099523 0.1791006 0.6260007 -0.504106 0.5949792 0.474233 -0.4411528 0.7618972 0.463795 -0.4583143 0.7581835 0.4896847 -0.6664469 0.5621898 0.5476359 -0.7218618 0.4230962 0.5399634 -0.7314563 0.4164267 0.5810877 -0.7537809 0.3068414 0.4329372 -0.1957305 0.8799176 0.4024441 -0.2147508 0.8898993 0.3355098 -0.917766 0.2124586 0.9428517 -0.3332087 0.00166136 0.8653811 -0.5011127 -0.001315891 0.741564 -0.6708801 0.00170809 0.5300331 -0.8479769 -3.0537e-4 0.4427847 -0.896626 0.001868486 0.9593506 -0.2004933 -0.1986172 0.862714 -0.1269767 -0.489491 0.8637988 -0.4873819 -0.127713 0.8569288 -0.4969635 -0.1367491 0.8497439 -0.4500338 -0.2746001 0.873806 -0.2566561 -0.4130265 0.7781013 -0.5244316 -0.3457309 0.5619379 -0.8056626 -0.1874399 0.5733633 -0.1980847 -0.7949949 0.5155112 -0.8290624 -0.2165729 0.5282744 -0.6029138 -0.5978469 0.565621 -0.4643148 -0.6815313 0.4979453 -0.4483824 -0.7422962 0.5509015 -0.2143775 -0.8065667 0.407105 -0.8225398 -0.3971067 0.4577992 -0.7767227 -0.432576 0.3576545 -0.7151809 -0.6004993 0.9443928 -0.009975373 -0.3286682 0.8449534 0.001693308 -0.5348373 0.5638775 -0.005874574 -0.8258376 0.502533 -9.26809e-4 -0.8645576 0.4157035 -0.7896341 -0.4512966 0.7267879 -0.5968119 -0.3399924 0.4943175 -0.7262634 -0.4776941 0.7737239 -0.557047 -0.3017449 0.897709 -0.3667105 -0.2442166 0.3067573 -0.6503018 -0.6949874 0.612515 -0.5681805 -0.549542 0.8777679 -0.289667 -0.3815975 0.9206814 -0.2543755 -0.2960387 0.4825085 -0.5179347 -0.7063492 0.6811583 -0.3071409 -0.664596 0.2126831 -0.3712407 -0.9038508 0.5524641 -0.3915978 -0.7358224 0.9421603 -0.1905338 -0.2757372 0.8707993 -0.103652 -0.480588 0.4460455 -0.2004548 -0.8722736 0.4989066 -0.1595608 -0.8518407 0.8560447 -0.1201412 -0.5027462 0.268482 9.8692e-4 -0.9632842 0.3389902 -0.001056849 -0.9407894 0.9393109 0.001370847 -0.3430644 0.9134411 -0.0019719 -0.4069662 0.6394919 -0.001163721 -0.7687969 0.5957407 0.001285254 -0.8031758 0.04648882 0.9067711 0.4190523 0.627912 0.7254616 0.281837 0.8300112 0.5463531 0.1121595 0.9145768 0.2094484 -0.3459485 0.103461 0.87138 -0.4795756 0.4933106 0.7518991 -0.43737 0.8696132 0.3238946 -0.3726463 0.7933673 0.5646712 -0.2274091 0.4947565 0.8245397 0.2745 0.06180965 0.6647654 -0.7444908 0.03431046 0.7776061 -0.6278148 0.5693162 0.752467 -0.3311684 0.6126725 0.3244339 -0.7206769 0.2214457 0.3301521 -0.9175845 0.4609631 0.4969886 -0.7351976 0.4533677 0.4969708 -0.7399174 0.4213107 0.8341628 0.355907 0.4261561 0.9045894 0.01044166 0.07638406 0.631776 0.7713784 0.632439 0.4932635 0.5972538 0.4752149 0.5454756 0.6903821 0.4347711 0.566797 0.6997964 0.8175362 0.3578882 0.4511659 0.9262551 0.2550616 0.2774795 0.5752748 0.6074048 0.5478306 0.4134954 0.7042051 0.5771628 0.4827507 0.6918768 0.5368969 0.7622762 0.5039913 0.406113 0.9150096 0.3331799 0.227483 0.4114837 0.7864207 0.4606774 0.4179545 0.7853443 0.4566709 0.8530789 0.4510121 0.2623825 0.2640735 0.8837934 0.3862311 0.4147531 0.8486278 0.3283454 0.8431624 0.4743605 0.2530995 0.9479497 0.2878035 0.1362379 -0.3788344 0.7934456 0.4763701 0.4619245 0.8298051 -0.3131279 0.04251831 0.9261006 0.3748731 0.2641746 0.9614145 0.0767728 0.6550724 0.7305305 -0.1928876 0.2440298 0.9480646 0.2040169 0.05982315 0.8016161 0.5948385 0.1857603 0.9341352 0.3047697 -0.7569355 -0.3727686 0.536742 0.4736644 0.8631857 0.1747928 0.2745722 0.906751 0.3200199 0.3801015 0.7886834 0.4832196 0.05511456 0.8113014 0.5820245 0.1587793 0.7481095 0.6442991 0.1619352 0.8110486 0.5621184 0.4480037 0.6887025 0.5700715 0.4763587 0.7348224 0.4828234 0.7621718 0.6271318 0.1606234 0.5662726 0.5200408 0.6394474 0.8197224 0.5501397 0.159379 0.7637526 0.6051642 0.2246292 0.6714872 0.454609 0.5851799 0.4559195 0.4707981 0.7553056 0.8497896 0.4055355 0.3367472 0.6008365 0.3582496 0.7145997 0.9677358 0.1736178 0.1826039 0.2866543 0.1735308 0.942187 0.4481953 0.1821729 0.8751766 0.7278525 0.1277154 0.6737354 0.7520448 0.1300714 0.6461502 0.9698987 0.04227375 0.2398117 0.1649866 0.002453923 0.9862928 0.2782893 0.003420352 0.9604911 0.4238753 0.001608848 0.9057192 0.5881153 0.00221771 0.8087741 0.76139 -4.09721e-4 0.648294 0.931705 0.002297103 0.3632087 0.5372847 0.008210122 0.843361 0.2680116 0.9622943 0.04646891 -0.7895254 0.3923059 0.4719595 -0.7683035 0.4870702 0.4152979 -0.7366157 0.4988703 0.4566464 -0.7240411 0.5842904 0.3665642 0.374412 0.8145282 0.4431249 0.4201831 0.7932742 0.4406382 -0.8556852 0.1419993 0.4976336 -0.8175188 0.2821351 0.5020586 -0.7523224 0.338307 0.5652958 -0.613532 0.6044485 0.508154 -0.06505262 0.8315156 0.5516792 -0.01910424 0.8367598 0.5472368 0.1264278 0.8501476 0.5111411 0.1761286 0.8142092 0.5532108 0.4282379 0.7355682 0.5249302 0.4836645 0.7003532 0.5249515 0.5876135 0.5939836 0.5494487 0.6944599 0.5733686 0.4347111 0.7134883 0.4690906 0.5204694 0.6876831 0.4300584 0.5849289 0.7357224 0.3931691 0.5514804 0.8323996 0.2379931 0.5004701 0.8534018 0.154308 0.4978898 0.8225057 0.1285604 0.5540367 0.822657 0.08392524 0.5623095 -0.7603072 0.1650664 0.6282405 -0.3468413 0.6889132 0.6364744 -0.2998809 0.7367176 0.6060682 -0.226467 0.705231 0.671835 -0.210739 0.7162311 0.6652834 0.02457803 0.7748938 0.6316135 0.4721146 0.5756019 0.6676751 0.5163315 0.5572609 0.6502783 -0.4668663 0.5081277 0.7237694 -0.4478889 0.6168624 0.6472067 -0.344516 0.6150593 0.7092326 -0.1280071 0.6710702 0.7302595 0.1927541 0.6195043 0.7609602 0.1723285 0.6122382 0.7716652 0.6835504 0.2505124 0.6855672 -0.5104549 0.09702616 0.854413 -0.5039426 0.2308658 0.8323117 -0.3315677 0.2682089 0.9045037 -0.4232914 0.4474068 0.7878144 0.3361316 0.2717716 0.9017516 0.4357691 0.2984973 0.84912 0.4582285 0.1443037 0.8770421 0.4932308 0.1215666 0.8613622 -0.3402552 0.088903 0.9361211 -0.2958649 0.2289578 0.9273846 -0.1569803 0.2663054 0.9510198 0.02249568 0.4269804 0.903981 0.08723008 0.3801116 0.9208182 0.2434509 0.4520515 0.8581265 0.2108418 0.3327065 0.9191583 -0.1158438 0.2090371 0.971022 -0.01468729 0.2833297 0.9589101 0.2814117 0.1087932 0.9534 0.05257743 0.06138086 0.9967287 -0.4174603 2.95697e-4 0.9086951 -0.5696988 0.003269731 0.8218471 -0.8599206 0.001537442 0.5104254 -0.8458158 0.002213835 0.5334704 -0.8394174 0.1000232 0.5342038 -0.8433572 0.0967487 0.5285722 -0.4375912 0.1694165 0.8830697 -0.4082078 0.1647369 0.8979021 -0.02029848 0.9442222 0.3286829 -0.2413954 0.9652344 0.1002532 -0.01061856 0.8371148 0.5469243 -0.2349261 0.9299091 0.2829817 -0.2452738 0.9661625 -0.0798186 -0.1587879 0.8712702 0.4644078 -0.04255151 0.6390042 0.7680253 -0.4884691 0.869305 -0.07554292 -0.4242721 0.9048125 0.03616148 -0.3056029 0.8246634 0.4759593 -0.3292987 0.8308857 0.4485436 -0.2234104 0.6985938 0.6797459 -0.6558172 0.7452718 -0.120307 -0.61977 0.7255798 0.2990303 -0.4101154 0.6994308 0.585322 -0.379814 0.6557956 0.6524366 -0.4190835 0.01543533 -0.9078165 -0.8519596 0.4807831 -0.2073945 -0.7874047 0.5418148 0.293991 -0.5062043 0.4603837 0.729249 -0.8100939 0.5207431 0.2693966 -0.5274645 0.4980786 0.6882578 -0.5695222 0.4693849 0.6747757 -0.5228072 0.4552809 0.7206885 -0.8294446 0.327883 0.4522327 -0.8371789 0.3372043 0.4306098 -0.3914987 0.2558397 0.8838974 0.3967204 0.1182122 -0.9102959 0.9609872 0.1735597 -0.2153617 -0.9154245 0.1571822 -0.3705291 -0.2309727 0.1342295 -0.9636566 -0.2837176 0.1424584 -0.9482668 -0.6841009 0.2935457 -0.6677101 -0.7138436 0.2668033 -0.6474901 -0.8497495 0.2653056 -0.4555643 -0.3256314 0.3423293 -0.8813483 -0.4609539 0.3800088 -0.8019445 -0.5283302 0.4253728 -0.7347961 0.8148357 0.2425191 -0.5265239 0.8197554 0.214105 -0.5311875 0.5995693 0.5873069 -0.5436794 0.3050511 0.3150368 -0.8987189 0.2858876 0.7325066 -0.6178207 0.1845087 0.8086726 -0.5585743 0.069678 0.5037557 -0.8610315 -0.2342374 0.8686125 -0.4366293 -0.3121421 0.8453652 -0.4335032 -0.03777366 0.3817915 -0.9234762 -0.06905895 0.5025148 -0.861806 -0.1139398 0.5213389 -0.8457089 -0.5496187 0.7027048 -0.4518023 -0.6244258 0.6843142 -0.376572 -0.4324315 0.6226079 -0.652198 0.7715458 0.6359634 -0.01636075 0.708858 0.4476539 -0.5450928 0.7461209 0.371093 -0.5528053 0.7228603 0.331531 -0.6062675 0.7470127 0.26476 -0.6098148 0.6854032 0.4507387 -0.5718889 0.6799886 0.5636521 -0.4689477 0.3541712 0.1552897 -0.9221973 0.3409686 0.9208801 -0.1889978 0.4267492 0.7790207 -0.4593605 0.4575085 0.7018603 -0.5459655 0.2368988 0.1354978 -0.9620392 0.3416184 0.243228 -0.9078199 0.4554911 0.5116565 -0.728516 0.4289586 0.6050078 -0.6707907 0.3215915 0.7719776 -0.5482969 0.1509475 0.8791322 -0.4520416 0.2248199 0.8089376 -0.543209 0.101596 0.1366962 -0.9853895 0.1890351 0.3571186 -0.9147305 0.1796679 0.396895 -0.9001076 0.06674748 0.7715628 -0.6326419 0.01922166 0.8049824 -0.5929871 -0.1571391 0.8944731 -0.4185991 -0.2288385 0.8799288 -0.416363 -0.05917537 0.7161813 -0.695401 -0.479545 0.8773099 -0.01907849 -0.3844686 0.9229928 -0.0163778 0.04953569 0.2173633 -0.974833 0.0520718 0.3890159 -0.9197582 -0.3330754 0.7376291 -0.5873366 -0.3917831 0.740172 -0.5464901 -0.6380209 0.5739855 -0.5132933 -0.1471417 0.4074403 -0.9013 -0.7361128 0.3698117 -0.5669015 -0.7252765 0.4156543 -0.5488218 -0.3346393 0.4486266 -0.8287042 -0.1015096 0.2149586 -0.9713334 -0.03190952 0.7874023 -0.6156129 0.3981857 0.7968554 -0.4543893 -0.2407497 0.809435 -0.535588 0.1547291 0.8996397 -0.4082982 -0.02296096 0.7118488 -0.7019574 0.1721326 0.9823025 -0.07383936 0.2936509 0.9222732 -0.2513589 0.07115077 0.8050568 -0.5889152 0.3076672 0.9265978 0.2162342 0.2015571 0.7755045 -0.5983039 0.5250301 0.8479755 0.07267034 0.2084096 0.9214643 -0.3278247 0.4655839 0.8849753 0.007102012 0.3513667 0.7713339 -0.5306462 0.3791552 0.7649588 -0.5206528 0.6994442 0.7017039 0.1356077 0.6969958 0.6999468 -0.1557924 0.54179 0.7524865 -0.3744698 0.3125857 0.5766408 -0.7548348 0.8933929 0.4461328 -0.05305427 0.6609175 0.5214408 -0.5397107 0.7630157 0.5867392 -0.2711902 0.5578953 0.5460453 -0.6249698 0.4266876 0.4844847 -0.7636834 0.8453904 0.3349696 -0.4160655 0.3966731 0.3281925 -0.8572865 0.8492951 0.3398265 -0.4039995 0.852522 0.09390604 -0.5141869 0.835329 0.1072428 -0.5391887 0.542846 0.1635083 -0.8237617 0.4709039 0.1534675 -0.8687331 0.04802638 0.001685321 -0.9988447 0.4778912 0.00236684 -0.8784158 0.5218319 0.001565873 -0.853047 0.8198468 0.002448678 -0.5725778 0.8193893 0.002468526 -0.5732321 -0.09764778 0.994381 -0.04088222 -0.01874929 0.9988719 -0.04362761 0.6046143 0.7958956 -0.03149229 0.6662025 0.7451787 -0.029715 0.2083538 0.9559776 -0.2066288 0.147918 0.9699319 -0.1932675 -0.4613468 0.7834386 -0.4163929 -0.5240432 0.7441344 -0.4142977 -0.8196719 0.3658928 -0.44075 -0.8446981 0.3062191 -0.438993 0.8514831 0.03810721 -0.5229955 0.8174964 0.2860831 -0.4998561 0.7780175 0.3226701 -0.5390481 0.6437404 0.5790827 -0.5002616 0.6095553 0.6163627 -0.4985371 -0.519068 0.6519804 -0.5527116 -0.5612472 0.5997895 -0.5703106 -0.5600089 0.5902086 -0.5814153 -0.6200202 0.5628677 -0.5465849 -0.7354421 0.4229048 -0.5294113 -0.7598606 0.3776939 -0.5291117 -0.8747609 0.1439355 -0.4626834 0.7766689 0.1477195 -0.6123434 0.7483898 0.1543292 -0.6450543 0.4987502 0.573123 -0.6502141 0.4851005 0.6725385 -0.5589001 0.371971 0.6754887 -0.6366731 0.3602683 0.6665516 -0.6526222 0.3020603 0.7797349 -0.5484278 0.2203651 0.7646247 -0.6056306 0.170543 0.6881857 -0.7052061 0.1026346 0.7641367 -0.636837 -0.2144685 0.7526599 -0.6225001 -0.3099501 0.7876889 -0.532426 -0.3532298 0.7055331 -0.6143711 -0.7189168 0.173478 -0.6731002 -0.7252051 0.1569258 -0.6704117 0.5796992 0.3036493 -0.7561389 0.588665 0.3748264 -0.7162254 0.5447996 0.3960706 -0.7391357 0.006328105 0.6880215 -0.7256627 -0.006181836 0.652504 -0.7577601 -0.09435135 0.6350103 -0.7667201 -0.0540744 0.7000283 -0.7120649 -0.1747152 0.6909577 -0.7014642 -0.5941727 0.4078764 -0.6932501 -0.6028784 0.08180135 -0.7936285 0.4174488 0.1925693 -0.8880617 0.369264 0.3192119 -0.8727816 0.3904485 0.4293161 -0.814394 0.2325181 0.430467 -0.872143 -0.1401456 0.4540668 -0.8798764 -0.240424 0.4275723 -0.8714231 -0.2427163 0.4422554 -0.8634228 -0.2871769 0.2965218 -0.910826 0.4420949 0.08942788 -0.8924992 0.4082068 0.08791393 -0.9086465 0.1733065 0.2694652 -0.9472874 0.1251518 0.4661776 -0.8757942 -0.3409577 0.2162141 -0.9148767 -0.4221187 0.1885053 -0.8867251 -0.4120615 0.1715834 -0.8948546 0.03619951 0.2299643 -0.9725255 -0.05912464 0.2590957 -0.9640403 -0.1300696 0.1860983 -0.9738836 -0.2692641 0.1835244 -0.9454182 0.02227562 0.02247917 -0.9994991 -0.537518 0.001564323 -0.8432508 -0.6086677 0.003288269 -0.7934184 -0.8620882 9.44909e-4 -0.5067573 -0.9223909 0.00290817 -0.3862466 -0.3311699 0.1560073 -0.9305849 -0.5481669 0.1720099 -0.8184899 -0.7398962 0.1245021 -0.6610997 -0.8603697 0.1132895 -0.4969201 -0.9363155 0.05938667 -0.3461017 -0.09588271 0.9462715 -0.3088313 -0.3523948 0.9031726 0.2451473 -0.6214821 0.6884031 0.37398 -0.4922852 0.8633982 -0.1104485 -0.1567509 0.9230329 -0.3513392 -0.1191973 0.9540953 -0.2747619 -0.4099083 0.9120253 0.01360082 -0.4634172 0.8748494 -0.1410073 0.09570735 0.6761547 -0.7305169 -0.1746626 0.887685 -0.4260381 -0.4337457 0.8141291 -0.386081 -0.1726787 0.862984 -0.4748061 -0.1827711 0.7595286 -0.6242685 -0.09389901 0.9151616 -0.3919978 -0.3519692 0.6466851 -0.6766948 -0.3648204 0.6488568 -0.6677507 -0.5194528 0.755409 -0.3994072 -0.7239385 0.6699248 -0.1646627 -0.7119899 0.7003857 -0.05030071 -0.5786019 0.5719207 -0.5814865 -0.8234524 0.5662003 -0.03665399 -0.2378265 0.4373752 -0.8672609 -0.6616004 0.4634553 -0.5894864 -0.8121081 0.387946 -0.4358651 -0.8625873 0.4166005 -0.2870317 -0.9043182 0.3438421 -0.2529448 -0.4678982 0.3746007 -0.8004659 -0.8862343 0.304274 -0.3492939 0.9999104 0.002788305 0.01309913 0.334286 0.9417101 0.0378797 0.9645501 0.1692645 0.2024667 -0.4033753 0.1323203 0.9054169 -0.9567573 0.1727992 0.2339999 0.07089495 0.05628645 0.9958944 0.3799074 0.1946182 0.9043197 0.4620896 0.1691483 0.8705527 0.1955986 0.2001392 0.9600445 0.2391706 0.3234989 0.9155031 0.4570659 0.4024323 0.7931828 0.7949808 0.2829415 0.5366094 0.8482757 0.261835 0.4602944 0.8554611 0.2216994 0.4680128 -0.8249815 0.2501531 0.5067828 -0.6158063 0.6074362 0.5018008 -0.6293307 0.5747078 0.5231193 -0.3120881 0.3629262 0.8780009 -0.1208741 0.4668734 0.8760244 0.09163773 -0.1488211 0.984609 0.1746107 0.8313019 0.527682 0.0998221 0.4153873 0.9041509 0.1972085 0.6421315 0.7407943 0.307775 0.7012566 0.6430504 0.3557943 0.6537016 0.6678957 0.6641647 0.6762735 0.3186525 0.7075875 0.6312937 0.3174718 0.354523 0.6804758 0.6413004 0.4475597 0.6266831 0.637933 0.518018 0.6580638 0.5464516 0.5433585 0.647754 0.534019 -0.7925661 0.2459757 0.5579739 -0.7412286 0.3488717 0.5734708 -0.7268974 0.2672924 0.6325939 -0.6534904 0.3921834 0.6474121 -0.3341706 0.7778653 0.5322178 -0.5345528 0.404891 0.7418333 -0.5563147 0.3728325 0.7426372 -0.3720555 0.8535347 0.3647645 -0.4195086 0.7033415 0.5738669 -0.4592862 0.6976277 0.5498836 -0.2744779 0.141712 0.9510939 -0.3449733 0.3180562 0.8830819 -0.4549809 0.5677664 0.6860275 -0.3278669 0.8346803 0.4425066 -0.237553 0.8665123 0.4390047 0.1038312 0.9602827 0.2589909 0.03717303 0.9474059 0.3178681 -0.1208599 0.8544918 0.5052095 -0.1813935 0.8218334 0.5400798 0.2826973 0.9586245 0.03348714 0.2791334 0.9595581 0.03650712 -0.1235989 0.2005092 0.9718639 -0.1873968 0.3932688 0.9001234 -0.1829183 0.4638888 0.8668034 -0.09185832 0.8326815 0.5460804 -0.009080469 0.8349124 0.5503081 0.1717092 0.809173 0.5619207 0.05866998 0.6183884 0.7836794 -0.003392994 0.6437964 0.7651894 -0.04451471 0.322667 0.9454652 0.7620152 0.4482094 0.467377 0.8229756 0.4024236 0.400957 0.6250209 0.422793 0.6561975 0.6111451 0.4407407 0.6574567 0.1723864 0.2964144 0.9393729 0.04225885 0.1154235 0.9924171 0.006462275 -0.7221413 -0.6917155 -0.07971775 -0.8959636 -0.4369146 -0.1135059 -0.860466 -0.4967039 -0.07316672 -0.683297 -0.7264654 -0.03117072 -0.3468175 -0.9374145 -0.001049995 -0.1793912 -0.9837772 -0.03944921 -0.896434 -0.4414181 -0.02187442 -0.880978 -0.4726514 -0.05370277 -0.8223415 -0.5664544 -0.0380271 -0.7539832 -0.655792 -0.04453158 -0.6325289 -0.7732555 -0.02587461 -0.4994433 -0.8659601 -0.01629364 -0.5200073 -0.8540064 -0.03627043 -0.3313212 -0.9428206 0.04872846 -0.9211745 -0.386087 0.107576 -0.8741324 -0.4736243 0.03663408 -0.8866565 -0.4609753 0.04744452 -0.8970383 -0.4393988 0.03540068 -0.8068398 -0.5897088 0.02598619 -0.8145281 -0.579542 0.0533055 -0.7461471 -0.6636437 0.02121925 -0.6078547 -0.7937647 0.01343631 -0.3872687 -0.921869 0.05385369 -0.5272461 -0.8480044 0.03555023 -0.218837 -0.9751136 0.0183745 -0.2562975 -0.9664233 -0.008078932 -0.8731637 0.4873602 -0.05435472 -0.7445681 0.6653301 -0.0518279 -0.8187115 0.5718612 -0.09518224 -0.8683303 0.4867678 -0.05096447 -0.51603 0.855053 -0.006286025 -0.1598274 0.9871249 -0.03248041 -0.241922 0.969752 -0.01358556 -0.3875066 0.9217668 -0.02501195 -0.5819277 0.8128558 -0.04361087 -0.7289771 0.6831474 0.09824824 -0.9400614 0.3265453 0.06416797 -0.8889582 0.453471 0.04744619 -0.8785271 0.4753304 0.02691143 -0.8911114 0.452986 0.04909539 -0.8978359 0.4375847 0.03275269 -0.7475209 0.6634305 0.1294003 -0.6416233 0.7560259 0.04644703 -0.7704965 0.6357498 0.0306071 -0.58678 0.8091678 0.02564394 -0.5988108 0.8004799 0.01819652 -0.3766737 0.9261673 0.03258788 -0.4081591 0.912329 0.02409237 -0.1852689 0.9823925 0.01119869 -0.2220129 0.9749794 -0.02894556 -0.2311004 -0.9724993 0.005172014 -0.3526453 -0.9357428 -0.01481562 -0.4035467 -0.9148391 -7.58417e-4 -0.6387959 -0.7693759 -0.00905174 -0.6512411 -0.758817 -0.02617359 -0.7754129 -0.6309119 0.02652817 -0.8657783 -0.4997241 -0.02732074 -0.9184036 -0.3947004 -0.03653609 -0.974119 -0.2230638 -0.04869139 -0.2262391 0.9728541 0.02342516 -0.5248344 0.850882 -0.002300739 -0.4961683 0.8682232 -0.01427036 -0.7531088 0.6577413 -3.29521e-4 -0.7694109 0.6387541 -0.006472766 -0.9182332 0.3959873 0.00876826 -0.9333782 0.3587872 -0.02688962 -0.9764631 0.2140015 0.0356419 -0.9736285 -0.2253377 0.01488858 -0.914355 -0.4046398 -0.02732706 -0.8799633 -0.4742548 0.02874714 -0.7519636 -0.6585775 -0.01210606 -0.659932 -0.7512279 0.03063797 -0.5169454 -0.8554698 -0.01818645 -0.3776428 -0.9257727 0.03427779 -0.2388834 -0.9704431 0.04376423 -0.9683621 0.2456819 -0.007308065 -0.8693766 0.4940961 -0.02889776 -0.8508602 0.524597 0.0289067 -0.7442791 0.667243 0.008440315 -0.5424396 0.8400524 -0.03252983 -0.4871227 0.8727276 0.04593575 -0.2596731 0.9646035 -0.2518491 0.963868 -0.0867775 -0.9827935 0.176458 -0.05458456 -0.9321289 0.3615186 0.02097553 -0.707805 0.6398556 -0.2993274 -0.1190059 0.8442215 0.5226162 -0.09412395 0.9936146 0.06221562 -0.03567785 0.9659272 -0.2563427 -0.9686189 0.1904938 -0.1596541 -0.8390843 0.4361597 -0.3251187 -0.8567866 0.4335972 -0.2791238 -0.6389629 0.6233444 -0.4507417 -0.5962154 0.7180108 -0.3591486 -0.4425332 0.7113916 -0.5459729 -0.1911192 0.7816552 -0.5937075 -0.940837 0.2095136 -0.2663267 -0.2893235 0.6612933 -0.6920862 -0.06490141 0.7418918 -0.6673713 0.04710209 0.6753764 -0.7359675 -0.8609915 0.2522016 -0.4416875 -0.6599882 0.3844578 -0.6454516 -0.6836044 0.3920894 -0.6155899 -0.4678493 0.5513501 -0.6907461 -0.9571974 0.1503124 -0.2473447 -0.8118467 0.2227645 -0.5397045 -0.08183199 0.2888204 -0.9538797 -0.7020117 0.3020739 -0.6449271 -0.5458198 0.173654 -0.8197103 -0.391424 0.3453242 -0.8529586 -0.225489 0.2409611 -0.9439769 -0.0544483 0.352461 -0.9342412 -0.3970067 -0.002778112 -0.9178115 -0.3617604 6.01305e-4 -0.932271 -0.07094293 6.23609e-5 -0.9974805 -0.09479677 -0.002346813 -0.9954939 -0.6489541 0.008183062 -0.7607836 -0.7177764 -0.008622109 -0.6962203 -0.5407481 0.001345336 -0.8411835 -0.8726117 5.43077e-5 -0.4884145 -0.8484051 -0.002883493 -0.5293397 0.02447277 0.7848507 0.6192015 0.6478908 0.6603584 -0.3796895 0.8588423 0.4366188 -0.2678691 -0.02697169 0.9896791 -0.1407407 0.2628468 0.9575856 -0.1180743 0.2687535 0.9567089 -0.1117131 0.9795386 0.06963908 -0.1888237 0.898293 0.2355047 -0.3709544 0.6645296 0.3378267 -0.6665386 0.4945194 0.3400743 -0.7998751 0.3370139 0.4794258 -0.8102917 0.1076062 0.3564193 -0.9281089 0.8471367 0.254832 -0.4662834 0.7552409 0.3704071 -0.5407494 0.5989896 0.4100839 -0.6877809 0.2482106 0.4131699 -0.8761748 0.02883774 0.5864378 -0.8094807 0.2397254 0.7416405 -0.6264991 0.1995922 0.8016765 -0.5634518 0.4812369 0.713576 -0.5091369 0.464283 0.7312029 -0.4997836 0.6955341 0.5798377 -0.4242883 0.8355898 0.4870051 -0.2541965 0.9243613 0.3294504 -0.1924024 0.9703639 0.1880132 -0.1518052 0.07530647 -2.0923e-4 -0.9971604 0.03923511 -0.003919482 -0.9992223 0.2222878 0.003440499 -0.9749751 0.8804424 0.002832233 -0.4741447 0.7722815 -0.001253783 -0.6352793 0.7441228 0.002445161 -0.6680384 0.6037693 -9.57724e-4 -0.7971585 0.4055938 -0.002248764 -0.9140506 0.3912274 -6.86182e-4 -0.9202938 0.5620209 0.002330541 -0.8271197 0.9990887 0.02258002 -0.03621941 0.970809 0.2082911 0.1189317 0.884214 0.4502534 0.1242482 0.04581111 0.9786406 -0.2004094 0.09489619 0.9945573 0.04301762 0.3344546 0.9099659 0.2451571 0.09502089 0.9525482 0.2891763 0.06684249 0.9389308 0.3375517 0.9356496 0.2147391 0.2800838 0.7428795 0.5964157 0.3040041 0.4635475 0.6646915 0.5859258 0.3348606 0.7413892 0.5815587 0.04772758 0.7841334 0.6187543 0.8614284 0.3897579 0.325622 0.6253263 0.5163863 0.5850746 0.3551773 0.7521067 0.5551439 0.9371068 0.2140595 0.2756981 0.3763219 0.4080093 0.8318114 0.08670037 0.7080926 0.7007766 0.1032517 0.3797091 0.9193259 0.6809448 0.221877 0.6979144 0.5169221 0.3827064 0.7657201 0.3327007 0.3393911 0.8798431 0.06342756 0.4717888 0.8794272 0.9505745 0.1584821 0.2670047 0.8275945 0.1347116 0.5449221 0.7218783 0.2506002 0.6450514 0.7546176 -0.003563404 0.6561552 0.3563483 0.004664242 0.9343416 0.4733121 -0.01120597 0.8808236 0.2683565 9.28791e-4 0.9633193 0.07875233 -0.001706957 0.9968928 0.6419575 0.001330673 0.7667391 0.5418356 -0.004079699 0.8404746 0.7620043 -0.002472698 0.6475672 0.8749439 -1.40251e-4 0.4842244 -0.01998281 0.7195746 -0.6941276 -0.01739585 0.9179074 -0.396413 -0.05733495 0.8416114 -0.5370316 -0.5496 0.7647994 0.3361871 -0.5675705 0.6837576 0.4586278 -0.9807964 0.1574862 0.1150504 0.03005743 0.9992309 0.02517896 -0.07669395 0.9725737 0.2195867 -0.1010074 0.8520587 0.5136083 -0.02625674 0.6821917 0.7307018 -0.2934869 0.8548546 0.4278889 -0.06337678 0.4485552 0.8915053 -0.9300634 0.2182933 0.2955164 -0.9404252 0.1416694 0.3090796 -0.793933 0.2365893 0.5600857 -0.7455149 0.30652 0.5918219 -0.5045388 0.3419504 0.7927866 -0.398837 0.247644 0.8829504 -0.939575 0.2600567 0.2226417 -0.8078747 0.4416158 0.390274 -0.6592165 0.6342337 0.403957 -0.3795499 0.7105387 0.5925173 -0.6985244 0.4468614 0.5589085 -0.459059 0.4856788 0.7438958 -0.3008958 0.5679196 0.7661129 -0.9062625 0.3693509 0.2055928 -0.09263813 -0.004759311 0.9956885 -0.8805971 0.004019498 0.4738489 -0.7475413 -0.002468943 0.6642109 -0.7366616 -5.83876e-4 0.6762614 -0.3331534 0.00243324 0.9428695 -0.3492085 7.51546e-4 0.9370447 -0.6160228 0.002357423 0.7877249 -0.5812141 -2.20852e-4 0.8137506 -0.03738731 0.6359493 0.7708247 -0.01311862 0.8832321 0.4687524 -0.08070611 0.9386712 -0.3352354 0.08088874 0.9247499 0.37188 0.0268253 0.9980213 -0.05686807 0.07338368 0.9402776 -0.3324043 -0.001477599 0.9234331 0.3837564 0.01242154 0.9722885 0.2334541 0.005449414 0.9449579 0.3271467 -8.14905e-5 0.9242463 0.3817968 -0.02966552 0.9382549 0.3446704 0.0061329 0.9937896 0.1111062 -0.03418296 0.9873237 0.154995 0.00226587 0.5224512 0.8526662 0.001770257 0.6162372 0.7875586 -9.02963e-4 0.5751997 0.8180125 7.64013e-4 0.4682967 0.883571 3.77817e-6 0.4544044 0.8907955 7.54222e-4 0.3224967 0.9465703 9.489e-5 0.3324916 0.9431062 3.17954e-4 0.1830416 0.9831051 -1.78243e-4 0.1883778 0.9820966 -4.16168e-4 0.9251089 0.3797015 2.78064e-4 0.8728179 0.488046 -3.50538e-4 0.8656237 0.5006951 -3.57171e-4 0.7955549 0.6058813 3.12458e-4 0.8048236 0.5935141 1.00467e-4 0.7117748 0.7024077 -1.28673e-5 0.7100487 0.7041525 -3.55858e-4 0.6157941 0.7879071 -3.83606e-4 0.6151269 0.7884281 -1.79184e-4 0.4312919 -0.9022123 -0.001351356 0.5913119 -0.806442 4.34563e-4 0.5431897 -0.8396099 -1.37188e-4 0.4356364 -0.9001227 -0.001152515 0.3567684 -0.9341922 0.001428663 0.4578806 -0.8890126 9.48887e-4 0.3113263 -0.9503026 -5.40643e-5 0.1880137 -0.9821664 -9.08917e-4 0.1979762 -0.9802063 -0.001374661 0.9202653 -0.3912924 -7.31229e-5 0.9242051 -0.3818964 -0.003814995 0.9686056 -0.248573 0.02396982 0.9954618 -0.0920937 -0.007485866 0.9770952 -0.2126711 0.05550515 0.9917811 -0.1152799 -4.94109e-4 0.9686687 -0.248356 1.05147e-4 0.5699641 -0.8216696 5.65168e-5 0.6107581 -0.7918172 1.10191e-4 0.6098285 -0.7925334 2.68497e-4 0.6913519 -0.7225182 -0.001027226 0.711818 -0.7023634 -0.001106441 0.8166117 -0.5771864 2.71142e-4 0.79764 -0.6031339 2.15848e-4 0.8724124 -0.4887705 8.81636e-4 0.8660234 -0.5000027 -1.50618e-4 0.9254287 -0.3789218 0.001285672 0.9215071 -0.3883593 -0.2850399 0.9563314 -0.0646727 -0.5042511 0.8584821 0.09348469 -0.6359233 0.7709919 -0.03424996 -0.9196628 0.3926649 0.00589013 -0.9350345 0.3495914 0.05913007 -0.9948278 -0.07973337 -0.06293082 -0.9448004 -0.3146427 0.09139037 -0.8738964 -0.4828444 -0.05627024 -0.5899962 -0.8054416 0.05628806 -0.4576639 -0.8864233 -0.069265 -0.2055405 -0.9770725 0.05551844 0.03751814 -0.997752 -0.05552971 0.3012628 -0.9510276 0.06918942 0.4452992 -0.8936092 -0.05631297 0.7797036 -0.6236139 0.05628567 0.8780328 -0.4697918 -0.09140068 0.9670503 -0.2466861 0.06292694 0.9858794 0.1593369 -0.05151283 0.9639799 0.2609346 0.05153483 0.7442901 0.6633542 -0.07741767 0.6311357 0.771803 0.07738071 0.2187868 0.9743967 -0.05180138 0.1225693 0.9914472 0.04482531 -8.2311e-6 1.46126e-5 1 -9.66526e-6 -2.72237e-6 1 -8.50459e-6 -6.64888e-6 1 -1.01077e-6 -6.43978e-6 1 -2.36751e-6 -1.50838e-5 1 -6.54432e-6 -4.04514e-6 1 -2.08879e-5 -9.28213e-6 1 -6.92893e-6 2.48148e-6 1 -6.42936e-6 -1.06311e-6 1 -3.52157e-5 2.25911e-5 1 -2.00576e-5 3.65018e-5 1 -1.38134e-5 6.27941e-6 1 2.76119e-6 1.31036e-5 1 5.95925e-6 -1.62904e-6 1 -1.53491e-6 -3.19719e-6 1 4.74653e-5 3.53411e-6 1 4.30279e-6 8.96262e-6 1 1.88501e-5 6.71365e-5 1 -2.21339e-5 -5.90723e-5 1 -2.26392e-5 -5.89525e-5 1 1.2096e-5 7.04676e-6 1 -0.2187553 0.9740265 0.05846756 -0.3105089 0.9498541 -0.03689664 -0.7547171 0.6559987 0.008248567 -0.7661026 0.6418945 0.03253394 -0.9972455 0.06664854 -0.03254812 -0.9987841 0.0485996 -0.00827825 -0.8824974 -0.4688807 0.03673279 -0.8475394 -0.5296661 -0.03362715 -0.551356 -0.8342078 0.01020097 -0.5418926 -0.8401781 0.02128887 -0.1061494 -0.9941241 -0.02120858 -0.06345653 -0.9977579 0.02127122 0.3682332 -0.9295406 -0.01893889 0.4024476 -0.9153696 0.01159304 0.6993865 -0.7146528 -0.01140272 0.7453934 -0.6651508 0.04430508 0.9393571 -0.3371195 -0.06291782 0.9850556 -0.164182 0.0520544 0.995431 0.08004993 -0.05204904 0.9548512 0.2854183 0.08243542 0.7620943 0.638559 -0.1070262 0.6564202 0.7529602 0.04651296 0.2856502 0.9582757 0.01057034 0.2187374 0.9740315 -0.0584504 -3.51317e-5 -4.49651e-5 1 1.60326e-5 -1.46367e-5 1 2.00525e-5 -1.3336e-6 1 -1.31186e-5 -2.03397e-5 1 5.30124e-6 -6.56321e-7 1 1.21011e-5 1.61096e-5 1 -2.82269e-5 2.94088e-5 1 -1.7512e-5 -1.28591e-5 1 4.47452e-6 -5.28872e-6 1 -5.83273e-6 6.89407e-6 1 -2.15384e-5 5.35078e-6 1 -4.00086e-5 -3.4559e-5 1 3.0837e-5 -1.46714e-5 1 3.17734e-5 1.81775e-5 1 2.56064e-6 2.18547e-5 1 -1.39321e-6 -1.18908e-5 1 1.20113e-5 1.24872e-5 1 -1.05571e-5 1.80124e-5 1 -1.46469e-5 6.61509e-6 1 4.10844e-6 -1.85552e-6 1 1.23768e-5 9.23221e-6 1 1.19213e-5 -8.66234e-6 1 -0.05345952 0.9982972 0.02334117 -0.1765758 0.9813705 -0.07571667 -0.4773974 0.8758786 0.07020252 -0.6958746 0.7163259 -0.0513392 -0.7990072 0.5991364 0.05121445 -0.9294136 0.3622928 -0.07024484 -0.9949864 0.08001339 0.05999881 -0.9885147 -0.13279 -0.07214999 -0.9393429 -0.3371546 0.06294178 -0.7276821 -0.6839821 -0.05145156 -0.6994386 -0.7146196 -0.01021629 -0.3681346 -0.9292669 0.03066003 -0.2973082 -0.9542917 -0.03058296 0.09514236 -0.9954102 0.01032447 0.07448065 -0.9971699 -0.01023471 0.4544875 -0.8902292 0.03054875 0.5199462 -0.8536511 -0.03059071 0.8258196 -0.5637801 0.01319319 0.8334565 -0.5517827 0.02976876 0.9995108 -0.009600758 -0.02976578 0.9990604 0.03625929 0.023736 0.8480337 0.5294113 -0.02371555 0.822742 0.5676354 0.02976191 0.3795025 0.9247058 -0.02995145 0.3630494 0.9317271 -0.00893253 -6.51317e-6 1.13955e-5 1 1.00545e-4 8.38611e-5 1 6.6727e-5 1.39838e-4 1 4.79096e-5 8.26913e-5 1 -4.33329e-6 9.95694e-6 1 1.95807e-6 1.96804e-5 1 5.97629e-5 1.68596e-6 1 -6.75825e-6 1.23541e-5 1 -7.32383e-6 -5.40973e-6 1 6.07357e-6 -9.28141e-7 1 7.93641e-6 -2.39896e-5 1 -3.73006e-5 -1.69321e-5 1 -3.64438e-7 5.25512e-5 1 4.56436e-5 2.92923e-5 1 9.24354e-6 1.24739e-5 1 2.26694e-5 1.45541e-5 1 2.19988e-5 1.66403e-5 1 -1.08152e-5 -8.18083e-6 1 -6.59931e-6 -1.32464e-5 1 6.01196e-6 1.90991e-6 1 1.26371e-5 1.3492e-5 1 6.38672e-6 -1.23247e-6 1 -2.56616e-5 4.95203e-6 1 -2.7993e-5 -1.52835e-5 1 4.97208e-6 2.71464e-6 1 -0.1179689 0.991563 -0.05372273 -0.2444466 0.9676474 0.06248337 -0.7021347 0.7102871 -0.04999017 -0.7651414 0.6411399 0.05914658 -0.9645553 0.2562645 -0.06294083 -0.9954319 0.0800355 0.05205303 -0.9897119 -0.1372271 -0.04048401 -0.9397513 -0.3373206 0.05552029 -0.8147317 -0.5759361 -0.06715506 -0.6985797 -0.7139741 0.04719442 -0.4543931 -0.8902612 -0.03101277 -0.3681403 -0.9292482 0.03115373 -0.04705601 -0.9974266 -0.05409121 0.1058961 -0.9919105 0.06999737 0.5154457 -0.8553707 -0.05154323 0.5512089 -0.8343015 -0.01046603 0.8309686 -0.5554869 0.03042227 0.893247 -0.4434396 -0.07396668 0.9924115 -0.07488614 0.09752684 0.9824861 0.158772 -0.09753262 0.8692056 0.4908037 0.0599457 0.7635369 0.6433948 -0.0552662 0.5896922 0.8057155 0.05554968 0.3646401 0.9291316 -0.06125438 0.1804186 0.9825392 0.04545205 0 -6.2912e-6 1 1.28341e-5 -1.55861e-5 1 4.13126e-6 -4.14019e-5 1 3.72106e-5 -3.69381e-5 1 7.65772e-6 1.4397e-5 1 -1.5299e-6 -2.87632e-6 1 7.54775e-6 -8.3055e-6 1 2.34932e-6 -1.76271e-5 1 -4.35356e-5 -4.53789e-7 1 -4.72307e-5 -2.26695e-5 1 8.33094e-6 -3.34602e-5 1 1.81353e-6 1.40187e-5 1 7.37899e-6 1.4012e-5 1 3.55722e-6 1.89423e-6 1 0 0 1 -8.94975e-5 5.10334e-5 1 -3.38445e-5 8.95595e-5 1 1.57676e-5 -6.25412e-6 1 -9.75353e-7 -1.25069e-5 1 -2.57656e-5 7.64766e-6 1 -2.76457e-5 4.99071e-6 1 -2.59623e-7 -1.80168e-5 1 2.28745e-5 -6.4358e-6 1 1.19782e-5 5.47566e-6 1 -0.00176531 0.001144289 -0.9999979 2.43709e-4 4.4201e-5 -1 1.13004e-4 1.23791e-4 -1 -1.76175e-5 -3.25091e-5 -1 -0.01062828 -0.002216219 -0.9999411 -4.38121e-6 -4.38404e-6 -1 -2.66613e-6 1.91596e-6 -1 -4.39388e-7 -2.13849e-6 -1 8.43138e-5 -5.90337e-5 -1 -0.01022881 0.01318913 -0.9998607 -0.008919715 0.002555012 -0.9999569 -4.7051e-6 -5.05329e-6 -1 2.64083e-6 -4.95173e-6 -1 -5.25293e-7 -1.377e-6 -1 3.00535e-6 3.79642e-6 -1 1.65675e-6 -2.80063e-6 -1 0 1.52733e-5 -1 -0.0470609 -0.05155378 -0.9975607 -0.1765563 -0.2159588 -0.960307 -5.78588e-6 -5.78961e-6 -1 8.96926e-6 6.84616e-6 -1 7.16461e-6 5.94552e-6 -1 2.60495e-6 2.79772e-6 -1 1.06078e-5 4.06976e-5 -1 -8.5859e-6 -1.58433e-5 -1 -7.17326e-6 5.02248e-6 -1 1.46866e-5 1.95415e-4 -1 -2.8395e-6 2.10095e-4 -1 -5.93407e-5 1.32765e-4 -1 -9.09195e-4 0.001334249 -0.9999988 -0.02126634 -0.007749736 -0.9997438 -2.53264e-6 -8.35536e-7 -1 -2.17318e-5 0.002260923 -0.9999975 -9.17017e-5 1.4334e-4 -1 0.001791954 7.77191e-4 -0.9999981 0.004188895 -4.3029e-4 -0.9999911 -1.38302e-6 3.11014e-6 -1 -1.1769e-6 -1.21295e-6 -1 -4.00775e-6 2.3662e-6 -1 -3.12984e-6 1.26985e-6 -1 -6.54978e-6 3.793e-6 -1 -1.5509e-4 1.02601e-4 -1 1.67993e-5 1.48457e-4 -1 2.03681e-5 -1.71779e-5 -1 -1.80815e-4 1.14056e-4 -1 0.002170026 3.92853e-4 -0.9999975 0.002926886 0.006476759 -0.9999747 0.001071631 0.00142014 -0.9999984 6.32888e-4 -2.16337e-4 -0.9999998 2.66698e-4 0.005466282 -0.999985 0.001006007 0.00154531 -0.9999983 2.58239e-5 6.05992e-5 -1 -5.21664e-4 0.003243744 -0.9999946 0.02383321 0.02050668 -0.9995056 -2.80482e-4 0.003445148 -0.999994 0.003319263 7.70919e-4 -0.9999942 0.004475831 2.23134e-4 -0.99999 0.005163967 0.01360672 -0.999894 -0.001005411 8.35688e-4 -0.9999992 -0.001884698 0.004430472 -0.9999885 -0.002397716 8.51983e-4 -0.9999968 -0.002394556 7.44931e-4 -0.9999969 -0.00137794 0.00170958 -0.9999976 0.9973452 0.06754529 -0.02720814 0.9849257 0.1729329 0.003957688 0.9809362 0.193897 -0.0129643 0.9503844 0.3108302 -0.01241648 0.9552713 0.2957309 1.9449e-4 0.905124 0.4251472 -6.2926e-4 0.8943622 0.4468272 -0.02149051 0.8370527 0.5467168 -0.02105855 0.844308 0.5357423 -0.011155 0.7855518 0.6186599 -0.01297223 0.7787224 0.6273528 -0.004463315 0.6874548 0.7262123 -0.004660308 0.5673811 0.8234416 0.004762172 0.4848845 0.8745745 0.00254625 0.4817147 0.8763279 -4.17702e-4 0.3828081 0.9238276 -7.92618e-4 0.1299477 0.991375 0.01700431 0.09562492 0.9950827 -0.0258128 0.005743384 0.9996567 -0.02556264 -0.1358643 0.9906513 -0.0122869 -0.234204 0.972052 -0.01622509 -0.2473168 0.9689193 -0.005469858 -0.3630247 0.9317616 -0.005777537 -0.3756099 0.9266106 -0.01760816 -0.4671231 0.8840162 -0.01764261 -0.4701297 0.882378 -0.01967316 -0.5886697 0.8083077 0.01033294 -0.5955449 0.8030907 0.01927345 -0.667674 0.7442045 0.01926571 -0.6864227 0.7272011 -0.001618266 -0.7789292 0.6271101 0.001482367 -0.7856048 0.6186972 -0.006222486 -0.840304 0.5421082 -0.002837836 -0.8316652 0.5552119 0.008524 -0.9018785 0.4318693 0.01020783 -0.9030573 0.4294425 0.00815463 -0.9477401 0.3188373 0.01146227 -0.9559441 0.2933589 -0.01054805 -0.9828113 0.1844891 -0.006753504 -0.9807173 0.1953729 0.004806399 0.9999316 -7.86258e-4 0.0116682 0.995351 0.007638633 -0.09601002 -0.9995462 0.002502381 0.03001683 -0.9995689 0.01433283 -0.02562624 -0.9983978 0.00507903 -0.05635797 -0.9999164 0.001817286 -0.01279592 -0.02277588 3.48054e-4 0.9997406 8.67176e-7 8.42625e-7 -1 1.93e-7 0 -1 2.00365e-7 2.236e-6 -1 -1.83294e-6 3.20173e-6 -1 -2.7465e-6 1.04909e-6 -1 -1.02787e-6 8.33878e-7 -1 1.75029e-7 1.19771e-7 -1 -9.7114e-7 9.30065e-7 -1 -9.58206e-7 5.71575e-7 -1 -6.00866e-7 0 -1 1.91288e-6 1.69438e-6 -1 1.79448e-6 2.24769e-6 -1 7.25747e-7 5.19605e-7 -1 8.7103e-7 -1.98855e-7 -1 -5.20063e-7 2.66445e-7 -1 -8.7146e-7 0 -1 -1.85401e-6 1.35472e-6 -1 -1.87081e-6 2.3423e-6 -1 -2.51364e-6 -3.67315e-6 -1 8.14362e-7 -3.18588e-6 -1 -2.55932e-7 -4.44283e-7 -1 0 -2.42312e-7 -1 2.22204e-7 2.1894e-6 -1 0.1619992 0.9843301 -0.0696454 0.4153513 0.9039709 0.1015868 0.6619305 0.7450308 -0.08232259 0.8792474 0.4704144 0.07506215 0.9250203 0.3789478 -0.0271306 0.9867555 -0.1594613 0.02976304 0.9847309 -0.1735876 0.01312941 0.825302 -0.5638637 -0.03056645 0.744521 -0.663496 0.07390302 0.4956032 -0.8657054 -0.07022529 0.2196394 -0.9735488 0.06293809 0.0913282 -0.9948363 -0.04427117 -0.3120664 -0.9474783 0.06999522 -0.4536759 -0.8895246 -0.05407679 -0.7181572 -0.6951846 0.03112018 -0.798986 -0.5991587 -0.05128496 -0.9381256 -0.3363819 0.08226501 -0.9926011 -0.01804161 -0.1200731 -0.9560263 0.2675722 0.1200787 -0.7836256 0.6095243 -0.120046 -0.5994729 0.7944294 0.09754091 -0.2878782 0.955786 -0.05999344 -0.1059748 0.992834 0.05522716 5.51816e-7 -2.03614e-7 -1 0 -6.01439e-7 -1 -4.31892e-7 1.59363e-7 -1 -5.11872e-7 -2.43381e-7 -1 -1.20704e-7 0 -1 2.47562e-7 -6.63679e-7 -1 -5.44967e-7 3.20987e-7 -1 1.60265e-6 -1.38336e-6 -1 2.30615e-6 -3.87181e-7 -1 0 -2.53494e-7 -1 -3.68761e-7 4.5764e-7 -1 3.17236e-7 -1.4976e-6 -1 0 -1.40701e-6 -1 -4.63735e-7 -1.59731e-6 -1 -9.36489e-7 8.29523e-7 -1 2.56053e-7 6.67877e-7 -1 -1.86441e-7 0 -1 0 -2.65988e-7 -1 5.87813e-7 -1.29051e-7 -1 7.1721e-7 -8.30825e-7 -1 2.4892e-7 -6.60067e-7 -1 -0.06050032 0.9964141 -0.05914843 0.3912854 0.9176053 0.06997323 0.5767992 0.8102794 -0.1036822 0.7882285 0.6095854 0.08427113 0.9593144 0.2684988 -0.08731877 0.9906152 0.1206051 0.0643109 0.9161795 -0.3942537 -0.07196593 0.8769972 -0.478906 0.03904873 0.4822371 -0.876001 -0.008349835 0.493056 -0.8699582 0.008268117 -0.05202442 -0.9978827 -0.03903162 -0.09144872 -0.9957779 0.007959663 -0.5197976 -0.8530282 0.0464046 -0.621472 -0.7796046 -0.07739078 -0.8950259 -0.4437993 0.0443955 -0.9441893 -0.3233556 -0.06283062 -0.9966005 -0.004642128 0.08225625 -0.9530041 0.2854071 -0.1016169 -0.8459722 0.5286636 0.06961202 -0.6518813 0.7551482 -0.069296 -0.550955 0.8338329 0.03422397 -0.1061607 0.9943313 -0.00593543 8.78531e-7 1.18388e-6 -1 1.0566e-6 2.59475e-7 -1 4.97496e-7 -1.42994e-7 -1 -9.11569e-7 1.78614e-6 -1 -7.47948e-7 1.81085e-6 -1 0 -3.60905e-7 -1 4.88596e-7 -1.29805e-7 -1 -1.15366e-6 8.75801e-7 -1 5.74073e-7 4.65875e-7 -1 -1.39876e-7 -6.5587e-7 -1 1.16633e-6 -1.28099e-6 -1 1.81869e-6 4.18005e-6 -1 2.80235e-6 3.45558e-6 -1 3.3315e-7 -2.21104e-7 -1 1.97707e-7 0 -1 4.63727e-7 1.79472e-7 -1 0 -2.05835e-6 -1 1.79526e-6 -2.30725e-6 -1 2.16514e-6 -1.60135e-7 -1 3.23914e-7 1.08378e-6 -1 8.4848e-7 0 -1 2.63629e-7 -3.23294e-7 -1 -1.76895e-7 2.1693e-7 -1 3.11253e-7 9.00083e-7 -1 0.04697656 0.9978178 -0.04639917 0.4544909 0.8906863 -0.01077067 0.5376246 0.8386459 0.0873664 0.8137003 0.5751575 -0.08417743 0.9436646 0.3142362 0.1036959 0.9895484 0.1372163 -0.04433697 0.9664191 -0.2567481 -0.01071077 0.9443327 -0.3235173 0.05976748 0.7353443 -0.6757233 -0.05164051 0.621684 -0.7797694 0.07394939 0.3421126 -0.9370288 -0.07025718 0.05192023 -0.9966725 0.06283438 -0.04733294 -0.9986998 -0.01892709 -0.4687363 -0.8830828 0.02123898 -0.5061711 -0.8621705 -0.02127975 -0.8256093 -0.5639244 0.01893162 -0.8619669 -0.5055579 -0.03774017 -0.9833716 -0.1733566 0.05410885 -0.9954866 0.009535372 -0.09442168 -0.922219 0.3777736 0.08245646 -0.8247628 0.5630747 -0.05208909 -0.6632061 0.7466279 0.05200463 -0.491871 0.8667564 -0.08244001 -0.1083571 0.9883363 0.1070044 3.1627e-7 -7.64065e-7 -1 -1.04445e-6 -2.27987e-7 -1 -5.40115e-7 4.38657e-7 -1 2.77456e-6 -1.35381e-6 -1 2.859e-6 -2.41981e-6 -1 -3.45912e-7 8.95489e-7 -1 -5.44906e-7 4.9204e-7 -1 2.34563e-7 3.42315e-7 -1 2.09206e-7 -3.16305e-6 -1 5.98043e-7 2.26668e-6 -1 0 -6.51466e-7 -1 6.86733e-7 0 -1 1.87389e-7 2.03644e-7 -1 -3.41657e-7 -3.71293e-7 -1 -4.81767e-7 -2.39359e-7 -1 0 1.54853e-7 -1 -3.45834e-6 1.17039e-6 -1 -4.79145e-6 -5.96774e-6 -1 -1.57121e-6 2.87814e-7 -1 2.94646e-6 1.92935e-6 -1 5.50859e-7 3.78399e-6 -1 1.15259e-6 3.5826e-7 -1 1.34385e-7 2.29764e-7 -1 0 -5.3925e-7 -1 0.09505885 0.9943544 0.04714864 0.2719776 0.9599611 -0.06710326 0.5193216 0.8527714 0.05555254 0.6838829 0.7284679 -0.04048198 0.8247469 0.5631042 0.05202364 0.9114236 0.406625 -0.06295359 0.9986271 0.009575366 0.05149894 0.9977346 -0.06382924 -0.02125322 0.8752492 -0.4833025 0.01890963 0.839497 -0.5420497 -0.0377745 0.6194289 -0.7836353 0.04715311 0.4677938 -0.8812823 -0.0671612 0.1623625 -0.983525 0.07947874 -0.0518285 -0.9941834 -0.09440958 -0.4396362 -0.8932003 0.09440934 -0.6434304 -0.7584447 -0.1037248 -0.8503475 -0.516318 0.1016106 -0.9711823 -0.2155901 -0.1016162 -0.9934524 0.07495141 0.08622312 -0.9475215 0.3125581 -0.06715959 -0.7977581 0.5977178 0.07946991 -0.6746633 0.7348034 -0.06995224 -0.3265139 0.9441538 0.04429668 -0.2309873 0.9722231 -0.03777772 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 6.20659e-5 -5.65634e-4 -0.9999998 0 0 -1 -0.001275718 2.06198e-4 -0.9999992 -0.003984689 -3.15155e-4 -0.999992 -5.65209e-5 -5.92699e-4 -0.9999999 1.34741e-4 -5.53783e-4 -0.9999998 4.68096e-4 -5.26941e-4 -0.9999997 0.001187205 -4.86326e-4 -0.9999992 -2.98068e-4 -4.89192e-4 -0.9999998 -6.77379e-7 0 -1 0 0 -1 -3.36484e-4 4.22142e-4 -0.9999999 0 0 -1 -0.00161767 0.006462633 -0.9999778 -0.001935362 0.001056909 -0.9999976 -0.002592027 -4.73342e-4 -0.9999966 -0.002362966 0.005302906 -0.9999832 -2.64971e-4 -3.21998e-5 -1 0 0 -1 0.004141151 -0.002834737 -0.9999874 0 0 -1 2.5747e-4 -7.44506e-4 -0.9999997 0.002821683 -0.002114176 -0.9999938 0.008332073 -2.28907e-4 -0.9999653 0.004378676 7.71913e-4 -0.9999901 0.002449154 0.001672923 -0.9999956 -2.39633e-5 4.62643e-4 -1 9.86608e-4 8.22639e-4 -0.9999992 5.0839e-4 9.58132e-4 -0.9999995 0.00310117 9.48669e-4 -0.9999947 0 0 -1 -7.78325e-4 -4.16438e-4 -0.9999995 1.85341e-7 0 -1 -0.003731131 0.005506277 -0.999978 -0.003324627 0.006039202 -0.9999763 -4.08118e-4 -4.40099e-4 -0.9999998 -5.69046e-4 -3.88493e-4 -0.9999997 -1.16704e-6 5.73853e-7 -1 0 -1.6793e-7 -1 -3.5723e-4 5.11837e-4 -0.9999999 0 0 -1 -2.10297e-4 9.3285e-4 -0.9999995 -5.49292e-4 4.89355e-4 -0.9999997 0 0 -1 0.00185579 8.62112e-6 -0.9999984 0.001050829 5.21007e-4 -0.9999994 -2.58632e-4 0.002535521 -0.9999967 0.002970874 0.0048756 -0.9999837 3.5694e-4 0.003885447 -0.9999923 4.33282e-7 -8.28605e-7 -1 0 -1.30755e-7 -1 0 0 -1 0 0 -1 -6.03532e-4 4.32242e-4 -0.9999998 0.004323184 -0.001050412 -0.9999901 0 0 -1 0 0 -1 0.9999795 0.001906275 0.006108105 0.9999045 0.002466976 0.0135948 -0.9840623 0.1777492 0.005156159 -0.9831985 0.1825394 -2.67332e-5 -0.9480401 0.3181293 0.003724217 -0.9513508 0.3080735 -0.004740417 -0.9084972 0.4178875 -0.001702904 -0.9056833 0.4238975 -0.006972134 -0.8331861 0.5529618 -0.005859792 -0.8441121 0.5357154 -0.02200156 -0.7847577 0.6193829 -0.02280867 -0.7668458 0.6418285 0.001935005 -0.686739 0.7269036 8.35332e-4 -0.6670535 0.7446374 0.02355712 -0.5967522 0.8020682 0.0239439 -0.5727862 0.8197032 0.001628816 -0.5060876 0.8624718 0.004207193 -0.3548572 0.934849 0.01156914 -0.2462139 0.9691724 0.009142458 -0.2308995 0.972736 0.02168577 -0.1043689 0.9943146 0.02111315 -0.1518605 0.9883414 -0.01094192 -0.009321689 0.9998573 -0.01409298 0.007521688 0.9999717 4.93363e-7 0.1357778 0.9907392 4.46933e-4 0.1220537 0.9923896 -0.01630479 0.3535153 0.9354118 0.005609929 0.3434394 0.939173 -0.001869678 0.4834645 0.8753551 -0.003960013 0.4854634 0.8742547 -0.002020955 0.5962761 0.8027705 -0.003773033 0.5982738 0.8012893 -0.001987874 0.6707814 0.741636 -0.005317151 0.6751751 0.7376571 -7.10738e-4 0.7587234 0.6514129 -2.13665e-4 0.8432283 0.5374803 -0.008995234 0.8493979 0.5277501 0.001741528 0.9091566 0.4164383 0.003671705 0.9090122 0.4167512 0.003917992 0.9447496 0.3276492 0.009711146 0.9499226 0.3124738 -0.002652227 0.9827786 0.1847087 -0.005386054 0.9840499 0.1778777 0.002306103 -0.9999665 0.002808928 0.007694125 -0.9999362 0.001657605 0.01117008 -0.9965797 0.007002294 0.08234083 -0.9989809 0.01195096 0.0435242 -2.23661e-7 -2.82946e-7 1 -3.24723e-4 3.5743e-4 0.9999999 0 0 1 1.61298e-6 -1.65872e-7 1 7.07286e-7 -6.83549e-7 1 8.70355e-7 -7.93921e-7 1 -1.84744e-7 -2.5346e-7 1 6.92109e-7 3.63315e-7 1 -3.15448e-6 2.58022e-6 1 -2.9997e-6 2.94981e-6 1 -0.00172615 0.008409142 0.9999631 -0.004144966 0.004633069 0.9999807 -1.7748e-7 0 1 8.40263e-4 0.002395451 0.9999968 0.00570333 5.4467e-4 0.9999836 0.003869235 0.01082777 0.9999339 -1.59367e-7 3.15581e-7 1 -2.08966e-7 7.1805e-7 1 3.19695e-7 3.69709e-7 1 -3.89723e-4 3.19602e-4 1 -3.89307e-6 6.69949e-6 1 3.27534e-6 -1.85986e-6 1 2.99951e-6 -1.45724e-6 1 -7.81296e-4 0.001832246 0.999998 1.29292e-4 0.002915561 0.9999957 4.03324e-4 0.002934515 0.9999956 -3.23243e-4 0.002741396 0.9999963 1.45057e-5 -1.58983e-5 1 -8.87109e-6 8.60709e-6 1 -0.004940569 0.005665838 0.9999718 0.001153945 0.002219915 0.9999969 0.00453782 0.00270766 0.999986 0 0 1 0 0 1 6.35439e-5 3.86253e-4 0.9999999 0 0 1 3.0658e-4 3.43696e-4 1 -0.008029103 0.001371562 0.9999668 0.005324542 0.001836955 0.9999842 0.0019207 0.003779113 0.9999911 0.001692235 0.001692473 0.9999971 6.45311e-7 7.88715e-7 1 0 -5.00369e-7 1 -0.01066499 -0.002368688 0.9999403 -0.009286344 0.002733111 0.9999531 -0.008930265 -0.001752436 0.9999586 -0.001566946 0.001283943 0.9999979 0 0 1 -1.69286e-4 4.72336e-4 0.9999999 -9.5241e-6 5.9569e-4 1 2.95643e-5 5.63844e-4 0.9999999 1.88892e-7 2.54208e-7 1 3.8454e-7 4.50817e-7 1 -5.05455e-7 -7.83309e-7 1 2.2685e-4 4.16178e-4 0.9999998 4.00544e-4 2.99778e-4 0.9999999 1.85297e-7 -1.8938e-7 1 -6.33813e-7 7.02732e-7 1 0 2.80204e-7 1 3.99133e-7 -1.43574e-7 1 3.83168e-4 3.09976e-4 1 -0.006685018 0.004549801 0.9999673 -0.008415699 0.00413233 0.999956 -7.73626e-7 8.35189e-7 1 -0.003805816 -0.9996344 -0.02676904 0.999982 8.01933e-4 -0.005948543 0.9997661 0.02159661 0.001142144 0.99995 -0.00946021 -0.003265023 0.9999652 0.007196247 0.004226267 0.9999656 0.008216619 0.001180887 0.9999746 0.007094085 7.51223e-4 -0.9999807 0.006208717 2.72931e-4 -0.9999846 0.005509674 5.84109e-4 -0.9998921 0.01221585 -0.008159637 -0.9996926 0.01681131 0.01822328 -0.9998926 0.01257413 0.007529258 -0.01550638 -0.9998795 6.90223e-4 0.02835673 -0.9994537 -0.01697707 0.001998186 -0.9999585 0.008897006 -0.01892453 -0.999821 0 0 -1 0 0 -1 0 0 -1 0 0.051521 -0.9981322 0.03282636 -0.0514844 -0.9893217 0.1363522 0.07001256 -0.838267 0.5407466 -0.1036905 -0.7011458 0.705438 0.08422088 -0.467558 0.8799411 -0.06000703 -0.1641303 0.9846118 0.07216179 0.04850167 0.9962129 -0.06291532 0.2562459 0.9645619 0.04431498 0.5994143 0.7992113 -0.01148813 0.6527596 0.7574779 0.01334595 0.890731 0.454335 0.003700315 0.8951445 0.4457607 -0.03422254 0.9993599 0.0104174 0.04823547 0.9946494 -0.09135627 -0.04824048 0.9129037 -0.4053144 0.03423786 0.8673706 -0.4964838 -0.008302927 0.5189986 -0.8547347 0.008295118 0.5295379 -0.8482456 -0.03672641 0.02097696 -0.9991051 0.05972194 -0.07509595 -0.9953864 -0.05974984 -0.4951724 -0.8667377 0.01076686 -0.5558902 -0.8311859 0.04648137 -0.8481458 -0.5277199 -0.07743585 -0.9059315 -0.4162833 -1 1.69926e-6 1.88282e-6 -1 0 0 -1 0 0 -1 0 1.99597e-7 -1 0 2.06233e-7 -1 0 -1.65506e-7 -1 0 -1.93203e-7 -1 0 1.72559e-7 -1 -2.2523e-7 0 -1 -3.01464e-7 2.07109e-7 -1 -4.8419e-7 0 -1 0 -3.08803e-7 -1 0 0 -1 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.23834e-7 -2.17027e-6 -1 4.44264e-6 -6.12302e-7 -0.08422613 -0.9908161 0.1057801 0.1036913 -0.9159982 0.3875505 -0.04436033 -0.8334731 0.5507764 -0.01074892 -0.5558712 0.831199 0.08730578 -0.4699545 0.8783624 -0.070243 -0.1370081 0.9880763 0.06287592 0.1592266 0.9852377 -0.01892715 0.2567208 0.9663003 0.02367049 0.665137 0.7463461 0.04302686 0.6522156 0.7568115 -0.06777316 0.8930801 0.4447638 0.08621901 0.9718585 0.2192198 -0.08624154 0.9949249 -0.05183476 0.06774252 0.9554072 -0.287416 -0.04300409 0.770757 -0.6356762 -0.02371054 0.7816897 -0.6232168 0.02371603 0.3670205 -0.9299105 0.04304665 0.3821628 -0.9230918 -0.06774359 -0.004943609 -0.9976905 0.08624422 -0.2417807 -0.9664905 -0.08623933 -0.4942033 -0.8650583 0.08421123 -0.7044485 -0.7047417 -0.07396376 -0.9061683 -0.4163993 0.07396239 -0.9666173 -0.2453176 -1 0 0 -1 -1.82426e-7 0 -1 0 -2.3124e-7 -1 0 -1.91348e-7 -1 0 -2.43594e-7 -1 0 0 -1 0 -1.34305e-7 -1 -1.66079e-7 0 -1 1.51873e-7 0 -1 2.08357e-7 -1.66116e-7 -1 0 -1.44315e-7 -1 0 -2.29486e-7 -1 2.16045e-7 -2.59174e-7 -1 0 4.33392e-7 -1 0 4.19857e-7 -1 0 -2.46229e-7 -1 0 -2.09954e-7 -1 3.23949e-7 2.16439e-7 -1 1.72592e-7 0 -1 0 0 -1 -1.30196e-7 0 -1 -1.2904e-7 0 -1 3.69099e-7 1.45489e-7 0.9655939 -0.2589313 -0.02414357 0.9996839 0.02503591 0.002334415 1 0 0 1 0 0 0.9999937 7.00413e-4 -0.003494858 0.9999897 -0.003249943 -0.003166437 0.9999919 -1.20024e-5 -0.004025042 0.9999975 -0.002028703 -9.12043e-4 0.9999946 -0.002563595 -0.002107799 0.9994936 0.02503114 0.01964509 1 0 -1.50505e-7 1 0 0 1 -3.78597e-7 0 -1 0 1.99099e-7 -1 0 2.04284e-7 -1 0 2.13399e-7 -1 0 1.99923e-7 -1 0 1.57322e-7 -1 0 1.63425e-7 -1 0 0 -1 -2.26947e-7 0 -1 -2.29859e-7 0 -1 2.40453e-7 0 -1 2.05169e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.46516e-7 -1.87843e-7 -1 0 -2.21545e-7 -1 0 1.60655e-7 -1 1.2256e-7 1.32073e-7 -1 0 0 -1 -2.23037e-7 0 -1 -2.18393e-7 0 -1 -2.1472e-7 0 -1 -1.64645e-7 -1.77424e-7 -0.06000113 -0.9748032 0.2148451 0.0721516 -0.9062939 0.4164438 -0.06294792 -0.7994595 0.597413 0.04428178 -0.5180816 0.8541842 -0.01156723 -0.4594166 0.8881456 0.011541 -0.1166759 0.9931031 -0.04428553 -0.04908496 0.9978123 0.06999444 0.3519981 0.9333799 -0.05408525 0.4910353 0.8694592 0.03774237 0.763836 0.6443058 -0.01894885 0.8067572 0.5905791 0.0236923 0.9863666 0.1628484 0.04305082 0.9828864 0.1791112 -0.06774848 0.9742559 -0.2150246 0.06963872 0.9062482 -0.416971 -0.0552085 0.7632106 -0.6437867 0.0431376 0.6522042 -0.7568149 -0.05972689 0.3234804 -0.9443479 0.06430566 0.2042052 -0.9768137 -0.05629968 -0.2561061 -0.9650078 0.04821866 -0.3786484 -0.9242838 -0.03918927 -0.6315502 -0.774344 0.05999404 -0.7462198 -0.6629908 -0.0975359 -0.9269719 -0.3622291 0.09753328 -0.9859101 -0.135899 0.9999949 0 -0.003175854 1 0 0 1 -1.22337e-7 0 0.9999883 -0.003926157 0.002817809 1 1.84819e-5 3.46159e-5 1 0 -1.43473e-7 1 0 0 0.9999578 -0.008820593 0.002586185 0.9999892 -0.001029312 0.004520475 1 0 0 0.9991946 0.04012674 0 0.9963847 0.04001361 0.0749439 0.9999943 -0.003215789 0.001030623 -0.001100361 0.01667368 0.9998604 -3.03894e-5 0.007609188 0.999971 5.9219e-5 -8.21388e-4 0.9999997 -1.20891e-4 -7.34526e-4 0.9999997 0 -8.0122e-7 1 1.11048e-5 -1.32658e-7 1 7.8225e-6 -1.32033e-5 1 -3.51448e-6 -5.76166e-6 1 -1.07817e-6 5.65652e-7 1 0 0 1 6.15184e-4 -6.42117e-4 0.9999997 3.20567e-7 -1.56407e-6 1 2.92253e-7 -1.42593e-6 1 2.12049e-4 -7.54705e-4 0.9999997 -5.99354e-4 -5.95711e-4 0.9999997 -0.003150284 -3.25173e-4 0.9999949 -9.44507e-4 -4.81754e-4 0.9999995 0.002031147 -4.62184e-4 0.9999978 0.002407371 -4.3578e-4 0.9999971 1 0 2.11934e-6 1 0 1.03243e-6 1 0 -1.72625e-6 1 0 -1.6884e-6 -0.002180278 -6.04502e-5 -0.9999976 1.75044e-4 0.0308156 -0.9995251 -4.95881e-4 -7.24029e-4 -0.9999997 0.001183867 -4.68624e-4 -0.9999992 -1.84078e-4 -8.3074e-4 -0.9999997 -2.435e-5 -7.41029e-4 -0.9999998 3.82661e-4 -5.97066e-4 -0.9999998 0.002160608 -4.04655e-4 -0.9999976 -1.06718e-6 9.24253e-7 -1 -1.09191e-6 9.45669e-7 -1 0 -3.48039e-6 -1 8.05157e-6 1.06988e-5 -1 -8.55362e-6 1.57887e-5 -1 1.88513e-6 -5.74984e-5 -1 1.87389e-6 -5.75084e-5 -1 3.59022e-5 1.30619e-5 -1 -0.00166881 -5.49208e-4 -0.9999985 -0.001648783 -5.50572e-4 -0.9999985 -0.03282594 -0.9989716 0.03127586 0.09091377 -0.9952893 -0.0336737 0.5545222 -0.8314873 0.03367483 0.6531183 -0.7566097 -0.03127914 0.9263738 -0.3749302 0.03548121 0.9411619 -0.3377884 0.01064008 0.9955528 0.0800721 -0.04962873 0.9269046 0.3676401 0.07542216 0.7455701 0.6621467 -0.07541143 0.4649979 0.8820895 0.0754649 0.0544067 0.9959478 -0.07160919 -0.1627748 0.9858283 0.04058051 -0.5653322 0.8245383 -0.02315467 -0.6446223 0.7642451 0.01978451 -0.8703932 0.4915435 -0.02829682 -0.944863 0.3236978 0.04953479 -0.9978587 -0.04908961 -0.04322475 -0.9476825 -0.315595 0.04793369 -0.8748847 -0.4834342 -0.02946507 -0.5647462 -0.8245772 0.03367662 -0.4585506 -0.8881184 -0.0312612 0.9923331 0.1234644 -0.00562489 0.9733529 0.2292934 0.002955853 0.7153176 0.6987978 0.001512527 0.6616141 0.7498217 -0.005848467 0.1450345 0.9894114 0.005475401 0.0242986 0.9996897 -0.005476653 -0.4822568 0.8760163 0.004891395 -0.6091328 0.7930403 -0.006652712 -0.8625466 0.505937 0.006415486 -0.9580883 0.2864241 -0.005298733 -0.9985969 0.05286514 0.003076434 -0.9905181 -0.1373478 -0.003075838 -0.9303511 -0.3666316 0.005299925 -0.8002843 -0.5995706 -0.007750988 -0.5908304 -0.8067715 0.006268382 -0.3268442 -0.9450703 -0.003891289 -0.1756275 -0.9844489 0.003898978 0.09515154 -0.9954485 -0.005344867 0.3772597 -0.9260963 0.00456506 0.5421184 -0.8402917 -0.004194617 0.725376 -0.68834 0.004217028 0.8884682 -0.4589051 -0.00550723 0.9632092 -0.268694 0.005616962 0.2620077 -0.9648027 0.0225318 0.2459635 -0.9691999 0.01239186 0.6963214 -0.7176226 -0.01242756 0.7072571 -0.7069495 -0.00310719 0.9620471 -0.2722058 0.01921796 0.9834687 -0.1783557 -0.03128087 0.9794462 0.2004386 0.02256911 0.9442885 0.3284782 -0.02052575 0.8077034 0.5890501 0.02520644 0.7436411 0.6683385 -0.01793396 0.3000833 0.9538967 0.005586922 0.3388352 0.9404585 -0.02698969 -0.2197722 0.9742078 0.05118012 -0.4134611 0.9086671 -0.05808579 -0.7656984 0.6415702 0.04575836 -0.8542641 0.5187471 -0.03367996 -0.9982506 0.04859483 0.03367841 -0.9936496 -0.102787 -0.04577386 -0.8671656 -0.495385 0.05116254 -0.7078441 -0.7035421 -0.06312894 -0.388887 -0.9191217 0.06310552 -0.1622692 -0.9859406 -0.03987163 0.002564847 -0.9766119 -0.2149948 -0.04679185 -0.9510271 -0.3055455 0.0511586 -0.7433297 -0.666966 -0.05117774 -0.5671741 -0.8220064 0.04576712 -0.186677 -0.9813547 -0.03367906 -0.03624951 -0.9987751 0.02946835 0.4159534 -0.9089083 -0.05996882 0.5971714 -0.7998688 0.03140795 0.7535813 -0.6566041 0.00550723 0.9729002 -0.2311597 -0.07046151 0.9914146 -0.1101465 0.06615281 0.9512231 0.3013277 -0.05333113 0.7916499 0.6086429 0.0479331 0.5742844 0.8172515 -0.01792025 0.4407881 0.8974323 0.004340648 -0.04862564 0.9988077 0.01702558 -0.06668245 0.9976289 -0.01556956 -0.620646 0.7839363 0.03096324 -0.6783764 0.7340619 -0.04111212 -0.9453769 0.3233762 0.02088993 -0.9780532 0.2073056 -0.02089101 -0.9780551 -0.207296 0.05696403 -0.9341497 -0.3523061 -0.04954862 -0.6979336 -0.7144463 0.04162454 -0.5290628 -0.8475612 -0.04164719 -0.2044469 -0.9779913 0.04952919 0.009584844 -0.9987267 -0.04953157 0.4026445 -0.9140153 0.05443614 0.6130705 -0.7881506 -0.04415512 0.815519 -0.5770434 0.03874707 0.9654312 -0.2577621 -0.03875273 0.9961546 -0.0785771 0.05117559 0.9520584 0.3016052 -0.05116617 0.8553801 0.5154676 0.03873199 0.5991801 0.7996769 -0.03877133 0.4443641 0.8950069 0.05116593 0.07513886 0.9958595 -0.06311714 -0.1865109 0.9804233 0.06311398 -0.5437417 0.8368761 -0.05116051 -0.7432984 0.6670008 0.04680269 -0.9510323 0.3055276 -0.002567291 -0.9766209 0.2149535 -0.9999991 -2.09347e-4 -0.001295328 -0.9999998 -6.57045e-4 -3.35139e-4 -0.9999762 -0.006886124 4.56185e-4 -0.9999803 -0.00624603 5.73689e-4 -0.9999989 -9.34581e-4 -0.001048684 -1 0 0 -0.9999791 -0.005865931 0.002698957 -0.9999981 -0.001913547 -4.3164e-4 -0.9999991 -9.35596e-4 -0.001046717 -0.9999983 -0.001197457 0.001389503 -0.9999758 -0.006935119 3.76696e-4 -0.9999958 -0.002506315 0.001434624 -1 0 0 -0.9999787 -0.006467819 9.27457e-4 -0.9999983 -3.82063e-4 0.001827538 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999995 9.54112e-4 -6.15476e-4 -1 0 0 -0.9999236 -0.01219755 -0.002013802 -0.9999359 -0.01123088 -0.001519203 -0.9999958 0.001361966 -0.002545535 -0.9999024 0.008352994 0.01119816 -0.9999991 0.001266241 3.21366e-4 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999964 0.002542018 8.34568e-4 -0.9999967 0.002529799 3.48713e-4 -0.9999998 2.48066e-4 6.05531e-4 -0.9999955 0.001266121 -0.002757787 -0.9999991 0.001387655 6.6869e-5 -0.9999989 0.00149846 -4.92815e-5 -0.9999939 0.002096831 0.002788722 -0.9999989 0.001341938 -6.16642e-4 -0.9999991 0.001317679 2.15372e-4 -1 0 0 -0.9999451 0.003655135 -0.009820103 -0.9999997 1.54062e-4 7.73493e-4 -0.9999999 3.51124e-4 3.11962e-4 -0.9999949 -7.3067e-4 0.003072261 -0.9997324 -0.003355383 -0.02289128 -0.9999004 0.005335569 0.01306545 -0.9999764 -0.001818597 -0.006639659 -0.9999993 0.00104016 -4.40098e-4 -0.999997 0.001939535 -0.001543998 -0.9890073 -0.06112444 0.1346415 -0.9999874 -0.001046001 0.004906117 -0.9999932 -0.001163065 -0.003486096 -0.9999866 0.003066956 0.004174053 -0.9999312 0.007163524 0.009289681 -1 0 0 -0.9999993 0.00109291 -2.54535e-4 -0.9999986 0.001197159 0.001197636 -0.9997802 0.01095211 -0.01788318 -0.9999844 0.002235531 0.005125463 -0.02124685 -0.01182162 -0.9997044 -0.00749427 -0.007566034 -0.9999433 -0.0142495 -0.9997849 -0.01507359 -0.02834564 -0.999454 0.01697587 0 -1 0 0 -1 0 0 -1 0 0.02172797 -0.9997639 0 0.01643353 -0.9998644 -0.001060724 0.0367341 -0.9936794 -0.1060749 -0.03362214 -0.9839029 -0.1755124 0.01029276 -0.8226505 -0.5684543 0.05156958 -0.797204 -0.6015034 -0.06995081 -0.4680529 -0.8809276 0.07945823 -0.2977804 -0.9513218 -0.05550503 -0.004954397 -0.9984462 0.06924742 0.2606276 -0.9629529 -0.03423964 0.3822897 -0.923408 0.003696739 0.7473847 -0.6643813 0.04486584 0.7733524 -0.6323869 -0.04712831 0.9452503 -0.3229254 0.04712605 0.9827072 -0.1790691 -0.04484915 0.9835619 0.1749131 0.0271483 0.969037 0.2454186 -0.02975052 0.6985399 0.7149525 0.05916839 0.6411337 0.7651448 -0.06292885 0.2562524 0.9645593 0.07216036 0.04848718 0.9962137 -0.06000155 -0.1641256 0.9846129 0.09753215 -0.4936687 0.8641636 -0.07606703 -0.6637508 0.7440758 0.05056822 -0.9249473 0.3767165 -0.008284568 -0.9086374 0.4175038 1 3.14372e-6 2.06859e-6 1 3.24679e-6 1.2951e-6 1 -2.68869e-6 1.6212e-6 1 -1.88749e-6 3.30403e-6 1 1.36915e-6 8.40573e-7 1 0 0 1 -1.10793e-6 3.19968e-6 1 2.49286e-6 2.97504e-6 1 0 -3.57205e-6 1 0 2.49876e-6 1 3.91971e-6 9.92707e-7 1 1.25606e-6 -2.21924e-6 1 -1.14841e-6 2.02905e-6 1 -3.13702e-7 2.46784e-6 1 2.32047e-7 -1.82547e-6 1 6.6092e-6 -3.48964e-6 1 5.27662e-7 -7.35085e-6 1 1.5573e-6 -9.51847e-7 1 -2.18885e-6 1.33786e-6 1 2.95862e-6 5.21316e-6 1 2.93446e-6 5.33555e-6 1 2.90829e-6 5.33739e-6 1 -3.39547e-6 -6.23146e-6 1 -5.36687e-6 -3.53144e-6 0.06430113 -0.9948391 -0.07848924 -0.03359991 -0.9839071 -0.1754934 0.01028567 -0.8226237 -0.5684931 0.05149221 -0.7972203 -0.6014885 -0.07745212 -0.4433381 -0.893002 0.07743161 -0.2978271 -0.9514744 -0.051512 0.1593189 -0.9858824 0.05151093 0.2609015 -0.9639901 -0.07743394 0.6633002 -0.7443365 0.1070079 0.7885002 -0.605654 -0.09442704 0.9711297 -0.219068 0.07947719 0.9968177 -0.006144046 -0.07946574 0.9378222 0.3378975 0.04437685 0.8771492 0.4781631 0.01076161 0.6243891 0.7810393 -0.05976599 0.5668947 0.8216195 0.05974394 0.1592527 0.9854284 -0.06431466 0.03618133 0.9972735 0.06431216 -0.44374 0.8938449 -0.05974525 -0.5510106 0.8323567 0.0597462 -0.8549913 0.5151896 -0.06431031 -0.9118649 0.4054215 1 1.92222e-6 2.60664e-6 1 -5.02954e-6 -6.82034e-6 1 -5.27915e-6 -1.03481e-6 1 0 0 1 1.54599e-6 -6.16068e-6 1 3.38052e-6 -4.93244e-6 1 -6.54847e-7 -1.5286e-6 1 -1.54399e-6 -3.60411e-6 1 4.3067e-6 -4.0597e-6 1 0 0 1 -2.87876e-6 1.45112e-6 1 0 0 1 2.11076e-6 1.50835e-6 1 3.17593e-6 1.24661e-6 1 0 0 1 -3.13382e-6 -2.36441e-6 1 -2.76022e-6 -2.27675e-6 1 2.55634e-7 -3.74995e-6 1 0 0 1 -1.24881e-6 -1.88002e-7 1 -9.2225e-7 3.29528e-6 1 -4.78012e-6 1.45497e-6 -0.9999949 0 0.003175377 -1 0 0 -1 0 0 -1 0 1.23696e-6 -0.999985 -0.00442332 -0.003214061 -1 5.77134e-5 -9.99303e-5 -1 0 0 -0.9999583 0.00390762 -0.008261084 -0.9991948 0.04012137 0 -0.9967924 0.04002487 -0.06930273 -0.999994 -0.003215312 -0.001372337 -1 1.9216e-6 0 1 3.86522e-6 -1.63333e-6 1 3.6658e-6 -1.10284e-6 1 2.85758e-6 -1.36634e-6 1 3.01329e-6 -2.6272e-6 1 3.72741e-6 -2.73275e-6 1 2.91726e-6 -5.97687e-6 1 -1.66886e-6 -1.4707e-6 1 -2.31447e-6 -2.03965e-6 1 -1.76428e-6 -2.73287e-6 1 1.00441e-6 -1.64035e-6 1 0 0 1 0 0 1 -1.95398e-7 -2.32569e-6 1 -3.93901e-6 2.50324e-7 1 -2.83221e-6 1.21286e-6 1 -5.07342e-6 5.12464e-6 1 -4.19074e-6 5.79185e-6 1 1.20576e-6 3.01084e-6 1 0 0 1 0 0 1 -2.56594e-6 -2.08114e-6 1 -2.08988e-6 -3.34977e-6 1 4.26401e-6 6.83457e-6 1 7.28859e-6 1.17207e-6 0.0377922 -0.9972739 0.06337678 -0.05407083 -0.9561067 -0.2879869 0.06999003 -0.8999672 -0.4303029 -0.05911052 -0.6129098 -0.7879388 -0.04311275 -0.6024876 -0.796963 0.06773054 -0.2465968 -0.9667484 -0.1037042 0.01807916 -0.9944439 0.09441685 0.2600749 -0.9609612 -0.09441667 0.6179518 -0.7805261 0.05410188 0.7526401 -0.6562055 -0.03110414 0.9255872 -0.3772544 0.03111839 0.9571393 -0.2879514 -0.05408 0.9978227 0.03775388 0.04437124 0.9863433 0.158613 0.01068407 0.8488459 0.5285325 -0.05973458 0.8082098 0.5858573 0.05976098 0.4784395 0.8760846 -0.06430131 0.3663449 0.9282547 0.06431037 -0.1206439 0.9906105 -0.08729839 -0.2685001 0.9593157 0.07023078 -0.5847538 0.8081649 -0.06288063 -0.7966822 0.6011186 0.01893001 -0.8539705 0.519977 -0.01891922 -0.991083 0.131896 -0.9655928 -0.2589354 0.02414393 -0.999684 0.02503085 -0.002333939 -1 0 0 -0.9998833 -0.009071052 0.01229214 -0.9999977 -0.002028346 7.39927e-4 -0.9999901 2.30311e-4 0.004447102 -1 0 0 -0.9999565 -0.004261732 0.008294045 -0.99944 0.02502471 -0.02221721 -0.9996932 0.01853525 -0.01643121 -1 0 -1.02711e-6 -1 4.53147e-7 -8.11857e-7 0.004441022 -0.02283561 0.9997293 -2.01522e-4 0.03306597 0.9994531 0.001137375 -6.09355e-4 0.9999992 0 2.19381e-6 1 -2.04724e-4 -6.44721e-4 0.9999998 3.27187e-4 -7.67906e-4 0.9999997 1.83153e-4 -8.31546e-4 0.9999997 -0.002123117 -4.05215e-4 0.9999977 -6.2054e-6 -1.8219e-6 1 -1.64415e-7 -6.28924e-6 1 4.00198e-6 2.04857e-6 1 -4.06698e-6 3.4939e-6 1 -4.78421e-7 4.11007e-7 1 9.78649e-7 1.34001e-6 1 1.83854e-6 -1.51909e-6 1 0.001941919 -5.49309e-4 0.999998 -9.17747e-4 -5.00396e-4 0.9999995 -1 -5.39024e-7 -7.94983e-6 -1 0 4.23879e-6 -1 -5.08815e-7 -3.43708e-6 -1 -4.86381e-7 -3.74447e-6 0.001654863 0.01393181 -0.9999015 -6.02392e-5 -9.52694e-4 -0.9999995 -3.20384e-4 -7.09391e-4 -0.9999997 8.03685e-4 -5.61331e-4 -0.9999995 0.001757323 -4.81235e-4 -0.9999984 -7.2849e-6 3.77783e-6 -1 -5.8881e-5 -8.24896e-4 -0.9999997 1.96655e-4 -7.01772e-4 -0.9999998 2.4968e-5 -1.2948e-5 -1 1.34494e-5 1.71061e-5 -1 -8.21526e-6 4.02643e-5 -1 -1.31051e-5 -9.63311e-6 -1 6.99819e-6 -2.31814e-6 -1 1.27252e-6 5.62402e-6 -1 -5.61028e-7 -2.47952e-6 -1 2.22809e-6 8.02446e-7 -1 0 0 -1 -0.002350211 -4.61525e-4 -0.9999971 -0.001352965 -5.33779e-4 -0.9999989 0.0328232 -0.9982334 -0.04952496 0.2749956 -0.9599032 0.05443578 0.5642663 -0.8238688 -0.05332803 0.8165507 -0.573812 0.06312435 0.9468831 -0.3153232 -0.06311714 0.999059 0.004649579 0.04312115 0.945516 0.323907 -0.03291845 0.9091439 0.4163646 0.009891688 0.6447404 0.764321 -0.01110064 0.6363121 0.7714128 -0.005391538 0.2584069 0.9658759 0.01759892 0.2154679 0.9764949 -0.00560671 -0.2060721 0.9782348 -0.02431118 -0.3553811 0.9330312 0.05618762 -0.7332606 0.6776224 -0.05618554 -0.8308503 0.5559656 0.02429211 -0.9864244 0.1641203 0.005604982 -0.9950509 0.09431463 -0.03127837 -0.9282238 -0.3703269 0.03547656 -0.9023586 -0.4309509 -0.005511462 -0.554494 -0.8314962 -0.03391963 -0.4151699 -0.9075583 0.06302392 -0.9838931 -0.1787076 0.004234373 -0.9552841 -0.295648 -0.004953444 -0.6964283 -0.7176097 0.004891276 -0.6230003 -0.7822174 -0.002556324 -0.2419394 -0.970291 7.77222e-4 -0.2311411 -0.9729189 0.001613438 0.2579659 -0.9661524 -0.001800656 0.3308154 -0.9436825 0.004948914 0.7719461 -0.635649 -0.007039487 0.8908548 -0.4541931 0.009299814 0.9926362 -0.1208851 -0.007752835 0.9721083 0.2343527 0.009179294 0.8776296 0.4792816 -0.007438182 0.6330069 0.7741258 0.005629479 0.5285527 0.8488973 -0.002315938 0.1586084 0.9873412 7.94314e-4 0.147848 0.9890088 0.001613616 -0.3128651 0.9497961 -0.001613259 -0.3532906 0.9355123 0.00161314 -0.7363488 0.6766003 -0.00161302 -0.7437641 0.6684418 -7.83459e-4 -0.9449306 0.3272625 0.002329528 -0.9733499 0.2292901 -0.004003345 0.2418618 -0.9701454 0.01791095 0.3892043 -0.9199044 -0.04791456 0.6223946 -0.7815091 0.04322856 0.8803374 -0.4710086 -0.05618554 0.9535499 -0.2984898 0.04057765 0.9759957 0.214945 -0.03508716 0.972554 0.2315183 -0.02319699 0.7143489 0.6979154 0.05118352 0.5331641 0.8428773 -0.07275903 0.1748652 0.9831463 0.05334329 -0.1448284 0.9879583 -0.05443561 -0.3231712 0.9460567 0.02317488 -0.6643862 0.7473685 0.005599796 -0.733651 0.6779828 -0.04577612 -0.9233276 0.382247 0.03678733 -0.9949981 0.09431338 -0.03292113 -0.9990928 -0.03573459 0.02316474 -0.8758028 -0.4806032 -0.04461121 -0.7882367 -0.6131333 0.0524441 -0.3041823 -0.951846 -0.03824073 -0.2579456 -0.9661497 -0.00433743 0.0384944 -0.9513654 0.3056504 -0.01487815 -0.9191543 0.3936166 0.01702094 -0.5447571 0.8384211 -0.03822773 -0.4767344 0.8782158 0.0446214 0.04907673 0.9977978 -0.05994552 0.2880146 0.955748 0.02945542 0.4833618 0.8749249 -0.03370261 0.8245395 0.5647998 0.0175687 0.8761199 0.4817731 -0.00541234 0.9972147 0.07438844 -0.01111388 0.9979255 0.06341195 0.01111042 0.9197852 -0.3922649 -0.01112073 0.9021193 -0.4313434 0.01240885 0.5896049 -0.8075966 -0.0155676 0.551926 -0.8337478 0.01418673 0.03576141 -0.9992596 -0.0234754 -0.03624558 -0.9990671 0.02465671 -0.3824235 -0.9236582 -0.03513598 -0.5420384 -0.8396189 0.0291239 -0.7471666 -0.6639984 -0.02570587 -0.8768748 -0.4800311 0.03168284 -0.9556677 -0.2927376 -0.03198945 -0.9973781 -0.06491398 0.03039562 -0.9991148 -0.02908504 -0.03788149 -0.981292 0.1887621 0.03030544 -0.8969792 0.4410328 -0.0288943 -0.7640618 0.6444959 0.03140968 -0.6314988 0.7747403 -0.05116683 -0.323655 0.9447907 0.05116969 -0.09425044 0.9942327 -0.04577541 0.3156199 0.9477809 0.01923269 0.4309012 0.9021942 -0.00191158 0.8009807 0.5986871 -0.05511462 0.8565185 0.5131652 0.04294431 0.969421 0.2416169 -0.02699404 0.9658042 -0.2578638 0.03062736 0.9818573 -0.1871317 -0.03982919 0.7815753 -0.6225382 0.0631197 0.6127702 -0.7877364 -0.06311488 0.2689766 -0.9610766 0.06311786 -0.01813018 -0.9978414 -0.05333429 -0.3665982 -0.9288494 0.03647869 -0.59961 -0.7994605 -0.02118718 -0.7712593 -0.6361684 0.02117574 -0.8778138 -0.4785336 -0.0306192 -0.9579207 -0.2853951 0.9999698 -0.007323384 -0.002638578 1 -1.59622e-6 0 0.9998645 -0.003789067 -0.01602166 0.9999938 0.003508269 -5.01845e-4 0.9999779 0.002230763 0.006256282 0.9999947 -0.001855015 -0.002688586 0.9999238 -0.01043796 0.006590068 0.9998801 -0.01510488 0.003407359 0.9999703 -0.007668137 -6.9892e-4 1 2.39129e-4 -3.61228e-4 0.9999853 -1.99847e-4 -0.005438566 0.9999876 -0.001249074 -0.004824459 1 1.83301e-6 1.28616e-7 1 -1.79302e-6 3.23134e-6 1 -2.02985e-6 3.08646e-6 0.9999965 0.002622544 4.66305e-4 0.9999953 0.002289652 -0.002036809 0.9999991 0.001162767 8.03571e-4 0.9999991 0.001392304 -3.05164e-4 1 -8.57932e-6 1.88035e-6 1 1.46637e-6 5.2436e-7 1 -1.78488e-6 0 0.9999981 -0.001761019 -8.5933e-4 1 1.71882e-6 6.14635e-7 0.9999941 0.00339055 -6.90039e-4 0.9999969 0.00177282 -0.00178039 0.9999919 9.17087e-5 -0.004017531 0.9999839 0.003536105 0.004447221 0.9999992 0.001182854 -5.23137e-4 0.9882668 0.05490058 0.1425296 0.9983471 -0.02332395 -0.0525251 0.9999704 -0.001953184 -0.007443785 0.9999938 0.003507435 -4.65025e-4 0.9999897 0.004188776 0.00176084 0.9999997 6.96217e-4 -5.25315e-4 0.9999123 -0.001747906 0.01312625 0.9999929 -6.4246e-4 0.003730297 0.9999976 0.001333773 0.001716494 0.9999057 0.005921363 -0.01238787 0.9999977 0.002041041 6.13217e-4 0.9999638 0.002142012 -0.008234679 0.9999985 0.0017066 3.04434e-4 0.9999963 -0.001681983 0.002122461 0.9999829 -1.04016e-4 0.005842745 0.9999853 -5.99207e-4 0.005369603 0.9999191 0.003045558 -0.01235616 0.999969 0.003047168 -0.007264137 0.9999967 0.001445353 0.002128958 0.9999967 0.002464771 6.85236e-4 0.9999992 -0.001156449 3.95088e-4 0.9999989 0.00148046 1.86346e-4 0.9999933 0.003028452 0.002092659 0.9999783 0.001618206 0.006384015 1 0 0 1 -1.40151e-6 9.13592e-7 0.9999951 -0.003107488 -5.50388e-5 0.9968534 -0.07804358 -0.01388025 0.9999966 -0.001138448 0.002357244 0.9999997 -6.04339e-4 5.37222e-4 0.9999943 -0.003370583 -1.27532e-4 0.9999976 -0.002044379 8.3328e-4 1 -2.31577e-6 9.13509e-7 1 1.75642e-6 3.58765e-6 1 1.45862e-6 3.69589e-6 1 3.79924e-6 1.2045e-6 0.9999516 -0.009375154 -0.002972245 -1.8029e-4 -7.89663e-4 -0.9999997 0 0 -1 3.85341e-4 -3.30229e-4 -0.9999999 4.39008e-4 -2.89421e-4 -0.9999999 -1.26175e-4 0.001289308 -0.9999992 6.68592e-4 -0.002867758 -0.9999957 6.20668e-4 0.002710402 -0.9999961 -0.004502892 0.999987 0.002422213 -0.002758443 0.9999955 -0.001195192 2.55053e-4 -0.003926694 0.9999923 9.61908e-4 -6.40125e-4 0.9999994 -0.003399908 -4.24912e-4 0.9999942 0.001246929 1.52243e-4 0.9999992 -6.9285e-4 -6.03949e-4 0.9999995 0 -7.19961e-5 1 1.90143e-4 0 1 0.004192113 0.9999902 -0.001421749 0.002735435 0.999995 0.001564383 0.003291606 -0.00807023 -0.999962 0.00426197 -0.007748484 -0.9999609 0.05337369 0.9982685 -0.02472096 -0.1887868 0.9815759 0.02946722 -0.3372951 0.9411075 -0.02342396 -0.6675259 0.7439298 0.03126448 -0.7723237 0.6333631 -0.04865372 -0.9849966 0.1565999 0.07251352 -0.9947276 -0.07252335 -0.07250636 -0.8409512 -0.5395177 0.04149478 -0.7281055 -0.6845039 -0.03628832 -0.4930443 -0.8692384 0.03649562 -0.2455401 -0.967921 -0.05328202 0.07852029 -0.9954848 0.05333566 0.3392748 -0.9399785 -0.03651082 0.5511886 -0.834113 0.02113538 0.6992015 -0.7146095 -0.02122229 0.8309421 -0.5555997 0.02905654 0.9408326 -0.3376245 -0.0290479 0.9903014 -0.1373115 0.02118444 0.9964104 0.08015155 -0.02724099 0.9572116 0.286144 0.04321593 0.7993054 0.5993688 -0.04321885 0.6569009 0.7534833 0.02727895 0.4784918 0.8778378 -0.02112692 0.285548 0.9578743 0.03064417 0.002548217 0.999752 -0.02212136 -0.2188743 0.9746006 0.04740887 -0.4638373 0.8847584 -0.0453602 -0.7657009 0.6415668 0.04576176 -0.8399372 0.5423436 -0.01921337 -0.9979549 0.06384664 0.003101766 -0.9987399 0.04863154 0.01239401 -0.8765953 -0.4810324 -0.0137304 -0.8827985 -0.4691817 -0.02313762 -0.5154785 -0.8553714 0.05120307 -0.3302445 -0.9421066 -0.05808377 0.04720753 -0.9983901 0.03144633 0.2057476 -0.9783917 -0.02043491 0.454482 -0.8905194 0.02052479 0.5906453 -0.8063188 -0.03143692 0.8327646 -0.5512583 0.05116087 0.93842 -0.3416868 -0.05116617 0.9967273 0.06662291 0.04578191 0.981661 0.1896635 -0.0192191 0.7647092 0.6443682 0.003080487 0.754665 0.6559923 0.01245069 0.3787966 0.9254285 -0.009760618 0.3106992 0.9502691 0.02132719 -0.3525918 0.9349743 0.03875523 -0.4401539 0.8976866 -0.02057474 -0.8256606 0.5641642 0.001842081 -0.8480435 0.5294074 0.02345681 -0.9794042 0.200398 -0.02465718 -0.9991605 0.0210157 0.03516656 -0.9442601 -0.3256328 -0.04833239 -0.8825566 -0.4690691 0.03268128 -0.5684919 -0.8226559 0.007355213 -0.4602299 -0.8859102 -0.05789309 -0.1753978 -0.9835487 0.04321575 0.2009511 -0.9783493 -0.04951179 0.4332434 -0.8996291 0.05447381 0.6566382 -0.7533693 -0.03550881 0.8973565 -0.4407307 0.02253252 0.8900641 -0.4556665 0.01240044 0.9999389 -0.004930257 -0.009897768 0.9949968 0.09432888 0.03291726 0.9233302 0.3822391 -0.03680622 0.7541199 0.6555926 0.03875064 0.6445123 0.7641174 -0.02699297 0.2786794 0.9598503 0.03201937 0.1622822 0.9862677 -0.03066849 -0.2216461 0.9724577 0.07210499 -0.4396307 0.8967068 -0.05139726 -0.8544501 0.5188319 0.02699136 -0.8490239 0.5280298 0.0185166 -0.9945461 -0.1029 -0.01702493 -0.9926564 -0.1208904 -0.004343569 -0.7521007 -0.6586926 0.02164953 -0.7090592 -0.7047498 -0.0237199 -0.1364954 -0.9906394 0.001674115 -0.1507201 -0.9885404 -0.008444905 0.3267188 -0.9449582 0.01757335 0.3921613 -0.9196956 -0.01922762 0.7748764 -0.6321099 0.001932382 0.8000931 -0.5994146 0.02351844 0.9588884 -0.2827115 -0.0246452 0.9902215 -0.1373072 0.0246613 0.9759634 0.216667 -0.02347075 0.9664768 0.2567467 -0.001938521 0.7572581 0.6528704 0.01790249 0.667491 0.7437398 -0.03615117 0.4161292 0.9085528 0.03698962 0.1621057 0.9853629 -0.05274277 0.01329743 -0.01498585 0.9997993 -0.01096367 -0.00685352 0.9999164 -0.01018488 -0.006471574 0.9999272 0.003901302 -0.01022213 0.9999402 0.06173062 -2.71035e-4 0.9980928 0.09666705 -0.9945186 -0.0398522 0.5201917 -0.8536119 0.02733498 0.5078336 -0.8612856 0.01709705 0.9293881 -0.368637 -0.01856422 0.9252456 -0.3784079 -0.02698558 0.9826587 0.1782228 0.05117034 0.9253992 0.3745162 -0.05808645 0.6734889 0.7377785 0.04577791 0.5545027 0.8315004 -0.03367578 0.06057465 0.997451 0.0377112 -0.006719529 0.9999687 -0.004183292 -0.4212297 0.906658 -0.02316939 -0.5543064 0.831269 0.04167115 -0.8069846 0.5891017 -0.04165464 -0.8879687 0.4593188 0.0231927 -0.9967889 0.07987809 0.005610525 -0.9987869 -0.01815754 -0.0457707 -0.9187529 -0.3923535 0.0441786 -0.799461 -0.5996116 -0.03644496 -0.6111575 -0.7909807 0.02891296 -0.4523369 -0.8912712 -0.03204625 -0.1195033 -0.9914623 0.05216616 0.2356582 -0.9709188 -0.04221379 0.4750573 -0.8787307 0.04639869 0.7810865 -0.6243321 -0.01065093 0.8049494 -0.5922816 -0.03548038 0.9814884 -0.1896042 0.0270316 0.9958396 -0.08971089 -0.01598352 0.9530484 0.3027699 0.005401968 0.949596 0.3132784 0.0111345 0.6874168 0.7261577 -0.01237767 0.6533995 0.7568532 0.01557481 0.1364883 0.9905195 -0.01555919 0.09093451 0.9957795 0.01241421 -0.3682801 0.9296622 -0.009892225 -0.4313808 0.9019526 0.01979935 -0.718339 0.6951163 -0.02832698 -0.8159846 0.5769094 0.0366699 -0.9880504 0.1509901 -0.03095704 -0.9943905 0.1057264 -0.003096044 -0.919537 -0.3925337 0.01921546 -0.8897558 -0.4560967 -0.01761865 -0.6201328 -0.7844789 0.005313634 -0.588984 -0.8077439 0.025451 -0.2156097 -0.9759829 -0.03114002 -0.02055823 -0.9991003 0.03709226 0.150637 -0.9885765 0.004995942 0.1626508 -0.9866057 0.01241707 0.6329564 -0.7740885 -0.01237922 0.644674 -0.7644512 -0.003126204 0.9355239 -0.3527421 0.01918065 0.9711307 -0.2341158 -0.0457732 0.9826648 0.1781924 0.05116134 0.9017949 0.427529 -0.06312656 0.6953688 0.716672 0.05332642 0.4816088 0.8756271 -0.03647226 0.2011294 0.9788932 0.03626185 0.01855415 0.9989666 -0.0414924 -0.40561 0.9121357 0.05906808 -0.6291909 0.7752948 -0.05510747 -0.7974737 0.6028497 0.02465748 -0.9654346 0.2592087 -0.02732789 -0.968791 0.2471039 -0.01958531 -0.9717312 -0.2313292 0.0471726 -0.8768826 -0.4760025 -0.06707119 -0.7574452 -0.6524896 0.02311575 -0.417456 -0.9086877 0.00413829 -0.3801862 -0.9246689 -0.02111756 0.4905018 -0.8707809 -0.03389418 0.5545476 -0.8319133 0.01993173 0.9643899 -0.2636289 -0.02126157 0.960983 -0.2749087 -0.0306096 0.978165 0.2039721 0.03985518 0.9246523 0.378722 -0.03984701 0.6638781 0.7473708 0.02651238 0.6740942 0.7384495 0.01701205 0.1089903 0.9938967 -0.01704257 0.1223439 0.9921345 -0.02647638 -0.3265869 0.9443272 0.03983974 -0.5386097 0.840187 -0.0631296 -0.7802281 0.6240085 0.04309952 -0.9391208 0.3420054 -0.03293234 -0.9758607 0.2171621 0.02316522 -0.9811899 -0.1895321 -0.03665858 -0.9171966 -0.3946977 0.05444353 -0.7455062 -0.6643623 -0.05332165 -0.4950571 -0.8672801 0.05238109 -0.1929433 -0.9797667 -0.0531978 0.006261765 -0.9994294 0.03319215 1.62951e-4 -1.09639e-4 1 1.58978e-4 -1.09802e-4 1 1.93662e-5 -6.91627e-5 1 0.006790995 6.18232e-5 0.999977 -1.84725e-5 -1.09313e-5 1 -3.66164e-6 -8.50566e-6 1 9.62898e-6 1.508e-5 1 1.8775e-6 2.08635e-6 1 8.66076e-4 0.002873361 0.9999955 0.001779079 0.00164473 0.999997 4.78328e-7 -3.54888e-6 1 9.27039e-5 -1.15014e-4 1 2.52417e-4 -6.70626e-5 1 0.004346311 5.91524e-4 0.9999905 1.09449e-4 -1.14011e-4 1 -4.68628e-4 -4.041e-4 0.9999998 1.54463e-5 7.04445e-5 1 2.7699e-6 1.6944e-5 1 8.24175e-4 0.007718622 0.9999699 1.5901e-5 2.56965e-6 1 8.54068e-6 8.99969e-7 1 -6.94526e-6 -7.46129e-6 1 -1.86128e-4 -5.00271e-4 0.9999999 -4.67802e-4 -3.86501e-4 0.9999998 4.42755e-6 -5.02565e-6 1 -2.42739e-6 -2.6974e-6 1 -2.05987e-5 -1.59489e-5 1 -1.0687e-5 1.40561e-5 1 -6.79159e-6 8.93262e-6 1 1.22116e-5 6.14592e-6 1 1.22185e-5 6.15605e-6 1 -9.54491e-5 -4.36572e-4 1 0.005370497 0.008119165 0.9999526 8.68747e-4 0.006178259 0.9999806 -4.48801e-4 -3.40341e-4 0.9999998 7.13176e-5 -6.21337e-4 0.9999998 -4.89509e-4 -3.79011e-4 0.9999998 -0.001986861 -3.33821e-4 0.999998 -0.007334947 -1.44785e-4 0.9999731 7.0897e-6 -6.40863e-6 1 0.001498997 9.40206e-4 0.9999985 0.001399755 0.00114876 0.9999983 0.001253306 7.95195e-4 0.9999989 -6.3068e-4 0.006635963 0.9999778 -9.52497e-6 -8.67155e-6 1 -5.82159e-5 -4.82834e-5 1 4.36027e-6 -4.42221e-6 1 1.40236e-5 -1.38684e-5 1 -0.003890573 0.001425802 0.9999914 -0.002203047 0.002251148 0.999995 7.81448e-4 0.005886435 0.9999823 -0.004442334 0.01117622 0.9999276 -2.89476e-6 6.21174e-6 1 -2.53805e-6 6.02261e-6 1 -0.002449691 0.001303195 0.9999961 0.001725673 0.005688428 0.9999824 -0.002551853 0.005161225 0.9999835 -0.01139563 0.001124083 0.9999344 -9.37887e-5 0.002309143 0.9999973 -0.001974225 0.001681983 0.9999967 -0.002302169 0.001784086 0.9999957 3.05663e-7 -3.28899e-6 1 -5.55378e-7 -2.47308e-6 1 0 0 -1 0 -1 0 0.01609718 -0.9937551 -0.1104158 0.01714968 -0.9997657 0.01320803 0.01534456 -0.9997441 0.01662325 0 -1 0 0 -1 0 0 -1 0 0 -4.72831e-5 -1 -1.25432e-4 0 -1 7.80683e-4 -0.005780994 -0.999983 -3.27161e-6 5.28675e-7 -1 -1.23746e-4 1.55484e-6 -1 -1.3193e-4 4.41327e-6 -1 -2.64956e-5 -1.01916e-5 -1 1.4066e-5 -1.7391e-7 -1 1.56967e-5 -1.23647e-5 -1 -1.27316e-5 -1.73529e-6 -1 2.16609e-6 1.49035e-5 -1 0 0 -1 -6.79326e-7 5.84927e-7 -1 0 1.18776e-6 -1 0 -5.33748e-6 -1 -1.0991e-5 -5.87261e-6 -1 -3.63516e-7 7.35174e-6 -1 1.30391e-5 -6.6405e-6 -1 -5.98138e-6 -1.11125e-5 -1 -2.13758e-6 6.944e-6 -1 2.76215e-5 -7.71925e-6 -1 -5.31455e-6 -1.26911e-5 -1 -3.13238e-7 2.33146e-6 -1 -3.88958e-7 2.42273e-6 -1 -1.8671e-5 -1.27012e-5 -1 -9.6883e-6 -2.40346e-5 -1 -8.37717e-6 -2.04834e-5 -1 -3.38109e-5 0 -1 -3.14217e-5 2.1589e-6 -1 -1.95607e-5 1.28772e-5 -1 -1.97628e-5 1.24127e-5 -1 -1.14134e-5 4.00582e-6 -1 -1.28383e-5 3.55248e-6 -1 -1.37572e-5 1.24316e-5 -1 2.27641e-6 8.74721e-7 -1 -2.80125e-6 -5.62551e-6 -1 -2.13181e-6 -6.84362e-6 -1 4.97578e-6 -2.00947e-6 -1 2.32206e-6 4.95046e-7 -1 5.15085e-6 5.70589e-6 -1 6.44016e-6 4.88663e-6 -1 -3.00265e-6 -2.27833e-6 -1 -1.64799e-6 -4.21464e-6 -1 2.71115e-6 -4.10715e-6 -1 1.88452e-6 1.78934e-6 -1 3.92641e-6 7.65694e-7 -1 2.51701e-6 -1.86896e-6 -1 1.08192e-6 6.21401e-7 -1 -5.6767e-6 -3.26041e-6 -1 -5.25171e-6 -6.10735e-6 -1 3.89672e-6 -6.18721e-6 -1 3.4835e-6 3.04291e-6 -1 0 0 1 -5.73296e-5 -4.91304e-5 1 -1.39741e-4 -0.002637505 0.9999965 0.002298116 -0.00112158 0.9999967 -5.8843e-4 -3.94426e-4 0.9999998 -0.002948403 -4.8025e-4 0.9999955 7.11527e-4 -5.48874e-4 0.9999997 -1.10063e-5 2.07123e-5 1 -1.12108e-5 1.80225e-5 1 -5.54122e-6 1.715e-5 1 -1.47598e-5 -3.34823e-6 1 -5.25477e-6 -9.14256e-6 1 -7.38098e-6 -2.01488e-5 1 9.16991e-5 7.52138e-5 1 1.01619e-4 3.7521e-5 1 -6.70802e-6 4.49071e-6 1 -4.57248e-6 -2.45905e-6 1 0 3.14897e-6 1 -1.09536e-5 1.12176e-5 1 -1.11821e-5 1.63266e-5 1 5.86298e-6 1.96375e-5 1 2.4706e-5 -1.26758e-5 1 9.25303e-6 -1.90066e-5 1 0 0 1 -2.50029e-5 -2.39786e-5 1 -2.49093e-5 -2.4516e-5 1 -3.77152e-5 -2.72591e-5 1 -3.83313e-5 -2.57505e-5 1 9.69061e-6 2.76869e-6 1 3.50174e-6 9.06256e-6 1 5.34799e-6 1.15957e-5 1 -1.32507e-5 1.3949e-5 1 -8.96908e-6 6.83998e-5 1 -1.63376e-4 5.06791e-5 1 1.23168e-6 5.89489e-6 1 1.94452e-6 9.30658e-6 1 -4.32736e-5 -1.24827e-5 1 -4.06325e-5 -1.59192e-5 1 4.12099e-6 5.96329e-5 1 4.00053e-5 2.23475e-5 1 1.71179e-5 5.26189e-6 1 1.40052e-7 1.62149e-5 1 8.19532e-6 -4.48233e-6 1 1.87122e-5 3.53697e-7 1 -7.83042e-6 1.51063e-5 1 -1.34076e-5 -1.87386e-5 1 1.30083e-5 -1.10066e-5 1 -1.37054e-5 6.54585e-6 1 -1.96963e-5 -9.36943e-6 1 1.02847e-5 -5.94431e-6 1 9.26121e-6 -1.95562e-5 1 -1.93833e-5 -1.92609e-5 1 -3.4206e-6 6.02712e-6 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.01658087 -0.9996609 0.02008193 -0.01539623 -0.9997425 0.01667928 0.1014096 -0.9887602 -0.1098604 -0.01619571 -0.9998353 -0.008181929 0 -1 0 -0.03708952 -0.999294 0.005989015 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0.1165056 -0.9928346 0.026569 0.07133233 -0.9971798 -0.02333056 0.0424776 -0.9988005 -0.02435517 0.9531017 -0.3025127 -0.009117722 0.1027032 -0.9947116 -9.82501e-4 0.01850396 -0.9995887 0.02190923 0.1165114 -0.9926606 -0.03240382 -0.08245843 -0.9963306 0.02293312 0.3364801 -0.941011 0.03577136 1 -3.4359e-7 -1.44907e-7 1 0 0 1 0 2.67373e-7 1 -2.53678e-7 3.20419e-7 1 0 5.98907e-7 1 4.2145e-7 -3.55943e-7 1 -2.32498e-7 -4.72344e-7 1 -1.66284e-7 3.08617e-7 1 0 1.75581e-7 1 0 1.97887e-7 1 0 -1.83541e-7 1 3.96355e-7 0 1 5.19247e-7 -2.68641e-7 1 2.32356e-7 -3.48417e-7 1 -1.58377e-7 0 1 0 0 1 0 0 1 0 0 1 0 -4.68144e-7 1 -4.84247e-7 -2.5732e-7 1 -3.78443e-7 -1.21586e-7 1.16814e-5 -2.86754e-5 -1 -1.18146e-5 -6.62247e-5 -1 -2.29995e-5 -5.58077e-5 -1 2.2315e-5 -2.42322e-5 -1 2.24977e-5 -4.36681e-6 -1 -2.24815e-6 7.8662e-6 -1 -1.26176e-6 -2.81377e-6 -1 6.16599e-5 -1.62288e-5 -1 7.29761e-5 -1.50072e-5 -1 -9.83676e-7 4.97432e-6 -1 -2.75169e-6 6.27806e-7 -1 1.09403e-6 2.72295e-6 -1 1.74821e-6 1.72197e-7 -1 9.23257e-7 -2.71549e-6 -1 7.848e-6 3.0134e-6 -1 -1.13651e-4 -3.53667e-5 -1 -9.33864e-5 -3.77904e-5 -1 -3.7904e-5 -5.17574e-5 -1 -4.2649e-5 -1.40889e-5 1 9.72082e-6 6.59439e-6 1 -4.79947e-5 6.6663e-6 1 -1.47545e-5 2.84474e-5 1 -9.77771e-6 1.02846e-5 1 6.72766e-7 -3.1026e-5 1 3.4023e-5 -6.54595e-5 1 -8.30095e-6 -2.40022e-5 1 4.51077e-6 1.18893e-5 1 -5.60462e-7 -1.47724e-6 1 1.78253e-7 -3.73078e-6 1 -2.01603e-5 -1.91389e-5 1 -7.59357e-5 -1.05294e-5 1 1.01798e-4 -4.47341e-5 1 3.66953e-5 -6.3796e-5 1 -1.111e-5 1.49748e-6 1 1.78724e-4 -3.53542e-5 1 1 0 4.92852e-7 1 0 -2.11938e-6 1 -6.35924e-7 1.67614e-6 1 -2.04609e-7 7.599e-6 1 0 0 1 -1.22355e-7 -2.55419e-7 1 -5.40844e-7 2.2122e-7 1 0 3.0557e-7 1 0 0 1 3.95906e-7 -1.99137e-7 1 0 -1.16414e-6 1 -6.50454e-7 -4.02507e-7 1 0 0 1 0 0 1 -3.56507e-7 0 1 -3.93235e-7 0 1 -3.60054e-7 0 1 0 0 1 0 0 1 2.54466e-7 0 1 1.20861e-7 -5.48435e-7 1 -4.4367e-7 -1.49841e-7 1 2.39552e-7 5.66182e-7 1 3.06967e-7 0 1 0 0 1 0 0 0.007126569 -0.9999124 -0.01115566 -1 -4.00861e-6 -3.21283e-7 -1 -2.92458e-6 -3.56935e-6 -1 3.07089e-6 -3.47802e-6 -1 -1.24356e-6 1.40843e-6 -1 -2.39507e-6 -3.59118e-6 -1 0 -3.53872e-6 -1 -1.07251e-6 -9.06611e-7 -1 0 0 -1 3.38646e-6 -1.96473e-6 -1 2.1256e-6 -3.86055e-6 -1 -3.44015e-6 9.18499e-7 -1 -4.14278e-6 -8.00354e-7 -1 -3.67567e-6 -9.16119e-7 -1 -3.00351e-6 -2.24495e-6 -1 -5.7859e-7 2.94438e-6 -1 1.41604e-6 2.96481e-6 -1 9.68213e-7 4.92549e-6 -1 -2.98247e-7 3.14616e-6 -1 -4.34745e-7 3.23795e-6 -1 4.84959e-7 -3.61195e-6 -1 3.60759e-6 -1.77381e-6 -1 3.8731e-6 -1.79562e-6 -1 3.19269e-6 3.99048e-6 -1.16055e-5 -6.27066e-7 -1 1.04635e-5 -2.35171e-5 -1 2.98675e-5 -1.66337e-5 -1 4.76929e-5 -1.46758e-5 -1 1.77286e-6 -5.45536e-7 -1 -5.18079e-6 -5.60995e-6 -1 1.88008e-5 1.02397e-5 -1 -4.79397e-6 1.23228e-5 -1 3.59407e-7 1.70228e-6 -1 0 0 -1 -1.05179e-6 -5.89147e-7 -1 -5.56379e-5 -5.6171e-5 -1 0 0 -1 -1.7824e-5 -7.50246e-5 -1 -3.40237e-5 -6.0933e-5 -1 -1.51138e-4 -3.58629e-5 -1 -1.80557e-4 -3.27952e-5 -1 4.6605e-5 -5.08087e-5 1 -2.10858e-5 -2.35208e-5 1 -1.99737e-5 -4.9613e-6 1 -1.60378e-7 -7.40705e-6 1 1.0766e-5 -5.29802e-6 1 9.13801e-6 9.43004e-6 1 7.27626e-5 -3.58069e-5 1 2.43713e-4 -1.8295e-5 1 1.55579e-5 -6.4527e-5 1 2.43084e-5 -5.69146e-5 1 -5.57338e-6 -3.17857e-5 1 -5.56404e-5 -1.55325e-5 1 -6.5219e-5 -1.44985e-5 1 -3.45327e-5 8.08596e-5 1 -9.69379e-6 2.60154e-5 1 3.04352e-5 1.95269e-5 1 -8.84254e-6 -5.67326e-6 1 -8.9497e-6 -4.88751e-6 1 -1 0 -4.23878e-6 -1 -2.28312e-7 8.82331e-7 -1 0 3.46789e-6 -1 -2.25079e-7 3.78829e-7 -1 -1.47466e-6 1.54963e-6 -1 -1.75122e-6 1.1606e-6 -1 0 0 -1 -6.47884e-7 -3.02536e-6 -1 1.29487e-6 -2.83984e-6 -1 0 0 -1 -1.77367e-6 -1.88504e-6 -1 -1.26809e-6 -2.29912e-6 -1 0 0 -1 0 0 -1 4.73192e-7 1.83701e-6 -1 -3.75922e-6 1.34919e-6 -1 -4.16262e-6 -2.04897e-6 -1 -3.08878e-6 -2.5192e-6 -1 -3.85755e-6 0 -1 -5.11259e-6 -1.66911e-6 -1 0 -3.86149e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 5.34039e-7 -1.64872e-6 -1 1.34443e-6 -1.41278e-6 -0.9999973 -5.33311e-4 -0.002268552 -0.9999629 -4.14812e-6 0.008610427 -0.9999752 -4.65145e-6 -0.007044196 -0.9999995 -5.14637e-4 -9.40292e-4 -0.999985 -3.00644e-6 -0.00547409 -0.9999991 -3.3381e-4 0.001292109 -0.99999 -3.56615e-7 0.004478693 -0.9999998 -3.28461e-4 5.54614e-4 0.9999525 -0.002231538 0.009486019 0.9993498 -1.73512e-5 -0.03605556 0.9995647 -5.75037e-6 0.02950495 0.9999904 -0.002151787 0.003799319 0.9999735 -4.00238e-6 0.007286131 0.9999983 -4.44996e-4 -0.001719295 0.9999823 4.99537e-7 -0.005961239 0.9999996 -4.37824e-4 -7.30735e-4 -1 -2.27921e-7 -2.66203e-6 -1 0 0 -1 -2.04008e-7 3.86968e-7 -1 3.02144e-7 -1.47049e-6 -1 0 -8.5593e-7 -1 -3.49859e-7 3.51027e-7 -1 -1.74052e-6 2.70111e-6 -1 -1.77692e-7 -3.22732e-7 -1 1.25665e-7 -1.36827e-6 0.01627874 -0.9357222 0.3523621 -0.01847082 -0.8555064 0.5174627 0.0127604 -0.6643393 0.7473222 -0.009306073 -0.4967265 0.8678573 0.01196372 -0.2972426 0.954727 -0.01898646 -0.09144037 0.9956296 0.0247001 0.3100588 0.9503965 -0.01783132 0.4822362 0.8758598 0.01017302 0.8079279 0.5891935 -0.01445794 0.8775625 0.4792443 0.01615732 0.9795818 0.2003954 -0.02011609 0.9883258 -0.1510214 0.008439838 0.9621863 -0.2722615 -0.001908123 0.6874479 -0.7262312 0.001905143 0.6963906 -0.7176604 -0.008977413 0.2012591 -0.9794969 0.01656013 0.1089483 -0.9939094 -0.01655721 -0.4338511 -0.9008325 0.02439773 -0.5635184 -0.8257432 -0.02284115 -0.8750556 -0.4834831 0.02007967 -0.9777321 -0.2088938 -0.009304523 -0.9984747 -0.05442357 1 -1.16373e-6 1.33625e-6 1 -3.12043e-7 -1.05498e-6 1 2.53311e-7 -1.62008e-6 1 1.11656e-6 -3.41335e-6 1 8.48161e-7 -2.99289e-6 1 -1.33751e-6 4.0888e-6 1 5.16364e-7 -1.49079e-6 1 9.69232e-6 -3.2635e-6 1 -2.21147e-5 -5.29802e-6 -0.01474726 -0.9981453 -0.0590614 0.01281505 -0.9498765 -0.3123628 -0.01381069 -0.8751662 -0.4836251 0.01938253 -0.6761518 -0.7365073 -0.01602655 -0.4818456 -0.8761096 0.01269006 -0.2311367 -0.9728385 -0.009911239 -0.07441425 -0.9971781 0.01187145 0.2726352 -0.9620443 -0.007021486 0.368277 -0.9296897 0.002374947 0.6994251 -0.714702 0.01184129 0.7285079 -0.6849351 -0.01447147 0.9411164 -0.3377729 0.0254746 0.9970291 -0.07269036 -0.003210961 0.9985983 0.05283045 -0.01378732 0.875388 0.4832243 0.0206871 0.7730894 0.6339597 -0.009902179 0.6199501 0.7845788 0.01373356 0.2836078 0.9588419 -0.01479285 0.1629008 0.9865316 0.01479011 -0.3272564 0.9448198 -0.01373773 -0.4415594 0.8971269 0.01186621 -0.7646136 0.6443797 -0.01760601 -0.8562349 0.5162865 0.02062928 -0.9817955 0.1888177 -1 1.21819e-7 -5.44433e-7 -1 -4.37196e-7 6.26005e-7 -1 0 -2.59619e-7 -1 -3.33856e-7 2.0248e-7 -1 2.09258e-7 -3.46296e-7 -1 4.2316e-7 -4.96854e-7 -1 -1.73285e-7 -1.64524e-7 -1 -3.18805e-7 8.22046e-7 -1 0 0 0.08932554 -0.119028 -0.9888647 -0.06341552 0.3608521 -0.9304645 0.02001136 0.4586634 -0.8883847 -0.01823782 0.8548934 -0.5184832 0.03015726 0.8897183 -0.4555126 -0.03169393 0.9926767 -0.1165693 0.05808871 0.9938563 0.09420877 -0.04561501 0.9435139 0.3281778 0.03401768 0.7247825 0.6881373 0.02189022 0.7342373 0.67854 -0.02186602 0.1928149 0.9809915 -0.03405952 0.2060168 0.9779556 0.04559892 -0.2152901 0.975485 -0.05809926 -0.4408634 0.8956918 0.04519319 -0.644122 0.7635865 -0.04519081 -0.8392267 0.5419006 0.0452013 -0.9347034 0.3525425 -0.04520165 -0.99694 0.06377744 0.04517912 -0.9879428 -0.1480813 -0.05354654 -0.8888461 -0.4550663 0.07991069 -0.7498723 -0.6567388 -0.1090646 -0.4053783 -0.9076196 -1 3.90802e-7 -1.47399e-7 -1 2.73282e-7 0 -1 0 0 -1 0 -3.31908e-7 -1 0 -4.07518e-7 -1 -3.97419e-7 -7.30808e-7 -1 2.34971e-7 4.32085e-7 -1 0 4.75909e-7 -1 0 0 -1 8.45562e-7 0 -1 8.71269e-7 0 -1 5.89735e-7 1.99957e-7 -1 4.14095e-7 -2.12006e-7 -1 0 2.35929e-7 -1 0 -2.85463e-7 -1 0 -2.7269e-7 -1 0 0 -1 -1.62146e-7 1.3126e-7 -1 4.64367e-7 9.36269e-7 -1 6.44785e-7 5.64703e-7 -1 3.78672e-7 4.85439e-7 -1 5.0401e-7 -1.6147e-7 -1 4.0524e-7 -1.29827e-7 0.1262717 -0.03258025 -0.9914606 -0.1233428 0.2294053 -0.9654842 0.1084087 0.5515593 -0.8270611 -0.04491871 0.6562822 -0.7531772 0.01519089 0.8974575 -0.4408391 -0.01521009 0.8880699 -0.4594567 0.04938632 0.9975736 -0.04907125 -0.05397051 0.9983224 0.02096813 0.005400836 0.875431 0.4833129 0.06594711 0.8528949 0.5179008 -0.06919342 0.6185678 0.7826788 0.1262665 0.4380871 0.8900204 -0.148561 0.1611011 0.9756926 0.1751148 -0.1898963 0.9660612 -0.142632 -0.4371036 0.8880295 0.1278221 -0.7601997 0.6369914 -0.09435409 -0.8509407 0.5167176 0.09435909 -0.9943612 0.04839551 -0.08767956 -0.9933239 -0.07496595 0.07579797 -0.8805271 -0.4678959 -0.1084572 -0.7955778 -0.5960645 0.1233057 -0.5379408 -0.8339158 -0.1262991 -0.2995592 -0.9456811 -1 0 0 -1 -1.33547e-7 0 -1 -2.03646e-7 -1.03589e-6 -1 0 0 -1 0 1.48727e-7 -1 2.09639e-7 2.63216e-7 -1 9.8708e-7 3.4364e-7 -1 0 4.05291e-7 -1 0 2.0145e-7 0.05351376 -0.09083306 -0.9944272 -0.03734487 0.2056792 -0.9779067 0.03713607 0.4310535 -0.9015619 -0.04039043 0.5903996 -0.8061 0.04726862 0.7968773 -0.6022892 -0.05057847 0.9475538 -0.3155691 0.01824033 0.9759594 -0.2171883 -0.02189671 0.9364437 0.3501341 -0.00553435 0.9301407 0.3671615 0.02632343 0.5867563 0.8093356 -0.04845404 0.5081802 0.8598867 0.04328256 0.006181299 0.9990438 -0.0588116 -0.1447587 0.9877176 0.04728811 -0.478039 0.8770648 -0.05054599 -0.7334725 0.6778372 -0.002469837 -0.7811138 0.6243839 0.0247029 -0.9815463 0.1896227 -0.02260762 -0.9924744 0.1203474 0.008858442 -0.9443682 -0.3287709 -0.003992378 -0.9496579 -0.3132633 0.02630114 -0.6532096 -0.7567203 -0.005336999 -0.6229937 -0.7822087 -0.02980715 -0.2417454 -0.9698818 -1 1.94998e-7 5.31881e-7 -1 1.02264e-6 7.18586e-7 -1 6.0728e-7 0 -1 5.98984e-7 0 -1 0 -2.27182e-7 -1 0 0 -1 0 0 -1 6.02498e-7 0 -1 4.56169e-7 -5.83829e-7 -1 -2.04166e-7 -3.821e-7 -1 2.43532e-7 4.55775e-7 -1 0 4.76657e-7 -1 0 0 -1 0 0 -1 1.93335e-7 2.93284e-7 -1 6.08285e-7 0 -1 0 -2.42047e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 4.2548e-7 -1 0 4.12235e-7 -1 1.73535e-7 6.05774e-7 0.08263427 0.2144734 -0.973228 -0.1015416 0.3620474 -0.9266127 0.08147692 0.5966007 -0.7983916 -0.1164488 0.802151 -0.5856565 0.1381572 0.9063671 -0.3992633 -0.1381512 0.9903655 -0.009513139 0.1515392 0.9609225 0.2316544 -0.123349 0.856011 0.5020263 0.1278624 0.6041361 0.7865563 -0.05393815 0.5055513 0.8611088 0.00543487 0.04738032 0.9988621 0.06589239 0.006174385 0.9978076 -0.06922441 -0.3421348 0.9370975 0.1262568 -0.5281978 0.8396823 -0.1485571 -0.7463575 0.6487537 0.1485494 -0.9152985 0.3743818 -0.1515661 -0.9862471 0.06591176 0.06514298 -0.9910576 -0.1164519 0.01172667 -0.8549763 -0.5185346 -0.1055379 -0.8136329 -0.5717197 0.1055278 -0.3874834 -0.9158169 -0.1055132 -0.2738546 -0.9559658 1 4.45391e-7 -1.93713e-6 1 4.82342e-7 0 1 4.19139e-7 2.54189e-7 1 0 3.24832e-6 1 0 2.20684e-6 1 5.86376e-7 0 1 -8.60991e-7 -1.25573e-6 1 -4.82508e-7 2.09857e-6 1 1.33858e-6 -1.50308e-5 -0.02536219 0.3353639 -0.9417473 0.04508674 0.4073868 -0.9121422 -0.04711341 0.7901968 -0.6110395 0.03639096 0.8747043 -0.483289 -0.03018444 0.992217 -0.1208069 0.01823461 0.9986283 -0.04908061 -0.01823353 0.8897505 0.4560829 0.008962273 0.8706892 0.4917522 -0.007762551 0.6200423 0.78453 0.02978038 0.5652408 0.8243883 -0.05212229 0.1626533 0.9853056 0.03124338 0.03778886 0.9987972 0.007209002 -0.377419 0.9260146 -0.07799702 -0.4901249 0.8681555 0.09738558 -0.7987002 0.5937963 -0.1127403 -0.9584578 0.2620084 0.06380289 -0.9961088 -0.06079965 -0.05056381 -0.9024515 -0.4278137 0.01823347 -0.854906 -0.5184625 -0.02381742 -0.4076899 -0.9128097 0.02733141 -0.3614379 -0.9319956 1 -8.79224e-7 1.103e-6 1 -2.62551e-6 3.29374e-6 1 -2.09602e-6 5.8859e-6 1 -9.07957e-7 5.66293e-6 1 1.04838e-6 1.55982e-6 1 -1.01043e-6 -1.50336e-6 1 4.22532e-6 -4.37143e-7 1 2.50064e-6 3.34952e-6 1 -2.25989e-6 -3.02705e-6 1 -2.33853e-6 -2.95891e-6 1 -1.87116e-6 4.45745e-7 1 0 0 1 0 0 1 1.17062e-6 4.74427e-7 1 8.17263e-6 -5.95542e-6 1 -4.29028e-6 -5.65292e-6 1 -7.04152e-6 4.5128e-6 1 -1.96227e-6 5.50177e-6 1 1.42501e-6 -3.99541e-6 1 4.90008e-6 -4.51228e-7 1 2.20052e-6 3.6519e-6 -0.0478245 0.06052303 -0.9970205 0.04781574 0.1088424 -0.9929084 -0.04374122 0.6528253 -0.7562446 0.08679497 0.706588 -0.702282 -0.1026006 0.9446665 -0.3115742 0.1515462 0.9832023 -0.10172 -0.1233632 0.9743453 0.1882362 0.08800172 0.8673912 0.4897838 -0.1059038 0.7423698 0.6615673 0.09231346 0.5880583 0.8035333 -0.08679884 0.1921526 0.977519 0.04375451 0.1173758 0.9921232 -0.04783165 -0.4658254 0.883583 -0.07426184 -0.4531341 0.8883438 0.09939354 -0.7772228 0.6213256 -0.1262868 -0.8999778 0.4172427 0.1262832 -0.9792861 0.1582757 -0.09937226 -0.9918696 -0.07949674 0.06328368 -0.8863904 -0.4585928 0.0348457 -0.8951515 -0.4443981 -0.03489041 -0.5545138 -0.8314428 0.04374992 -0.5156189 -0.8557004 1 -1.69796e-7 1.59066e-6 1 3.66744e-7 3.3891e-7 1 0 6.17006e-7 1 7.82183e-6 1.17275e-6 1 -4.57103e-6 3.36243e-6 1 -2.37579e-6 2.53097e-6 1 -8.36677e-7 -7.75842e-6 1 0 0 1 -2.0288e-6 7.99342e-6 -0.04711133 0.06333041 -0.9968801 0.05353355 0.245656 -0.9678778 -0.06210118 0.5873913 -0.8069169 0.0207647 0.6842533 -0.7289488 0.04617774 0.9122886 -0.4069365 -0.08612501 0.9798408 -0.1802622 0.06362819 0.9935209 0.09416854 -0.06362032 0.8758782 0.4783199 0.06993949 0.7326284 0.6770259 -0.080648 0.4554378 0.8866072 0.08067941 0.1745183 0.981343 -0.06340223 -0.2806217 0.9577221 0.0437982 -0.4092401 0.9113749 -0.06738239 -0.8366355 0.5435998 0.05731838 -0.9128121 0.4043371 -0.03464525 -0.9965688 -0.07516908 0.01432818 -0.9888446 -0.1482607 -0.01427435 -0.8164504 -0.577239 0.01426321 -0.79099 -0.6116628 -0.01431781 -0.4313501 -0.9020711 0.03465211 -0.3637298 -0.9308598 1 -8.1319e-6 1.27338e-6 1 4.1398e-6 -2.89608e-6 1 3.59234e-6 2.43377e-7 1 2.53504e-6 -1.34741e-6 1 -3.31494e-6 1.76193e-6 1 -3.18697e-6 -8.15637e-6 1 4.08609e-6 -5.1611e-6 1 -5.88326e-6 7.43109e-6 1 -6.33542e-6 6.30169e-6 1 -5.63863e-6 6.00711e-6 1 -8.16475e-6 3.64194e-6 1 -5.9975e-6 1.10336e-6 1 -4.05113e-6 2.1868e-6 1 0 0 1 1.24357e-6 2.68163e-6 1 1.40126e-6 2.72785e-6 1 1.28391e-7 8.63814e-6 1 -1.68699e-6 5.75746e-6 1 2.14706e-6 2.50222e-6 1 0 0 1 -3.60358e-6 5.69682e-6 0.06321519 0.2614912 -0.9631335 0.03488516 0.2458285 -0.9686854 -0.03125202 0.6759722 -0.7362642 -0.01517546 0.6843127 -0.7290309 0.044896 0.9123435 -0.4069566 -0.04489457 0.9402678 -0.3374626 0.01520323 0.9984869 0.05284506 0.07564151 0.9926861 0.09408879 -0.1134526 0.8427962 0.5261396 0.1563419 0.7253901 0.6703481 -0.1381679 0.3780773 0.9154055 0.1515438 0.1433259 0.9780042 -0.1485465 -0.1731477 0.9736293 0.1204918 -0.4510393 0.8843332 -0.1100932 -0.729939 0.6745877 0.03989613 -0.7993652 0.5995195 -0.04374492 -0.9945862 0.09425902 0.08679842 -0.9960616 0.01809042 -0.0922876 -0.9093951 -0.4055656 0.1059543 -0.8031079 -0.5863372 -0.08798009 -0.6615069 -0.7447604 0.1426418 -0.3602169 -0.9218986 -0.11149 -0.1613715 -0.980576 -3.50527e-5 3.79297e-5 1 5.72218e-6 3.84237e-7 1 3.8335e-6 5.8027e-7 1 0 0 1 -5.15484e-6 5.57793e-6 1 0 0 1 0 0 1 -8.06862e-6 -9.62953e-6 1 -2.84548e-6 2.44359e-6 1 0.9891734 0.1388739 0.04743421 0.9650471 0.2620084 -0.005983352 0.7173829 0.6961256 -0.02776688 0.621892 0.7822511 0.03651732 0.1784106 0.9837088 -0.02206045 0.1057221 0.9943541 0.009093046 -0.3528556 0.9356337 -0.009092271 -0.3926411 0.9196467 0.009094238 -0.74739 0.6643363 -0.008098602 -0.771432 0.6362928 0.004930377 -0.9547773 0.2972673 -0.005690097 -0.9659635 0.258418 0.0116102 -0.9659654 -0.2584106 -0.01160985 -0.9447448 -0.3272432 0.01921373 -0.7712742 -0.6361837 -0.02015733 -0.6442148 -0.7643029 0.02878409 -0.366874 -0.9296461 -0.03408199 -0.1594068 -0.9863802 0.04054319 0.2425037 -0.9693028 -0.04054731 0.4444226 -0.8951688 0.03407824 0.7258006 -0.6870602 -0.03408288 0.855817 -0.5156877 0.04054093 0.9861064 -0.1623052 -0.03537118 3.81728e-5 -1.16809e-5 1 2.1133e-5 -1.26072e-5 1 4.87446e-7 7.37926e-6 1 -8.73027e-6 -9.46607e-6 1 3.56704e-5 2.10453e-5 1 2.62525e-5 3.22233e-5 1 5.51499e-6 -1.65516e-5 1 -1.06909e-6 -1.48579e-5 1 -5.41786e-6 4.59002e-6 1 -1.24899e-5 5.57232e-6 1 -4.80826e-6 3.93213e-5 1 -4.24787e-5 3.81027e-5 1 -4.2009e-5 3.4375e-5 1 -8.03603e-5 1.74831e-5 1 -7.7682e-5 1.4205e-5 1 -7.08921e-5 2.44713e-5 1 3.10854e-5 -1.07304e-5 1 3.42513e-5 1.22061e-5 1 -3.59971e-5 2.85771e-6 1 -9.1227e-6 -2.75146e-5 1 -7.52918e-6 2.06245e-6 1 3.79955e-6 -1.0408e-6 1 -1.34814e-5 -4.49702e-5 1 3.98109e-5 -6.56356e-5 1 -0.9923902 -0.0338363 -0.1183934 -0.9908004 -0.1312032 0.03317147 -0.8318574 -0.5541835 0.02989965 -0.8171521 -0.5762651 -0.01345402 -0.5143241 -0.8551185 -0.06513744 -0.3760274 -0.9192655 0.1164231 -0.0360127 -0.9925455 -0.1164324 0.1164273 -0.9910613 0.06513231 0.5185687 -0.8549557 0.0117129 0.5510897 -0.8324674 -0.0574305 0.8906765 -0.4546054 0.005417287 0.9153661 -0.3872766 0.1100987 0.9919236 -0.07402038 -0.1029974 0.9635601 0.2445384 0.1084104 0.9287942 0.3678663 -0.04489547 0.7146162 0.6993513 0.0152136 0.6830256 0.7264681 0.07563209 0.2850409 0.9517748 -0.1134738 0.1640242 0.9840938 0.06823086 -0.2567257 0.9663558 0.01576048 -0.3228304 0.9423862 -0.08768641 -0.6515032 0.7559949 0.06336593 -0.7857918 0.606824 -0.1195654 -0.9011796 0.4139786 0.1284409 -9.57912e-6 4.19977e-5 -1 2.40979e-7 3.64456e-6 -1 1.28216e-6 -2.05641e-5 -1 8.01805e-6 1.8025e-5 -1 -1.67889e-5 -4.27133e-5 -1 4.78346e-5 8.76934e-5 -1 -3.98149e-6 -7.29912e-6 -1 -5.46769e-6 -8.21672e-6 -1 6.44645e-7 -1.88181e-6 -1 1.16239e-4 1.18853e-4 -1</float_array> + <technique_common> + <accessor source="#Link3-mesh-normals-array" count="7396" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Link3-mesh-vertices"> + <input semantic="POSITION" source="#Link3-mesh-positions"/> + </vertices> + <polylist material="Material_001-material" count="7396"> + <input semantic="VERTEX" source="#Link3-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Link3-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 6 2 6 3 5 3 7 3 8 4 9 4 10 4 10 5 9 5 11 5 14 6 15 6 13 6 13 7 15 7 16 7 13 8 16 8 12 8 14 9 13 9 17 9 17 10 13 10 18 10 18 11 19 11 1 11 1 12 0 12 18 12 20 13 17 13 18 13 20 14 18 14 0 14 21 15 20 15 0 15 21 16 0 16 2 16 22 17 23 17 24 17 24 18 23 18 25 18 7 19 5 19 27 19 27 20 5 20 26 20 22 21 24 21 27 21 22 22 27 22 26 22 23 23 28 23 29 23 23 24 29 24 25 24 25 25 29 25 30 25 31 26 32 26 33 26 33 27 32 27 871 27 36 28 37 28 35 28 35 29 37 29 38 29 35 30 38 30 34 30 36 31 35 31 42 31 42 32 35 32 43 32 40 33 41 33 43 33 40 34 43 34 39 34 44 35 42 35 43 35 44 36 43 36 41 36 11 37 9 37 45 37 11 38 45 38 46 38 47 39 48 39 49 39 49 40 48 40 50 40 51 41 47 41 8 41 9 42 8 42 45 42 45 43 8 43 47 43 47 44 49 44 45 44 48 45 52 45 53 45 48 46 53 46 50 46 50 47 53 47 54 47 55 48 56 48 24 48 24 49 56 49 27 49 59 50 60 50 61 50 61 51 60 51 62 51 61 52 62 52 63 52 63 53 62 53 57 53 63 54 57 54 58 54 42 55 44 55 64 55 64 56 44 56 1047 56 65 57 66 57 67 57 68 58 69 58 70 58 70 59 69 59 71 59 70 60 71 60 65 60 65 61 71 61 66 61 72 62 73 62 1268 62 74 63 75 63 76 63 77 64 78 64 73 64 73 65 78 65 79 65 73 66 79 66 80 66 81 67 82 67 1177 67 83 68 84 68 85 68 86 69 87 69 942 69 942 70 87 70 88 70 942 71 88 71 89 71 89 72 90 72 91 72 92 73 93 73 84 73 72 74 84 74 94 74 72 75 94 75 73 75 73 76 94 76 74 76 73 77 74 77 77 77 77 78 74 78 76 78 83 79 85 79 91 79 91 80 85 80 81 80 91 81 81 81 89 81 89 82 81 82 1177 82 89 83 1177 83 942 83 82 84 95 84 1177 84 1177 85 95 85 96 85 1177 86 96 86 1268 86 1268 87 96 87 97 87 1268 88 97 88 72 88 84 89 93 89 98 89 100 90 85 90 103 90 100 91 102 91 85 91 85 92 102 92 95 92 95 93 102 93 99 93 84 94 98 94 101 94 84 95 101 95 85 95 101 96 103 96 85 96 95 97 99 97 104 97 107 98 106 98 96 98 96 99 106 99 105 99 95 100 104 100 107 100 95 101 107 101 96 101 96 102 105 102 84 102 84 103 105 103 92 103 59 104 108 104 109 104 110 105 111 105 112 105 113 106 69 106 1266 106 1266 107 69 107 68 107 1266 108 68 108 114 108 117 109 118 109 119 109 119 110 118 110 110 110 120 111 1183 111 121 111 121 112 1183 112 122 112 123 113 124 113 114 113 114 114 124 114 125 114 114 115 125 115 1266 115 1266 116 125 116 118 116 110 117 112 117 119 117 119 118 112 118 126 118 119 119 126 119 127 119 120 120 119 120 1183 120 1183 121 119 121 127 121 1183 122 127 122 109 122 109 123 127 123 60 123 109 124 60 124 59 124 128 125 129 125 122 125 122 126 129 126 116 126 122 127 116 127 121 127 121 128 116 128 115 128 121 129 115 129 130 129 121 130 130 130 131 130 117 131 132 131 133 131 121 132 131 132 134 132 117 133 133 133 135 133 122 134 1266 134 128 134 128 135 1266 135 118 135 128 136 118 136 136 136 136 137 118 137 117 137 136 138 117 138 135 138 136 139 135 139 137 139 116 140 138 140 115 140 141 141 138 141 116 141 134 142 139 142 121 142 121 143 139 143 117 143 117 144 139 144 132 144 136 145 137 145 140 145 136 146 141 146 116 146 136 147 140 147 141 147 142 148 939 148 930 148 144 149 147 149 143 149 145 150 146 150 167 150 145 151 148 151 146 151 146 152 148 152 931 152 930 153 149 153 142 153 142 154 151 154 939 154 939 155 151 155 147 155 939 156 147 156 150 156 150 157 147 157 144 157 148 158 933 158 931 158 149 159 930 159 148 159 148 160 930 160 933 160 153 161 1267 161 154 161 939 162 150 162 152 162 155 163 939 163 152 163 155 164 154 164 1267 164 156 165 157 165 158 165 151 166 142 166 169 166 151 167 169 167 162 167 163 168 164 168 165 168 166 169 167 169 168 169 168 170 167 170 146 170 169 171 170 171 162 171 172 172 171 172 143 172 143 173 171 173 144 173 173 174 975 174 174 174 170 175 169 175 176 175 170 176 176 176 177 176 178 177 179 177 168 177 153 178 180 178 1267 178 1267 179 180 179 165 179 163 180 165 180 181 180 157 181 156 181 182 181 159 182 183 182 160 182 160 183 183 183 175 183 157 184 184 184 158 184 158 185 184 185 161 185 158 186 161 186 185 186 185 187 161 187 186 187 188 188 976 188 189 188 189 189 976 189 165 189 189 190 165 190 164 190 182 191 190 191 157 191 157 192 190 192 160 192 160 193 190 193 159 193 185 194 186 194 187 194 975 195 188 195 174 195 171 196 172 196 191 196 185 197 187 197 192 197 185 198 192 198 193 198 180 199 194 199 165 199 165 200 194 200 181 200 181 201 194 201 160 201 181 202 160 202 175 202 168 203 179 203 193 203 188 204 975 204 976 204 157 205 195 205 184 205 184 206 195 206 196 206 186 207 197 207 187 207 187 208 197 208 198 208 199 209 200 209 202 209 202 210 200 210 201 210 1010 211 202 211 201 211 193 212 192 212 168 212 168 213 192 213 166 213 177 214 176 214 197 214 197 215 176 215 198 215 178 216 168 216 1010 216 178 217 1010 217 201 217 191 218 172 218 195 218 195 219 172 219 196 219 203 220 205 220 204 220 206 221 207 221 205 221 205 222 207 222 204 222 207 223 206 223 208 223 207 224 208 224 209 224 207 225 209 225 212 225 210 226 213 226 204 226 204 227 213 227 211 227 211 228 203 228 204 228 215 229 214 229 216 229 217 230 218 230 219 230 215 231 220 231 214 231 222 232 221 232 223 232 220 233 215 233 222 233 220 234 222 234 223 234 216 235 214 235 224 235 224 236 225 236 216 236 225 237 217 237 216 237 216 238 217 238 219 238 222 239 226 239 221 239 227 240 228 240 229 240 227 241 230 241 228 241 233 242 232 242 227 242 233 243 231 243 234 243 233 244 234 244 232 244 233 245 227 245 239 245 230 246 235 246 228 246 228 247 235 247 236 247 229 248 239 248 227 248 236 249 237 249 228 249 237 250 238 250 228 250 240 251 243 251 242 251 244 252 245 252 241 252 241 253 245 253 240 253 240 254 242 254 246 254 240 255 246 255 247 255 240 256 247 256 241 256 248 257 249 257 250 257 242 258 243 258 250 258 242 259 250 259 249 259 204 260 251 260 252 260 204 261 252 261 210 261 210 262 252 262 253 262 210 263 253 263 213 263 213 264 253 264 254 264 213 265 254 265 255 265 213 266 255 266 211 266 211 267 255 267 256 267 211 268 256 268 203 268 203 269 256 269 257 269 203 270 257 270 205 270 205 271 257 271 258 271 205 272 258 272 206 272 206 273 258 273 208 273 208 274 258 274 259 274 208 275 259 275 260 275 208 276 260 276 209 276 209 277 260 277 212 277 212 278 260 278 261 278 212 279 261 279 207 279 207 280 261 280 262 280 207 281 262 281 204 281 204 282 262 282 251 282 217 283 263 283 218 283 218 284 263 284 264 284 218 285 264 285 219 285 219 286 264 286 265 286 219 287 265 287 216 287 216 288 265 288 266 288 216 289 266 289 215 289 215 290 266 290 267 290 215 291 267 291 222 291 222 292 267 292 226 292 226 293 267 293 268 293 226 294 268 294 269 294 226 295 269 295 221 295 221 296 269 296 270 296 221 297 270 297 223 297 223 298 270 298 220 298 220 299 270 299 271 299 220 300 271 300 214 300 214 301 271 301 272 301 214 302 272 302 224 302 224 303 272 303 273 303 224 304 273 304 225 304 225 305 273 305 274 305 225 306 274 306 217 306 217 307 274 307 263 307 239 308 285 308 275 308 239 309 275 309 233 309 233 310 275 310 231 310 231 311 275 311 276 311 231 312 276 312 277 312 231 313 277 313 234 313 234 314 277 314 278 314 234 315 278 315 232 315 232 316 278 316 227 316 227 317 278 317 279 317 227 318 279 318 280 318 227 319 280 319 230 319 230 320 280 320 235 320 235 321 280 321 281 321 235 322 281 322 236 322 236 323 281 323 282 323 236 324 282 324 237 324 237 325 282 325 283 325 237 326 283 326 238 326 238 327 283 327 284 327 238 328 284 328 228 328 228 329 284 329 229 329 229 330 284 330 285 330 229 331 285 331 239 331 244 332 286 332 287 332 244 333 287 333 245 333 245 334 287 334 288 334 245 335 288 335 240 335 240 336 288 336 289 336 240 337 289 337 243 337 243 338 289 338 290 338 243 339 290 339 250 339 250 340 290 340 291 340 250 341 291 341 248 341 248 342 291 342 292 342 248 343 292 343 249 343 249 344 292 344 293 344 249 345 293 345 242 345 242 346 293 346 294 346 242 347 294 347 246 347 246 348 294 348 295 348 246 349 295 349 247 349 247 350 295 350 296 350 247 351 296 351 241 351 241 352 296 352 286 352 241 353 286 353 244 353 298 354 297 354 301 354 298 355 301 355 299 355 301 356 302 356 299 356 297 357 298 357 300 357 299 358 302 358 303 358 299 359 303 359 304 359 297 360 300 360 305 360 305 361 306 361 297 361 311 362 308 362 307 362 307 363 309 363 313 363 309 364 310 364 313 364 307 365 313 365 311 365 310 366 312 366 313 366 308 367 315 367 307 367 316 368 317 368 307 368 310 369 314 369 312 369 307 370 315 370 316 370 258 371 318 371 319 371 258 372 319 372 259 372 259 373 319 373 260 373 260 374 319 374 320 374 260 375 320 375 321 375 260 376 321 376 261 376 261 377 321 377 322 377 261 378 322 378 262 378 262 379 322 379 323 379 262 380 323 380 251 380 251 381 323 381 252 381 252 382 323 382 324 382 252 383 324 383 253 383 253 384 324 384 325 384 253 385 325 385 254 385 254 386 325 386 255 386 255 387 325 387 326 387 255 388 326 388 256 388 256 389 326 389 327 389 256 390 327 390 257 390 257 391 327 391 328 391 257 392 328 392 258 392 258 393 328 393 318 393 273 394 329 394 274 394 274 395 329 395 330 395 274 396 330 396 263 396 263 397 330 397 331 397 263 398 331 398 264 398 264 399 331 399 332 399 264 400 332 400 333 400 264 401 333 401 265 401 265 402 333 402 334 402 265 403 334 403 266 403 266 404 334 404 335 404 266 405 335 405 267 405 267 406 335 406 336 406 267 407 336 407 268 407 268 408 336 408 337 408 268 409 337 409 269 409 269 410 337 410 338 410 269 411 338 411 270 411 270 412 338 412 339 412 270 413 339 413 271 413 271 414 339 414 340 414 271 415 340 415 272 415 272 416 340 416 329 416 272 417 329 417 273 417 280 418 341 418 281 418 281 419 341 419 342 419 281 420 342 420 282 420 282 421 342 421 343 421 282 422 343 422 283 422 283 423 343 423 344 423 283 424 344 424 284 424 284 425 344 425 345 425 284 426 345 426 285 426 285 427 345 427 346 427 285 428 346 428 275 428 275 429 346 429 347 429 275 430 347 430 348 430 275 431 348 431 276 431 276 432 348 432 277 432 277 433 348 433 349 433 277 434 349 434 278 434 278 435 349 435 350 435 278 436 350 436 351 436 278 437 351 437 279 437 279 438 351 438 352 438 279 439 352 439 280 439 280 440 352 440 341 440 295 441 363 441 353 441 295 442 353 442 296 442 296 443 353 443 286 443 286 444 353 444 354 444 286 445 354 445 287 445 287 446 354 446 355 446 287 447 355 447 288 447 288 448 355 448 356 448 288 449 356 449 289 449 289 450 356 450 357 450 289 451 357 451 290 451 290 452 357 452 358 452 290 453 358 453 359 453 290 454 359 454 291 454 291 455 359 455 360 455 291 456 360 456 292 456 292 457 360 457 361 457 292 458 361 458 293 458 293 459 361 459 294 459 294 460 361 460 362 460 294 461 362 461 363 461 294 462 363 462 295 462 368 463 365 463 366 463 366 464 367 464 368 464 366 465 369 465 367 465 373 466 370 466 371 466 372 467 373 467 371 467 375 468 376 468 374 468 374 469 376 469 372 469 374 470 377 470 375 470 374 471 364 471 377 471 379 472 378 472 380 472 382 473 381 473 378 473 366 474 365 474 383 474 379 475 380 475 364 475 379 476 364 476 384 476 384 477 364 477 374 477 384 478 374 478 371 478 371 479 374 479 372 479 382 480 378 480 379 480 382 481 379 481 384 481 382 482 384 482 371 482 383 483 381 483 382 483 383 484 382 484 366 484 366 485 382 485 371 485 366 486 371 486 369 486 369 487 371 487 370 487 386 488 388 488 385 488 386 489 391 489 387 489 386 490 387 490 388 490 386 491 385 491 389 491 386 492 390 492 391 492 389 493 392 493 386 493 394 494 393 494 395 494 394 495 395 495 396 495 393 496 394 496 397 496 397 497 398 497 393 497 394 498 396 498 399 498 407 499 402 499 401 499 403 500 401 500 404 500 401 501 403 501 405 501 401 502 402 502 400 502 401 503 400 503 406 503 405 504 407 504 401 504 415 505 409 505 408 505 408 506 411 506 410 506 410 507 411 507 412 507 410 508 414 508 408 508 408 509 414 509 415 509 412 510 413 510 410 510 418 511 416 511 419 511 416 512 418 512 420 512 418 513 419 513 421 513 416 514 420 514 422 514 418 515 421 515 423 515 416 516 422 516 417 516 417 517 424 517 416 517 417 518 426 518 424 518 423 519 425 519 427 519 418 520 423 520 427 520 430 521 431 521 438 521 431 522 432 522 438 522 432 523 433 523 438 523 438 524 433 524 434 524 428 525 429 525 435 525 435 526 429 526 436 526 428 527 437 527 429 527 429 528 437 528 438 528 434 529 429 529 438 529 299 530 439 530 440 530 299 531 440 531 298 531 298 532 440 532 441 532 298 533 441 533 300 533 300 534 441 534 442 534 300 535 442 535 305 535 305 536 442 536 443 536 305 537 443 537 306 537 306 538 443 538 444 538 306 539 444 539 297 539 297 540 444 540 301 540 301 541 444 541 445 541 301 542 445 542 302 542 302 543 445 543 446 543 302 544 446 544 303 544 303 545 446 545 447 545 303 546 447 546 304 546 304 547 447 547 439 547 304 548 439 548 299 548 311 549 459 549 448 549 311 550 448 550 308 550 308 551 448 551 449 551 308 552 449 552 315 552 315 553 449 553 450 553 315 554 450 554 316 554 316 555 450 555 451 555 316 556 451 556 317 556 317 557 451 557 452 557 317 558 452 558 307 558 307 559 452 559 453 559 307 560 453 560 454 560 307 561 454 561 309 561 309 562 454 562 310 562 310 563 454 563 455 563 310 564 455 564 314 564 314 565 455 565 456 565 314 566 456 566 457 566 314 567 457 567 312 567 312 568 457 568 458 568 312 569 458 569 313 569 313 570 458 570 459 570 313 571 459 571 311 571 325 572 460 572 326 572 326 573 460 573 461 573 326 574 461 574 327 574 327 575 461 575 462 575 327 576 462 576 463 576 327 577 463 577 328 577 328 578 463 578 464 578 328 579 464 579 318 579 318 580 464 580 465 580 318 581 465 581 319 581 319 582 465 582 466 582 319 583 466 583 320 583 320 584 466 584 467 584 320 585 467 585 321 585 321 586 467 586 468 586 321 587 468 587 322 587 322 588 468 588 469 588 322 589 469 589 323 589 323 590 469 590 470 590 323 591 470 591 471 591 323 592 471 592 324 592 324 593 471 593 472 593 324 594 472 594 325 594 325 595 472 595 460 595 331 596 473 596 332 596 332 597 473 597 474 597 332 598 474 598 333 598 333 599 474 599 334 599 334 600 474 600 475 600 334 601 475 601 335 601 335 602 475 602 476 602 335 603 476 603 477 603 335 604 477 604 336 604 336 605 477 605 337 605 477 606 478 606 337 606 337 607 478 607 338 607 338 608 478 608 479 608 338 609 479 609 480 609 338 610 480 610 339 610 339 611 480 611 481 611 339 612 481 612 340 612 340 613 481 613 482 613 340 614 482 614 329 614 329 615 482 615 483 615 329 616 483 616 330 616 330 617 483 617 484 617 330 618 484 618 485 618 330 619 485 619 331 619 331 620 485 620 473 620 350 621 486 621 351 621 351 622 486 622 487 622 351 623 487 623 352 623 352 624 487 624 488 624 352 625 488 625 341 625 341 626 488 626 489 626 341 627 489 627 342 627 342 628 489 628 490 628 342 629 490 629 343 629 343 630 490 630 491 630 343 631 491 631 344 631 344 632 491 632 492 632 344 633 492 633 345 633 345 634 492 634 493 634 345 635 493 635 346 635 346 636 493 636 494 636 346 637 494 637 347 637 347 638 494 638 495 638 347 639 495 639 348 639 348 640 495 640 496 640 348 641 496 641 349 641 349 642 496 642 497 642 349 643 497 643 350 643 350 644 497 644 486 644 361 645 498 645 499 645 361 646 499 646 362 646 362 647 499 647 500 647 362 648 500 648 363 648 363 649 500 649 501 649 363 650 501 650 353 650 353 651 501 651 502 651 353 652 502 652 354 652 354 653 502 653 503 653 354 654 503 654 355 654 355 655 503 655 504 655 355 656 504 656 356 656 356 657 504 657 505 657 356 658 505 658 357 658 357 659 505 659 506 659 357 660 506 660 358 660 358 661 506 661 507 661 358 662 507 662 359 662 359 663 507 663 508 663 359 664 508 664 360 664 360 665 508 665 498 665 360 666 498 666 361 666 365 667 511 667 383 667 383 668 511 668 512 668 383 669 512 669 381 669 381 670 512 670 513 670 381 671 513 671 514 671 381 672 514 672 378 672 378 673 514 673 380 673 380 674 514 674 510 674 380 675 510 675 364 675 364 676 510 676 515 676 364 677 515 677 377 677 377 678 515 678 516 678 377 679 516 679 375 679 375 680 516 680 509 680 375 681 509 681 376 681 376 682 509 682 372 682 372 683 509 683 517 683 372 684 517 684 373 684 373 685 517 685 518 685 373 686 518 686 370 686 370 687 518 687 519 687 519 688 369 688 370 688 365 689 368 689 511 689 511 690 368 690 520 690 520 691 368 691 367 691 520 692 367 692 369 692 520 693 369 693 519 693 391 694 528 694 521 694 391 695 521 695 387 695 387 696 521 696 388 696 388 697 521 697 522 697 388 698 522 698 385 698 385 699 522 699 523 699 385 700 523 700 389 700 389 701 523 701 524 701 389 702 524 702 525 702 389 703 525 703 392 703 392 704 525 704 526 704 392 705 526 705 386 705 386 706 526 706 527 706 386 707 527 707 390 707 390 708 527 708 528 708 390 709 528 709 391 709 398 710 534 710 393 710 393 711 534 711 529 711 393 712 529 712 395 712 395 713 529 713 530 713 395 714 530 714 396 714 396 715 530 715 531 715 396 716 531 716 399 716 399 717 531 717 532 717 399 718 532 718 394 718 394 719 532 719 533 719 394 720 533 720 397 720 397 721 533 721 534 721 397 722 534 722 398 722 404 723 540 723 535 723 404 724 535 724 403 724 403 725 535 725 536 725 403 726 536 726 405 726 405 727 536 727 537 727 405 728 537 728 407 728 407 729 537 729 402 729 402 730 537 730 538 730 402 731 538 731 400 731 400 732 538 732 539 732 400 733 539 733 406 733 406 734 539 734 401 734 401 735 539 735 540 735 401 736 540 736 404 736 408 737 541 737 411 737 411 738 541 738 542 738 411 739 542 739 412 739 412 740 542 740 543 740 412 741 543 741 413 741 543 742 544 742 413 742 413 743 544 743 410 743 410 744 544 744 545 744 410 745 545 745 414 745 414 746 545 746 546 746 414 747 546 747 415 747 415 748 546 748 547 748 415 749 547 749 409 749 409 750 547 750 548 750 409 751 548 751 408 751 408 752 548 752 541 752 559 753 418 753 549 753 549 754 418 754 550 754 550 755 418 755 427 755 550 756 427 756 425 756 550 757 425 757 551 757 551 758 425 758 423 758 551 759 423 759 552 759 552 760 423 760 421 760 552 761 421 761 553 761 553 762 421 762 419 762 553 763 419 763 554 763 554 764 419 764 555 764 555 765 419 765 416 765 555 766 416 766 424 766 555 767 424 767 556 767 556 768 424 768 426 768 556 769 426 769 417 769 556 770 417 770 557 770 557 771 417 771 558 771 558 772 417 772 422 772 558 773 422 773 559 773 559 774 422 774 420 774 559 775 420 775 418 775 560 776 437 776 428 776 560 777 428 777 561 777 561 778 428 778 562 778 562 779 428 779 435 779 562 780 435 780 563 780 563 781 435 781 436 781 563 782 436 782 564 782 564 783 436 783 429 783 564 784 429 784 565 784 565 785 429 785 434 785 565 786 434 786 566 786 566 787 434 787 433 787 566 788 433 788 567 788 567 789 433 789 432 789 567 790 432 790 568 790 568 791 432 791 431 791 568 792 431 792 569 792 569 793 431 793 430 793 569 794 430 794 570 794 570 795 430 795 438 795 570 796 438 796 560 796 560 797 438 797 437 797 441 798 581 798 571 798 441 799 571 799 442 799 442 800 571 800 572 800 442 801 572 801 443 801 443 802 572 802 573 802 443 803 573 803 444 803 444 804 573 804 574 804 444 805 574 805 575 805 444 806 575 806 445 806 445 807 575 807 576 807 445 808 576 808 446 808 446 809 576 809 577 809 446 810 577 810 578 810 446 811 578 811 447 811 447 812 578 812 579 812 447 813 579 813 439 813 439 814 579 814 580 814 439 815 580 815 440 815 440 816 580 816 581 816 440 817 581 817 441 817 449 818 582 818 450 818 450 819 582 819 583 819 450 820 583 820 451 820 451 821 583 821 584 821 451 822 584 822 452 822 452 823 584 823 585 823 452 824 585 824 453 824 453 825 585 825 586 825 453 826 586 826 454 826 454 827 586 827 587 827 454 828 587 828 455 828 455 829 587 829 456 829 456 830 587 830 588 830 456 831 588 831 457 831 457 832 588 832 589 832 457 833 589 833 458 833 458 834 589 834 590 834 458 835 590 835 459 835 459 836 590 836 591 836 459 837 591 837 448 837 448 838 591 838 592 838 448 839 592 839 449 839 449 840 592 840 582 840 596 841 597 841 541 841 491 842 490 842 595 842 595 843 490 843 601 843 601 844 490 844 489 844 489 845 488 845 601 845 601 846 488 846 600 846 600 847 488 847 487 847 604 848 530 848 529 848 603 849 529 849 534 849 532 850 531 850 600 850 530 851 602 851 531 851 531 852 602 852 600 852 602 853 530 853 604 853 533 854 532 854 600 854 604 855 529 855 603 855 476 856 603 856 477 856 475 857 474 857 605 857 605 858 474 858 599 858 603 859 476 859 605 859 605 860 476 860 475 860 473 861 599 861 474 861 599 862 606 862 607 862 524 863 523 863 599 863 599 864 523 864 522 864 599 865 522 865 606 865 606 866 522 866 521 866 606 867 521 867 598 867 526 868 525 868 608 868 521 869 528 869 598 869 598 870 528 870 527 870 525 871 524 871 608 871 608 872 524 872 599 872 598 873 460 873 472 873 598 874 472 874 610 874 469 875 609 875 470 875 470 876 609 876 610 876 472 877 471 877 610 877 610 878 471 878 470 878 609 879 469 879 468 879 609 880 468 880 467 880 609 881 467 881 612 881 539 882 538 882 611 882 593 883 536 883 535 883 540 884 539 884 612 884 612 885 539 885 611 885 611 886 538 886 613 886 613 887 538 887 537 887 537 888 536 888 613 888 613 889 536 889 593 889 501 890 500 890 614 890 614 891 500 891 615 891 615 892 500 892 597 892 597 893 500 893 499 893 613 894 502 894 501 894 613 895 501 895 614 895 595 896 544 896 543 896 546 897 545 897 595 897 616 898 596 898 548 898 616 899 548 899 547 899 595 900 545 900 544 900 541 901 548 901 596 901 616 902 547 902 546 902 616 903 546 903 595 903 593 904 466 904 465 904 593 905 465 905 464 905 608 906 463 906 462 906 612 907 467 907 466 907 593 908 464 908 463 908 593 909 463 909 608 909 608 910 462 910 461 910 608 911 461 911 460 911 534 912 478 912 477 912 534 913 477 913 603 913 481 914 480 914 533 914 478 915 534 915 533 915 478 916 533 916 479 916 533 917 480 917 479 917 473 918 485 918 599 918 599 919 485 919 608 919 608 920 485 920 484 920 608 921 482 921 533 921 533 922 482 922 481 922 484 923 483 923 608 923 483 924 482 924 608 924 487 925 486 925 600 925 600 926 486 926 497 926 495 927 533 927 496 927 600 928 497 928 533 928 533 929 497 929 496 929 533 930 495 930 494 930 493 931 492 931 594 931 533 932 494 932 594 932 594 933 494 933 493 933 492 934 491 934 594 934 499 935 498 935 597 935 597 936 498 936 541 936 541 937 498 937 508 937 541 938 508 938 594 938 504 939 593 939 505 939 508 940 507 940 594 940 594 941 507 941 506 941 594 942 506 942 593 942 593 943 506 943 505 943 504 944 503 944 593 944 593 945 503 945 613 945 613 946 503 946 502 946 608 947 511 947 520 947 608 948 520 948 593 948 512 949 511 949 608 949 608 950 513 950 512 950 533 951 514 951 608 951 608 952 514 952 513 952 515 953 510 953 533 953 594 954 509 954 516 954 594 955 516 955 533 955 533 956 516 956 515 956 594 957 517 957 509 957 517 958 594 958 518 958 518 959 594 959 593 959 593 960 520 960 519 960 593 961 519 961 518 961 466 962 593 962 612 962 612 963 593 963 540 963 593 964 535 964 540 964 543 965 542 965 594 965 594 966 542 966 541 966 491 967 595 967 594 967 594 968 595 968 543 968 460 969 598 969 608 969 608 970 598 970 527 970 608 971 527 971 526 971 514 972 533 972 510 972 617 973 641 973 618 973 617 974 618 974 619 974 619 975 618 975 620 975 620 976 618 976 621 976 620 977 621 977 622 977 620 978 622 978 623 978 623 979 622 979 624 979 623 980 624 980 625 980 625 981 624 981 626 981 625 982 626 982 627 982 625 983 627 983 628 983 628 984 627 984 629 984 628 985 629 985 630 985 630 986 629 986 631 986 630 987 631 987 632 987 632 988 631 988 633 988 632 989 633 989 634 989 634 990 633 990 635 990 634 991 635 991 636 991 636 992 635 992 637 992 636 993 637 993 638 993 638 994 637 994 639 994 638 995 639 995 640 995 640 996 639 996 641 996 640 997 641 997 617 997 642 998 643 998 644 998 644 999 643 999 645 999 644 1000 645 1000 646 1000 644 1001 646 1001 647 1001 647 1002 646 1002 648 1002 647 1003 648 1003 649 1003 649 1004 648 1004 650 1004 649 1005 650 1005 651 1005 651 1006 650 1006 652 1006 651 1007 652 1007 653 1007 653 1008 652 1008 654 1008 653 1009 654 1009 655 1009 655 1010 654 1010 656 1010 655 1011 656 1011 657 1011 657 1012 656 1012 658 1012 657 1013 658 1013 659 1013 659 1014 658 1014 660 1014 659 1015 660 1015 661 1015 659 1016 661 1016 662 1016 662 1017 661 1017 663 1017 662 1018 663 1018 643 1018 662 1019 643 1019 642 1019 664 1020 665 1020 666 1020 666 1021 665 1021 667 1021 666 1022 667 1022 668 1022 666 1023 668 1023 669 1023 669 1024 668 1024 670 1024 669 1025 670 1025 671 1025 671 1026 670 1026 672 1026 671 1027 672 1027 673 1027 673 1028 672 1028 674 1028 674 1029 672 1029 675 1029 674 1030 675 1030 676 1030 676 1031 675 1031 677 1031 676 1032 677 1032 678 1032 678 1033 677 1033 679 1033 678 1034 679 1034 680 1034 680 1035 679 1035 681 1035 680 1036 681 1036 682 1036 682 1037 681 1037 683 1037 682 1038 683 1038 684 1038 684 1039 683 1039 685 1039 684 1040 685 1040 664 1040 664 1041 685 1041 665 1041 686 1042 644 1042 647 1042 686 1043 647 1043 687 1043 687 1044 647 1044 688 1044 688 1045 647 1045 649 1045 688 1046 649 1046 689 1046 689 1047 649 1047 651 1047 689 1048 651 1048 653 1048 689 1049 653 1049 690 1049 690 1050 653 1050 655 1050 690 1051 655 1051 691 1051 691 1052 655 1052 692 1052 692 1053 655 1053 657 1053 692 1054 657 1054 693 1054 693 1055 657 1055 659 1055 693 1056 659 1056 694 1056 694 1057 659 1057 662 1057 694 1058 662 1058 695 1058 695 1059 662 1059 642 1059 695 1060 642 1060 696 1060 696 1061 642 1061 644 1061 696 1062 644 1062 686 1062 697 1063 640 1063 617 1063 697 1064 617 1064 698 1064 698 1065 617 1065 699 1065 699 1066 617 1066 619 1066 699 1067 619 1067 620 1067 699 1068 620 1068 700 1068 700 1069 620 1069 701 1069 701 1070 620 1070 623 1070 701 1071 623 1071 702 1071 702 1072 623 1072 625 1072 702 1073 625 1073 703 1073 703 1074 625 1074 628 1074 703 1075 628 1075 704 1075 704 1076 628 1076 630 1076 704 1077 630 1077 705 1077 705 1078 630 1078 632 1078 705 1079 632 1079 706 1079 706 1080 632 1080 634 1080 706 1081 634 1081 707 1081 707 1082 634 1082 636 1082 707 1083 636 1083 708 1083 708 1084 636 1084 638 1084 708 1085 638 1085 697 1085 697 1086 638 1086 640 1086 720 1087 680 1087 682 1087 720 1088 682 1088 709 1088 709 1089 682 1089 684 1089 709 1090 684 1090 710 1090 710 1091 684 1091 711 1091 711 1092 684 1092 664 1092 711 1093 664 1093 712 1093 712 1094 664 1094 666 1094 712 1095 666 1095 713 1095 713 1096 666 1096 714 1096 714 1097 666 1097 669 1097 714 1098 669 1098 715 1098 715 1099 669 1099 671 1099 715 1100 671 1100 716 1100 716 1101 671 1101 673 1101 716 1102 673 1102 717 1102 717 1103 673 1103 674 1103 717 1104 674 1104 718 1104 718 1105 674 1105 676 1105 718 1106 676 1106 719 1106 719 1107 676 1107 678 1107 719 1108 678 1108 720 1108 720 1109 678 1109 680 1109 721 1110 724 1110 722 1110 723 1111 725 1111 724 1111 725 1112 726 1112 724 1112 726 1113 727 1113 724 1113 724 1114 727 1114 722 1114 721 1115 722 1115 728 1115 729 1116 730 1116 724 1116 724 1117 730 1117 731 1117 724 1118 731 1118 723 1118 728 1119 732 1119 721 1119 732 1120 733 1120 721 1120 550 1121 745 1121 734 1121 550 1122 734 1122 735 1122 550 1123 735 1123 549 1123 549 1124 735 1124 559 1124 559 1125 735 1125 736 1125 559 1126 736 1126 737 1126 559 1127 737 1127 558 1127 558 1128 737 1128 738 1128 558 1129 738 1129 557 1129 557 1130 738 1130 556 1130 556 1131 738 1131 739 1131 556 1132 739 1132 740 1132 556 1133 740 1133 555 1133 555 1134 740 1134 741 1134 555 1135 741 1135 554 1135 554 1136 741 1136 553 1136 553 1137 741 1137 742 1137 553 1138 742 1138 743 1138 553 1139 743 1139 552 1139 552 1140 743 1140 744 1140 552 1141 744 1141 551 1141 551 1142 744 1142 745 1142 551 1143 745 1143 550 1143 568 1144 746 1144 747 1144 568 1145 747 1145 567 1145 567 1146 747 1146 748 1146 567 1147 748 1147 566 1147 566 1148 748 1148 749 1148 566 1149 749 1149 565 1149 565 1150 749 1150 750 1150 565 1151 750 1151 751 1151 565 1152 751 1152 564 1152 564 1153 751 1153 752 1153 564 1154 752 1154 563 1154 563 1155 752 1155 753 1155 563 1156 753 1156 754 1156 563 1157 754 1157 562 1157 562 1158 754 1158 755 1158 562 1159 755 1159 561 1159 561 1160 755 1160 756 1160 561 1161 756 1161 560 1161 560 1162 756 1162 757 1162 560 1163 757 1163 570 1163 570 1164 757 1164 758 1164 570 1165 758 1165 569 1165 569 1166 758 1166 759 1166 569 1167 759 1167 568 1167 568 1168 759 1168 746 1168 760 1169 762 1169 761 1169 761 1170 762 1170 763 1170 761 1171 763 1171 764 1171 761 1172 764 1172 765 1172 761 1173 766 1173 760 1173 761 1174 765 1174 769 1174 761 1175 769 1175 770 1175 760 1176 766 1176 768 1176 768 1177 766 1177 767 1177 768 1178 767 1178 771 1178 580 1179 783 1179 772 1179 580 1180 772 1180 581 1180 581 1181 772 1181 773 1181 581 1182 773 1182 774 1182 581 1183 774 1183 571 1183 571 1184 774 1184 775 1184 571 1185 775 1185 572 1185 572 1186 775 1186 776 1186 572 1187 776 1187 573 1187 573 1188 776 1188 777 1188 573 1189 777 1189 574 1189 574 1190 777 1190 778 1190 574 1191 778 1191 575 1191 575 1192 778 1192 779 1192 575 1193 779 1193 576 1193 576 1194 779 1194 780 1194 576 1195 780 1195 577 1195 577 1196 780 1196 781 1196 577 1197 781 1197 578 1197 578 1198 781 1198 782 1198 578 1199 782 1199 579 1199 579 1200 782 1200 783 1200 579 1201 783 1201 580 1201 591 1202 784 1202 592 1202 592 1203 784 1203 785 1203 592 1204 785 1204 582 1204 582 1205 785 1205 786 1205 582 1206 786 1206 787 1206 582 1207 787 1207 583 1207 583 1208 787 1208 788 1208 583 1209 788 1209 584 1209 584 1210 788 1210 789 1210 584 1211 789 1211 585 1211 585 1212 789 1212 790 1212 585 1213 790 1213 586 1213 586 1214 790 1214 791 1214 586 1215 791 1215 587 1215 587 1216 791 1216 792 1216 587 1217 792 1217 588 1217 588 1218 792 1218 793 1218 588 1219 793 1219 589 1219 589 1220 793 1220 590 1220 590 1221 793 1221 794 1221 590 1222 794 1222 591 1222 591 1223 794 1223 784 1223 601 1224 796 1224 595 1224 595 1225 796 1225 795 1225 595 1226 795 1226 797 1226 595 1227 797 1227 616 1227 616 1228 797 1228 799 1228 616 1229 799 1229 800 1229 616 1230 800 1230 596 1230 596 1231 800 1231 798 1231 596 1232 798 1232 597 1232 597 1233 798 1233 801 1233 597 1234 801 1234 615 1234 615 1235 801 1235 614 1235 614 1236 801 1236 802 1236 614 1237 802 1237 613 1237 802 1238 803 1238 613 1238 613 1239 803 1239 611 1239 611 1240 803 1240 804 1240 611 1241 804 1241 612 1241 612 1242 804 1242 805 1242 612 1243 805 1243 609 1243 805 1244 806 1244 609 1244 609 1245 806 1245 610 1245 610 1246 806 1246 807 1246 610 1247 807 1247 808 1247 610 1248 808 1248 598 1248 808 1249 809 1249 598 1249 598 1250 809 1250 810 1250 598 1251 810 1251 606 1251 606 1252 810 1252 607 1252 607 1253 810 1253 811 1253 607 1254 811 1254 599 1254 599 1255 811 1255 812 1255 599 1256 812 1256 605 1256 605 1257 812 1257 813 1257 605 1258 813 1258 814 1258 605 1259 814 1259 603 1259 603 1260 814 1260 815 1260 603 1261 815 1261 604 1261 604 1262 815 1262 816 1262 816 1263 817 1263 604 1263 604 1264 817 1264 602 1264 602 1265 817 1265 818 1265 602 1266 818 1266 600 1266 600 1267 818 1267 819 1267 600 1268 819 1268 601 1268 601 1269 819 1269 796 1269 639 1270 830 1270 820 1270 639 1271 820 1271 641 1271 641 1272 820 1272 821 1272 641 1273 821 1273 618 1273 618 1274 821 1274 822 1274 618 1275 822 1275 621 1275 621 1276 822 1276 823 1276 621 1277 823 1277 622 1277 622 1278 823 1278 824 1278 622 1279 824 1279 624 1279 624 1280 824 1280 626 1280 626 1281 824 1281 825 1281 626 1282 825 1282 627 1282 627 1283 825 1283 826 1283 627 1284 826 1284 629 1284 629 1285 826 1285 631 1285 631 1286 826 1286 827 1286 631 1287 827 1287 633 1287 633 1288 827 1288 828 1288 633 1289 828 1289 635 1289 635 1290 828 1290 829 1290 635 1291 829 1291 637 1291 637 1292 829 1292 830 1292 637 1293 830 1293 639 1293 645 1294 842 1294 831 1294 645 1295 831 1295 646 1295 646 1296 831 1296 648 1296 648 1297 831 1297 832 1297 648 1298 832 1298 833 1298 648 1299 833 1299 650 1299 650 1300 833 1300 834 1300 650 1301 834 1301 652 1301 652 1302 834 1302 835 1302 652 1303 835 1303 654 1303 654 1304 835 1304 836 1304 654 1305 836 1305 656 1305 656 1306 836 1306 837 1306 656 1307 837 1307 658 1307 658 1308 837 1308 838 1308 658 1309 838 1309 660 1309 660 1310 838 1310 839 1310 660 1311 839 1311 661 1311 661 1312 839 1312 840 1312 661 1313 840 1313 841 1313 661 1314 841 1314 663 1314 663 1315 841 1315 643 1315 643 1316 841 1316 842 1316 643 1317 842 1317 645 1317 681 1318 843 1318 683 1318 683 1319 843 1319 844 1319 683 1320 844 1320 845 1320 683 1321 845 1321 685 1321 685 1322 845 1322 846 1322 685 1323 846 1323 847 1323 685 1324 847 1324 665 1324 665 1325 847 1325 848 1325 665 1326 848 1326 667 1326 667 1327 848 1327 668 1327 668 1328 848 1328 849 1328 668 1329 849 1329 670 1329 670 1330 849 1330 850 1330 670 1331 850 1331 672 1331 672 1332 850 1332 851 1332 672 1333 851 1333 675 1333 675 1334 851 1334 852 1334 675 1335 852 1335 677 1335 677 1336 852 1336 853 1336 677 1337 853 1337 854 1337 677 1338 854 1338 679 1338 679 1339 854 1339 681 1339 681 1340 854 1340 843 1340 692 1341 866 1341 691 1341 691 1342 866 1342 855 1342 691 1343 855 1343 690 1343 690 1344 855 1344 856 1344 690 1345 856 1345 857 1345 690 1346 857 1346 689 1346 689 1347 857 1347 858 1347 689 1348 858 1348 688 1348 688 1349 858 1349 859 1349 688 1350 859 1350 687 1350 687 1351 859 1351 860 1351 687 1352 860 1352 686 1352 686 1353 860 1353 861 1353 686 1354 861 1354 696 1354 696 1355 861 1355 862 1355 696 1356 862 1356 695 1356 695 1357 862 1357 863 1357 695 1358 863 1358 694 1358 694 1359 863 1359 864 1359 694 1360 864 1360 693 1360 693 1361 864 1361 865 1361 693 1362 865 1362 692 1362 692 1363 865 1363 866 1363 867 1364 871 1364 872 1364 868 1365 867 1365 872 1365 868 1366 872 1366 870 1366 869 1367 868 1367 870 1367 871 1368 32 1368 873 1368 852 1369 872 1369 873 1369 873 1370 872 1370 871 1370 874 1371 877 1371 876 1371 875 1372 874 1372 876 1372 875 1373 876 1373 873 1373 32 1374 875 1374 873 1374 700 1375 878 1375 699 1375 699 1376 878 1376 879 1376 699 1377 879 1377 698 1377 698 1378 879 1378 880 1378 698 1379 880 1379 697 1379 697 1380 880 1380 881 1380 697 1381 881 1381 708 1381 708 1382 881 1382 882 1382 708 1383 882 1383 707 1383 707 1384 882 1384 883 1384 707 1385 883 1385 706 1385 706 1386 883 1386 884 1386 706 1387 884 1387 705 1387 705 1388 884 1388 885 1388 705 1389 885 1389 886 1389 705 1390 886 1390 704 1390 704 1391 886 1391 703 1391 703 1392 886 1392 887 1392 703 1393 887 1393 702 1393 702 1394 887 1394 888 1394 702 1395 888 1395 701 1395 701 1396 888 1396 889 1396 701 1397 889 1397 700 1397 700 1398 889 1398 878 1398 711 1399 890 1399 891 1399 711 1400 891 1400 710 1400 710 1401 891 1401 892 1401 710 1402 892 1402 709 1402 709 1403 892 1403 893 1403 709 1404 893 1404 720 1404 720 1405 893 1405 894 1405 720 1406 894 1406 895 1406 720 1407 895 1407 719 1407 719 1408 895 1408 896 1408 719 1409 896 1409 718 1409 718 1410 896 1410 717 1410 717 1411 896 1411 897 1411 717 1412 897 1412 716 1412 716 1413 897 1413 898 1413 716 1414 898 1414 899 1414 716 1415 899 1415 715 1415 715 1416 899 1416 900 1416 715 1417 900 1417 714 1417 714 1418 900 1418 901 1418 714 1419 901 1419 713 1419 713 1420 901 1420 902 1420 713 1421 902 1421 712 1421 712 1422 902 1422 711 1422 711 1423 902 1423 890 1423 903 1424 41 1424 904 1424 904 1425 41 1425 40 1425 905 1426 735 1426 906 1426 906 1427 735 1427 734 1427 906 1428 734 1428 907 1428 907 1429 734 1429 745 1429 907 1430 745 1430 908 1430 908 1431 745 1431 744 1431 908 1432 744 1432 909 1432 909 1433 744 1433 743 1433 909 1434 743 1434 910 1434 910 1435 743 1435 742 1435 910 1436 742 1436 911 1436 911 1437 742 1437 741 1437 911 1438 741 1438 912 1438 912 1439 741 1439 740 1439 912 1440 740 1440 913 1440 913 1441 740 1441 739 1441 913 1442 739 1442 914 1442 914 1443 739 1443 738 1443 914 1444 738 1444 915 1444 915 1445 738 1445 737 1445 915 1446 737 1446 916 1446 916 1447 737 1447 736 1447 916 1448 736 1448 905 1448 905 1449 736 1449 735 1449 917 1450 756 1450 918 1450 918 1451 756 1451 755 1451 918 1452 755 1452 919 1452 919 1453 755 1453 754 1453 919 1454 754 1454 920 1454 920 1455 754 1455 753 1455 920 1456 753 1456 752 1456 920 1457 752 1457 921 1457 921 1458 752 1458 751 1458 921 1459 751 1459 922 1459 922 1460 751 1460 750 1460 922 1461 750 1461 923 1461 923 1462 750 1462 749 1462 923 1463 749 1463 748 1463 923 1464 748 1464 924 1464 924 1465 748 1465 747 1465 924 1466 747 1466 746 1466 924 1467 746 1467 925 1467 925 1468 746 1468 759 1468 925 1469 759 1469 926 1469 926 1470 759 1470 758 1470 926 1471 758 1471 927 1471 927 1472 758 1472 917 1472 917 1473 758 1473 757 1473 917 1474 757 1474 756 1474 932 1475 930 1475 929 1475 933 1476 930 1476 932 1476 933 1477 932 1477 934 1477 931 1478 933 1478 934 1478 931 1479 934 1479 928 1479 155 1480 937 1480 939 1480 937 1481 936 1481 935 1481 939 1482 937 1482 940 1482 940 1483 937 1483 935 1483 939 1484 940 1484 938 1484 27 1485 56 1485 6 1485 27 1486 6 1486 7 1486 941 1487 876 1487 877 1487 941 1488 877 1488 942 1488 943 1489 944 1489 945 1489 945 1490 944 1490 946 1490 947 1491 782 1491 781 1491 947 1492 781 1492 948 1492 948 1493 781 1493 780 1493 947 1494 783 1494 782 1494 946 1495 774 1495 773 1495 774 1496 946 1496 944 1496 774 1497 944 1497 775 1497 778 1498 948 1498 779 1498 946 1499 773 1499 772 1499 946 1500 772 1500 783 1500 946 1501 783 1501 947 1501 948 1502 780 1502 779 1502 777 1503 776 1503 944 1503 948 1504 778 1504 777 1504 948 1505 777 1505 944 1505 776 1506 775 1506 944 1506 949 1507 950 1507 951 1507 951 1508 950 1508 952 1508 953 1509 793 1509 954 1509 954 1510 793 1510 792 1510 784 1511 794 1511 953 1511 790 1512 789 1512 950 1512 953 1513 794 1513 793 1513 952 1514 786 1514 785 1514 785 1515 784 1515 952 1515 952 1516 784 1516 953 1516 954 1517 792 1517 791 1517 950 1518 789 1518 788 1518 786 1519 952 1519 787 1519 787 1520 952 1520 950 1520 791 1521 790 1521 954 1521 954 1522 790 1522 950 1522 950 1523 788 1523 787 1523 963 1524 955 1524 956 1524 956 1525 955 1525 957 1525 959 1526 955 1526 960 1526 958 1527 957 1527 955 1527 955 1528 959 1528 958 1528 961 1529 956 1529 962 1529 961 1530 963 1530 956 1530 961 1531 962 1531 965 1531 961 1532 965 1532 966 1532 960 1533 964 1533 959 1533 967 1534 968 1534 969 1534 969 1535 968 1535 970 1535 969 1536 970 1536 971 1536 972 1537 977 1537 976 1537 972 1538 976 1538 975 1538 973 1539 972 1539 978 1539 978 1540 972 1540 975 1540 978 1541 974 1541 973 1541 980 1542 979 1542 984 1542 982 1543 981 1543 980 1543 982 1544 980 1544 984 1544 983 1545 982 1545 984 1545 813 1546 985 1546 814 1546 813 1547 986 1547 985 1547 812 1548 986 1548 813 1548 986 1549 812 1549 987 1549 812 1550 811 1550 987 1550 987 1551 811 1551 988 1551 988 1552 811 1552 810 1552 988 1553 810 1553 989 1553 989 1554 810 1554 809 1554 989 1555 809 1555 990 1555 809 1556 808 1556 990 1556 808 1557 807 1557 990 1557 990 1558 807 1558 991 1558 991 1559 807 1559 806 1559 991 1560 806 1560 992 1560 806 1561 805 1561 992 1561 992 1562 805 1562 993 1562 993 1563 805 1563 804 1563 993 1564 804 1564 994 1564 994 1565 804 1565 803 1565 994 1566 803 1566 995 1566 803 1567 802 1567 995 1567 995 1568 802 1568 996 1568 996 1569 802 1569 801 1569 996 1570 801 1570 997 1570 997 1571 801 1571 798 1571 997 1572 798 1572 998 1572 798 1573 800 1573 998 1573 998 1574 800 1574 999 1574 999 1575 800 1575 799 1575 999 1576 799 1576 797 1576 999 1577 797 1577 1000 1577 797 1578 795 1578 1000 1578 1000 1579 795 1579 1001 1579 1001 1580 795 1580 796 1580 1001 1581 796 1581 1002 1581 796 1582 819 1582 1002 1582 1002 1583 819 1583 818 1583 1002 1584 818 1584 1003 1584 818 1585 817 1585 1003 1585 1003 1586 817 1586 1004 1586 817 1587 816 1587 1004 1587 1004 1588 816 1588 1005 1588 814 1589 985 1589 815 1589 815 1590 985 1590 1005 1590 815 1591 1005 1591 816 1591 1006 1592 1009 1592 1010 1592 1010 1593 1009 1593 202 1593 1007 1594 1006 1594 1010 1594 1007 1595 1010 1595 1008 1595 1012 1596 1011 1596 1015 1596 1013 1597 1012 1597 1016 1597 1016 1598 1012 1598 1015 1598 1013 1599 1016 1599 1014 1599 1002 1600 1017 1600 1001 1600 847 1601 993 1601 994 1601 825 1602 824 1602 1018 1602 1018 1603 824 1603 1017 1603 997 1604 998 1604 833 1604 833 1605 998 1605 834 1605 834 1606 998 1606 999 1606 834 1607 999 1607 1000 1607 847 1608 992 1608 993 1608 840 1609 851 1609 841 1609 870 1610 826 1610 1018 1610 1018 1611 826 1611 825 1611 824 1612 823 1612 1017 1612 1017 1613 823 1613 1001 1613 1001 1614 823 1614 1000 1614 1002 1615 1003 1615 1017 1615 1017 1616 1003 1616 1013 1616 1013 1617 1003 1617 1004 1617 1000 1618 823 1618 822 1618 994 1619 995 1619 847 1619 847 1620 995 1620 996 1620 847 1621 996 1621 848 1621 848 1622 996 1622 997 1622 844 1623 843 1623 941 1623 872 1624 839 1624 838 1624 1004 1625 1005 1625 1012 1625 1012 1626 1005 1626 985 1626 834 1627 1000 1627 835 1627 835 1628 1000 1628 822 1628 835 1629 822 1629 821 1629 997 1630 833 1630 832 1630 838 1631 828 1631 827 1631 838 1632 827 1632 872 1632 826 1633 870 1633 872 1633 848 1634 997 1634 832 1634 848 1635 832 1635 849 1635 1176 1636 845 1636 941 1636 941 1637 845 1637 844 1637 852 1638 873 1638 853 1638 853 1639 873 1639 876 1639 872 1640 852 1640 839 1640 839 1641 852 1641 851 1641 839 1642 851 1642 840 1642 851 1643 850 1643 841 1643 821 1644 820 1644 836 1644 826 1645 872 1645 827 1645 981 1646 982 1646 988 1646 941 1647 843 1647 854 1647 941 1648 854 1648 876 1648 849 1649 832 1649 831 1649 849 1650 831 1650 842 1650 849 1651 842 1651 850 1651 850 1652 842 1652 841 1652 835 1653 821 1653 836 1653 838 1654 837 1654 828 1654 828 1655 837 1655 829 1655 829 1656 837 1656 836 1656 986 1657 987 1657 982 1657 982 1658 987 1658 988 1658 853 1659 876 1659 854 1659 836 1660 820 1660 830 1660 836 1661 830 1661 829 1661 1012 1662 1013 1662 1004 1662 989 1663 981 1663 988 1663 981 1664 989 1664 1176 1664 1176 1665 989 1665 990 1665 1176 1666 990 1666 991 1666 1176 1667 991 1667 992 1667 992 1668 847 1668 846 1668 992 1669 846 1669 1176 1669 1176 1670 846 1670 845 1670 109 1671 869 1671 870 1671 109 1672 870 1672 1018 1672 728 1673 861 1673 732 1673 732 1674 861 1674 860 1674 732 1675 860 1675 733 1675 733 1676 860 1676 859 1676 733 1677 859 1677 721 1677 721 1678 859 1678 858 1678 721 1679 858 1679 724 1679 724 1680 858 1680 857 1680 724 1681 857 1681 729 1681 729 1682 857 1682 730 1682 730 1683 857 1683 856 1683 730 1684 856 1684 855 1684 730 1685 855 1685 731 1685 731 1686 855 1686 866 1686 731 1687 866 1687 723 1687 723 1688 866 1688 865 1688 723 1689 865 1689 725 1689 725 1690 865 1690 864 1690 725 1691 864 1691 726 1691 726 1692 864 1692 727 1692 727 1693 864 1693 863 1693 727 1694 863 1694 722 1694 722 1695 863 1695 862 1695 722 1696 862 1696 728 1696 728 1697 862 1697 861 1697 8 1698 57 1698 51 1698 51 1699 57 1699 62 1699 51 1700 62 1700 47 1700 47 1701 62 1701 48 1701 48 1702 62 1702 60 1702 48 1703 60 1703 52 1703 33 1704 871 1704 867 1704 867 1705 868 1705 33 1705 33 1706 868 1706 1019 1706 869 1707 1019 1707 868 1707 877 1708 874 1708 1020 1708 874 1709 875 1709 1020 1709 1020 1710 875 1710 31 1710 31 1711 875 1711 32 1711 1021 1712 18 1712 88 1712 88 1713 18 1713 13 1713 88 1714 13 1714 12 1714 18 1715 1021 1715 1022 1715 18 1716 1022 1716 19 1716 19 1717 1022 1717 1023 1717 19 1718 1023 1718 1 1718 887 1719 1024 1719 1025 1719 887 1720 1025 1720 1026 1720 887 1721 1026 1721 888 1721 888 1722 1026 1722 1027 1722 888 1723 1027 1723 889 1723 889 1724 1027 1724 1028 1724 889 1725 1028 1725 878 1725 878 1726 1028 1726 1029 1726 878 1727 1029 1727 879 1727 879 1728 1029 1728 880 1728 880 1729 1029 1729 1030 1729 880 1730 1030 1730 881 1730 881 1731 1030 1731 1031 1731 881 1732 1031 1732 882 1732 882 1733 1031 1733 1032 1733 882 1734 1032 1734 883 1734 883 1735 1032 1735 1033 1735 883 1736 1033 1736 884 1736 884 1737 1033 1737 1034 1737 884 1738 1034 1738 885 1738 885 1739 1034 1739 1035 1739 885 1740 1035 1740 886 1740 886 1741 1035 1741 1024 1741 886 1742 1024 1742 887 1742 900 1743 1036 1743 1037 1743 900 1744 1037 1744 901 1744 901 1745 1037 1745 1038 1745 901 1746 1038 1746 902 1746 902 1747 1038 1747 1039 1747 902 1748 1039 1748 890 1748 890 1749 1039 1749 1040 1749 890 1750 1040 1750 891 1750 891 1751 1040 1751 1041 1751 891 1752 1041 1752 892 1752 892 1753 1041 1753 1042 1753 892 1754 1042 1754 893 1754 893 1755 1042 1755 894 1755 894 1756 1042 1756 1043 1756 894 1757 1043 1757 895 1757 895 1758 1043 1758 1044 1758 895 1759 1044 1759 896 1759 896 1760 1044 1760 1045 1760 896 1761 1045 1761 897 1761 897 1762 1045 1762 898 1762 898 1763 1045 1763 1046 1763 898 1764 1046 1764 899 1764 899 1765 1046 1765 1036 1765 899 1766 1036 1766 900 1766 41 1767 903 1767 44 1767 44 1768 903 1768 1047 1768 1048 1769 771 1769 1049 1769 1049 1770 771 1770 767 1770 1049 1771 767 1771 1050 1771 1050 1772 767 1772 766 1772 1050 1773 766 1773 761 1773 1050 1774 761 1774 1051 1774 1051 1775 761 1775 1052 1775 1052 1776 761 1776 770 1776 1052 1777 770 1777 1053 1777 1053 1778 770 1778 769 1778 1053 1779 769 1779 1054 1779 1054 1780 769 1780 765 1780 1054 1781 765 1781 1055 1781 1055 1782 765 1782 764 1782 1055 1783 764 1783 763 1783 1055 1784 763 1784 1056 1784 1056 1785 763 1785 762 1785 1056 1786 762 1786 1057 1786 1057 1787 762 1787 760 1787 1057 1788 760 1788 1058 1788 1058 1789 760 1789 1059 1789 1059 1790 760 1790 768 1790 1059 1791 768 1791 1048 1791 1048 1792 768 1792 771 1792 67 1793 40 1793 39 1793 67 1794 39 1794 65 1794 65 1795 39 1795 43 1795 65 1796 43 1796 70 1796 70 1797 43 1797 68 1797 68 1798 43 1798 35 1798 68 1799 35 1799 34 1799 22 1800 1060 1800 23 1800 23 1801 1060 1801 78 1801 23 1802 78 1802 28 1802 1060 1803 22 1803 26 1803 1060 1804 26 1804 1061 1804 1061 1805 26 1805 5 1805 1062 1806 1063 1806 1064 1806 1064 1807 1063 1807 1065 1807 1064 1808 1065 1808 1066 1808 1066 1809 1065 1809 1067 1809 1066 1810 1067 1810 1068 1810 1068 1811 1067 1811 1069 1811 1069 1812 1067 1812 1070 1812 1069 1813 1070 1813 1071 1813 1069 1814 1071 1814 1072 1814 1072 1815 1071 1815 1073 1815 1073 1816 1071 1816 1074 1816 1073 1817 1074 1817 1075 1817 1075 1818 1074 1818 1076 1818 1075 1819 1076 1819 1077 1819 1077 1820 1076 1820 1078 1820 1077 1821 1078 1821 1079 1821 1079 1822 1078 1822 1080 1822 1079 1823 1080 1823 1081 1823 1081 1824 1080 1824 1082 1824 1081 1825 1082 1825 1083 1825 1081 1826 1083 1826 1062 1826 1062 1827 1083 1827 1063 1827 1084 1828 1085 1828 1086 1828 1084 1829 1086 1829 1087 1829 1087 1830 1086 1830 1088 1830 1087 1831 1088 1831 1089 1831 1089 1832 1088 1832 1090 1832 1089 1833 1090 1833 1091 1833 1091 1834 1090 1834 1092 1834 1091 1835 1092 1835 1093 1835 1091 1836 1093 1836 1094 1836 1094 1837 1093 1837 1095 1837 1094 1838 1095 1838 1096 1838 1096 1839 1095 1839 1097 1839 1096 1840 1097 1840 1098 1840 1098 1841 1097 1841 1099 1841 1098 1842 1099 1842 1100 1842 1098 1843 1100 1843 1101 1843 1101 1844 1100 1844 1102 1844 1102 1845 1100 1845 1103 1845 1102 1846 1103 1846 1104 1846 1104 1847 1103 1847 1105 1847 1104 1848 1105 1848 1106 1848 1106 1849 1105 1849 1107 1849 1106 1850 1107 1850 1108 1850 1108 1851 1107 1851 1085 1851 1108 1852 1085 1852 1084 1852 1109 1853 1110 1853 1111 1853 1111 1854 1110 1854 1112 1854 1110 1855 908 1855 1112 1855 1112 1856 908 1856 909 1856 913 1857 1113 1857 912 1857 1114 1858 916 1858 905 1858 1114 1859 915 1859 916 1859 1110 1860 907 1860 908 1860 1112 1861 909 1861 910 1861 1112 1862 910 1862 911 1862 1114 1863 905 1863 1110 1863 1110 1864 905 1864 906 1864 1110 1865 906 1865 907 1865 913 1866 914 1866 1113 1866 1113 1867 914 1867 1114 1867 1114 1868 914 1868 915 1868 1112 1869 911 1869 912 1869 1112 1870 912 1870 1113 1870 1115 1871 1116 1871 1117 1871 1117 1872 1116 1872 1118 1872 1119 1873 917 1873 1116 1873 1116 1874 917 1874 918 1874 918 1875 919 1875 1116 1875 924 1876 1120 1876 923 1876 1120 1877 924 1877 925 1877 920 1878 921 1878 1118 1878 919 1879 920 1879 1116 1879 1116 1880 920 1880 1118 1880 1118 1881 921 1881 922 1881 922 1882 923 1882 1118 1882 1118 1883 923 1883 1120 1883 1120 1884 925 1884 1119 1884 1119 1885 925 1885 926 1885 1119 1886 926 1886 927 1886 1119 1887 927 1887 917 1887 1121 1888 1122 1888 1123 1888 1123 1889 1124 1889 1121 1889 1121 1890 1125 1890 1126 1890 1123 1891 1122 1891 1127 1891 1129 1892 1128 1892 1130 1892 1123 1893 1127 1893 1129 1893 1124 1894 1125 1894 1121 1894 1126 1895 1131 1895 1121 1895 1129 1896 1127 1896 1128 1896 1132 1897 1133 1897 1134 1897 1134 1898 1133 1898 1135 1898 1134 1899 1135 1899 1136 1899 1137 1900 1064 1900 1066 1900 1137 1901 1066 1901 1138 1901 1138 1902 1066 1902 1068 1902 1138 1903 1068 1903 1139 1903 1139 1904 1068 1904 1069 1904 1139 1905 1069 1905 1072 1905 1139 1906 1072 1906 1140 1906 1140 1907 1072 1907 1073 1907 1140 1908 1073 1908 1141 1908 1141 1909 1073 1909 1142 1909 1142 1910 1073 1910 1075 1910 1142 1911 1075 1911 1143 1911 1143 1912 1075 1912 1077 1912 1143 1913 1077 1913 1144 1913 1144 1914 1077 1914 1079 1914 1144 1915 1079 1915 1145 1915 1145 1916 1079 1916 1081 1916 1145 1917 1081 1917 1146 1917 1146 1918 1081 1918 1062 1918 1146 1919 1062 1919 1147 1919 1147 1920 1062 1920 1064 1920 1147 1921 1064 1921 1137 1921 1159 1922 1059 1922 1148 1922 1148 1923 1059 1923 1048 1923 1148 1924 1048 1924 1149 1924 1149 1925 1048 1925 1049 1925 1149 1926 1049 1926 1150 1926 1150 1927 1049 1927 1050 1927 1150 1928 1050 1928 1151 1928 1151 1929 1050 1929 1051 1929 1151 1930 1051 1930 1152 1930 1152 1931 1051 1931 1052 1931 1152 1932 1052 1932 1153 1932 1153 1933 1052 1933 1053 1933 1153 1934 1053 1934 1154 1934 1154 1935 1053 1935 1155 1935 1155 1936 1053 1936 1054 1936 1155 1937 1054 1937 1156 1937 1156 1938 1054 1938 1055 1938 1156 1939 1055 1939 1157 1939 1157 1940 1055 1940 1056 1940 1157 1941 1056 1941 1158 1941 1158 1942 1056 1942 1057 1942 1158 1943 1057 1943 1058 1943 1158 1944 1058 1944 1159 1944 1159 1945 1058 1945 1059 1945 1160 1946 1091 1946 1161 1946 1161 1947 1091 1947 1094 1947 1161 1948 1094 1948 1162 1948 1162 1949 1094 1949 1096 1949 1162 1950 1096 1950 1163 1950 1163 1951 1096 1951 1164 1951 1164 1952 1096 1952 1098 1952 1164 1953 1098 1953 1165 1953 1165 1954 1098 1954 1101 1954 1165 1955 1101 1955 1102 1955 1165 1956 1102 1956 1166 1956 1166 1957 1102 1957 1104 1957 1166 1958 1104 1958 1167 1958 1167 1959 1104 1959 1106 1959 1167 1960 1106 1960 1168 1960 1168 1961 1106 1961 1108 1961 1168 1962 1108 1962 1169 1962 1169 1963 1108 1963 1084 1963 1169 1964 1084 1964 1170 1964 1170 1965 1084 1965 1087 1965 1170 1966 1087 1966 1171 1966 1171 1967 1087 1967 1089 1967 1171 1968 1089 1968 1160 1968 1160 1969 1089 1969 1091 1969 929 1970 1172 1970 932 1970 932 1971 1172 1971 1173 1971 932 1972 1173 1972 934 1972 934 1973 1173 1973 928 1973 936 1974 1174 1974 935 1974 935 1975 1174 1975 940 1975 940 1976 1174 1976 1175 1976 940 1977 1175 1977 938 1977 1176 1978 941 1978 1177 1978 941 1979 942 1979 1177 1979 28 1980 78 1980 77 1980 28 1981 77 1981 1178 1981 76 1982 1179 1982 77 1982 77 1983 1179 1983 1178 1983 20 1984 21 1984 17 1984 17 1985 21 1985 1180 1985 1181 1986 90 1986 1182 1986 1182 1987 90 1987 89 1987 1182 1988 89 1988 12 1988 12 1989 89 1989 88 1989 877 1990 1020 1990 942 1990 942 1991 1020 1991 86 1991 947 1992 72 1992 946 1992 946 1993 72 1993 97 1993 946 1994 97 1994 945 1994 943 1995 945 1995 96 1995 96 1996 945 1996 97 1996 943 1997 96 1997 944 1997 944 1998 96 1998 84 1998 944 1999 84 1999 948 1999 948 2000 84 2000 947 2000 947 2001 84 2001 72 2001 953 2002 85 2002 952 2002 952 2003 85 2003 95 2003 952 2004 95 2004 951 2004 949 2005 951 2005 82 2005 82 2006 951 2006 95 2006 949 2007 82 2007 950 2007 950 2008 82 2008 81 2008 950 2009 81 2009 954 2009 85 2010 953 2010 81 2010 81 2011 953 2011 954 2011 961 2012 92 2012 963 2012 963 2013 92 2013 105 2013 963 2014 105 2014 955 2014 955 2015 105 2015 106 2015 955 2016 106 2016 960 2016 960 2017 106 2017 107 2017 960 2018 107 2018 964 2018 964 2019 107 2019 104 2019 964 2020 104 2020 959 2020 959 2021 104 2021 99 2021 959 2022 99 2022 958 2022 958 2023 99 2023 102 2023 958 2024 102 2024 957 2024 957 2025 102 2025 100 2025 957 2026 100 2026 956 2026 956 2027 100 2027 103 2027 956 2028 103 2028 962 2028 962 2029 103 2029 101 2029 962 2030 101 2030 965 2030 965 2031 101 2031 98 2031 965 2032 98 2032 966 2032 966 2033 98 2033 93 2033 966 2034 93 2034 961 2034 961 2035 93 2035 92 2035 971 2036 84 2036 969 2036 969 2037 84 2037 83 2037 74 2038 968 2038 75 2038 75 2039 968 2039 967 2039 94 2040 970 2040 74 2040 74 2041 970 2041 968 2041 84 2042 971 2042 94 2042 94 2043 971 2043 970 2043 1177 2044 979 2044 980 2044 1177 2045 980 2045 1176 2045 1176 2046 980 2046 981 2046 979 2047 977 2047 972 2047 979 2048 972 2048 984 2048 984 2049 972 2049 973 2049 984 2050 973 2050 983 2050 983 2051 973 2051 974 2051 1011 2052 985 2052 986 2052 986 2053 982 2053 983 2053 983 2054 1011 2054 986 2054 985 2055 1011 2055 1012 2055 1011 2056 1009 2056 1015 2056 1015 2057 1009 2057 1006 2057 1015 2058 1006 2058 1016 2058 1016 2059 1006 2059 1007 2059 1016 2060 1007 2060 1014 2060 1014 2061 1007 2061 1008 2061 1017 2062 1013 2062 1183 2062 1183 2063 1013 2063 1014 2063 109 2064 1018 2064 1183 2064 1183 2065 1018 2065 1017 2065 109 2066 108 2066 869 2066 869 2067 108 2067 1019 2067 88 2068 87 2068 1021 2068 1021 2069 87 2069 1184 2069 1021 2070 1184 2070 1022 2070 1184 2071 1185 2071 1022 2071 1022 2072 1185 2072 1023 2072 52 2073 60 2073 127 2073 52 2074 127 2074 1186 2074 126 2075 1187 2075 127 2075 127 2076 1187 2076 1186 2076 46 2077 45 2077 1188 2077 1188 2078 45 2078 49 2078 1189 2079 123 2079 1190 2079 1190 2080 123 2080 114 2080 1190 2081 114 2081 34 2081 34 2082 114 2082 68 2082 79 2083 78 2083 1191 2083 1191 2084 78 2084 1060 2084 1191 2085 1060 2085 1061 2085 1191 2086 1061 2086 1192 2086 1113 2087 136 2087 1112 2087 1112 2088 136 2088 116 2088 1112 2089 116 2089 1111 2089 1109 2090 1111 2090 129 2090 129 2091 1111 2091 116 2091 1109 2092 129 2092 1110 2092 1110 2093 129 2093 128 2093 1110 2094 128 2094 1114 2094 136 2095 1113 2095 128 2095 128 2096 1113 2096 1114 2096 1120 2097 119 2097 1118 2097 1118 2098 119 2098 120 2098 1118 2099 120 2099 1117 2099 1115 2100 1117 2100 121 2100 121 2101 1117 2101 120 2101 1115 2102 121 2102 1116 2102 1116 2103 121 2103 117 2103 1116 2104 117 2104 1119 2104 1119 2105 117 2105 1120 2105 1120 2106 117 2106 119 2106 140 2107 1122 2107 141 2107 141 2108 1122 2108 1121 2108 141 2109 1121 2109 138 2109 138 2110 1121 2110 1131 2110 138 2111 1131 2111 115 2111 115 2112 1131 2112 1126 2112 115 2113 1126 2113 130 2113 130 2114 1126 2114 1125 2114 130 2115 1125 2115 131 2115 131 2116 1125 2116 134 2116 134 2117 1125 2117 1124 2117 134 2118 1124 2118 139 2118 139 2119 1124 2119 1123 2119 139 2120 1123 2120 132 2120 132 2121 1123 2121 1129 2121 132 2122 1129 2122 133 2122 133 2123 1129 2123 1130 2123 133 2124 1130 2124 135 2124 135 2125 1130 2125 1128 2125 135 2126 1128 2126 137 2126 137 2127 1128 2127 1127 2127 137 2128 1127 2128 140 2128 140 2129 1127 2129 1122 2129 111 2130 110 2130 1134 2130 1134 2131 110 2131 1132 2131 1132 2132 110 2132 1133 2132 1133 2133 110 2133 118 2133 125 2134 1135 2134 118 2134 118 2135 1135 2135 1133 2135 124 2136 1136 2136 125 2136 125 2137 1136 2137 1135 2137 1193 2138 1147 2138 1194 2138 1194 2139 1147 2139 1137 2139 1194 2140 1137 2140 1195 2140 1195 2141 1137 2141 1138 2141 1195 2142 1138 2142 1196 2142 1196 2143 1138 2143 1139 2143 1196 2144 1139 2144 1197 2144 1197 2145 1139 2145 1140 2145 1197 2146 1140 2146 1198 2146 1198 2147 1140 2147 1141 2147 1198 2148 1141 2148 1199 2148 1199 2149 1141 2149 1142 2149 1199 2150 1142 2150 1200 2150 1200 2151 1142 2151 1143 2151 1200 2152 1143 2152 1201 2152 1201 2153 1143 2153 1144 2153 1201 2154 1144 2154 1202 2154 1202 2155 1144 2155 1145 2155 1202 2156 1145 2156 1203 2156 1203 2157 1145 2157 1146 2157 1203 2158 1146 2158 1193 2158 1193 2159 1146 2159 1147 2159 1215 2160 1148 2160 1204 2160 1204 2161 1148 2161 1149 2161 1204 2162 1149 2162 1205 2162 1205 2163 1149 2163 1150 2163 1205 2164 1150 2164 1151 2164 1205 2165 1151 2165 1206 2165 1206 2166 1151 2166 1152 2166 1206 2167 1152 2167 1207 2167 1207 2168 1152 2168 1153 2168 1207 2169 1153 2169 1208 2169 1208 2170 1153 2170 1154 2170 1208 2171 1154 2171 1209 2171 1209 2172 1154 2172 1155 2172 1209 2173 1155 2173 1210 2173 1210 2174 1155 2174 1156 2174 1210 2175 1156 2175 1211 2175 1211 2176 1156 2176 1157 2176 1211 2177 1157 2177 1212 2177 1212 2178 1157 2178 1158 2178 1212 2179 1158 2179 1213 2179 1213 2180 1158 2180 1159 2180 1213 2181 1159 2181 1214 2181 1214 2182 1159 2182 1215 2182 1215 2183 1159 2183 1148 2183 1227 2184 1169 2184 1216 2184 1216 2185 1169 2185 1170 2185 1216 2186 1170 2186 1217 2186 1217 2187 1170 2187 1171 2187 1217 2188 1171 2188 1218 2188 1218 2189 1171 2189 1160 2189 1218 2190 1160 2190 1219 2190 1219 2191 1160 2191 1220 2191 1220 2192 1160 2192 1161 2192 1220 2193 1161 2193 1162 2193 1220 2194 1162 2194 1221 2194 1221 2195 1162 2195 1163 2195 1221 2196 1163 2196 1164 2196 1221 2197 1164 2197 1222 2197 1222 2198 1164 2198 1165 2198 1222 2199 1165 2199 1223 2199 1223 2200 1165 2200 1224 2200 1224 2201 1165 2201 1166 2201 1224 2202 1166 2202 1225 2202 1225 2203 1166 2203 1167 2203 1225 2204 1167 2204 1226 2204 1226 2205 1167 2205 1168 2205 1226 2206 1168 2206 1227 2206 1227 2207 1168 2207 1169 2207 928 2208 1173 2208 1266 2208 1266 2209 1173 2209 113 2209 929 2210 938 2210 1172 2210 1172 2211 938 2211 1175 2211 73 2212 80 2212 936 2212 936 2213 80 2213 1174 2213 1177 2214 1268 2214 979 2214 979 2215 1268 2215 977 2215 983 2216 974 2216 1011 2216 1011 2217 974 2217 1009 2217 1014 2218 1008 2218 1183 2218 1183 2219 1008 2219 122 2219 1193 2220 1194 2220 1228 2220 1229 2221 1199 2221 1200 2221 1229 2222 1200 2222 1230 2222 1230 2223 1200 2223 1231 2223 1195 2224 1196 2224 1232 2224 1231 2225 1200 2225 1201 2225 1231 2226 1201 2226 1233 2226 1233 2227 1201 2227 1202 2227 1233 2228 1202 2228 1203 2228 1233 2229 1203 2229 1234 2229 1234 2230 1203 2230 1235 2230 1235 2231 1203 2231 1193 2231 1235 2232 1193 2232 1228 2232 1228 2233 1194 2233 1236 2233 1236 2234 1194 2234 1195 2234 1236 2235 1195 2235 1232 2235 1198 2236 1237 2236 1238 2236 1198 2237 1238 2237 1197 2237 1197 2238 1238 2238 1239 2238 1199 2239 1229 2239 1237 2239 1199 2240 1237 2240 1198 2240 1232 2241 1196 2241 1239 2241 1239 2242 1196 2242 1197 2242 1205 2243 1206 2243 1241 2243 1240 2244 1204 2244 1242 2244 1242 2245 1204 2245 1205 2245 1242 2246 1205 2246 1241 2246 1241 2247 1206 2247 1243 2247 1206 2248 1207 2248 1243 2248 1243 2249 1207 2249 1244 2249 1244 2250 1207 2250 1208 2250 1244 2251 1208 2251 1245 2251 1246 2252 1210 2252 1211 2252 1246 2253 1211 2253 1247 2253 1247 2254 1211 2254 1212 2254 1247 2255 1212 2255 1248 2255 1248 2256 1212 2256 1213 2256 1248 2257 1213 2257 1249 2257 1249 2258 1213 2258 1214 2258 1249 2259 1214 2259 1250 2259 1250 2260 1214 2260 1215 2260 1250 2261 1215 2261 1251 2261 1251 2262 1215 2262 1204 2262 1251 2263 1204 2263 1240 2263 1208 2264 1209 2264 1245 2264 1245 2265 1209 2265 1252 2265 1252 2266 1209 2266 1210 2266 1252 2267 1210 2267 1246 2267 1253 2268 1216 2268 1217 2268 1253 2269 1217 2269 1255 2269 1216 2270 1253 2270 1227 2270 1227 2271 1253 2271 1256 2271 1227 2272 1256 2272 1257 2272 1227 2273 1257 2273 1226 2273 1226 2274 1257 2274 1258 2274 1226 2275 1258 2275 1225 2275 1225 2276 1258 2276 1259 2276 1225 2277 1259 2277 1224 2277 1224 2278 1259 2278 1260 2278 1224 2279 1260 2279 1223 2279 1223 2280 1260 2280 1254 2280 1223 2281 1254 2281 1222 2281 1255 2282 1217 2282 1261 2282 1261 2283 1217 2283 1218 2283 1222 2284 1254 2284 1262 2284 1222 2285 1262 2285 1221 2285 1221 2286 1262 2286 1263 2286 1221 2287 1263 2287 1264 2287 1221 2288 1264 2288 1220 2288 1220 2289 1264 2289 1265 2289 1220 2290 1265 2290 1219 2290 1218 2291 1219 2291 1261 2291 1261 2292 1219 2292 1265 2292 146 2293 931 2293 1266 2293 1266 2294 931 2294 928 2294 938 2295 929 2295 930 2295 938 2296 930 2296 939 2296 73 2297 936 2297 937 2297 73 2298 937 2298 1267 2298 155 2299 1267 2299 937 2299 1267 2300 165 2300 73 2300 73 2301 165 2301 1268 2301 165 2302 976 2302 1268 2302 1268 2303 976 2303 977 2303 1009 2304 974 2304 978 2304 975 2305 202 2305 978 2305 978 2306 202 2306 1009 2306 199 2307 202 2307 173 2307 173 2308 202 2308 975 2308 122 2309 1008 2309 168 2309 168 2310 1008 2310 1010 2310 1266 2311 122 2311 168 2311 1266 2312 168 2312 146 2312 1229 2313 145 2313 1237 2313 1237 2314 145 2314 167 2314 1237 2315 167 2315 1238 2315 1238 2316 167 2316 166 2316 1238 2317 166 2317 1239 2317 1239 2318 166 2318 192 2318 1239 2319 192 2319 1232 2319 1232 2320 192 2320 187 2320 1232 2321 187 2321 1236 2321 1236 2322 187 2322 198 2322 1236 2323 198 2323 1228 2323 1228 2324 198 2324 176 2324 1228 2325 176 2325 1235 2325 1235 2326 176 2326 169 2326 1235 2327 169 2327 1234 2327 1234 2328 169 2328 142 2328 1234 2329 142 2329 1233 2329 1233 2330 142 2330 149 2330 1233 2331 149 2331 1231 2331 1231 2332 149 2332 148 2332 1231 2333 148 2333 1230 2333 1230 2334 148 2334 145 2334 1230 2335 145 2335 1229 2335 1252 2336 177 2336 1245 2336 1245 2337 177 2337 197 2337 1245 2338 197 2338 1244 2338 1244 2339 197 2339 186 2339 1244 2340 186 2340 1243 2340 1243 2341 186 2341 161 2341 1243 2342 161 2342 1241 2342 1241 2343 161 2343 184 2343 1241 2344 184 2344 1242 2344 1242 2345 184 2345 196 2345 1242 2346 196 2346 1240 2346 1240 2347 196 2347 172 2347 1240 2348 172 2348 1251 2348 1251 2349 172 2349 143 2349 1251 2350 143 2350 1250 2350 1250 2351 143 2351 1249 2351 1249 2352 143 2352 147 2352 1249 2353 147 2353 151 2353 1249 2354 151 2354 1248 2354 1248 2355 151 2355 1247 2355 1247 2356 151 2356 162 2356 1247 2357 162 2357 170 2357 1247 2358 170 2358 1246 2358 1246 2359 170 2359 177 2359 1246 2360 177 2360 1252 2360 1262 2361 191 2361 195 2361 1262 2362 195 2362 1263 2362 1263 2363 195 2363 1264 2363 1264 2364 195 2364 157 2364 1264 2365 157 2365 1265 2365 1265 2366 157 2366 160 2366 1265 2367 160 2367 1261 2367 1261 2368 160 2368 194 2368 1261 2369 194 2369 180 2369 1261 2370 180 2370 1255 2370 1255 2371 180 2371 1253 2371 1253 2372 180 2372 153 2372 1253 2373 153 2373 154 2373 1253 2374 154 2374 1256 2374 1256 2375 154 2375 155 2375 1256 2376 155 2376 1257 2376 1257 2377 155 2377 152 2377 1257 2378 152 2378 1258 2378 1258 2379 152 2379 150 2379 1258 2380 150 2380 1259 2380 1259 2381 150 2381 144 2381 1259 2382 144 2382 1260 2382 1260 2383 144 2383 1254 2383 1254 2384 144 2384 171 2384 1254 2385 171 2385 1262 2385 1262 2386 171 2386 191 2386 1271 2387 1272 2387 1273 2387 1273 2388 1272 2388 1274 2388 1274 2389 1272 2389 1275 2389 1274 2390 1275 2390 1276 2390 1276 2391 1275 2391 1277 2391 1276 2392 1277 2392 1278 2392 1278 2393 1277 2393 1279 2393 1269 2394 1280 2394 1270 2394 1270 2395 1280 2395 1281 2395 1281 2396 1280 2396 1282 2396 1281 2397 1282 2397 1283 2397 1283 2398 1282 2398 1284 2398 1283 2399 1284 2399 1271 2399 1271 2400 1284 2400 1272 2400 1278 2401 1279 2401 1285 2401 1278 2402 1285 2402 1286 2402 1286 2403 1285 2403 1287 2403 1287 2404 1285 2404 1288 2404 1287 2405 1288 2405 1289 2405 1289 2406 1288 2406 1269 2406 1289 2407 1269 2407 1270 2407 1271 2408 1300 2408 1290 2408 1271 2409 1290 2409 1283 2409 1283 2410 1290 2410 1291 2410 1283 2411 1291 2411 1281 2411 1281 2412 1291 2412 1292 2412 1281 2413 1292 2413 1270 2413 1270 2414 1292 2414 1293 2414 1270 2415 1293 2415 1289 2415 1289 2416 1293 2416 1294 2416 1289 2417 1294 2417 1287 2417 1287 2418 1294 2418 1295 2418 1287 2419 1295 2419 1296 2419 1287 2420 1296 2420 1286 2420 1286 2421 1296 2421 1297 2421 1286 2422 1297 2422 1278 2422 1278 2423 1297 2423 1298 2423 1278 2424 1298 2424 1276 2424 1276 2425 1298 2425 1299 2425 1276 2426 1299 2426 1274 2426 1274 2427 1299 2427 1300 2427 1274 2428 1300 2428 1273 2428 1273 2429 1300 2429 1271 2429 1301 2430 1302 2430 1303 2430 1303 2431 1302 2431 1304 2431 1320 2432 1305 2432 1306 2432 1306 2433 1305 2433 1307 2433 1306 2434 1307 2434 1308 2434 1308 2435 1307 2435 1309 2435 1309 2436 1307 2436 1310 2436 1309 2437 1310 2437 1311 2437 1311 2438 1310 2438 1312 2438 1311 2439 1312 2439 1313 2439 1301 2440 1303 2440 1314 2440 1301 2441 1314 2441 1315 2441 1301 2442 1315 2442 1316 2442 1316 2443 1315 2443 1313 2443 1316 2444 1313 2444 1312 2444 1318 2445 1317 2445 1319 2445 1318 2446 1319 2446 1320 2446 1302 2447 1321 2447 1304 2447 1304 2448 1321 2448 1322 2448 1322 2449 1321 2449 1317 2449 1322 2450 1317 2450 1318 2450 1320 2451 1319 2451 1305 2451 1306 2452 1323 2452 1320 2452 1320 2453 1323 2453 1324 2453 1320 2454 1324 2454 1318 2454 1318 2455 1324 2455 1325 2455 1318 2456 1325 2456 1322 2456 1322 2457 1325 2457 1326 2457 1322 2458 1326 2458 1304 2458 1304 2459 1326 2459 1327 2459 1304 2460 1327 2460 1328 2460 1304 2461 1328 2461 1303 2461 1303 2462 1328 2462 1329 2462 1303 2463 1329 2463 1314 2463 1314 2464 1329 2464 1330 2464 1314 2465 1330 2465 1315 2465 1315 2466 1330 2466 1331 2466 1315 2467 1331 2467 1313 2467 1313 2468 1331 2468 1332 2468 1313 2469 1332 2469 1311 2469 1311 2470 1332 2470 1333 2470 1311 2471 1333 2471 1309 2471 1309 2472 1333 2472 1334 2472 1309 2473 1334 2473 1308 2473 1308 2474 1334 2474 1306 2474 1306 2475 1334 2475 1323 2475 1336 2476 1335 2476 1337 2476 1336 2477 1337 2477 1338 2477 1338 2478 1337 2478 1339 2478 1338 2479 1339 2479 1340 2479 1340 2480 1339 2480 1341 2480 1340 2481 1341 2481 1342 2481 1342 2482 1341 2482 1343 2482 1343 2483 1341 2483 1344 2483 1343 2484 1344 2484 1345 2484 1343 2485 1345 2485 1346 2485 1346 2486 1345 2486 1347 2486 1346 2487 1347 2487 1348 2487 1348 2488 1347 2488 1349 2488 1348 2489 1349 2489 1350 2489 1350 2490 1349 2490 1351 2490 1351 2491 1349 2491 1352 2491 1351 2492 1352 2492 1353 2492 1353 2493 1352 2493 1354 2493 1353 2494 1354 2494 1355 2494 1355 2495 1354 2495 1356 2495 1355 2496 1356 2496 1357 2496 1357 2497 1356 2497 1358 2497 1358 2498 1356 2498 1335 2498 1358 2499 1335 2499 1336 2499 1336 2500 1359 2500 1360 2500 1336 2501 1360 2501 1358 2501 1358 2502 1360 2502 1361 2502 1358 2503 1361 2503 1357 2503 1357 2504 1361 2504 1362 2504 1357 2505 1362 2505 1355 2505 1355 2506 1362 2506 1353 2506 1353 2507 1362 2507 1363 2507 1353 2508 1363 2508 1351 2508 1351 2509 1363 2509 1364 2509 1351 2510 1364 2510 1350 2510 1350 2511 1364 2511 1365 2511 1350 2512 1365 2512 1348 2512 1348 2513 1365 2513 1366 2513 1348 2514 1366 2514 1346 2514 1346 2515 1366 2515 1367 2515 1346 2516 1367 2516 1343 2516 1343 2517 1367 2517 1368 2517 1343 2518 1368 2518 1342 2518 1342 2519 1368 2519 1369 2519 1342 2520 1369 2520 1340 2520 1340 2521 1369 2521 1370 2521 1340 2522 1370 2522 1338 2522 1338 2523 1370 2523 1359 2523 1338 2524 1359 2524 1336 2524 1372 2525 1371 2525 1373 2525 1391 2526 1374 2526 1375 2526 1375 2527 1374 2527 1371 2527 1375 2528 1371 2528 1372 2528 1371 2529 1376 2529 1373 2529 1373 2530 1376 2530 1377 2530 1373 2531 1377 2531 1378 2531 1380 2532 1379 2532 1381 2532 1381 2533 1379 2533 1378 2533 1381 2534 1378 2534 1377 2534 1379 2535 1380 2535 1382 2535 1379 2536 1382 2536 1383 2536 1383 2537 1382 2537 1384 2537 1383 2538 1384 2538 1385 2538 1385 2539 1384 2539 1386 2539 1385 2540 1386 2540 1387 2540 1387 2541 1386 2541 1388 2541 1387 2542 1388 2542 1389 2542 1389 2543 1388 2543 1390 2543 1390 2544 1388 2544 1391 2544 1390 2545 1391 2545 1392 2545 1392 2546 1391 2546 1375 2546 1378 2547 1404 2547 1373 2547 1373 2548 1404 2548 1393 2548 1373 2549 1393 2549 1372 2549 1372 2550 1393 2550 1394 2550 1372 2551 1394 2551 1395 2551 1372 2552 1395 2552 1375 2552 1375 2553 1395 2553 1396 2553 1375 2554 1396 2554 1392 2554 1392 2555 1396 2555 1397 2555 1392 2556 1397 2556 1390 2556 1390 2557 1397 2557 1398 2557 1390 2558 1398 2558 1389 2558 1389 2559 1398 2559 1399 2559 1389 2560 1399 2560 1387 2560 1387 2561 1399 2561 1400 2561 1387 2562 1400 2562 1385 2562 1385 2563 1400 2563 1401 2563 1385 2564 1401 2564 1383 2564 1383 2565 1401 2565 1402 2565 1383 2566 1402 2566 1379 2566 1379 2567 1402 2567 1403 2567 1379 2568 1403 2568 1404 2568 1379 2569 1404 2569 1378 2569 1405 2570 1406 2570 1407 2570 1407 2571 1406 2571 173 2571 1407 2572 173 2572 1408 2572 173 2573 174 2573 1408 2573 1408 2574 174 2574 1409 2574 1409 2575 174 2575 188 2575 1409 2576 188 2576 1410 2576 1410 2577 188 2577 189 2577 1410 2578 189 2578 164 2578 1410 2579 164 2579 1411 2579 1411 2580 164 2580 1412 2580 1412 2581 164 2581 163 2581 1412 2582 163 2582 181 2582 1412 2583 181 2583 1413 2583 1413 2584 181 2584 175 2584 1413 2585 175 2585 1414 2585 1414 2586 175 2586 183 2586 1414 2587 183 2587 1415 2587 1415 2588 183 2588 159 2588 1415 2589 159 2589 1416 2589 1416 2590 159 2590 190 2590 1416 2591 190 2591 1417 2591 1417 2592 190 2592 1418 2592 1418 2593 190 2593 182 2593 1418 2594 182 2594 1419 2594 1419 2595 182 2595 156 2595 1419 2596 156 2596 1420 2596 1420 2597 156 2597 158 2597 1420 2598 158 2598 185 2598 1420 2599 185 2599 1421 2599 1421 2600 185 2600 193 2600 1421 2601 193 2601 1422 2601 1422 2602 193 2602 179 2602 1422 2603 179 2603 1423 2603 1423 2604 179 2604 178 2604 1423 2605 178 2605 1424 2605 1424 2606 178 2606 1425 2606 1425 2607 178 2607 201 2607 1425 2608 201 2608 200 2608 1425 2609 200 2609 1426 2609 1426 2610 200 2610 199 2610 1426 2611 199 2611 1405 2611 1405 2612 199 2612 1406 2612 199 2613 173 2613 1406 2613 1299 2614 1408 2614 1300 2614 1300 2615 1408 2615 1409 2615 1408 2616 1299 2616 1407 2616 1407 2617 1299 2617 1298 2617 1423 2618 1366 2618 1422 2618 1359 2619 1370 2619 1411 2619 1412 2620 1334 2620 1411 2620 1411 2621 1334 2621 1333 2621 1365 2622 1422 2622 1366 2622 1418 2623 1395 2623 1417 2623 1394 2624 1416 2624 1417 2624 1394 2625 1417 2625 1395 2625 1418 2626 1419 2626 1397 2626 1416 2627 1394 2627 1393 2627 1416 2628 1393 2628 1415 2628 1397 2629 1396 2629 1418 2629 1418 2630 1396 2630 1395 2630 1359 2631 1332 2631 1331 2631 1414 2632 1325 2632 1324 2632 1414 2633 1324 2633 1413 2633 1413 2634 1324 2634 1323 2634 1413 2635 1323 2635 1412 2635 1412 2636 1323 2636 1334 2636 1332 2637 1359 2637 1411 2637 1332 2638 1411 2638 1333 2638 1407 2639 1298 2639 1405 2639 1419 2640 1398 2640 1397 2640 1415 2641 1393 2641 1404 2641 1415 2642 1404 2642 1414 2642 1359 2643 1331 2643 1330 2643 1327 2644 1360 2644 1328 2644 1298 2645 1297 2645 1405 2645 1405 2646 1297 2646 1426 2646 1295 2647 1424 2647 1425 2647 1295 2648 1425 2648 1296 2648 1296 2649 1425 2649 1426 2649 1296 2650 1426 2650 1297 2650 1414 2651 1404 2651 1403 2651 1402 2652 1401 2652 1360 2652 1360 2653 1327 2653 1414 2653 1414 2654 1327 2654 1326 2654 1414 2655 1326 2655 1325 2655 1423 2656 1367 2656 1366 2656 1293 2657 1292 2657 1370 2657 1370 2658 1292 2658 1411 2658 1411 2659 1292 2659 1291 2659 1411 2660 1291 2660 1290 2660 1411 2661 1290 2661 1410 2661 1410 2662 1290 2662 1300 2662 1410 2663 1300 2663 1409 2663 1365 2664 1364 2664 1422 2664 1422 2665 1364 2665 1421 2665 1403 2666 1402 2666 1414 2666 1414 2667 1402 2667 1360 2667 1361 2668 1360 2668 1400 2668 1360 2669 1401 2669 1400 2669 1424 2670 1368 2670 1423 2670 1423 2671 1368 2671 1367 2671 1364 2672 1363 2672 1421 2672 1421 2673 1363 2673 1420 2673 1420 2674 1363 2674 1362 2674 1420 2675 1362 2675 1419 2675 1419 2676 1362 2676 1398 2676 1398 2677 1362 2677 1399 2677 1399 2678 1362 2678 1361 2678 1361 2679 1400 2679 1399 2679 1359 2680 1330 2680 1329 2680 1359 2681 1329 2681 1360 2681 1360 2682 1329 2682 1328 2682 1295 2683 1294 2683 1369 2683 1369 2684 1294 2684 1370 2684 1370 2685 1294 2685 1293 2685 1295 2686 1369 2686 1424 2686 1424 2687 1369 2687 1368 2687 1377 2688 1427 2688 1381 2688 1381 2689 1427 2689 1428 2689 1381 2690 1428 2690 1380 2690 1380 2691 1428 2691 1429 2691 1380 2692 1429 2692 1382 2692 1382 2693 1429 2693 1430 2693 1382 2694 1430 2694 1384 2694 1384 2695 1430 2695 1431 2695 1384 2696 1431 2696 1432 2696 1384 2697 1432 2697 1386 2697 1386 2698 1432 2698 1388 2698 1388 2699 1432 2699 1433 2699 1388 2700 1433 2700 1434 2700 1388 2701 1434 2701 1391 2701 1391 2702 1434 2702 1435 2702 1391 2703 1435 2703 1374 2703 1374 2704 1435 2704 1436 2704 1374 2705 1436 2705 1371 2705 1371 2706 1436 2706 1437 2706 1371 2707 1437 2707 1438 2707 1371 2708 1438 2708 1376 2708 1376 2709 1438 2709 1427 2709 1376 2710 1427 2710 1377 2710 1439 2711 1440 2711 1335 2711 1335 2712 1440 2712 1337 2712 1337 2713 1440 2713 1441 2713 1337 2714 1441 2714 1339 2714 1339 2715 1441 2715 1442 2715 1339 2716 1442 2716 1341 2716 1341 2717 1442 2717 1443 2717 1341 2718 1443 2718 1344 2718 1344 2719 1443 2719 1345 2719 1345 2720 1443 2720 1444 2720 1345 2721 1444 2721 1347 2721 1347 2722 1444 2722 1445 2722 1347 2723 1445 2723 1349 2723 1349 2724 1445 2724 1446 2724 1349 2725 1446 2725 1352 2725 1352 2726 1446 2726 1354 2726 1354 2727 1446 2727 1447 2727 1354 2728 1447 2728 1356 2728 1356 2729 1447 2729 1448 2729 1356 2730 1448 2730 1439 2730 1356 2731 1439 2731 1335 2731 1305 2732 1449 2732 1307 2732 1307 2733 1449 2733 1450 2733 1307 2734 1450 2734 1451 2734 1307 2735 1451 2735 1310 2735 1310 2736 1451 2736 1452 2736 1310 2737 1452 2737 1312 2737 1312 2738 1452 2738 1453 2738 1312 2739 1453 2739 1316 2739 1316 2740 1453 2740 1454 2740 1316 2741 1454 2741 1301 2741 1301 2742 1454 2742 1455 2742 1301 2743 1455 2743 1456 2743 1301 2744 1456 2744 1302 2744 1302 2745 1456 2745 1457 2745 1302 2746 1457 2746 1321 2746 1321 2747 1457 2747 1458 2747 1321 2748 1458 2748 1317 2748 1317 2749 1458 2749 1459 2749 1317 2750 1459 2750 1319 2750 1319 2751 1459 2751 1460 2751 1319 2752 1460 2752 1305 2752 1305 2753 1460 2753 1449 2753 1284 2754 1461 2754 1462 2754 1284 2755 1462 2755 1272 2755 1272 2756 1462 2756 1275 2756 1275 2757 1462 2757 1463 2757 1275 2758 1463 2758 1277 2758 1277 2759 1463 2759 1464 2759 1277 2760 1464 2760 1279 2760 1279 2761 1464 2761 1465 2761 1279 2762 1465 2762 1466 2762 1279 2763 1466 2763 1285 2763 1285 2764 1466 2764 1467 2764 1285 2765 1467 2765 1468 2765 1285 2766 1468 2766 1288 2766 1288 2767 1468 2767 1469 2767 1288 2768 1469 2768 1269 2768 1269 2769 1469 2769 1470 2769 1269 2770 1470 2770 1280 2770 1280 2771 1470 2771 1282 2771 1282 2772 1470 2772 1471 2772 1282 2773 1471 2773 1284 2773 1284 2774 1471 2774 1461 2774 1455 2775 1472 2775 1456 2775 1456 2776 1472 2776 1473 2776 1456 2777 1473 2777 1457 2777 1457 2778 1473 2778 1474 2778 1457 2779 1474 2779 1458 2779 1458 2780 1474 2780 1475 2780 1458 2781 1475 2781 1459 2781 1459 2782 1475 2782 1476 2782 1459 2783 1476 2783 1460 2783 1460 2784 1476 2784 1449 2784 1449 2785 1476 2785 1477 2785 1449 2786 1477 2786 1450 2786 1450 2787 1477 2787 1478 2787 1450 2788 1478 2788 1451 2788 1451 2789 1478 2789 1479 2789 1451 2790 1479 2790 1452 2790 1452 2791 1479 2791 1480 2791 1452 2792 1480 2792 1481 2792 1452 2793 1481 2793 1453 2793 1453 2794 1481 2794 1482 2794 1453 2795 1482 2795 1454 2795 1454 2796 1482 2796 1455 2796 1455 2797 1482 2797 1472 2797 1446 2798 1483 2798 1484 2798 1446 2799 1484 2799 1447 2799 1447 2800 1484 2800 1485 2800 1447 2801 1485 2801 1448 2801 1448 2802 1485 2802 1486 2802 1448 2803 1486 2803 1439 2803 1439 2804 1486 2804 1487 2804 1439 2805 1487 2805 1440 2805 1440 2806 1487 2806 1488 2806 1440 2807 1488 2807 1441 2807 1441 2808 1488 2808 1489 2808 1441 2809 1489 2809 1442 2809 1442 2810 1489 2810 1490 2810 1442 2811 1490 2811 1491 2811 1442 2812 1491 2812 1443 2812 1443 2813 1491 2813 1444 2813 1444 2814 1491 2814 1492 2814 1444 2815 1492 2815 1493 2815 1444 2816 1493 2816 1445 2816 1445 2817 1493 2817 1494 2817 1445 2818 1494 2818 1446 2818 1446 2819 1494 2819 1483 2819 1433 2820 1430 2820 1429 2820 1433 2821 1429 2821 1428 2821 1427 2822 1438 2822 1433 2822 1430 2823 1433 2823 1431 2823 1431 2824 1433 2824 1432 2824 1433 2825 1428 2825 1427 2825 1438 2826 1437 2826 1433 2826 1437 2827 1436 2827 1433 2827 1436 2828 1435 2828 1433 2828 1435 2829 1434 2829 1433 2829 1467 2830 1464 2830 1463 2830 1467 2831 1461 2831 1471 2831 1467 2832 1470 2832 1469 2832 1469 2833 1468 2833 1467 2833 1464 2834 1467 2834 1465 2834 1465 2835 1467 2835 1466 2835 1463 2836 1462 2836 1467 2836 1467 2837 1462 2837 1461 2837 1471 2838 1470 2838 1467 2838 1495 2839 1496 2839 1499 2839 1496 2840 1497 2840 1498 2840 1498 2841 1499 2841 1496 2841 1500 2842 1501 2842 1495 2842 1496 2843 1502 2843 1497 2843 1501 2844 1500 2844 1504 2844 1501 2845 1496 2845 1495 2845 1497 2846 1502 2846 1503 2846 1496 2847 1505 2847 1502 2847 1502 2848 1505 2848 1506 2848 1502 2849 1506 2849 1507 2849 1502 2850 1507 2850 1503 2850 1503 2851 1507 2851 1508 2851 1503 2852 1508 2852 1497 2852 1497 2853 1508 2853 1509 2853 1497 2854 1509 2854 1498 2854 1498 2855 1509 2855 1510 2855 1498 2856 1510 2856 1499 2856 1499 2857 1510 2857 1511 2857 1499 2858 1511 2858 1495 2858 1495 2859 1511 2859 1512 2859 1495 2860 1512 2860 1500 2860 1500 2861 1512 2861 1513 2861 1500 2862 1513 2862 1504 2862 1504 2863 1513 2863 1514 2863 1504 2864 1514 2864 1501 2864 1501 2865 1514 2865 1515 2865 1501 2866 1515 2866 1516 2866 1501 2867 1516 2867 1496 2867 1496 2868 1516 2868 1505 2868 1511 2869 1517 2869 1512 2869 1512 2870 1517 2870 1518 2870 1512 2871 1518 2871 1513 2871 1513 2872 1518 2872 1519 2872 1513 2873 1519 2873 1514 2873 1514 2874 1519 2874 1515 2874 1515 2875 1519 2875 1520 2875 1515 2876 1520 2876 1516 2876 1516 2877 1520 2877 1521 2877 1516 2878 1521 2878 1505 2878 1505 2879 1521 2879 1522 2879 1505 2880 1522 2880 1506 2880 1506 2881 1522 2881 1523 2881 1506 2882 1523 2882 1507 2882 1507 2883 1523 2883 1524 2883 1507 2884 1524 2884 1508 2884 1508 2885 1524 2885 1525 2885 1508 2886 1525 2886 1509 2886 1509 2887 1525 2887 1526 2887 1509 2888 1526 2888 1510 2888 1510 2889 1526 2889 1527 2889 1510 2890 1527 2890 1511 2890 1511 2891 1527 2891 1517 2891 1527 2892 1477 2892 1517 2892 1517 2893 1477 2893 1476 2893 1517 2894 1476 2894 1518 2894 1518 2895 1476 2895 1475 2895 1518 2896 1475 2896 1519 2896 1519 2897 1475 2897 1474 2897 1519 2898 1474 2898 1520 2898 1520 2899 1474 2899 1473 2899 1520 2900 1473 2900 1521 2900 1521 2901 1473 2901 1472 2901 1521 2902 1472 2902 1522 2902 1522 2903 1472 2903 1482 2903 1522 2904 1482 2904 1523 2904 1523 2905 1482 2905 1481 2905 1523 2906 1481 2906 1524 2906 1524 2907 1481 2907 1480 2907 1524 2908 1480 2908 1525 2908 1525 2909 1480 2909 1479 2909 1525 2910 1479 2910 1526 2910 1526 2911 1479 2911 1478 2911 1526 2912 1478 2912 1527 2912 1527 2913 1478 2913 1477 2913 1528 2914 1529 2914 1535 2914 1528 2915 1532 2915 1529 2915 1529 2916 1532 2916 1530 2916 1531 2917 1530 2917 1533 2917 1531 2918 1533 2918 1534 2918 1531 2919 1529 2919 1530 2919 1535 2920 1536 2920 1537 2920 1535 2921 1537 2921 1538 2921 1528 2922 1535 2922 1538 2922 1535 2923 1539 2923 1536 2923 1529 2924 1540 2924 1535 2924 1535 2925 1540 2925 1541 2925 1535 2926 1541 2926 1539 2926 1539 2927 1541 2927 1542 2927 1539 2928 1542 2928 1536 2928 1536 2929 1542 2929 1543 2929 1536 2930 1543 2930 1544 2930 1536 2931 1544 2931 1537 2931 1537 2932 1544 2932 1545 2932 1537 2933 1545 2933 1538 2933 1538 2934 1545 2934 1546 2934 1538 2935 1546 2935 1528 2935 1528 2936 1546 2936 1547 2936 1528 2937 1547 2937 1532 2937 1532 2938 1547 2938 1548 2938 1532 2939 1548 2939 1530 2939 1530 2940 1548 2940 1549 2940 1530 2941 1549 2941 1533 2941 1533 2942 1549 2942 1534 2942 1534 2943 1549 2943 1550 2943 1534 2944 1550 2944 1531 2944 1531 2945 1550 2945 1551 2945 1531 2946 1551 2946 1529 2946 1529 2947 1551 2947 1540 2947 1548 2948 1552 2948 1553 2948 1548 2949 1553 2949 1549 2949 1549 2950 1553 2950 1554 2950 1549 2951 1554 2951 1550 2951 1550 2952 1554 2952 1555 2952 1550 2953 1555 2953 1551 2953 1551 2954 1555 2954 1556 2954 1551 2955 1556 2955 1557 2955 1551 2956 1557 2956 1540 2956 1540 2957 1557 2957 1541 2957 1541 2958 1557 2958 1558 2958 1541 2959 1558 2959 1542 2959 1542 2960 1558 2960 1559 2960 1542 2961 1559 2961 1543 2961 1543 2962 1559 2962 1560 2962 1543 2963 1560 2963 1544 2963 1544 2964 1560 2964 1561 2964 1544 2965 1561 2965 1545 2965 1545 2966 1561 2966 1562 2966 1545 2967 1562 2967 1546 2967 1546 2968 1562 2968 1563 2968 1546 2969 1563 2969 1547 2969 1547 2970 1563 2970 1548 2970 1548 2971 1563 2971 1552 2971 1487 2972 1486 2972 1563 2972 1563 2973 1486 2973 1552 2973 1552 2974 1486 2974 1485 2974 1552 2975 1485 2975 1553 2975 1553 2976 1485 2976 1484 2976 1553 2977 1484 2977 1554 2977 1554 2978 1484 2978 1483 2978 1554 2979 1483 2979 1555 2979 1555 2980 1483 2980 1494 2980 1555 2981 1494 2981 1556 2981 1556 2982 1494 2982 1493 2982 1556 2983 1493 2983 1557 2983 1557 2984 1493 2984 1492 2984 1557 2985 1492 2985 1558 2985 1558 2986 1492 2986 1491 2986 1558 2987 1491 2987 1559 2987 1559 2988 1491 2988 1490 2988 1559 2989 1490 2989 1560 2989 1560 2990 1490 2990 1489 2990 1560 2991 1489 2991 1561 2991 1561 2992 1489 2992 1488 2992 1561 2993 1488 2993 1562 2993 1562 2994 1488 2994 1487 2994 1562 2995 1487 2995 1563 2995 1564 2996 15 2996 14 2996 14 2997 17 2997 1565 2997 1577 2998 1184 2998 1565 2998 1565 2999 1184 2999 87 2999 1565 3000 87 3000 14 3000 14 3001 87 3001 1566 3001 14 3002 1566 3002 1564 3002 1567 3003 1 3003 1023 3003 1567 3004 1023 3004 1568 3004 1568 3005 1023 3005 1185 3005 61 3006 1569 3006 59 3006 59 3007 1569 3007 1570 3007 1570 3008 49 3008 59 3008 59 3009 49 3009 50 3009 59 3010 50 3010 1571 3010 1571 3011 50 3011 54 3011 1569 3012 61 3012 63 3012 1569 3013 63 3013 1572 3013 1572 3014 63 3014 58 3014 71 3015 1573 3015 1574 3015 71 3016 1574 3016 66 3016 1192 3017 1575 3017 1191 3017 1191 3018 1575 3018 1576 3018 1568 3019 1185 3019 1577 3019 1577 3020 1185 3020 1184 3020 1581 3021 1582 3021 1583 3021 1578 3022 1583 3022 1580 3022 1580 3023 1583 3023 1582 3023 1586 3024 1578 3024 1580 3024 1586 3025 1580 3025 1579 3025 1588 3026 1586 3026 1579 3026 1585 3027 1584 3027 1586 3027 1579 3028 1587 3028 1588 3028 1589 3029 1592 3029 1590 3029 1589 3030 1594 3030 1596 3030 1594 3031 1761 3031 1597 3031 1761 3032 1584 3032 1585 3032 1597 3033 1596 3033 1594 3033 1597 3034 1761 3034 1585 3034 1592 3035 1589 3035 1596 3035 1597 3036 1585 3036 1588 3036 1598 3037 1597 3037 1588 3037 1588 3038 1585 3038 1586 3038 1592 3039 1596 3039 1593 3039 1593 3040 1596 3040 1598 3040 1598 3041 1596 3041 1597 3041 1599 3042 1598 3042 1588 3042 1595 3043 1598 3043 1599 3043 1599 3044 1588 3044 1587 3044 1591 3045 1593 3045 1598 3045 1591 3046 1598 3046 1595 3046 1592 3047 1593 3047 1602 3047 1603 3048 1604 3048 1592 3048 1593 3049 1591 3049 1602 3049 1602 3050 1591 3050 1605 3050 1602 3051 1605 3051 1606 3051 1603 3052 1592 3052 1602 3052 1603 3053 1602 3053 1600 3053 1606 3054 1601 3054 1602 3054 1601 3055 1600 3055 1602 3055 1607 3056 1600 3056 1608 3056 1608 3057 1600 3057 1601 3057 1608 3058 1601 3058 1612 3058 1608 3059 1612 3059 1611 3059 1601 3060 1606 3060 1612 3060 1610 3061 1609 3061 1608 3061 1610 3062 1608 3062 1611 3062 1617 3063 1616 3063 1615 3063 1618 3064 1616 3064 1619 3064 1619 3065 1616 3065 1617 3065 1613 3066 1619 3066 1617 3066 1615 3067 1616 3067 1614 3067 1619 3068 1613 3068 1618 3068 1618 3069 1613 3069 1621 3069 1618 3070 1621 3070 1620 3070 1624 3071 1625 3071 1623 3071 1627 3072 1628 3072 1634 3072 1628 3073 1627 3073 1623 3073 1623 3074 1627 3074 1631 3074 1631 3075 1620 3075 1621 3075 1624 3076 1632 3076 1633 3076 1633 3077 1632 3077 1621 3077 1633 3078 1621 3078 1622 3078 1625 3079 1624 3079 1626 3079 1626 3080 1624 3080 1633 3080 1626 3081 1633 3081 1629 3081 1629 3082 1633 3082 1630 3082 1630 3083 1633 3083 1622 3083 1632 3084 1623 3084 1631 3084 1632 3085 1631 3085 1621 3085 1632 3086 1624 3086 1623 3086 1621 3087 1613 3087 1622 3087 1636 3088 1628 3088 1623 3088 1623 3089 1625 3089 1637 3089 1623 3090 1637 3090 1636 3090 1636 3091 1637 3091 1638 3091 1637 3092 1639 3092 1638 3092 1636 3093 1638 3093 1635 3093 1628 3094 1636 3094 1634 3094 1634 3095 1636 3095 1635 3095 1634 3096 1635 3096 1646 3096 1643 3097 1640 3097 1645 3097 1645 3098 1640 3098 1642 3098 1642 3099 1640 3099 1644 3099 1646 3100 1643 3100 1645 3100 1641 3101 1645 3101 1642 3101 1635 3102 1638 3102 1643 3102 1635 3103 1643 3103 1646 3103 1638 3104 1639 3104 1643 3104 1639 3105 1640 3105 1643 3105 1651 3106 1647 3106 1652 3106 1655 3107 2225 3107 1649 3107 1654 3108 2225 3108 1652 3108 1652 3109 2225 3109 1655 3109 1652 3110 1655 3110 1651 3110 1655 3111 1649 3111 1653 3111 1653 3112 1649 3112 1648 3112 1655 3113 1650 3113 1651 3113 1651 3114 1650 3114 1647 3114 1655 3115 1653 3115 1650 3115 1652 3116 1656 3116 1654 3116 1660 3117 1658 3117 1659 3117 1659 3118 1654 3118 1656 3118 1661 3119 1660 3119 1656 3119 1647 3120 1657 3120 1661 3120 1659 3121 1656 3121 1660 3121 1661 3122 1656 3122 1647 3122 1647 3123 1656 3123 1652 3123 1721 3124 1663 3124 1664 3124 1662 3125 1661 3125 1665 3125 1667 3126 1668 3126 1671 3126 1666 3127 1664 3127 1670 3127 1666 3128 1670 3128 1717 3128 1717 3129 1670 3129 1672 3129 1660 3130 1661 3130 1662 3130 1662 3131 1665 3131 1669 3131 1669 3132 1665 3132 1667 3132 1669 3133 1667 3133 1671 3133 1671 3134 1670 3134 1669 3134 1662 3135 1669 3135 1658 3135 1662 3136 1658 3136 1660 3136 1670 3137 1671 3137 1672 3137 1670 3138 1664 3138 1669 3138 1669 3139 1664 3139 1658 3139 1658 3140 1664 3140 1663 3140 1673 3141 1672 3141 1674 3141 1674 3142 1672 3142 1671 3142 1674 3143 1671 3143 1675 3143 1675 3144 1671 3144 1668 3144 1674 3145 1678 3145 1677 3145 1675 3146 1678 3146 1674 3146 1679 3147 1673 3147 1674 3147 1679 3148 1674 3148 1677 3148 1687 3149 1685 3149 1686 3149 1690 3150 1684 3150 1682 3150 1692 3151 1680 3151 1689 3151 1685 3152 1687 3152 1680 3152 1680 3153 1687 3153 1689 3153 1681 3154 1682 3154 1687 3154 1687 3155 1682 3155 1684 3155 1684 3156 1689 3156 1687 3156 1681 3157 1687 3157 1686 3157 1684 3158 1690 3158 1689 3158 1698 3159 1699 3159 1694 3159 1695 3160 1694 3160 1699 3160 1699 3161 1691 3161 1695 3161 1692 3162 1695 3162 1693 3162 1692 3163 1689 3163 1695 3163 1695 3164 1689 3164 1690 3164 1695 3165 1691 3165 1693 3165 1694 3166 1695 3166 1690 3166 1693 3167 1700 3167 1692 3167 1699 3168 1701 3168 1691 3168 1691 3169 1701 3169 1706 3169 1706 3170 1701 3170 1702 3170 1706 3171 1702 3171 1707 3171 1707 3172 1704 3172 1705 3172 1704 3173 1707 3173 1702 3173 1701 3174 1699 3174 1698 3174 1707 3175 1705 3175 1697 3175 1693 3176 1691 3176 1706 3176 1693 3177 1706 3177 1700 3177 1700 3178 1706 3178 1707 3178 1700 3179 1707 3179 1703 3179 1703 3180 1707 3180 1697 3180 1703 3181 1697 3181 1696 3181 1696 3182 1697 3182 1709 3182 1709 3183 1697 3183 1708 3183 1708 3184 1697 3184 1710 3184 1697 3185 1705 3185 1710 3185 1711 3186 1806 3186 1712 3186 1713 3187 1711 3187 1712 3187 1714 3188 1713 3188 1708 3188 1710 3189 1715 3189 1714 3189 1710 3190 1714 3190 1708 3190 1716 3191 1672 3191 1673 3191 1723 3192 1724 3192 1720 3192 1720 3193 1724 3193 1721 3193 1725 3194 1723 3194 1720 3194 1720 3195 1721 3195 1722 3195 1722 3196 1721 3196 1664 3196 1722 3197 1664 3197 1719 3197 1719 3198 1664 3198 1666 3198 1732 3199 1720 3199 1722 3199 1726 3200 1727 3200 1728 3200 1729 3201 1730 3201 1731 3201 1731 3202 1730 3202 1726 3202 1731 3203 1726 3203 1732 3203 1732 3204 1726 3204 1728 3204 1733 3205 1729 3205 1719 3205 1719 3206 1729 3206 1731 3206 1717 3207 1718 3207 1666 3207 1666 3208 1718 3208 1733 3208 1666 3209 1733 3209 1719 3209 1719 3210 1731 3210 1722 3210 1722 3211 1731 3211 1732 3211 1732 3212 1734 3212 1720 3212 1716 3213 1717 3213 1672 3213 1725 3214 1720 3214 1734 3214 1734 3215 1732 3215 1728 3215 1736 3216 1735 3216 1737 3216 1736 3217 1737 3217 1738 3217 1736 3218 1738 3218 1739 3218 1743 3219 1744 3219 1742 3219 1745 3220 1701 3220 1698 3220 1704 3221 1702 3221 1741 3221 1746 3222 1705 3222 1704 3222 1702 3223 1701 3223 1747 3223 1702 3224 1747 3224 1741 3224 1741 3225 1747 3225 1748 3225 1701 3226 1745 3226 1747 3226 1744 3227 1743 3227 1698 3227 1698 3228 1743 3228 1745 3228 1747 3229 1745 3229 1749 3229 1747 3230 1749 3230 1748 3230 1743 3231 1738 3231 1745 3231 1745 3232 1738 3232 1737 3232 1745 3233 1737 3233 1749 3233 1749 3234 1737 3234 1750 3234 1742 3235 1740 3235 1743 3235 1743 3236 1740 3236 1739 3236 1743 3237 1739 3237 1738 3237 1737 3238 1735 3238 1750 3238 1746 3239 1710 3239 1705 3239 1711 3240 1713 3240 1714 3240 1751 3241 1752 3241 1753 3241 1751 3242 1753 3242 1754 3242 1754 3243 1753 3243 1755 3243 1590 3244 1759 3244 1760 3244 1760 3245 1589 3245 1590 3245 1757 3246 1761 3246 1594 3246 1594 3247 1762 3247 1757 3247 1589 3248 1760 3248 1594 3248 1594 3249 1760 3249 1764 3249 1594 3250 1764 3250 1762 3250 1762 3251 1764 3251 1763 3251 1759 3252 1758 3252 1760 3252 1764 3253 1765 3253 1763 3253 1758 3254 1755 3254 1760 3254 1760 3255 1755 3255 1764 3255 1764 3256 1755 3256 1753 3256 1764 3257 1753 3257 1765 3257 1765 3258 1753 3258 1752 3258 2590 3259 1756 3259 1758 3259 1758 3260 1756 3260 1755 3260 1755 3261 1756 3261 1754 3261 1766 3262 1586 3262 1584 3262 1586 3263 1766 3263 1578 3263 1786 3264 1581 3264 1583 3264 1767 3265 1613 3265 1617 3265 1767 3266 1622 3266 1613 3266 1630 3267 1622 3267 1767 3267 1769 3268 1630 3268 1768 3268 1770 3269 1629 3269 1769 3269 1771 3270 1772 3270 1625 3270 1630 3271 1769 3271 1629 3271 1774 3272 1772 3272 1771 3272 1772 3273 1774 3273 1775 3273 1771 3274 1776 3274 1774 3274 1771 3275 1625 3275 1773 3275 1773 3276 1625 3276 1626 3276 1776 3277 1771 3277 1777 3277 1773 3278 1626 3278 1770 3278 1770 3279 1626 3279 1629 3279 1777 3280 1771 3280 1773 3280 1778 3281 1779 3281 1782 3281 1780 3282 1781 3282 1784 3282 1784 3283 1781 3283 1778 3283 1784 3284 1778 3284 1782 3284 1769 3285 1783 3285 1770 3285 1770 3286 1783 3286 1780 3286 1784 3287 1782 3287 1777 3287 1770 3288 1780 3288 1773 3288 1773 3289 1780 3289 1784 3289 1773 3290 1784 3290 1777 3290 1776 3291 1777 3291 1782 3291 1785 3292 1782 3292 1779 3292 1788 3293 1579 3293 1787 3293 1580 3294 1790 3294 1787 3294 1580 3295 1787 3295 1579 3295 1582 3296 1791 3296 1789 3296 1582 3297 1789 3297 1580 3297 1580 3298 1789 3298 1790 3298 1582 3299 1581 3299 1792 3299 1582 3300 1792 3300 1791 3300 1581 3301 1786 3301 1792 3301 1786 3302 1793 3302 1792 3302 1614 3303 1795 3303 1615 3303 1795 3304 2408 3304 1615 3304 1795 3305 1614 3305 1796 3305 1614 3306 1616 3306 1796 3306 1616 3307 1794 3307 1796 3307 1618 3308 1797 3308 1794 3308 1616 3309 1618 3309 1794 3309 1618 3310 1798 3310 1797 3310 1676 3311 1801 3311 1800 3311 1802 3312 1801 3312 1676 3312 1676 3313 1677 3313 1802 3313 1802 3314 1677 3314 1678 3314 1678 3315 1803 3315 1802 3315 1799 3316 1803 3316 1678 3316 1675 3317 1804 3317 1799 3317 1678 3318 1675 3318 1799 3318 1675 3319 1805 3319 1804 3319 1679 3320 1677 3320 1800 3320 1800 3321 1677 3321 1676 3321 1710 3322 1746 3322 1715 3322 2644 3323 1709 3323 1808 3323 1708 3324 1808 3324 1709 3324 1708 3325 1809 3325 1807 3325 1708 3326 1807 3326 1808 3326 1713 3327 1809 3327 1708 3327 1712 3328 1810 3328 1713 3328 1713 3329 1810 3329 1809 3329 1712 3330 1806 3330 1810 3330 1806 3331 1811 3331 1810 3331 1584 3332 1630 3332 1767 3332 1584 3333 1767 3333 1766 3333 1617 3334 1583 3334 1578 3334 1617 3335 1578 3335 1767 3335 1767 3336 1578 3336 1766 3336 1615 3337 1786 3337 1583 3337 1615 3338 1583 3338 1617 3338 33 3339 1779 3339 1778 3339 33 3340 1778 3340 31 3340 1630 3341 1584 3341 1768 3341 1768 3342 1584 3342 1761 3342 1768 3343 1761 3343 1769 3343 1769 3344 1761 3344 1757 3344 1769 3345 1757 3345 1783 3345 1783 3346 1757 3346 1762 3346 1783 3347 1762 3347 1780 3347 1780 3348 1762 3348 1763 3348 1780 3349 1763 3349 1765 3349 1780 3350 1765 3350 1781 3350 1781 3351 1765 3351 1778 3351 1778 3352 1765 3352 1752 3352 1778 3353 1752 3353 31 3353 1175 3354 1727 3354 1726 3354 1800 3355 1806 3355 1711 3355 1711 3356 1679 3356 1800 3356 1711 3357 1714 3357 1679 3357 1679 3358 1714 3358 1673 3358 1673 3359 1714 3359 1715 3359 1746 3360 1716 3360 1673 3360 1673 3361 1715 3361 1746 3361 1175 3362 1726 3362 1172 3362 1735 3363 1172 3363 1750 3363 1750 3364 1172 3364 1726 3364 1750 3365 1726 3365 1730 3365 1750 3366 1730 3366 1749 3366 1749 3367 1730 3367 1748 3367 1748 3368 1730 3368 1729 3368 1748 3369 1729 3369 1733 3369 1748 3370 1733 3370 1741 3370 1741 3371 1733 3371 1718 3371 1741 3372 1718 3372 1704 3372 1704 3373 1718 3373 1717 3373 1704 3374 1717 3374 1746 3374 1746 3375 1717 3375 1716 3375 1814 3376 1813 3376 1816 3376 2306 3377 1814 3377 1816 3377 1817 3378 1812 3378 1816 3378 1822 3379 1815 3379 1821 3379 1821 3380 1819 3380 1820 3380 1821 3381 1820 3381 1822 3381 1822 3382 1820 3382 1823 3382 1822 3383 1823 3383 1813 3383 1815 3384 1822 3384 1813 3384 1816 3385 1823 3385 1817 3385 1817 3386 1823 3386 1820 3386 1823 3387 1816 3387 1813 3387 1819 3388 1821 3388 1818 3388 1813 3389 1814 3389 1815 3389 1820 3390 1819 3390 1818 3390 1815 3391 1849 3391 1824 3391 1824 3392 1821 3392 1815 3392 1825 3393 1821 3393 1824 3393 1821 3394 1825 3394 1818 3394 1818 3395 1825 3395 1847 3395 1826 3396 1833 3396 1827 3396 1828 3397 1827 3397 1834 3397 1828 3398 1834 3398 1829 3398 1829 3399 1834 3399 1835 3399 1829 3400 1835 3400 1836 3400 1829 3401 1836 3401 1830 3401 1831 3402 1830 3402 1837 3402 1831 3403 1837 3403 1832 3403 1818 3404 1832 3404 1820 3404 1827 3405 1833 3405 1834 3405 1830 3406 1836 3406 1838 3406 1830 3407 1838 3407 1837 3407 1837 3408 1838 3408 1839 3408 1837 3409 1839 3409 1832 3409 1832 3410 1839 3410 1820 3410 1834 3411 1840 3411 1835 3411 1836 3412 1835 3412 1841 3412 1836 3413 1841 3413 1838 3413 1833 3414 1842 3414 1834 3414 1834 3415 1842 3415 1840 3415 1835 3416 1840 3416 1841 3416 1838 3417 1841 3417 1843 3417 1838 3418 1843 3418 1839 3418 1839 3419 1843 3419 1820 3419 1820 3420 1843 3420 1817 3420 1841 3421 1840 3421 1844 3421 1842 3422 1845 3422 1840 3422 1840 3423 1845 3423 1844 3423 1841 3424 1844 3424 1846 3424 1841 3425 1846 3425 1843 3425 1843 3426 1846 3426 1817 3426 1817 3427 1846 3427 1812 3427 1848 3428 1863 3428 1825 3428 1825 3429 1863 3429 1847 3429 1824 3430 1849 3430 1848 3430 1825 3431 1824 3431 1848 3431 1885 3432 1845 3432 1842 3432 1885 3433 1842 3433 1850 3433 1850 3434 1842 3434 1833 3434 1850 3435 1833 3435 1851 3435 1851 3436 1833 3436 1826 3436 1851 3437 1826 3437 1852 3437 1856 3438 1855 3438 1857 3438 1854 3439 1853 3439 1858 3439 1860 3440 1858 3440 1861 3440 1862 3441 1854 3441 1860 3441 1862 3442 1860 3442 1861 3442 1862 3443 1861 3443 1863 3443 1857 3444 1862 3444 1863 3444 1855 3445 1862 3445 1857 3445 1857 3446 1863 3446 1848 3446 1857 3447 1848 3447 1859 3447 1859 3448 1848 3448 1849 3448 1861 3449 1847 3449 1863 3449 1858 3450 1860 3450 1854 3450 1856 3451 1857 3451 1859 3451 1864 3452 1870 3452 1865 3452 1865 3453 1870 3453 1871 3453 1865 3454 1871 3454 1872 3454 1865 3455 1872 3455 1866 3455 1866 3456 1872 3456 1867 3456 1867 3457 1873 3457 1868 3457 1869 3458 1868 3458 1874 3458 1869 3459 1874 3459 1875 3459 1869 3460 1875 3460 1852 3460 1852 3461 1875 3461 1851 3461 1867 3462 1872 3462 1876 3462 1867 3463 1876 3463 1873 3463 1868 3464 1873 3464 1874 3464 1870 3465 1877 3465 1871 3465 1871 3466 1877 3466 1878 3466 1871 3467 1878 3467 1872 3467 1872 3468 1878 3468 1876 3468 1873 3469 1876 3469 1879 3469 1851 3470 1875 3470 1850 3470 1879 3471 1880 3471 1873 3471 1873 3472 1880 3472 1874 3472 1875 3473 1874 3473 1881 3473 1875 3474 1881 3474 1850 3474 1876 3475 1878 3475 1879 3475 1874 3476 1880 3476 1881 3476 1877 3477 1882 3477 1878 3477 1878 3478 1882 3478 1879 3478 1879 3479 1883 3479 1880 3479 1880 3480 1883 3480 1884 3480 1880 3481 1884 3481 1881 3481 1881 3482 1884 3482 1885 3482 1881 3483 1885 3483 1850 3483 1879 3484 1882 3484 1883 3484 1854 3485 1862 3485 1855 3485 1877 3486 1900 3486 1882 3486 1882 3487 1900 3487 1886 3487 1887 3488 1905 3488 1888 3488 1887 3489 1891 3489 1856 3489 1856 3490 1891 3490 1892 3490 1856 3491 1892 3491 1855 3491 1855 3492 1892 3492 1893 3492 1855 3493 1893 3493 1854 3493 1854 3494 1893 3494 1894 3494 1854 3495 1894 3495 1853 3495 1896 3496 1899 3496 1898 3496 1864 3497 1895 3497 1870 3497 1870 3498 1895 3498 1897 3498 1877 3499 1898 3499 1900 3499 1896 3500 1897 3500 1895 3500 1898 3501 1877 3501 1896 3501 1896 3502 1877 3502 1897 3502 1897 3503 1877 3503 1870 3503 1899 3504 1901 3504 1898 3504 1901 3505 1886 3505 1898 3505 1898 3506 1886 3506 1900 3506 1906 3507 1905 3507 1859 3507 1905 3508 1906 3508 1907 3508 1888 3509 1905 3509 1907 3509 1907 3510 1906 3510 1911 3510 1911 3511 1906 3511 1903 3511 1908 3512 1907 3512 1911 3512 1911 3513 1909 3513 1908 3513 1908 3514 1889 3514 1907 3514 1907 3515 1889 3515 1888 3515 1890 3516 1889 3516 1908 3516 1904 3517 1908 3517 1909 3517 1904 3518 1909 3518 1920 3518 1908 3519 1904 3519 1890 3519 1891 3520 1887 3520 1912 3520 1912 3521 1887 3521 1888 3521 1912 3522 1888 3522 1913 3522 1913 3523 1888 3523 1914 3523 1914 3524 1888 3524 1889 3524 1914 3525 1889 3525 1890 3525 1914 3526 1890 3526 1915 3526 1892 3527 1891 3527 1916 3527 1864 3528 1917 3528 1918 3528 1864 3529 1918 3529 1895 3529 1931 3530 1896 3530 1918 3530 1918 3531 1896 3531 1895 3531 1896 3532 1931 3532 1932 3532 1896 3533 1932 3533 1899 3533 1910 3534 1903 3534 1906 3534 1921 3535 1920 3535 1909 3535 1919 3536 1920 3536 1921 3536 1921 3537 1909 3537 1911 3537 1903 3538 1921 3538 1911 3538 1894 3539 1893 3539 1922 3539 1916 3540 1891 3540 1924 3540 1892 3541 1916 3541 1925 3541 1922 3542 1929 3542 1928 3542 1928 3543 1929 3543 1927 3543 1926 3544 1925 3544 1929 3544 1893 3545 1892 3545 1925 3545 1893 3546 1925 3546 1926 3546 1893 3547 1926 3547 1929 3547 1929 3548 1922 3548 1893 3548 1928 3549 1927 3549 1930 3549 1928 3550 1923 3550 1922 3550 1922 3551 1923 3551 1894 3551 1929 3552 1931 3552 1927 3552 1918 3553 1930 3553 1927 3553 1918 3554 1927 3554 1931 3554 1932 3555 1931 3555 1929 3555 1932 3556 1929 3556 1925 3556 1918 3557 1917 3557 1930 3557 1933 3558 1919 3558 1921 3558 1933 3559 1921 3559 1947 3559 1947 3560 1921 3560 1949 3560 1934 3561 1949 3561 1903 3561 1903 3562 1949 3562 1921 3562 1934 3563 1903 3563 1910 3563 1912 3564 1913 3564 1938 3564 1891 3565 1912 3565 1924 3565 1914 3566 1937 3566 1938 3566 1938 3567 1937 3567 1935 3567 1913 3568 1914 3568 1938 3568 1938 3569 1935 3569 1939 3569 1936 3570 2040 3570 1940 3570 1914 3571 1915 3571 1936 3571 1914 3572 1936 3572 1937 3572 1937 3573 1936 3573 1940 3573 1935 3574 1937 3574 1940 3574 1935 3575 1940 3575 1952 3575 1924 3576 1938 3576 1939 3576 1912 3577 1938 3577 1924 3577 1941 3578 1924 3578 1939 3578 1941 3579 1939 3579 1942 3579 1945 3580 1943 3580 1954 3580 1945 3581 1944 3581 1943 3581 1948 3582 1949 3582 1945 3582 1945 3583 1949 3583 1944 3583 1948 3584 1947 3584 1949 3584 1949 3585 1934 3585 1944 3585 1945 3586 1946 3586 1948 3586 1951 3587 1942 3587 1939 3587 1951 3588 1939 3588 1935 3588 1951 3589 1935 3589 1952 3589 1950 3590 1952 3590 1940 3590 1953 3591 1942 3591 1951 3591 1945 3592 1954 3592 1955 3592 1947 3593 1948 3593 1946 3593 1991 3594 1953 3594 1956 3594 1951 3595 1956 3595 1953 3595 1956 3596 1951 3596 1983 3596 1983 3597 1951 3597 1952 3597 1983 3598 1952 3598 1950 3598 1983 3599 1950 3599 1957 3599 1933 3600 1947 3600 1958 3600 1958 3601 1965 3601 1959 3601 1963 3602 1966 3602 1964 3602 1964 3603 1966 3603 1967 3603 1947 3604 1946 3604 1958 3604 1958 3605 1946 3605 1965 3605 1959 3606 1965 3606 1968 3606 1959 3607 1968 3607 1960 3607 1960 3608 1968 3608 1961 3608 1962 3609 1961 3609 1969 3609 1962 3610 1969 3610 1963 3610 1963 3611 1969 3611 1966 3611 1961 3612 1968 3612 1969 3612 1967 3613 1966 3613 1970 3613 1946 3614 1945 3614 1965 3614 1965 3615 1945 3615 1955 3615 1965 3616 1955 3616 1971 3616 1965 3617 1971 3617 1968 3617 1968 3618 1971 3618 1972 3618 1968 3619 1972 3619 1969 3619 1969 3620 1973 3620 1966 3620 1969 3621 1972 3621 1973 3621 1966 3622 1973 3622 1974 3622 1966 3623 1974 3623 1970 3623 1971 3624 1955 3624 1975 3624 1971 3625 1975 3625 1972 3625 1955 3626 1954 3626 1975 3626 1972 3627 1975 3627 1973 3627 1973 3628 1975 3628 1974 3628 1974 3629 1975 3629 1976 3629 1974 3630 1976 3630 1970 3630 1956 3631 1983 3631 1984 3631 1984 3632 1978 3632 1977 3632 1983 3633 1981 3633 1984 3633 1984 3634 1981 3634 1980 3634 1984 3635 1980 3635 1978 3635 1977 3636 1991 3636 1984 3636 1984 3637 1991 3637 1956 3637 1957 3638 1982 3638 1983 3638 1983 3639 1982 3639 1981 3639 1979 3640 1978 3640 1980 3640 1985 3641 1964 3641 1967 3641 1985 3642 1967 3642 1986 3642 1986 3643 1967 3643 1970 3643 1986 3644 1970 3644 1987 3644 1987 3645 1970 3645 1988 3645 1988 3646 1970 3646 1976 3646 1988 3647 1976 3647 1989 3647 1981 3648 1982 3648 1990 3648 1990 3649 1980 3649 1981 3649 1985 3650 1986 3650 1992 3650 1994 3651 1997 3651 1995 3651 1992 3652 1986 3652 1998 3652 1992 3653 1998 3653 1993 3653 1993 3654 1998 3654 1999 3654 1993 3655 1999 3655 2000 3655 1993 3656 2000 3656 1994 3656 1994 3657 2000 3657 1997 3657 1957 3658 1996 3658 1982 3658 1995 3659 1997 3659 2001 3659 1995 3660 2001 3660 1996 3660 1986 3661 1987 3661 1998 3661 1998 3662 1987 3662 2002 3662 1998 3663 2002 3663 1999 3663 2000 3664 2003 3664 1997 3664 1997 3665 2003 3665 2001 3665 1996 3666 2001 3666 1990 3666 1996 3667 1990 3667 1982 3667 2000 3668 1999 3668 2003 3668 2001 3669 2004 3669 1990 3669 1987 3670 1988 3670 2002 3670 2002 3671 1988 3671 2005 3671 2002 3672 2005 3672 1999 3672 1999 3673 2005 3673 2003 3673 2001 3674 2003 3674 2004 3674 1990 3675 2004 3675 2006 3675 1990 3676 2006 3676 1980 3676 2003 3677 2005 3677 2007 3677 2003 3678 2007 3678 2004 3678 1980 3679 2006 3679 1979 3679 1988 3680 1989 3680 2005 3680 2005 3681 1989 3681 2007 3681 2004 3682 2007 3682 2006 3682 1923 3683 1928 3683 2014 3683 1928 3684 1930 3684 2014 3684 2014 3685 1930 3685 2013 3685 2013 3686 1930 3686 1917 3686 2014 3687 2015 3687 1923 3687 1923 3688 2015 3688 2016 3688 1923 3689 2016 3689 1894 3689 2013 3690 2012 3690 2014 3690 2014 3691 2012 3691 2015 3691 2012 3692 2017 3692 2015 3692 2015 3693 2017 3693 2016 3693 2012 3694 2011 3694 2017 3694 2017 3695 2011 3695 2018 3695 2017 3696 2018 3696 2016 3696 2016 3697 2018 3697 2019 3697 2011 3698 2010 3698 2018 3698 2010 3699 2009 3699 2020 3699 2010 3700 2020 3700 2018 3700 2018 3701 2020 3701 2021 3701 2018 3702 2021 3702 2019 3702 2009 3703 2008 3703 2022 3703 2009 3704 2022 3704 2020 3704 2020 3705 2022 3705 2021 3705 2023 3706 2021 3706 2022 3706 2023 3707 2022 3707 2024 3707 2024 3708 2022 3708 2008 3708 2024 3709 2008 3709 2025 3709 1847 3710 1861 3710 2027 3710 2026 3711 2027 3711 2029 3711 2031 3712 2034 3712 2032 3712 2026 3713 1847 3713 2027 3713 2031 3714 2030 3714 2035 3714 2031 3715 2035 3715 2034 3715 2032 3716 2034 3716 2036 3716 2032 3717 2036 3717 2033 3717 2025 3718 2033 3718 2024 3718 2029 3719 2027 3719 2037 3719 2029 3720 2037 3720 2030 3720 2030 3721 2037 3721 2035 3721 2033 3722 2036 3722 2024 3722 2027 3723 1861 3723 2028 3723 2027 3724 2028 3724 2037 3724 2034 3725 2035 3725 2036 3725 1861 3726 1858 3726 2028 3726 2036 3727 2035 3727 2038 3727 2024 3728 2036 3728 2023 3728 2028 3729 1858 3729 1853 3729 2037 3730 2028 3730 2039 3730 2037 3731 2039 3731 2035 3731 2036 3732 2038 3732 2023 3732 2028 3733 1853 3733 2039 3733 2035 3734 2039 3734 2038 3734 1950 3735 1940 3735 2040 3735 2040 3736 1936 3736 2041 3736 1915 3737 2043 3737 2044 3737 1915 3738 2044 3738 2041 3738 1915 3739 2041 3739 1936 3739 2042 3740 2045 3740 2043 3740 2043 3741 2046 3741 2044 3741 2042 3742 2047 3742 2045 3742 2045 3743 2047 3743 2048 3743 2043 3744 2045 3744 2049 3744 2043 3745 2049 3745 2046 3745 2044 3746 2046 3746 2041 3746 2045 3747 2048 3747 2050 3747 2045 3748 2050 3748 2049 3748 2046 3749 2051 3749 2041 3749 2047 3750 2052 3750 2048 3750 2049 3751 2050 3751 2053 3751 2041 3752 2051 3752 2054 3752 2041 3753 2054 3753 2040 3753 2048 3754 2052 3754 2055 3754 2048 3755 2055 3755 2050 3755 2049 3756 2053 3756 2056 3756 2049 3757 2056 3757 2046 3757 2046 3758 2056 3758 2051 3758 2042 3759 2057 3759 2058 3759 2042 3760 2058 3760 2047 3760 2047 3761 2058 3761 2052 3761 2052 3762 2058 3762 2059 3762 2064 3763 1904 3763 2061 3763 2061 3764 1904 3764 1920 3764 2064 3765 1890 3765 1904 3765 2058 3766 2057 3766 2063 3766 2064 3767 2069 3767 2060 3767 2064 3768 2060 3768 2062 3768 2067 3769 2058 3769 2063 3769 2067 3770 2063 3770 2068 3770 2068 3771 2063 3771 2065 3771 2061 3772 2066 3772 2064 3772 2064 3773 2062 3773 1890 3773 2071 3774 2065 3774 2069 3774 2071 3775 2069 3775 2070 3775 2059 3776 2058 3776 2067 3776 2071 3777 2068 3777 2065 3777 2063 3778 2057 3778 2060 3778 2063 3779 2060 3779 2065 3779 2065 3780 2060 3780 2069 3780 2069 3781 2064 3781 2070 3781 2070 3782 2064 3782 2066 3782 2061 3783 1920 3783 1919 3783 2030 3784 2072 3784 2029 3784 2029 3785 2072 3785 2026 3785 2026 3786 2072 3786 2073 3786 2026 3787 2073 3787 1847 3787 2031 3788 2075 3788 2030 3788 2030 3789 2075 3789 2072 3789 1829 3790 1830 3790 2074 3790 2074 3791 1830 3791 1831 3791 2074 3792 1831 3792 2076 3792 2076 3793 1831 3793 1832 3793 2076 3794 1832 3794 2077 3794 2077 3795 1832 3795 1818 3795 2025 3796 1826 3796 1827 3796 2025 3797 1827 3797 2033 3797 2033 3798 1827 3798 1828 3798 2033 3799 1828 3799 2032 3799 2032 3800 1828 3800 1829 3800 2032 3801 1829 3801 2031 3801 2031 3802 1829 3802 2074 3802 2031 3803 2074 3803 2075 3803 1960 3804 2078 3804 1959 3804 1959 3805 2078 3805 1958 3805 1958 3806 2078 3806 2079 3806 1958 3807 2079 3807 1933 3807 2071 3808 2080 3808 2081 3808 2071 3809 2070 3809 2080 3809 2080 3810 2070 3810 2082 3810 2082 3811 2070 3811 2066 3811 2082 3812 2066 3812 2061 3812 2082 3813 2061 3813 2083 3813 2083 3814 2061 3814 1919 3814 1964 3815 2059 3815 2067 3815 1964 3816 2067 3816 1963 3816 1963 3817 2067 3817 2068 3817 1963 3818 2068 3818 2071 3818 1963 3819 2071 3819 1962 3819 1962 3820 2071 3820 1961 3820 1961 3821 2071 3821 2081 3821 1961 3822 2081 3822 1960 3822 1960 3823 2081 3823 2078 3823 2056 3824 2084 3824 2051 3824 2051 3825 2084 3825 2054 3825 2054 3826 2084 3826 2085 3826 2054 3827 2085 3827 2040 3827 2040 3828 2085 3828 1950 3828 2056 3829 2087 3829 2084 3829 1993 3830 1994 3830 2086 3830 2086 3831 1994 3831 2088 3831 2088 3832 1994 3832 1995 3832 2088 3833 1995 3833 1996 3833 2088 3834 1996 3834 2089 3834 2089 3835 1996 3835 1957 3835 2052 3836 1985 3836 1992 3836 2052 3837 1992 3837 2055 3837 2055 3838 1992 3838 2050 3838 2050 3839 1992 3839 1993 3839 2050 3840 1993 3840 2053 3840 2053 3841 1993 3841 2056 3841 2056 3842 1993 3842 2086 3842 2056 3843 2086 3843 2087 3843 1867 3844 2090 3844 1866 3844 1866 3845 2090 3845 1865 3845 1865 3846 2090 3846 2091 3846 1865 3847 2091 3847 1864 3847 2011 3848 2092 3848 2093 3848 2011 3849 2012 3849 2092 3849 2092 3850 2012 3850 2094 3850 2094 3851 2012 3851 2013 3851 2094 3852 2013 3852 2095 3852 2095 3853 2013 3853 1917 3853 1852 3854 2008 3854 2009 3854 1852 3855 2009 3855 1869 3855 1869 3856 2009 3856 2010 3856 1869 3857 2010 3857 1868 3857 1868 3858 2010 3858 2011 3858 1868 3859 2011 3859 1867 3859 1867 3860 2011 3860 2093 3860 1867 3861 2093 3861 2090 3861 2102 3862 2395 3862 2103 3862 2102 3863 2103 3863 2098 3863 1934 3864 2100 3864 1944 3864 1944 3865 2100 3865 2104 3865 2100 3866 2099 3866 2104 3866 2099 3867 2101 3867 2098 3867 2099 3868 2098 3868 2104 3868 2101 3869 2102 3869 2098 3869 2103 3870 2109 3870 2098 3870 1944 3871 2104 3871 1943 3871 2098 3872 2109 3872 2096 3872 2098 3873 2096 3873 2105 3873 2098 3874 2105 3874 2104 3874 2104 3875 2105 3875 1943 3875 2109 3876 2097 3876 2096 3876 1943 3877 2105 3877 1954 3877 2103 3878 2106 3878 2107 3878 2103 3879 2395 3879 2106 3879 2107 3880 2106 3880 2108 3880 2107 3881 2108 3881 2110 3881 2112 3882 2114 3882 2111 3882 2109 3883 2103 3883 2107 3883 2109 3884 2107 3884 2112 3884 2112 3885 2107 3885 2110 3885 2112 3886 2110 3886 2115 3886 2115 3887 2110 3887 2113 3887 2113 3888 2116 3888 2115 3888 2109 3889 2112 3889 2111 3889 2114 3890 2115 3890 2117 3890 2117 3891 2115 3891 2116 3891 2118 3892 2117 3892 2116 3892 2114 3893 2112 3893 2115 3893 2097 3894 2109 3894 2111 3894 2118 3895 1646 3895 2117 3895 2117 3896 1646 3896 1645 3896 2117 3897 1645 3897 2114 3897 2114 3898 1645 3898 1641 3898 2114 3899 1641 3899 2111 3899 2111 3900 1641 3900 2097 3900 1640 3901 1639 3901 2119 3901 2119 3902 2120 3902 2125 3902 2125 3903 2120 3903 2126 3903 2120 3904 2122 3904 2127 3904 2127 3905 2122 3905 2123 3905 1640 3906 2119 3906 1644 3906 2126 3907 2120 3907 2127 3907 2125 3908 1644 3908 2119 3908 2127 3909 2123 3909 2128 3909 2128 3910 2123 3910 2124 3910 2125 3911 2126 3911 2129 3911 2129 3912 2126 3912 2127 3912 1644 3913 2125 3913 2130 3913 2130 3914 2125 3914 2129 3914 2129 3915 2127 3915 2128 3915 1642 3916 1644 3916 2130 3916 2130 3917 2129 3917 2131 3917 2131 3918 2129 3918 2132 3918 2132 3919 2129 3919 2128 3919 1641 3920 1642 3920 2130 3920 1641 3921 2130 3921 2131 3921 2124 3922 2133 3922 2128 3922 2128 3923 2133 3923 2134 3923 2128 3924 2134 3924 2132 3924 2132 3925 2134 3925 2135 3925 2135 3926 2134 3926 2138 3926 2135 3927 2138 3927 2139 3927 2135 3928 2139 3928 2136 3928 2136 3929 2139 3929 2140 3929 2136 3930 2140 3930 2137 3930 2138 3931 2141 3931 2139 3931 2137 3932 2140 3932 2142 3932 2139 3933 2143 3933 2140 3933 2134 3934 2133 3934 2138 3934 2138 3935 2133 3935 2144 3935 2138 3936 2144 3936 2141 3936 2139 3937 2141 3937 2145 3937 2139 3938 2145 3938 2143 3938 2141 3939 2146 3939 2145 3939 2140 3940 2143 3940 2147 3940 2140 3941 2147 3941 2148 3941 2140 3942 2148 3942 2142 3942 2141 3943 2144 3943 2146 3943 2143 3944 2145 3944 2147 3944 2142 3945 2148 3945 2149 3945 2149 3946 2150 3946 2142 3946 2142 3947 2150 3947 2151 3947 2142 3948 2151 3948 2152 3948 2142 3949 2152 3949 2137 3949 2137 3950 2152 3950 2136 3950 2152 3951 2154 3951 2153 3951 2153 3952 2154 3952 2156 3952 2152 3953 2151 3953 2154 3953 2153 3954 2156 3954 2157 3954 2153 3955 2157 3955 2155 3955 2154 3956 2151 3956 2158 3956 2154 3957 2158 3957 2156 3957 2155 3958 2157 3958 2159 3958 2151 3959 2150 3959 2160 3959 2151 3960 2160 3960 2158 3960 2156 3961 2158 3961 2161 3961 2156 3962 2161 3962 2157 3962 2158 3963 2160 3963 2162 3963 2157 3964 2161 3964 2163 3964 2157 3965 2163 3965 2159 3965 2158 3966 2162 3966 2161 3966 2159 3967 2594 3967 2173 3967 2159 3968 2173 3968 2155 3968 2155 3969 2173 3969 2174 3969 2155 3970 2174 3970 2153 3970 1682 3971 1681 3971 1686 3971 2167 3972 1690 3972 2168 3972 2168 3973 1690 3973 1682 3973 2170 3974 1682 3974 1686 3974 2170 3975 1686 3975 2169 3975 2169 3976 1686 3976 1688 3976 2168 3977 1682 3977 2170 3977 2166 3978 2167 3978 2168 3978 2165 3979 2166 3979 2171 3979 2171 3980 2166 3980 2168 3980 2171 3981 2168 3981 2172 3981 2172 3982 2168 3982 2170 3982 2172 3983 2170 3983 2169 3983 2164 3984 2165 3984 2171 3984 2164 3985 2171 3985 2172 3985 2174 3986 2172 3986 2169 3986 2173 3987 2164 3987 2172 3987 2173 3988 2172 3988 2174 3988 2594 3989 2164 3989 2173 3989 2175 3990 1688 3990 1686 3990 2175 3991 1686 3991 2176 3991 2176 3992 1686 3992 1685 3992 2176 3993 1685 3993 1680 3993 2176 3994 1680 3994 2177 3994 2177 3995 1680 3995 1683 3995 2182 3996 2177 3996 2180 3996 2645 3997 2180 3997 1683 3997 1683 3998 2180 3998 2177 3998 2182 3999 2180 3999 2181 3999 2184 4000 2182 4000 2181 4000 2188 4001 2183 4001 2186 4001 2183 4002 2188 4002 2181 4002 2181 4003 2188 4003 2184 4003 2182 4004 2184 4004 2176 4004 2182 4005 2176 4005 2177 4005 2186 4006 2183 4006 2529 4006 2184 4007 2185 4007 2176 4007 2188 4008 2179 4008 2178 4008 2187 4009 2179 4009 2188 4009 2185 4010 2178 4010 2175 4010 2185 4011 2175 4011 2176 4011 2178 4012 2185 4012 2184 4012 2178 4013 2184 4013 2188 4013 2188 4014 2186 4014 2187 4014 2192 4015 2190 4015 2187 4015 2194 4016 2187 4016 2190 4016 2194 4017 2179 4017 2187 4017 2195 4018 2179 4018 2194 4018 2178 4019 2179 4019 2195 4019 2178 4020 2195 4020 2196 4020 2178 4021 2196 4021 2175 4021 2190 4022 2191 4022 2194 4022 2194 4023 2191 4023 2195 4023 2191 4024 2193 4024 2197 4024 2191 4025 2197 4025 2195 4025 2195 4026 2197 4026 2198 4026 2195 4027 2198 4027 2196 4027 2193 4028 2189 4028 2199 4028 2193 4029 2199 4029 2197 4029 2197 4030 2199 4030 2198 4030 2189 4031 1991 4031 1977 4031 2189 4032 1977 4032 2199 4032 2199 4033 1977 4033 1978 4033 2199 4034 1978 4034 1979 4034 2199 4035 1979 4035 2198 4035 2198 4036 1979 4036 2196 4036 2221 4037 2204 4037 2205 4037 2451 4038 2221 4038 2205 4038 1899 4039 2206 4039 1901 4039 2206 4040 2207 4040 2209 4040 2206 4041 2209 4041 1901 4041 2205 4042 2204 4042 2203 4042 2205 4043 2203 4043 2208 4043 2208 4044 2203 4044 2207 4044 2207 4045 2203 4045 2209 4045 2202 4046 2203 4046 2204 4046 2209 4047 1902 4047 1901 4047 2203 4048 2202 4048 2201 4048 2209 4049 2203 4049 2210 4049 2209 4050 2210 4050 1902 4050 2203 4051 2201 4051 2210 4051 1901 4052 1902 4052 1886 4052 2202 4053 2200 4053 2201 4053 2201 4054 2200 4054 2210 4054 1902 4055 2210 4055 1886 4055 2210 4056 2200 4056 2215 4056 2213 4057 2218 4057 2212 4057 2200 4058 2219 4058 2215 4058 2215 4059 2219 4059 2213 4059 2213 4060 2220 4060 2218 4060 2221 4061 2222 4061 2217 4061 2202 4062 2223 4062 2200 4062 2219 4063 2220 4063 2213 4063 2212 4064 2218 4064 2224 4064 2224 4065 2218 4065 2220 4065 2219 4066 2200 4066 2223 4066 2204 4067 2223 4067 2202 4067 2211 4068 2212 4068 2224 4068 2224 4069 2220 4069 2214 4069 2214 4070 2220 4070 2216 4070 2217 4071 2216 4071 2223 4071 2217 4072 2223 4072 2221 4072 2221 4073 2223 4073 2204 4073 2223 4074 2216 4074 2219 4074 2219 4075 2216 4075 2220 4075 1648 4076 2215 4076 2213 4076 1648 4077 2213 4077 1653 4077 1653 4078 2213 4078 1650 4078 1650 4079 2213 4079 2212 4079 1650 4080 2212 4080 1647 4080 1647 4081 2212 4081 2211 4081 2230 4082 2229 4082 2231 4082 2225 4083 1654 4083 2226 4083 2232 4084 2228 4084 2229 4084 2233 4085 2226 4085 2227 4085 2233 4086 2227 4086 2228 4086 2233 4087 2228 4087 2234 4087 2234 4088 2228 4088 2232 4088 1649 4089 2225 4089 2226 4089 1649 4090 2226 4090 2233 4090 2232 4091 2229 4091 2230 4091 2235 4092 2234 4092 2232 4092 2235 4093 2232 4093 2236 4093 2236 4094 2232 4094 2230 4094 2233 4095 2234 4095 2235 4095 1648 4096 1649 4096 2237 4096 2237 4097 1649 4097 2233 4097 2237 4098 2233 4098 2235 4098 2239 4099 2235 4099 2236 4099 2239 4100 2236 4100 2238 4100 2239 4101 1648 4101 2237 4101 2239 4102 2237 4102 2235 4102 2242 4103 2238 4103 2240 4103 2240 4104 2238 4104 2236 4104 2240 4105 2236 4105 2230 4105 2240 4106 2230 4106 2241 4106 2241 4107 2230 4107 2231 4107 2243 4108 2245 4108 2244 4108 2242 4109 2247 4109 2243 4109 2244 4110 2245 4110 2246 4110 2242 4111 2240 4111 2247 4111 2243 4112 2247 4112 2248 4112 2243 4113 2248 4113 2245 4113 2247 4114 2240 4114 2249 4114 2245 4115 2250 4115 2246 4115 2248 4116 2247 4116 2251 4116 2249 4117 2252 4117 2247 4117 2247 4118 2252 4118 2251 4118 2248 4119 2251 4119 2253 4119 2248 4120 2253 4120 2245 4120 2245 4121 2253 4121 2254 4121 2245 4122 2254 4122 2250 4122 2240 4123 2241 4123 2249 4123 2249 4124 2241 4124 2252 4124 2250 4125 2254 4125 2255 4125 2256 4126 2244 4126 2246 4126 2256 4127 2246 4127 2257 4127 2257 4128 2246 4128 2250 4128 2257 4129 2250 4129 2258 4129 2258 4130 2250 4130 2255 4130 2260 4131 2259 4131 2261 4131 2260 4132 2262 4132 2263 4132 2256 4133 2257 4133 2259 4133 2259 4134 2257 4134 2264 4134 2259 4135 2264 4135 2261 4135 2260 4136 2261 4136 2262 4136 2261 4137 2264 4137 2265 4137 2257 4138 2258 4138 2264 4138 2263 4139 2262 4139 2266 4139 2264 4140 2258 4140 2267 4140 2261 4141 2265 4141 2268 4141 2261 4142 2268 4142 2262 4142 2262 4143 2268 4143 2269 4143 2262 4144 2269 4144 2266 4144 2264 4145 2267 4145 2270 4145 2264 4146 2270 4146 2265 4146 2265 4147 2270 4147 2268 4147 2271 4148 2260 4148 2263 4148 2271 4149 2263 4149 2272 4149 2272 4150 2263 4150 2266 4150 2272 4151 2266 4151 2273 4151 2275 4152 1607 4152 1608 4152 2275 4153 1608 4153 1609 4153 2276 4154 1607 4154 2275 4154 2275 4155 1609 4155 2277 4155 2277 4156 1609 4156 1610 4156 2278 4157 2276 4157 2275 4157 2279 4158 2278 4158 2275 4158 2279 4159 2275 4159 2277 4159 2279 4160 2277 4160 2282 4160 2274 4161 2276 4161 2278 4161 2280 4162 2278 4162 2279 4162 2281 4163 2274 4163 2278 4163 2281 4164 2278 4164 2280 4164 2280 4165 2279 4165 2282 4165 2271 4166 2280 4166 2282 4166 2273 4167 2281 4167 2272 4167 2272 4168 2281 4168 2280 4168 2272 4169 2280 4169 2271 4169 1606 4170 2297 4170 2298 4170 1606 4171 2298 4171 1612 4171 2283 4172 1610 4172 2295 4172 2295 4173 1610 4173 1611 4173 2295 4174 1611 4174 1612 4174 2295 4175 1612 4175 2298 4175 2288 4176 2289 4176 2287 4176 2290 4177 2286 4177 2285 4177 2290 4178 2285 4178 2284 4178 2284 4179 2283 4179 2295 4179 2292 4180 2293 4180 2291 4180 2294 4181 2292 4181 2291 4181 2295 4182 2294 4182 2284 4182 2284 4183 2294 4183 2290 4183 2290 4184 2288 4184 2286 4184 2296 4185 2626 4185 2292 4185 2292 4186 2626 4186 2293 4186 2291 4187 2290 4187 2294 4187 2294 4188 2295 4188 2298 4188 2297 4189 2296 4189 2298 4189 2296 4190 2292 4190 2298 4190 2292 4191 2294 4191 2298 4191 2287 4192 2286 4192 2288 4192 2288 4193 2290 4193 2291 4193 2301 4194 2287 4194 2310 4194 2285 4195 2286 4195 2303 4195 2303 4196 2286 4196 2301 4196 2301 4197 2286 4197 2287 4197 2304 4198 2285 4198 2303 4198 2285 4199 2304 4199 2284 4199 2301 4200 2300 4200 2303 4200 2300 4201 2302 4201 2305 4201 2300 4202 2305 4202 2303 4202 2303 4203 2305 4203 2306 4203 2303 4204 2306 4204 2304 4204 2302 4205 2299 4205 2307 4205 2302 4206 2307 4206 2305 4206 2305 4207 2307 4207 2306 4207 2299 4208 1815 4208 1814 4208 2299 4209 1814 4209 2307 4209 2307 4210 1814 4210 2306 4210 2306 4211 1816 4211 1812 4211 2306 4212 1812 4212 2304 4212 2312 4213 2313 4213 2314 4213 2311 4214 2289 4214 2312 4214 2316 4215 2312 4215 2314 4215 2316 4216 2314 4216 2315 4216 2311 4217 2312 4217 2316 4217 2318 4218 2310 4218 2311 4218 2319 4219 2311 4219 2316 4219 2319 4220 2316 4220 2318 4220 2316 4221 2315 4221 2317 4221 2320 4222 2318 4222 2316 4222 2320 4223 2316 4223 2317 4223 2311 4224 2319 4224 2318 4224 2320 4225 2317 4225 2321 4225 2318 4226 2320 4226 2321 4226 2322 4227 2321 4227 2317 4227 2322 4228 2317 4228 2323 4228 2323 4229 2317 4229 2315 4229 2325 4230 2322 4230 2323 4230 2325 4231 2323 4231 2324 4231 2324 4232 2323 4232 2315 4232 2326 4233 2322 4233 2325 4233 2308 4234 2322 4234 2326 4234 2309 4235 2325 4235 2324 4235 2327 4236 2326 4236 2325 4236 2327 4237 2325 4237 2309 4237 2328 4238 2308 4238 2326 4238 2328 4239 2326 4239 2329 4239 2329 4240 2326 4240 2327 4240 2329 4241 2327 4241 2330 4241 2330 4242 2327 4242 2309 4242 2331 4243 2328 4243 2379 4243 2379 4244 2328 4244 2369 4244 2369 4245 2328 4245 2329 4245 2369 4246 2329 4246 2332 4246 2332 4247 2329 4247 2330 4247 2332 4248 2330 4248 2333 4248 2333 4249 2330 4249 2309 4249 2342 4250 2343 4250 2344 4250 2354 4251 2355 4251 2358 4251 2354 4252 2358 4252 2353 4252 2353 4253 2358 4253 2359 4253 2353 4254 2359 4254 2352 4254 2341 4255 2342 4255 2360 4255 2341 4256 2360 4256 2340 4256 2357 4257 2361 4257 2356 4257 2355 4258 2356 4258 2362 4258 2355 4259 2362 4259 2358 4259 2352 4260 2359 4260 2351 4260 2346 4261 2347 4261 2363 4261 2346 4262 2363 4262 2345 4262 2344 4263 2345 4263 2364 4263 2344 4264 2364 4264 2342 4264 2340 4265 2360 4265 2365 4265 2340 4266 2365 4266 2339 4266 2338 4267 2339 4267 2366 4267 2338 4268 2366 4268 2337 4268 2337 4269 2366 4269 2336 4269 2336 4270 2366 4270 2367 4270 2336 4271 2367 4271 2335 4271 2334 4272 2335 4272 2368 4272 2334 4273 2368 4273 2333 4273 2333 4274 2368 4274 2369 4274 2333 4275 2369 4275 2332 4275 2356 4276 2361 4276 2362 4276 2349 4277 2350 4277 2370 4277 2349 4278 2370 4278 2348 4278 2348 4279 2370 4279 2371 4279 2348 4280 2371 4280 2347 4280 2345 4281 2363 4281 2364 4281 2339 4282 2365 4282 2372 4282 2339 4283 2372 4283 2366 4283 2351 4284 2359 4284 2374 4284 2351 4285 2374 4285 2350 4285 2350 4286 2374 4286 2370 4286 2347 4287 2371 4287 2363 4287 2342 4288 2364 4288 2375 4288 2342 4289 2375 4289 2360 4289 2335 4290 2367 4290 2368 4290 2361 4291 2373 4291 2362 4291 2362 4292 2376 4292 2358 4292 2359 4293 2358 4293 2377 4293 2359 4294 2377 4294 2374 4294 2366 4295 2372 4295 2378 4295 2366 4296 2378 4296 2367 4296 2368 4297 2367 4297 2379 4297 2368 4298 2379 4298 2369 4298 2362 4299 2373 4299 2376 4299 2358 4300 2376 4300 2377 4300 2374 4301 2377 4301 2370 4301 2364 4302 2363 4302 2380 4302 2364 4303 2380 4303 2375 4303 2360 4304 2375 4304 2365 4304 2365 4305 2375 4305 2372 4305 2370 4306 2377 4306 2371 4306 2363 4307 2371 4307 2380 4307 2367 4308 2378 4308 2379 4308 2372 4309 2375 4309 2378 4309 2381 4310 2373 4310 2382 4310 2382 4311 2373 4311 2361 4311 2382 4312 2361 4312 2357 4312 2382 4313 2357 4313 2383 4313 2383 4314 2385 4314 2386 4314 2383 4315 2386 4315 2382 4315 2382 4316 2386 4316 2381 4316 2381 4317 2386 4317 2384 4317 2392 4318 2108 4318 2394 4318 2396 4319 2392 4319 2394 4319 2396 4320 2394 4320 2393 4320 2396 4321 2393 4321 2397 4321 2396 4322 2391 4322 2392 4322 2397 4323 2393 4323 2398 4323 2398 4324 2393 4324 2395 4324 2390 4325 2391 4325 2396 4325 2390 4326 2396 4326 2399 4326 2399 4327 2396 4327 2397 4327 2399 4328 2397 4328 2400 4328 2400 4329 2397 4329 2398 4329 2401 4330 2388 4330 2390 4330 2401 4331 2390 4331 2399 4331 2401 4332 2399 4332 2389 4332 2389 4333 2399 4333 2400 4333 2389 4334 2400 4334 2398 4334 2402 4335 2387 4335 2388 4335 2402 4336 2388 4336 2401 4336 2403 4337 2401 4337 2389 4337 2404 4338 2402 4338 2401 4338 2404 4339 2401 4339 2403 4339 2404 4340 2403 4340 2384 4340 2384 4341 2403 4341 2389 4341 2385 4342 2402 4342 2386 4342 2386 4343 2402 4343 2404 4343 2386 4344 2404 4344 2384 4344 2409 4345 1792 4345 1793 4345 1791 4346 2410 4346 1789 4346 2405 4347 1796 4347 1794 4347 2411 4348 2408 4348 2412 4348 2412 4349 2408 4349 1795 4349 2412 4350 1795 4350 2414 4350 2414 4351 1795 4351 1796 4351 2414 4352 1796 4352 2405 4352 2413 4353 2411 4353 2440 4353 2440 4354 2411 4354 2412 4354 2440 4355 2412 4355 2443 4355 2415 4356 2410 4356 1792 4356 1792 4357 2410 4357 1791 4357 2407 4358 2420 4358 2421 4358 2421 4359 2423 4359 2424 4359 2425 4360 2430 4360 2426 4360 2426 4361 2430 4361 2343 4361 2431 4362 2430 4362 2434 4362 2436 4363 2437 4363 2406 4363 2406 4364 2437 4364 2432 4364 2434 4365 2433 4365 2435 4365 2434 4366 2435 4366 2436 4366 2436 4367 2435 4367 2437 4367 2439 4368 2440 4368 2441 4368 2441 4369 2440 4369 2442 4369 2439 4370 2438 4370 2440 4370 2420 4371 2337 4371 2416 4371 2416 4372 2417 4372 2422 4372 2422 4373 2417 4373 2415 4373 2422 4374 2415 4374 2409 4374 2409 4375 2415 4375 1792 4375 2422 4376 2421 4376 2416 4376 2416 4377 2421 4377 2420 4377 2422 4378 2409 4378 1793 4378 2426 4379 2343 4379 2418 4379 2418 4380 2419 4380 2425 4380 2425 4381 2419 4381 2407 4381 1793 4382 2423 4382 2422 4382 2422 4383 2423 4383 2421 4383 2421 4384 2424 4384 2407 4384 2407 4385 2424 4385 2425 4385 2418 4386 2425 4386 2426 4386 2427 4387 2343 4387 2431 4387 2431 4388 2343 4388 2430 4388 2423 4389 2429 4389 2424 4389 2424 4390 2429 4390 2425 4390 2425 4391 2429 4391 2430 4391 2431 4392 2434 4392 2427 4392 2427 4393 2434 4393 2428 4393 2428 4394 2436 4394 2445 4394 2445 4395 2436 4395 2406 4395 2436 4396 2428 4396 2434 4396 2432 4397 2439 4397 2349 4397 2432 4398 2349 4398 2406 4398 2429 4399 2433 4399 2430 4399 2430 4400 2433 4400 2434 4400 2437 4401 2438 4401 2432 4401 2432 4402 2438 4402 2439 4402 2443 4403 2442 4403 2440 4403 2438 4404 2437 4404 2435 4404 2414 4405 2444 4405 2412 4405 2412 4406 2444 4406 2443 4406 2413 4407 2440 4407 2438 4407 2413 4408 2438 4408 2435 4408 2222 4409 2221 4409 2451 4409 2222 4410 2451 4410 2452 4410 2453 4411 2222 4411 2452 4411 2454 4412 2453 4412 2452 4412 2454 4413 2452 4413 2451 4413 2456 4414 2453 4414 2454 4414 2456 4415 2454 4415 2457 4415 2455 4416 2454 4416 2451 4416 2459 4417 2456 4417 2457 4417 2458 4418 2454 4418 2455 4418 2450 4419 2459 4419 2457 4419 2457 4420 2454 4420 2458 4420 2460 4421 2450 4421 2457 4421 2460 4422 2457 4422 2458 4422 2449 4423 2460 4423 2458 4423 2448 4424 2450 4424 2461 4424 2461 4425 2450 4425 2460 4425 2461 4426 2460 4426 2462 4426 2462 4427 2460 4427 2449 4427 2447 4428 2448 4428 2461 4428 2463 4429 2461 4429 2462 4429 2463 4430 2447 4430 2461 4430 2463 4431 2462 4431 2464 4431 2464 4432 2462 4432 2449 4432 2465 4433 2447 4433 2463 4433 2465 4434 2463 4434 2464 4434 2446 4435 2447 4435 2465 4435 2466 4436 2446 4436 2465 4436 2466 4437 2465 4437 2468 4437 2468 4438 2465 4438 2467 4438 2467 4439 2465 4439 2464 4439 2467 4440 2516 4440 2469 4440 2467 4441 2469 4441 2470 4441 2467 4442 2470 4442 2468 4442 2468 4443 2470 4443 2471 4443 2468 4444 2471 4444 2466 4444 2483 4445 2482 4445 2484 4445 2483 4446 2484 4446 2485 4446 2489 4447 2491 4447 2490 4447 2490 4448 2491 4448 2492 4448 2486 4449 2487 4449 2498 4449 2486 4450 2498 4450 2485 4450 2479 4451 2480 4451 2499 4451 2479 4452 2499 4452 2478 4452 2473 4453 2475 4453 2500 4453 2473 4454 2500 4454 2474 4454 2471 4455 2470 4455 2497 4455 2495 4456 2496 4456 2502 4456 2495 4457 2502 4457 2494 4457 2492 4458 2493 4458 2503 4458 2492 4459 2503 4459 2490 4459 2478 4460 2499 4460 2504 4460 2478 4461 2504 4461 2477 4461 2477 4462 2504 4462 2505 4462 2477 4463 2505 4463 2476 4463 2475 4464 2476 4464 2506 4464 2475 4465 2506 4465 2500 4465 2472 4466 2474 4466 2501 4466 2497 4467 2470 4467 2496 4467 2496 4468 2470 4468 2502 4468 2490 4469 2503 4469 2507 4469 2490 4470 2507 4470 2489 4470 2489 4471 2507 4471 2488 4471 2488 4472 2507 4472 2508 4472 2488 4473 2508 4473 2487 4473 2487 4474 2508 4474 2498 4474 2498 4475 2508 4475 2509 4475 2498 4476 2509 4476 2485 4476 2481 4477 2482 4477 2510 4477 2481 4478 2510 4478 2480 4478 2480 4479 2510 4479 2499 4479 2474 4480 2500 4480 2511 4480 2474 4481 2511 4481 2501 4481 2494 4482 2502 4482 2512 4482 2494 4483 2512 4483 2493 4483 2493 4484 2512 4484 2503 4484 2485 4485 2509 4485 2483 4485 2483 4486 2509 4486 2513 4486 2483 4487 2513 4487 2482 4487 2482 4488 2513 4488 2514 4488 2482 4489 2514 4489 2510 4489 2476 4490 2505 4490 2506 4490 2501 4491 2511 4491 2515 4491 2502 4492 2516 4492 2512 4492 2503 4493 2512 4493 2517 4493 2503 4494 2517 4494 2507 4494 2508 4495 2507 4495 2518 4495 2510 4496 2514 4496 2519 4496 2510 4497 2519 4497 2499 4497 2499 4498 2519 4498 2504 4498 2505 4499 2504 4499 2520 4499 2470 4500 2469 4500 2502 4500 2502 4501 2469 4501 2516 4501 2507 4502 2517 4502 2518 4502 2508 4503 2518 4503 2509 4503 2506 4504 2505 4504 2521 4504 2506 4505 2521 4505 2500 4505 2500 4506 2521 4506 2511 4506 2509 4507 2518 4507 2513 4507 2514 4508 2513 4508 2519 4508 2504 4509 2519 4509 2520 4509 2505 4510 2520 4510 2521 4510 2517 4511 2512 4511 2518 4511 2515 4512 2522 4512 2523 4512 2515 4513 2523 4513 2501 4513 2501 4514 2523 4514 2524 4514 2501 4515 2524 4515 2472 4515 2522 4516 2525 4516 2544 4516 2522 4517 2544 4517 2523 4517 2523 4518 2544 4518 2545 4518 2523 4519 2545 4519 2524 4519 2524 4520 2545 4520 2526 4520 2528 4521 2529 4521 2530 4521 2530 4522 2529 4522 2531 4522 2530 4523 2532 4523 2533 4523 2530 4524 2533 4524 2535 4524 2527 4525 2528 4525 2534 4525 2534 4526 2528 4526 2530 4526 2534 4527 2530 4527 2535 4527 2536 4528 2535 4528 2533 4528 2192 4529 2527 4529 2534 4529 2534 4530 2535 4530 2537 4530 2537 4531 2535 4531 2536 4531 2192 4532 2534 4532 2537 4532 2537 4533 2536 4533 2538 4533 2529 4534 2528 4534 2527 4534 2539 4535 2538 4535 2540 4535 2540 4536 2538 4536 2536 4536 2540 4537 2536 4537 2541 4537 2541 4538 2536 4538 2533 4538 2541 4539 2533 4539 2542 4539 2543 4540 2540 4540 2541 4540 2543 4541 2541 4541 2542 4541 2544 4542 2539 4542 2540 4542 2544 4543 2540 4543 2545 4543 2545 4544 2540 4544 2543 4544 2546 4545 2543 4545 2542 4545 2545 4546 2543 4546 2546 4546 2525 4547 2539 4547 2544 4547 2545 4548 2546 4548 2526 4548 2632 4549 1799 4549 1804 4549 2575 4550 2487 4550 2574 4550 2547 4551 1803 4551 1799 4551 2551 4552 1810 4552 1811 4552 1809 4553 2552 4553 1807 4553 2554 4554 1801 4554 2553 4554 2553 4555 1801 4555 2550 4555 2550 4556 1801 4556 1802 4556 2554 4557 2553 4557 2581 4557 2580 4558 2554 4558 2581 4558 2577 4559 2581 4559 2553 4559 2555 4560 2550 4560 1802 4560 2555 4561 1802 4561 2547 4561 2547 4562 1802 4562 1803 4562 2556 4563 2552 4563 1809 4563 2549 4564 2583 4564 2562 4564 2562 4565 2583 4565 2557 4565 2567 4566 2561 4566 2562 4566 2564 4567 2568 4567 2586 4567 2569 4568 2586 4568 2570 4568 2585 4569 2570 4569 2574 4569 2572 4570 2571 4570 2573 4570 2572 4571 2573 4571 2574 4571 2574 4572 2573 4572 2575 4572 2575 4573 2573 4573 2576 4573 2491 4574 2577 4574 2578 4574 2578 4575 2577 4575 2579 4575 2573 4576 2580 4576 2576 4576 2576 4577 2580 4577 2581 4577 2576 4578 2581 4578 2491 4578 2491 4579 2581 4579 2577 4579 2556 4580 1809 4580 1810 4580 2558 4581 2556 4581 2551 4581 2551 4582 2556 4582 1810 4582 2558 4583 2551 4583 2557 4583 2584 4584 2559 4584 2548 4584 2562 4585 2557 4585 2560 4585 2560 4586 2557 4586 2551 4586 2584 4587 2548 4587 2563 4587 2563 4588 2548 4588 2561 4588 2561 4589 2548 4589 2549 4589 2551 4590 1811 4590 2560 4590 2560 4591 2567 4591 2562 4591 2549 4592 2562 4592 2561 4592 2563 4593 2564 4593 2584 4593 2584 4594 2564 4594 2565 4594 2585 4595 2566 4595 2570 4595 2570 4596 2566 4596 2484 4596 2484 4597 2565 4597 2586 4597 2586 4598 2565 4598 2564 4598 2585 4599 2574 4599 2486 4599 2486 4600 2574 4600 2487 4600 2567 4601 2568 4601 2561 4601 2561 4602 2568 4602 2563 4602 2563 4603 2568 4603 2564 4603 2586 4604 2569 4604 2484 4604 2484 4605 2569 4605 2570 4605 2574 4606 2570 4606 2572 4606 2572 4607 2570 4607 2571 4607 2571 4608 2570 4608 2586 4608 2571 4609 2586 4609 2568 4609 2579 4610 2550 4610 2582 4610 2582 4611 2550 4611 2555 4611 2550 4612 2579 4612 2553 4612 2553 4613 2579 4613 2577 4613 2580 4614 2573 4614 2554 4614 2554 4615 2573 4615 2571 4615 2120 4616 2119 4616 2121 4616 2589 4617 1637 4617 1625 4617 2589 4618 1625 4618 1772 4618 2121 4619 1772 4619 1775 4619 2123 4620 2588 4620 2587 4620 2123 4621 2587 4621 2124 4621 1639 4622 1637 4622 2589 4622 2119 4623 1639 4623 2589 4623 2119 4624 2589 4624 1772 4624 2119 4625 1772 4625 2121 4625 2120 4626 2121 4626 1775 4626 2120 4627 1775 4627 2122 4627 2122 4628 1775 4628 2588 4628 2122 4629 2588 4629 2123 4629 1604 4630 1590 4630 1592 4630 1604 4631 1759 4631 1590 4631 1603 4632 1600 4632 1604 4632 1604 4633 1600 4633 1607 4633 1604 4634 1607 4634 2276 4634 1759 4635 1604 4635 2276 4635 1759 4636 2276 4636 1758 4636 1758 4637 2276 4637 2274 4637 2590 4638 2274 4638 2281 4638 1758 4639 2274 4639 2590 4639 2281 4640 2273 4640 2590 4640 2590 4641 2273 4641 2591 4641 2167 4642 1694 4642 1690 4642 2167 4643 1742 4643 1744 4643 2167 4644 1744 4644 1694 4644 1694 4645 1744 4645 1698 4645 2165 4646 2592 4646 1742 4646 2594 4647 2593 4647 2164 4647 2164 4648 2593 4648 2592 4648 2164 4649 2592 4649 2165 4649 2165 4650 1742 4650 2166 4650 2166 4651 1742 4651 2167 4651 1659 4652 1658 4652 1663 4652 2597 4653 1659 4653 1663 4653 2226 4654 1654 4654 1659 4654 2226 4655 1659 4655 2597 4655 2597 4656 1663 4656 1721 4656 2227 4657 2226 4657 2597 4657 2227 4658 2597 4658 1721 4658 2227 4659 1721 4659 1724 4659 2228 4660 2227 4660 1724 4660 2228 4661 1724 4661 1723 4661 2229 4662 2228 4662 2596 4662 2596 4663 2228 4663 1723 4663 2231 4664 2229 4664 2596 4664 2231 4665 2596 4665 2595 4665 2133 4666 2598 4666 2144 4666 2144 4667 2598 4667 2599 4667 2144 4668 2599 4668 2146 4668 2146 4669 2599 4669 2600 4669 2146 4670 2600 4670 2145 4670 2145 4671 2600 4671 2147 4671 2147 4672 2600 4672 2601 4672 2147 4673 2601 4673 2148 4673 2148 4674 2601 4674 2149 4674 2602 4675 2159 4675 2163 4675 2602 4676 2163 4676 2161 4676 2602 4677 2161 4677 2603 4677 2603 4678 2161 4678 2162 4678 2603 4679 2162 4679 2604 4679 2604 4680 2162 4680 2160 4680 2604 4681 2160 4681 2605 4681 2605 4682 2160 4682 2150 4682 2258 4683 2606 4683 2267 4683 2267 4684 2606 4684 2270 4684 2270 4685 2606 4685 2607 4685 2270 4686 2607 4686 2268 4686 2268 4687 2607 4687 2608 4687 2268 4688 2608 4688 2269 4688 2269 4689 2608 4689 2609 4689 2269 4690 2609 4690 2266 4690 2610 4691 2255 4691 2254 4691 2610 4692 2254 4692 2253 4692 2610 4693 2253 4693 2611 4693 2611 4694 2253 4694 2251 4694 2611 4695 2251 4695 2252 4695 2611 4696 2252 4696 2612 4696 2612 4697 2252 4697 2241 4697 2392 4698 2391 4698 2613 4698 2614 4699 2402 4699 2385 4699 2402 4700 2614 4700 2387 4700 2390 4701 2388 4701 2615 4701 2394 4702 2108 4702 2393 4702 2108 4703 2392 4703 2110 4703 2613 4704 2110 4704 2392 4704 2614 4705 2618 4705 2387 4705 2387 4706 2618 4706 2619 4706 2387 4707 2619 4707 2388 4707 2388 4708 2619 4708 2615 4708 2615 4709 2620 4709 2390 4709 2390 4710 2620 4710 2391 4710 2391 4711 2620 4711 2613 4711 2614 4712 1797 4712 2618 4712 2620 4713 2621 4713 2613 4713 2613 4714 2621 4714 2116 4714 2613 4715 2116 4715 2113 4715 2618 4716 2616 4716 2619 4716 2619 4717 2616 4717 2622 4717 2619 4718 2622 4718 2615 4718 2615 4719 2622 4719 2620 4719 1797 4720 1798 4720 2618 4720 2618 4721 1798 4721 2616 4721 2623 4722 2118 4722 2116 4722 2622 4723 2616 4723 2617 4723 2622 4724 2617 4724 2620 4724 2620 4725 2617 4725 2623 4725 2620 4726 2623 4726 2621 4726 2621 4727 2623 4727 2116 4727 2617 4728 1627 4728 2623 4728 2623 4729 1627 4729 1634 4729 1646 4730 2118 4730 1634 4730 1634 4731 2118 4731 2623 4731 2616 4732 1620 4732 2617 4732 1620 4733 1631 4733 2617 4733 2617 4734 1631 4734 1627 4734 1798 4735 1618 4735 1620 4735 1798 4736 1620 4736 2616 4736 2311 4737 2310 4737 2287 4737 2624 4738 2315 4738 2314 4738 2324 4739 2315 4739 2625 4739 2289 4740 2291 4740 2293 4740 2293 4741 2313 4741 2312 4741 2293 4742 2312 4742 2289 4742 1790 4743 2625 4743 1787 4743 1787 4744 2625 4744 1788 4744 2629 4745 2631 4745 2628 4745 2628 4746 2631 4746 2630 4746 2628 4747 2630 4747 2627 4747 2627 4748 2296 4748 2297 4748 1788 4749 2625 4749 2624 4749 1788 4750 2624 4750 2629 4750 2629 4751 2624 4751 2631 4751 2627 4752 2630 4752 2626 4752 2627 4753 2626 4753 2296 4753 2293 4754 2626 4754 2630 4754 2293 4755 2630 4755 2313 4755 2313 4756 2630 4756 2631 4756 2313 4757 2631 4757 2314 4757 2314 4758 2631 4758 2624 4758 2315 4759 2624 4759 2625 4759 2324 4760 2625 4760 1790 4760 2324 4761 1790 4761 2309 4761 2297 4762 1606 4762 2627 4762 2627 4763 1606 4763 1605 4763 2627 4764 1605 4764 1591 4764 1579 4765 1788 4765 1587 4765 1587 4766 1788 4766 2629 4766 1587 4767 2629 4767 1599 4767 1599 4768 2629 4768 2628 4768 2627 4769 1591 4769 1595 4769 2627 4770 1595 4770 2628 4770 2628 4771 1595 4771 1599 4771 2632 4772 2446 4772 2466 4772 2446 4773 2632 4773 2447 4773 2447 4774 2632 4774 2448 4774 2217 4775 2453 4775 2456 4775 2216 4776 2217 4776 2456 4776 2456 4777 2459 4777 2636 4777 2456 4778 2636 4778 2214 4778 2456 4779 2214 4779 2216 4779 2632 4780 2638 4780 2448 4780 2450 4781 2448 4781 2639 4781 2450 4782 2639 4782 2459 4782 2636 4783 2459 4783 2637 4783 2636 4784 2637 4784 2214 4784 2638 4785 2640 4785 2448 4785 2448 4786 2640 4786 2639 4786 2459 4787 2639 4787 2637 4787 2632 4788 1804 4788 2638 4788 2639 4789 2635 4789 2637 4789 2637 4790 2224 4790 2214 4790 2635 4791 2211 4791 2224 4791 2640 4792 2633 4792 2639 4792 2639 4793 2633 4793 2634 4793 2639 4794 2634 4794 2635 4794 2637 4795 2635 4795 2224 4795 1804 4796 1805 4796 2638 4796 2638 4797 1805 4797 2640 4797 2640 4798 1805 4798 2633 4798 2633 4799 1805 4799 1667 4799 2634 4800 1665 4800 2635 4800 1665 4801 1661 4801 2635 4801 2635 4802 1661 4802 1657 4802 1657 4803 2211 4803 2635 4803 2633 4804 1667 4804 1665 4804 2633 4805 1665 4805 2634 4805 1805 4806 1668 4806 1667 4806 1805 4807 1675 4807 1668 4807 2192 4808 2187 4808 2527 4808 2186 4809 2529 4809 2527 4809 2186 4810 2527 4810 2187 4810 2530 4811 2642 4811 2532 4811 2643 4812 2533 4812 2532 4812 2546 4813 2641 4813 2526 4813 2529 4814 2183 4814 2531 4814 2183 4815 2181 4815 2531 4815 2531 4816 2181 4816 2180 4816 2180 4817 2645 4817 2531 4817 2642 4818 2530 4818 2531 4818 2646 4819 2645 4819 1683 4819 1808 4820 2641 4820 2649 4820 1808 4821 2649 4821 2644 4821 2644 4822 2649 4822 2643 4822 2644 4823 2643 4823 2647 4823 2647 4824 2643 4824 2648 4824 2648 4825 2645 4825 2646 4825 2641 4826 2542 4826 2649 4826 2649 4827 2542 4827 2533 4827 2649 4828 2533 4828 2643 4828 2642 4829 2531 4829 2645 4829 2643 4830 2532 4830 2648 4830 2648 4831 2532 4831 2642 4831 2648 4832 2642 4832 2645 4832 2542 4833 2641 4833 2546 4833 1683 4834 1692 4834 2646 4834 1709 4835 2644 4835 1696 4835 1696 4836 2644 4836 2647 4836 1696 4837 2647 4837 1703 4837 1692 4838 1700 4838 2646 4838 2646 4839 1700 4839 2648 4839 2648 4840 1700 4840 2647 4840 2647 4841 1700 4841 1703 4841 2106 4842 2395 4842 2393 4842 2106 4843 2393 4843 2108 4843 2110 4844 2613 4844 2113 4844 2311 4845 2287 4845 2289 4845 2289 4846 2288 4846 2291 4846 2217 4847 2222 4847 2453 4847 1910 4848 2100 4848 1934 4848 1859 4849 1849 4849 1910 4849 1910 4850 1849 4850 2100 4850 1815 4851 2299 4851 1849 4851 1859 4852 1910 4852 1906 4852 1887 4853 1856 4853 1905 4853 1905 4854 1856 4854 1859 4854 2395 4855 2318 4855 2321 4855 2301 4856 2310 4856 2318 4856 2395 4857 2321 4857 2398 4857 2322 4858 2389 4858 2321 4858 2321 4859 2389 4859 2398 4859 2389 4860 2322 4860 2308 4860 2389 4861 2308 4861 2384 4861 2328 4862 2381 4862 2384 4862 2328 4863 2384 4863 2308 4863 2100 4864 1849 4864 2299 4864 2100 4865 2299 4865 2099 4865 2099 4866 2299 4866 2302 4866 2099 4867 2302 4867 2101 4867 2101 4868 2302 4868 2300 4868 2101 4869 2300 4869 2102 4869 2102 4870 2300 4870 2301 4870 2102 4871 2301 4871 2395 4871 2395 4872 2301 4872 2318 4872 2538 4873 2458 4873 2537 4873 2192 4874 2537 4874 2458 4874 2192 4875 2458 4875 2455 4875 2458 4876 2538 4876 2539 4876 2539 4877 2464 4877 2449 4877 2458 4878 2539 4878 2449 4878 2464 4879 2539 4879 2525 4879 2522 4880 2467 4880 2525 4880 2525 4881 2467 4881 2464 4881 1932 4882 1953 4882 2189 4882 2189 4883 1953 4883 1991 4883 1932 4884 1925 4884 1953 4884 1953 4885 1925 4885 1942 4885 1916 4886 1941 4886 1925 4886 1916 4887 1924 4887 1941 4887 1925 4888 1941 4888 1942 4888 2192 4889 2455 4889 2451 4889 2192 4890 2451 4890 2190 4890 2190 4891 2451 4891 2205 4891 2190 4892 2205 4892 2191 4892 2191 4893 2205 4893 2208 4893 2191 4894 2208 4894 2193 4894 2193 4895 2208 4895 2207 4895 2193 4896 2207 4896 2189 4896 2189 4897 2207 4897 2206 4897 2189 4898 2206 4898 1932 4898 1932 4899 2206 4899 1899 4899 2650 4900 2651 4900 2652 4900 2650 4901 2652 4901 2653 4901 2653 4902 2652 4902 2654 4902 2653 4903 2654 4903 2655 4903 2653 4904 2655 4904 2656 4904 2656 4905 2655 4905 2657 4905 2656 4906 2657 4906 2658 4906 2658 4907 2657 4907 2659 4907 2658 4908 2659 4908 2660 4908 2660 4909 2659 4909 2661 4909 2660 4910 2661 4910 2662 4910 2662 4911 2661 4911 2663 4911 2662 4912 2663 4912 2664 4912 2664 4913 2663 4913 2665 4913 2664 4914 2665 4914 2666 4914 2666 4915 2665 4915 2667 4915 2666 4916 2667 4916 2668 4916 2668 4917 2667 4917 2669 4917 2668 4918 2669 4918 2670 4918 2670 4919 2669 4919 2671 4919 2670 4920 2671 4920 2672 4920 2672 4921 2671 4921 2651 4921 2672 4922 2651 4922 2650 4922 2664 4923 2673 4923 2674 4923 2664 4924 2674 4924 2662 4924 2662 4925 2675 4925 2660 4925 2660 4926 2675 4926 2658 4926 2658 4927 2675 4927 2676 4927 2662 4928 2674 4928 2675 4928 2658 4929 2676 4929 2656 4929 2656 4930 2676 4930 2678 4930 2656 4931 2678 4931 2679 4931 2656 4932 2679 4932 2653 4932 2653 4933 2679 4933 2677 4933 2653 4934 2677 4934 2650 4934 2673 4935 2664 4935 2666 4935 2673 4936 2666 4936 2680 4936 2680 4937 2666 4937 2668 4937 2681 4938 2680 4938 2670 4938 2670 4939 2680 4939 2668 4939 2681 4940 2670 4940 2682 4940 2682 4941 2670 4941 2672 4941 2682 4942 2672 4942 2650 4942 2682 4943 2650 4943 2677 4943 2683 4944 2684 4944 2685 4944 2685 4945 2684 4945 2686 4945 2685 4946 2686 4946 2687 4946 2685 4947 2687 4947 2688 4947 2688 4948 2687 4948 2689 4948 2688 4949 2689 4949 2690 4949 2690 4950 2689 4950 2691 4950 2691 4951 2689 4951 2692 4951 2691 4952 2692 4952 2693 4952 2691 4953 2693 4953 2694 4953 2694 4954 2693 4954 2695 4954 2694 4955 2695 4955 2696 4955 2696 4956 2695 4956 2697 4956 2696 4957 2697 4957 2698 4957 2698 4958 2697 4958 2699 4958 2698 4959 2699 4959 2700 4959 2700 4960 2699 4960 2701 4960 2700 4961 2701 4961 2702 4961 2702 4962 2701 4962 2703 4962 2702 4963 2703 4963 2704 4963 2704 4964 2703 4964 2705 4964 2704 4965 2705 4965 2706 4965 2706 4966 2705 4966 2683 4966 2683 4967 2705 4967 2684 4967 2706 4968 2683 4968 2707 4968 2707 4969 2683 4969 2708 4969 2694 4970 2709 4970 2712 4970 2694 4971 2712 4971 2691 4971 2708 4972 2683 4972 2685 4972 2708 4973 2685 4973 2710 4973 2710 4974 2685 4974 2688 4974 2710 4975 2688 4975 2711 4975 2711 4976 2688 4976 2690 4976 2711 4977 2690 4977 2691 4977 2711 4978 2691 4978 2712 4978 2706 4979 2707 4979 2713 4979 2706 4980 2713 4980 2704 4980 2704 4981 2713 4981 2714 4981 2704 4982 2714 4982 2702 4982 2702 4983 2714 4983 2700 4983 2700 4984 2715 4984 2698 4984 2698 4985 2715 4985 2716 4985 2698 4986 2716 4986 2696 4986 2696 4987 2716 4987 2709 4987 2696 4988 2709 4988 2694 4988 2715 4989 2700 4989 2714 4989 2717 4990 2741 4990 2718 4990 2717 4991 2718 4991 2719 4991 2717 4992 2719 4992 2720 4992 2720 4993 2719 4993 2721 4993 2720 4994 2721 4994 2722 4994 2722 4995 2721 4995 2723 4995 2722 4996 2723 4996 2724 4996 2724 4997 2723 4997 2725 4997 2724 4998 2725 4998 2726 4998 2726 4999 2725 4999 2727 4999 2726 5000 2727 5000 2728 5000 2728 5001 2727 5001 2729 5001 2729 5002 2727 5002 2730 5002 2729 5003 2730 5003 2731 5003 2729 5004 2731 5004 2732 5004 2732 5005 2731 5005 2733 5005 2733 5006 2731 5006 2734 5006 2733 5007 2734 5007 2735 5007 2733 5008 2735 5008 2736 5008 2736 5009 2735 5009 2737 5009 2736 5010 2737 5010 2738 5010 2738 5011 2737 5011 2739 5011 2738 5012 2739 5012 2740 5012 2740 5013 2739 5013 2718 5013 2740 5014 2718 5014 2741 5014 2742 5015 2743 5015 2729 5015 2729 5016 2743 5016 2728 5016 2728 5017 2743 5017 2726 5017 2726 5018 2743 5018 2744 5018 2742 5019 2729 5019 2732 5019 2742 5020 2732 5020 2745 5020 2744 5021 2746 5021 2726 5021 2726 5022 2746 5022 2724 5022 2724 5023 2746 5023 2722 5023 2722 5024 2746 5024 2747 5024 2722 5025 2747 5025 2720 5025 2720 5026 2747 5026 2748 5026 2720 5027 2748 5027 2717 5027 2717 5028 2748 5028 2749 5028 2750 5029 2738 5029 2740 5029 2750 5030 2740 5030 2751 5030 2751 5031 2740 5031 2741 5031 2751 5032 2741 5032 2749 5032 2749 5033 2741 5033 2717 5033 2738 5034 2750 5034 2752 5034 2745 5035 2732 5035 2733 5035 2745 5036 2733 5036 2753 5036 2753 5037 2733 5037 2736 5037 2753 5038 2736 5038 2752 5038 2752 5039 2736 5039 2738 5039 2755 5040 2756 5040 2754 5040 2754 5041 2756 5041 2757 5041 2757 5042 2756 5042 2758 5042 2757 5043 2758 5043 2759 5043 2759 5044 2758 5044 2760 5044 2759 5045 2760 5045 2761 5045 2761 5046 2760 5046 2762 5046 2761 5047 2762 5047 2763 5047 2763 5048 2762 5048 2764 5048 2763 5049 2764 5049 2765 5049 2765 5050 2764 5050 2766 5050 2765 5051 2766 5051 2767 5051 2767 5052 2766 5052 2768 5052 2767 5053 2768 5053 2769 5053 2769 5054 2768 5054 2770 5054 2769 5055 2770 5055 2771 5055 2771 5056 2770 5056 2772 5056 2772 5057 2770 5057 2773 5057 2772 5058 2773 5058 2774 5058 2774 5059 2773 5059 2775 5059 2774 5060 2775 5060 2776 5060 2776 5061 2775 5061 2777 5061 2776 5062 2777 5062 2778 5062 2778 5063 2777 5063 2755 5063 2778 5064 2755 5064 2754 5064 2789 5065 2754 5065 2779 5065 2779 5066 2754 5066 2757 5066 2779 5067 2757 5067 2780 5067 2780 5068 2757 5068 2759 5068 2780 5069 2759 5069 2781 5069 2781 5070 2759 5070 2761 5070 2781 5071 2761 5071 2782 5071 2782 5072 2761 5072 2763 5072 2782 5073 2763 5073 2783 5073 2783 5074 2763 5074 2765 5074 2783 5075 2765 5075 2784 5075 2784 5076 2765 5076 2767 5076 2784 5077 2767 5077 2769 5077 2784 5078 2769 5078 2785 5078 2785 5079 2769 5079 2786 5079 2786 5080 2769 5080 2771 5080 2786 5081 2771 5081 2772 5081 2786 5082 2772 5082 2787 5082 2787 5083 2772 5083 2774 5083 2787 5084 2774 5084 2788 5084 2788 5085 2774 5085 2776 5085 2788 5086 2776 5086 2778 5086 2788 5087 2778 5087 2789 5087 2789 5088 2778 5088 2754 5088 2515 5089 2806 5089 2522 5089 2522 5090 2806 5090 2791 5090 2522 5091 2791 5091 2790 5091 2815 5092 2792 5092 2800 5092 2794 5093 2795 5093 2515 5093 2796 5094 2797 5094 2806 5094 2808 5095 2799 5095 2800 5095 2800 5096 2799 5096 2826 5096 2803 5097 2804 5097 2805 5097 2511 5098 2820 5098 2515 5098 2515 5099 2820 5099 2794 5099 2813 5100 2806 5100 2798 5100 2802 5101 2801 5101 2807 5101 2802 5102 2807 5102 2808 5102 2809 5103 2810 5103 2811 5103 2800 5104 2816 5104 2808 5104 2808 5105 2816 5105 2802 5105 2515 5106 2795 5106 2796 5106 2515 5107 2796 5107 2806 5107 2806 5108 2797 5108 2798 5108 2808 5109 2807 5109 2813 5109 2808 5110 2813 5110 2814 5110 2814 5111 2813 5111 2798 5111 2812 5112 2815 5112 2800 5112 2800 5113 2792 5113 2816 5113 2803 5114 2805 5114 2817 5114 2522 5115 2790 5115 2793 5115 2522 5116 2793 5116 2467 5116 2467 5117 2818 5117 2819 5117 2521 5118 2822 5118 2820 5118 2521 5119 2820 5119 2511 5119 2802 5120 2821 5120 2801 5120 2809 5121 2822 5121 2521 5121 2793 5122 2804 5122 2467 5122 2823 5123 2516 5123 2824 5123 2824 5124 2516 5124 2829 5124 2812 5125 2800 5125 2825 5125 2811 5126 2826 5126 2799 5126 2803 5127 2817 5127 2827 5127 2803 5128 2827 5128 2821 5128 2821 5129 2827 5129 2801 5129 2804 5130 2803 5130 2467 5130 2467 5131 2803 5131 2818 5131 2809 5132 2811 5132 2799 5132 2467 5133 2819 5133 2829 5133 2467 5134 2829 5134 2516 5134 2828 5135 2513 5135 2830 5135 2516 5136 2823 5136 2812 5136 2831 5137 2834 5137 2516 5137 2513 5138 2828 5138 2519 5138 2831 5139 2516 5139 2812 5139 2831 5140 2812 5140 2825 5140 2519 5141 2828 5141 2832 5141 2830 5142 2513 5142 2833 5142 2833 5143 2513 5143 2518 5143 2833 5144 2518 5144 2834 5144 2834 5145 2518 5145 2512 5145 2834 5146 2512 5146 2516 5146 2810 5147 2809 5147 2521 5147 2810 5148 2521 5148 2520 5148 2810 5149 2520 5149 2835 5149 2835 5150 2520 5150 2519 5150 2835 5151 2519 5151 2832 5151 1799 5152 2471 5152 2497 5152 1799 5153 2497 5153 2547 5153 2547 5154 2497 5154 2496 5154 2547 5155 2496 5155 2555 5155 2555 5156 2496 5156 2495 5156 2555 5157 2495 5157 2582 5157 2582 5158 2495 5158 2494 5158 2582 5159 2494 5159 2579 5159 2579 5160 2494 5160 2493 5160 2579 5161 2493 5161 2492 5161 2579 5162 2492 5162 2578 5162 2578 5163 2492 5163 2491 5163 2491 5164 2489 5164 2576 5164 2576 5165 2489 5165 2575 5165 2575 5166 2489 5166 2488 5166 2575 5167 2488 5167 2487 5167 2585 5168 2486 5168 2566 5168 2566 5169 2486 5169 2485 5169 2566 5170 2485 5170 2484 5170 2565 5171 2484 5171 2482 5171 2565 5172 2482 5172 2481 5172 2565 5173 2481 5173 2584 5173 2584 5174 2481 5174 2559 5174 2559 5175 2481 5175 2480 5175 2559 5176 2480 5176 2548 5176 2548 5177 2480 5177 2479 5177 2548 5178 2479 5178 2478 5178 2548 5179 2478 5179 2549 5179 2549 5180 2478 5180 2583 5180 2583 5181 2478 5181 2477 5181 2583 5182 2477 5182 2557 5182 2557 5183 2477 5183 2476 5183 2557 5184 2476 5184 2558 5184 2558 5185 2476 5185 2475 5185 2558 5186 2475 5186 2556 5186 2556 5187 2475 5187 2473 5187 2556 5188 2473 5188 2552 5188 2552 5189 2473 5189 2474 5189 2552 5190 2474 5190 1807 5190 1807 5191 2474 5191 2472 5191 2471 5192 1799 5192 2466 5192 2466 5193 1799 5193 2632 5193 2641 5194 1808 5194 1807 5194 2524 5195 2526 5195 2641 5195 2524 5196 2641 5196 1807 5196 2524 5197 1807 5197 2472 5197 1692 5198 1683 5198 1680 5198 2837 5199 2836 5199 2838 5199 2837 5200 2838 5200 2839 5200 2840 5201 2841 5201 2842 5201 2842 5202 2841 5202 2843 5202 2843 5203 2841 5203 2844 5203 2843 5204 2844 5204 2845 5204 2839 5205 2838 5205 2844 5205 2844 5206 2838 5206 2845 5206 2840 5207 2842 5207 2846 5207 2840 5208 2846 5208 2847 5208 2847 5209 2846 5209 2848 5209 2847 5210 2848 5210 2849 5210 2847 5211 2849 5211 2850 5211 2850 5212 2849 5212 2851 5212 2851 5213 2849 5213 2852 5213 2851 5214 2852 5214 2853 5214 2853 5215 2852 5215 2854 5215 2836 5216 2837 5216 2855 5216 2836 5217 2855 5217 2856 5217 2856 5218 2855 5218 2857 5218 2856 5219 2857 5219 2858 5219 2858 5220 2857 5220 2854 5220 2854 5221 2857 5221 2853 5221 2858 5222 2859 5222 2856 5222 2856 5223 2859 5223 2860 5223 2856 5224 2860 5224 2836 5224 2836 5225 2860 5225 2861 5225 2836 5226 2861 5226 2838 5226 2838 5227 2861 5227 2862 5227 2838 5228 2862 5228 2845 5228 2845 5229 2862 5229 2843 5229 2843 5230 2862 5230 2863 5230 2843 5231 2863 5231 2842 5231 2842 5232 2863 5232 2864 5232 2842 5233 2864 5233 2846 5233 2846 5234 2864 5234 2865 5234 2846 5235 2865 5235 2848 5235 2848 5236 2865 5236 2866 5236 2848 5237 2866 5237 2849 5237 2849 5238 2866 5238 2867 5238 2849 5239 2867 5239 2852 5239 2852 5240 2867 5240 2868 5240 2852 5241 2868 5241 2854 5241 2854 5242 2868 5242 2869 5242 2854 5243 2869 5243 2858 5243 2858 5244 2869 5244 2859 5244 2871 5245 2870 5245 2872 5245 2871 5246 2872 5246 2873 5246 2871 5247 2874 5247 2870 5247 2870 5248 2874 5248 2875 5248 2875 5249 2874 5249 2876 5249 2875 5250 2876 5250 2890 5250 2878 5251 2877 5251 2879 5251 2878 5252 2879 5252 2880 5252 2880 5253 2879 5253 2873 5253 2873 5254 2872 5254 2880 5254 2877 5255 2878 5255 2881 5255 2877 5256 2881 5256 2882 5256 2882 5257 2881 5257 2883 5257 2883 5258 2881 5258 2884 5258 2883 5259 2884 5259 2885 5259 2885 5260 2884 5260 2886 5260 2885 5261 2886 5261 2887 5261 2887 5262 2886 5262 2888 5262 2887 5263 2888 5263 2889 5263 2889 5264 2888 5264 2890 5264 2889 5265 2890 5265 2876 5265 2890 5266 2891 5266 2875 5266 2875 5267 2891 5267 2892 5267 2875 5268 2892 5268 2870 5268 2870 5269 2892 5269 2893 5269 2870 5270 2893 5270 2872 5270 2872 5271 2893 5271 2894 5271 2872 5272 2894 5272 2880 5272 2880 5273 2894 5273 2895 5273 2880 5274 2895 5274 2896 5274 2880 5275 2896 5275 2878 5275 2878 5276 2896 5276 2881 5276 2881 5277 2896 5277 2897 5277 2881 5278 2897 5278 2898 5278 2881 5279 2898 5279 2884 5279 2884 5280 2898 5280 2899 5280 2884 5281 2899 5281 2886 5281 2886 5282 2899 5282 2900 5282 2886 5283 2900 5283 2888 5283 2888 5284 2900 5284 2901 5284 2888 5285 2901 5285 2890 5285 2890 5286 2901 5286 2902 5286 2890 5287 2902 5287 2891 5287 2903 5288 2904 5288 2905 5288 2905 5289 2904 5289 2906 5289 2905 5290 2906 5290 2907 5290 2909 5291 2908 5291 2910 5291 2909 5292 2910 5292 2911 5292 2911 5293 2910 5293 2907 5293 2911 5294 2907 5294 2906 5294 2909 5295 2912 5295 2908 5295 2908 5296 2912 5296 2913 5296 2913 5297 2912 5297 2914 5297 2913 5298 2914 5298 2915 5298 2913 5299 2915 5299 2916 5299 2916 5300 2915 5300 2917 5300 2916 5301 2917 5301 2918 5301 2918 5302 2917 5302 2919 5302 2918 5303 2919 5303 2920 5303 2920 5304 2919 5304 2921 5304 2920 5305 2921 5305 2922 5305 2922 5306 2921 5306 2923 5306 2903 5307 2905 5307 2924 5307 2903 5308 2924 5308 2925 5308 2925 5309 2924 5309 2926 5309 2925 5310 2926 5310 2923 5310 2923 5311 2926 5311 2922 5311 2923 5312 2927 5312 2925 5312 2925 5313 2927 5313 2903 5313 2903 5314 2927 5314 2928 5314 2903 5315 2928 5315 2904 5315 2904 5316 2928 5316 2929 5316 2904 5317 2929 5317 2906 5317 2906 5318 2929 5318 2911 5318 2911 5319 2929 5319 2930 5319 2911 5320 2930 5320 2909 5320 2909 5321 2930 5321 2931 5321 2909 5322 2931 5322 2912 5322 2912 5323 2931 5323 2932 5323 2912 5324 2932 5324 2914 5324 2914 5325 2932 5325 2933 5325 2914 5326 2933 5326 2915 5326 2915 5327 2933 5327 2934 5327 2915 5328 2934 5328 2917 5328 2917 5329 2934 5329 2935 5329 2917 5330 2935 5330 2919 5330 2919 5331 2935 5331 2936 5331 2919 5332 2936 5332 2921 5332 2921 5333 2936 5333 2937 5333 2921 5334 2937 5334 2923 5334 2923 5335 2937 5335 2927 5335 2950 5336 2938 5336 2939 5336 2941 5337 2940 5337 2939 5337 2941 5338 2939 5338 2938 5338 2943 5339 2942 5339 2944 5339 2946 5340 2945 5340 2947 5340 2946 5341 2947 5341 2948 5341 2948 5342 2947 5342 2949 5342 2948 5343 2949 5343 2943 5343 2943 5344 2949 5344 2942 5344 2942 5345 2950 5345 2944 5345 2944 5346 2950 5346 2939 5346 2951 5347 2952 5347 2953 5347 2951 5348 2953 5348 2954 5348 2954 5349 2953 5349 2955 5349 2955 5350 2953 5350 2956 5350 2955 5351 2956 5351 2957 5351 2957 5352 2956 5352 2945 5352 2957 5353 2945 5353 2946 5353 2940 5354 2941 5354 2958 5354 2958 5355 2941 5355 2959 5355 2958 5356 2959 5356 2960 5356 2958 5357 2960 5357 2961 5357 2961 5358 2960 5358 2951 5358 2951 5359 2960 5359 2952 5359 2961 5360 2962 5360 2963 5360 2961 5361 2963 5361 2958 5361 2958 5362 2963 5362 2964 5362 2958 5363 2964 5363 2940 5363 2940 5364 2964 5364 2965 5364 2940 5365 2965 5365 2939 5365 2939 5366 2965 5366 2966 5366 2939 5367 2966 5367 2944 5367 2944 5368 2966 5368 2967 5368 2944 5369 2967 5369 2943 5369 2943 5370 2967 5370 2968 5370 2943 5371 2968 5371 2948 5371 2948 5372 2968 5372 2969 5372 2948 5373 2969 5373 2946 5373 2946 5374 2969 5374 2970 5374 2946 5375 2970 5375 2957 5375 2957 5376 2970 5376 2971 5376 2957 5377 2971 5377 2955 5377 2955 5378 2971 5378 2972 5378 2955 5379 2972 5379 2954 5379 2954 5380 2972 5380 2973 5380 2954 5381 2973 5381 2951 5381 2951 5382 2973 5382 2962 5382 2951 5383 2962 5383 2961 5383 2965 5384 2860 5384 2859 5384 2965 5385 2859 5385 2966 5385 2968 5386 2967 5386 2859 5386 2968 5387 2859 5387 2869 5387 2859 5388 2967 5388 2966 5388 2927 5389 2937 5389 1786 5389 2869 5390 2969 5390 2968 5390 2862 5391 2861 5391 2408 5391 2408 5392 2861 5392 1615 5392 2962 5393 1615 5393 2963 5393 1615 5394 2927 5394 1786 5394 2937 5395 2936 5395 1786 5395 1786 5396 2936 5396 2935 5396 1615 5397 2964 5397 2963 5397 2929 5398 2972 5398 2971 5398 2929 5399 2971 5399 2970 5399 2931 5400 2930 5400 2429 5400 2929 5401 2928 5401 2972 5401 2435 5402 2895 5402 2413 5402 2413 5403 2895 5403 2894 5403 2413 5404 2894 5404 2411 5404 2411 5405 2894 5405 2408 5405 2408 5406 2894 5406 2893 5406 2902 5407 2969 5407 2891 5407 1615 5408 2972 5408 2927 5408 2927 5409 2972 5409 2928 5409 1615 5410 2962 5410 2973 5410 1615 5411 2973 5411 2972 5411 1786 5412 2935 5412 1793 5412 1793 5413 2935 5413 2934 5413 2934 5414 2933 5414 1793 5414 2931 5415 2429 5415 2932 5415 2932 5416 2429 5416 2423 5416 2932 5417 2423 5417 2933 5417 2933 5418 2423 5418 1793 5418 2969 5419 2869 5419 2868 5419 2861 5420 2860 5420 1615 5420 2969 5421 2902 5421 2901 5421 2433 5422 2896 5422 2435 5422 2435 5423 2896 5423 2895 5423 2860 5424 2965 5424 1615 5424 1615 5425 2965 5425 2964 5425 2867 5426 2866 5426 2892 5426 2864 5427 2893 5427 2865 5427 2893 5428 2864 5428 2408 5428 2969 5429 2868 5429 2867 5429 2864 5430 2863 5430 2408 5430 2408 5431 2863 5431 2862 5431 2969 5432 2901 5432 2900 5432 2900 5433 2899 5433 2429 5433 2429 5434 2899 5434 2898 5434 2429 5435 2898 5435 2433 5435 2433 5436 2898 5436 2897 5436 2433 5437 2897 5437 2896 5437 2892 5438 2866 5438 2865 5438 2892 5439 2865 5439 2893 5439 2929 5440 2970 5440 2969 5440 2929 5441 2969 5441 2930 5441 2930 5442 2969 5442 2429 5442 2429 5443 2969 5443 2900 5443 2891 5444 2969 5444 2867 5444 2891 5445 2867 5445 2892 5445 2309 5446 1790 5446 1789 5446 2309 5447 1789 5447 2333 5447 1794 5448 2357 5448 2356 5448 1794 5449 2356 5449 2405 5449 2405 5450 2356 5450 2414 5450 2414 5451 2356 5451 2355 5451 2414 5452 2355 5452 2354 5452 2414 5453 2354 5453 2444 5453 2444 5454 2354 5454 2443 5454 2443 5455 2354 5455 2353 5455 2443 5456 2353 5456 2442 5456 2442 5457 2353 5457 2352 5457 2442 5458 2352 5458 2441 5458 2441 5459 2352 5459 2351 5459 2441 5460 2351 5460 2350 5460 2441 5461 2350 5461 2439 5461 2439 5462 2350 5462 2349 5462 2406 5463 2349 5463 2348 5463 2406 5464 2348 5464 2445 5464 2445 5465 2348 5465 2347 5465 2445 5466 2347 5466 2428 5466 2428 5467 2347 5467 2346 5467 2428 5468 2346 5468 2427 5468 2427 5469 2346 5469 2345 5469 2427 5470 2345 5470 2343 5470 2343 5471 2345 5471 2344 5471 2418 5472 2343 5472 2342 5472 2418 5473 2342 5473 2341 5473 2418 5474 2341 5474 2419 5474 2419 5475 2341 5475 2340 5475 2419 5476 2340 5476 2407 5476 2407 5477 2340 5477 2339 5477 2407 5478 2339 5478 2420 5478 2420 5479 2339 5479 2338 5479 2420 5480 2338 5480 2337 5480 2416 5481 2337 5481 2417 5481 2417 5482 2337 5482 2336 5482 2417 5483 2336 5483 2335 5483 2417 5484 2335 5484 2415 5484 2415 5485 2335 5485 2334 5485 2415 5486 2334 5486 2410 5486 2410 5487 2334 5487 1789 5487 1789 5488 2334 5488 2333 5488 1794 5489 1797 5489 2614 5489 2357 5490 1794 5490 2383 5490 2383 5491 1794 5491 2614 5491 2383 5492 2614 5492 2385 5492 2974 5493 2975 5493 2976 5493 2331 5494 2977 5494 2328 5494 2974 5495 2978 5495 2979 5495 2982 5496 2983 5496 2990 5496 2993 5497 2984 5497 2985 5497 2985 5498 2984 5498 2996 5498 2974 5499 2976 5499 2978 5499 2987 5500 2986 5500 2977 5500 2987 5501 2977 5501 2988 5501 2990 5502 2989 5502 2982 5502 3003 5503 2991 5503 2371 5503 2371 5504 2991 5504 2380 5504 2992 5505 2979 5505 2993 5505 2378 5506 2975 5506 2994 5506 2378 5507 2994 5507 2379 5507 2379 5508 2994 5508 2331 5508 2331 5509 2994 5509 2980 5509 2331 5510 2980 5510 2995 5510 2979 5511 2992 5511 2974 5511 2977 5512 2997 5512 2328 5512 2331 5513 2995 5513 2998 5513 2986 5514 2987 5514 2982 5514 2982 5515 2987 5515 2983 5515 2376 5516 3000 5516 3001 5516 2376 5517 3001 5517 2377 5517 2377 5518 3001 5518 3010 5518 2377 5519 3010 5519 2371 5519 2331 5520 2998 5520 2977 5520 2998 5521 3002 5521 2977 5521 2999 5522 3003 5522 2371 5522 2380 5523 2991 5523 3004 5523 2380 5524 3004 5524 2375 5524 2992 5525 2993 5525 2990 5525 2990 5526 2993 5526 2985 5526 3006 5527 3007 5527 2381 5527 2989 5528 2990 5528 2985 5528 3007 5529 3008 5529 2381 5529 2381 5530 3008 5530 2373 5530 2375 5531 3004 5531 2976 5531 2375 5532 2976 5532 2378 5532 2378 5533 2976 5533 2975 5533 2989 5534 2985 5534 3011 5534 2989 5535 3011 5535 3012 5535 3008 5536 3013 5536 2373 5536 2373 5537 3013 5537 3014 5537 2373 5538 3014 5538 2376 5538 2376 5539 3014 5539 3000 5539 2977 5540 3002 5540 2988 5540 2997 5541 3015 5541 2328 5541 2328 5542 3015 5542 2381 5542 2381 5543 3015 5543 2981 5543 3006 5544 3005 5544 3016 5544 3016 5545 3017 5545 3006 5545 3006 5546 3017 5546 3011 5546 2981 5547 3018 5547 2381 5547 2381 5548 3018 5548 3005 5548 3011 5549 3017 5549 3012 5549 2996 5550 2984 5550 3019 5550 2996 5551 3019 5551 3010 5551 3010 5552 3019 5552 3009 5552 3005 5553 3006 5553 2381 5553 2371 5554 3010 5554 3020 5554 2371 5555 3020 5555 2999 5555 3009 5556 3020 5556 3010 5556 1752 5557 1751 5557 31 5557 2023 5558 2038 5558 1853 5558 1853 5559 1894 5559 2016 5559 1853 5560 2016 5560 2019 5560 1853 5561 2038 5561 2039 5561 1853 5562 2019 5562 2021 5562 1853 5563 2021 5563 2023 5563 1915 5564 1890 5564 2057 5564 2057 5565 2042 5565 1915 5565 1915 5566 2042 5566 2043 5566 2062 5567 2060 5567 1890 5567 2060 5568 2057 5568 1890 5568 2150 5569 2149 5569 3021 5569 3021 5570 2149 5570 2601 5570 2605 5571 2150 5571 3022 5571 3022 5572 2150 5572 3021 5572 3022 5573 3021 5573 1134 5573 1134 5574 3021 5574 112 5574 1134 5575 112 5575 111 5575 3023 5576 3046 5576 3024 5576 3023 5577 3024 5577 3025 5577 3025 5578 3024 5578 3026 5578 3025 5579 3026 5579 3027 5579 3027 5580 3026 5580 3028 5580 3027 5581 3028 5581 3029 5581 3029 5582 3028 5582 3030 5582 3029 5583 3030 5583 3031 5583 3031 5584 3030 5584 3032 5584 3031 5585 3032 5585 3033 5585 3033 5586 3032 5586 3034 5586 3033 5587 3034 5587 3035 5587 3035 5588 3034 5588 3036 5588 3036 5589 3034 5589 3037 5589 3036 5590 3037 5590 3038 5590 3038 5591 3037 5591 3039 5591 3038 5592 3039 5592 3040 5592 3038 5593 3040 5593 3041 5593 3041 5594 3040 5594 3042 5594 3042 5595 3040 5595 3043 5595 3042 5596 3043 5596 3044 5596 3044 5597 3043 5597 3045 5597 3044 5598 3045 5598 3046 5598 3044 5599 3046 5599 3023 5599 3023 5600 3047 5600 3048 5600 3023 5601 3048 5601 3044 5601 3044 5602 3048 5602 3049 5602 3044 5603 3049 5603 3042 5603 3042 5604 3049 5604 3041 5604 3041 5605 3049 5605 3050 5605 3041 5606 3050 5606 3038 5606 3038 5607 3050 5607 3051 5607 3038 5608 3051 5608 3036 5608 3036 5609 3051 5609 3052 5609 3036 5610 3052 5610 3035 5610 3035 5611 3052 5611 3053 5611 3035 5612 3053 5612 3033 5612 3033 5613 3053 5613 3054 5613 3033 5614 3054 5614 3031 5614 3031 5615 3054 5615 3055 5615 3031 5616 3055 5616 3029 5616 3029 5617 3055 5617 3027 5617 3027 5618 3055 5618 3056 5618 3027 5619 3056 5619 3057 5619 3027 5620 3057 5620 3025 5620 3025 5621 3057 5621 3047 5621 3025 5622 3047 5622 3023 5622 3058 5623 3059 5623 3060 5623 3060 5624 3059 5624 3061 5624 3060 5625 3061 5625 3062 5625 3062 5626 3061 5626 3063 5626 3063 5627 3061 5627 3064 5627 3063 5628 3064 5628 3065 5628 3065 5629 3064 5629 3066 5629 3065 5630 3066 5630 3067 5630 3067 5631 3066 5631 3068 5631 3067 5632 3068 5632 3069 5632 3069 5633 3068 5633 3070 5633 3070 5634 3068 5634 3071 5634 3070 5635 3071 5635 3072 5635 3072 5636 3071 5636 3073 5636 3072 5637 3073 5637 3074 5637 3072 5638 3074 5638 3075 5638 3075 5639 3074 5639 3076 5639 3075 5640 3076 5640 3077 5640 3077 5641 3076 5641 3078 5641 3078 5642 3076 5642 3079 5642 3078 5643 3079 5643 3080 5643 3080 5644 3079 5644 3081 5644 3080 5645 3081 5645 3058 5645 3058 5646 3081 5646 3059 5646 3069 5647 3082 5647 3067 5647 3067 5648 3082 5648 3083 5648 3067 5649 3083 5649 3065 5649 3065 5650 3083 5650 3084 5650 3065 5651 3084 5651 3063 5651 3069 5652 3070 5652 3082 5652 3082 5653 3070 5653 3085 5653 3085 5654 3070 5654 3072 5654 3085 5655 3072 5655 3086 5655 3086 5656 3072 5656 3075 5656 3086 5657 3075 5657 3087 5657 3087 5658 3075 5658 3077 5658 3087 5659 3077 5659 3078 5659 3087 5660 3078 5660 3088 5660 3088 5661 3078 5661 3080 5661 3088 5662 3080 5662 3089 5662 3089 5663 3080 5663 3058 5663 3089 5664 3058 5664 3091 5664 3063 5665 3084 5665 3090 5665 3063 5666 3090 5666 3062 5666 3062 5667 3090 5667 3060 5667 3060 5668 3090 5668 3091 5668 3060 5669 3091 5669 3058 5669 54 5670 53 5670 1571 5670 1571 5671 53 5671 52 5671 1187 5672 3021 5672 1186 5672 1186 5673 3021 5673 2601 5673 2587 5674 2588 5674 1774 5674 1774 5675 2588 5675 1775 5675 2587 5676 52 5676 2598 5676 2598 5677 52 5677 1186 5677 2587 5678 1774 5678 1571 5678 2587 5679 1571 5679 52 5679 2601 5680 2600 5680 1186 5680 1186 5681 2600 5681 2599 5681 1186 5682 2599 5682 2598 5682 3092 5683 3093 5683 3094 5683 3092 5684 3094 5684 3095 5684 3092 5685 3095 5685 3096 5685 3096 5686 3095 5686 3097 5686 3096 5687 3097 5687 3098 5687 3098 5688 3097 5688 3099 5688 3098 5689 3099 5689 3100 5689 3100 5690 3099 5690 3101 5690 3100 5691 3101 5691 3102 5691 3100 5692 3102 5692 3103 5692 3103 5693 3102 5693 3104 5693 3103 5694 3104 5694 3105 5694 3105 5695 3104 5695 3106 5695 3106 5696 3104 5696 3107 5696 3106 5697 3107 5697 3108 5697 3108 5698 3107 5698 3109 5698 3108 5699 3109 5699 3110 5699 3108 5700 3110 5700 3111 5700 3111 5701 3110 5701 3112 5701 3092 5702 3113 5702 3093 5702 3093 5703 3113 5703 3114 5703 3114 5704 3113 5704 3112 5704 3112 5705 3113 5705 3115 5705 3112 5706 3115 5706 3111 5706 3112 5707 3116 5707 3114 5707 3114 5708 3116 5708 3117 5708 3114 5709 3117 5709 3093 5709 3093 5710 3117 5710 3118 5710 3093 5711 3118 5711 3094 5711 3094 5712 3118 5712 3119 5712 3094 5713 3119 5713 3095 5713 3095 5714 3119 5714 3120 5714 3095 5715 3120 5715 3097 5715 3097 5716 3120 5716 3121 5716 3097 5717 3121 5717 3099 5717 3099 5718 3121 5718 3122 5718 3099 5719 3122 5719 3101 5719 3101 5720 3122 5720 3102 5720 3102 5721 3122 5721 3123 5721 3102 5722 3123 5722 3104 5722 3104 5723 3123 5723 3124 5723 3104 5724 3124 5724 3107 5724 3107 5725 3124 5725 3125 5725 3107 5726 3125 5726 3109 5726 3109 5727 3125 5727 3126 5727 3109 5728 3126 5728 3110 5728 3110 5729 3126 5729 3127 5729 3110 5730 3127 5730 3112 5730 3112 5731 3127 5731 3116 5731 34 5732 38 5732 3128 5732 3022 5733 1189 5733 2605 5733 2605 5734 1189 5734 1190 5734 1740 5735 2593 5735 3129 5735 3129 5736 2593 5736 2602 5736 2604 5737 2605 5737 1190 5737 2602 5738 2603 5738 1190 5738 1742 5739 2592 5739 1740 5739 1740 5740 2592 5740 2593 5740 1190 5741 2603 5741 2604 5741 3128 5742 3129 5742 34 5742 34 5743 3129 5743 2602 5743 34 5744 2602 5744 1190 5744 1919 5745 1933 5745 2079 5745 1919 5746 2079 5746 2083 5746 2083 5747 2079 5747 3134 5747 2083 5748 3134 5748 3135 5748 3131 5749 3130 5749 1572 5749 1572 5750 3130 5750 3136 5750 1572 5751 3136 5751 1569 5751 1569 5752 3136 5752 3137 5752 3132 5753 3138 5753 1570 5753 1570 5754 3138 5754 3139 5754 2079 5755 3133 5755 3140 5755 1569 5756 3137 5756 1570 5756 1570 5757 3137 5757 3132 5757 2079 5758 3140 5758 3134 5758 3135 5759 3141 5759 2083 5759 2083 5760 3141 5760 3130 5760 2083 5761 3130 5761 3131 5761 1570 5762 3139 5762 2079 5762 2079 5763 3139 5763 3133 5763 1570 5764 2079 5764 49 5764 49 5765 2079 5765 2078 5765 2081 5766 1188 5766 49 5766 2081 5767 49 5767 2078 5767 1950 5768 2085 5768 1957 5768 1957 5769 2085 5769 2089 5769 2085 5770 3153 5770 3142 5770 2089 5771 3143 5771 3144 5771 2085 5772 3142 5772 2089 5772 2089 5773 3142 5773 3145 5773 2089 5774 3145 5774 3143 5774 2089 5775 3144 5775 3146 5775 3144 5776 3147 5776 3146 5776 3146 5777 3147 5777 3148 5777 3146 5778 3148 5778 1573 5778 1573 5779 3148 5779 3149 5779 1573 5780 3149 5780 1574 5780 1574 5781 3149 5781 3150 5781 1574 5782 3150 5782 3151 5782 3151 5783 3150 5783 3152 5783 3151 5784 3152 5784 2085 5784 2085 5785 3152 5785 3153 5785 3142 5786 3154 5786 3145 5786 3145 5787 3154 5787 3155 5787 3145 5788 3155 5788 3143 5788 3143 5789 3155 5789 3156 5789 3143 5790 3156 5790 3144 5790 3144 5791 3156 5791 3157 5791 3144 5792 3157 5792 3158 5792 3144 5793 3158 5793 3147 5793 3147 5794 3158 5794 3159 5794 3147 5795 3159 5795 3148 5795 3148 5796 3159 5796 3160 5796 3148 5797 3160 5797 3149 5797 3149 5798 3160 5798 3161 5798 3149 5799 3161 5799 3150 5799 3150 5800 3161 5800 3162 5800 3150 5801 3162 5801 3152 5801 3152 5802 3162 5802 3163 5802 3152 5803 3163 5803 3153 5803 3153 5804 3163 5804 3164 5804 3153 5805 3164 5805 3142 5805 3142 5806 3164 5806 3154 5806 3165 5807 3166 5807 3187 5807 3187 5808 3166 5808 3167 5808 3167 5809 3166 5809 3168 5809 3168 5810 3166 5810 3169 5810 3168 5811 3169 5811 3170 5811 3170 5812 3169 5812 3171 5812 3170 5813 3171 5813 3172 5813 3172 5814 3171 5814 3173 5814 3172 5815 3173 5815 3174 5815 3174 5816 3173 5816 3175 5816 3174 5817 3175 5817 3176 5817 3176 5818 3175 5818 3177 5818 3176 5819 3177 5819 3178 5819 3178 5820 3177 5820 3179 5820 3178 5821 3179 5821 3180 5821 3180 5822 3179 5822 3181 5822 3180 5823 3181 5823 3182 5823 3182 5824 3181 5824 3183 5824 3182 5825 3183 5825 3184 5825 3184 5826 3183 5826 3185 5826 3184 5827 3185 5827 3186 5827 3186 5828 3185 5828 3165 5828 3186 5829 3165 5829 3187 5829 3188 5830 3134 5830 3140 5830 3188 5831 3140 5831 3189 5831 3189 5832 3140 5832 3133 5832 3189 5833 3133 5833 3190 5833 3190 5834 3133 5834 3191 5834 3191 5835 3133 5835 3139 5835 3191 5836 3139 5836 3192 5836 3192 5837 3139 5837 3138 5837 3192 5838 3138 5838 3193 5838 3193 5839 3138 5839 3132 5839 3193 5840 3132 5840 3137 5840 3193 5841 3137 5841 3194 5841 3194 5842 3137 5842 3195 5842 3195 5843 3137 5843 3136 5843 3195 5844 3136 5844 3196 5844 3196 5845 3136 5845 3130 5845 3196 5846 3130 5846 3197 5846 3197 5847 3130 5847 3141 5847 3197 5848 3141 5848 3198 5848 3198 5849 3141 5849 3135 5849 3198 5850 3135 5850 3188 5850 3188 5851 3135 5851 3134 5851 3115 5852 3199 5852 3111 5852 3111 5853 3199 5853 3200 5853 3111 5854 3200 5854 3108 5854 3108 5855 3200 5855 3201 5855 3108 5856 3201 5856 3106 5856 3106 5857 3201 5857 3202 5857 3106 5858 3202 5858 3105 5858 3105 5859 3202 5859 3203 5859 3105 5860 3203 5860 3103 5860 3103 5861 3203 5861 3100 5861 3100 5862 3203 5862 3204 5862 3100 5863 3204 5863 3098 5863 3098 5864 3204 5864 3205 5864 3098 5865 3205 5865 3096 5865 3096 5866 3205 5866 3206 5866 3096 5867 3206 5867 3207 5867 3096 5868 3207 5868 3092 5868 3092 5869 3207 5869 3208 5869 3092 5870 3208 5870 3113 5870 3113 5871 3208 5871 3199 5871 3113 5872 3199 5872 3115 5872 3091 5873 3209 5873 3210 5873 3091 5874 3210 5874 3089 5874 3089 5875 3210 5875 3211 5875 3089 5876 3211 5876 3088 5876 3088 5877 3211 5877 3212 5877 3088 5878 3212 5878 3087 5878 3087 5879 3212 5879 3213 5879 3087 5880 3213 5880 3086 5880 3086 5881 3213 5881 3214 5881 3086 5882 3214 5882 3085 5882 3085 5883 3214 5883 3215 5883 3085 5884 3215 5884 3082 5884 3082 5885 3215 5885 3216 5885 3082 5886 3216 5886 3083 5886 3083 5887 3216 5887 3217 5887 3083 5888 3217 5888 3084 5888 3084 5889 3217 5889 3218 5889 3084 5890 3218 5890 3090 5890 3090 5891 3218 5891 3219 5891 3090 5892 3219 5892 3091 5892 3091 5893 3219 5893 3209 5893 3066 5894 3064 5894 2135 5894 2136 5895 3034 5895 3032 5895 3034 5896 2136 5896 2152 5896 3034 5897 2152 5897 3037 5897 3068 5898 3066 5898 2136 5898 3074 5899 3073 5899 3032 5899 3123 5900 3122 5900 2152 5900 3071 5901 3068 5901 2136 5901 3066 5902 2135 5902 2136 5902 2153 5903 3124 5903 3123 5903 3123 5904 2152 5904 2153 5904 2152 5905 3039 5905 3037 5905 3032 5906 3073 5906 3071 5906 3032 5907 3071 5907 2136 5907 2153 5908 3125 5908 3124 5908 3074 5909 3032 5909 3030 5909 3039 5910 3121 5910 3120 5910 3040 5911 3120 5911 3119 5911 3039 5912 3120 5912 3040 5912 3118 5913 3045 5913 3043 5913 3026 5914 3024 5914 1976 5914 3076 5915 3028 5915 3079 5915 2152 5916 3122 5916 3121 5916 2152 5917 3121 5917 3039 5917 3061 5918 2132 5918 3064 5918 2105 5919 2096 5919 1975 5919 3081 5920 1976 5920 3059 5920 3045 5921 3118 5921 3117 5921 3028 5922 3076 5922 3030 5922 3030 5923 3076 5923 3074 5923 3118 5924 3043 5924 3119 5924 3119 5925 3043 5925 3040 5925 2006 5926 2007 5926 3127 5926 3127 5927 2007 5927 3116 5927 3125 5928 2175 5928 3126 5928 2135 5929 3064 5929 2132 5929 1976 5930 3024 5930 1989 5930 1989 5931 3024 5931 3046 5931 2007 5932 1989 5932 3116 5932 3116 5933 1989 5933 3117 5933 3117 5934 1989 5934 3046 5934 3117 5935 3046 5935 3045 5935 2196 5936 2006 5936 3127 5936 2196 5937 3127 5937 2175 5937 2175 5938 3127 5938 3126 5938 2175 5939 2169 5939 1688 5939 1641 5940 2131 5940 2097 5940 2096 5941 2097 5941 3061 5941 3061 5942 2097 5942 2132 5942 2096 5943 3061 5943 3059 5943 3059 5944 1976 5944 1975 5944 3125 5945 2174 5945 2169 5945 3125 5946 2169 5946 2175 5946 2097 5947 2131 5947 2132 5947 3059 5948 1975 5948 2096 5948 2105 5949 1975 5949 1954 5949 3028 5950 3026 5950 3079 5950 3079 5951 3026 5951 1976 5951 3079 5952 1976 5952 3081 5952 2006 5953 2196 5953 1979 5953 3125 5954 2153 5954 2174 5954 2587 5955 2598 5955 2124 5955 2124 5956 2598 5956 2133 5956 3220 5957 2606 5957 2258 5957 2255 5958 2610 5958 3221 5958 83 5959 91 5959 969 5959 969 5960 91 5960 3220 5960 969 5961 3220 5961 3221 5961 3221 5962 3220 5962 2258 5962 3221 5963 2258 5963 2255 5963 3222 5964 3223 5964 3224 5964 3224 5965 3223 5965 3225 5965 3224 5966 3225 5966 3226 5966 3224 5967 3226 5967 3227 5967 3227 5968 3226 5968 3228 5968 3227 5969 3228 5969 3229 5969 3229 5970 3228 5970 3230 5970 3229 5971 3230 5971 3231 5971 3231 5972 3230 5972 3232 5972 3231 5973 3232 5973 3233 5973 3231 5974 3233 5974 3234 5974 3234 5975 3233 5975 3235 5975 3234 5976 3235 5976 3236 5976 3236 5977 3235 5977 3237 5977 3236 5978 3237 5978 3238 5978 3238 5979 3237 5979 3239 5979 3238 5980 3239 5980 3240 5980 3240 5981 3239 5981 3241 5981 3240 5982 3241 5982 3242 5982 3242 5983 3241 5983 3243 5983 3242 5984 3243 5984 3244 5984 3244 5985 3243 5985 3245 5985 3244 5986 3245 5986 3223 5986 3244 5987 3223 5987 3222 5987 3246 5988 3247 5988 3222 5988 3222 5989 3247 5989 3244 5989 3244 5990 3247 5990 3248 5990 3244 5991 3248 5991 3242 5991 3242 5992 3248 5992 3249 5992 3242 5993 3249 5993 3240 5993 3240 5994 3249 5994 3250 5994 3240 5995 3250 5995 3238 5995 3238 5996 3250 5996 3251 5996 3238 5997 3251 5997 3252 5997 3238 5998 3252 5998 3236 5998 3236 5999 3252 5999 3253 5999 3236 6000 3253 6000 3234 6000 3234 6001 3253 6001 3254 6001 3234 6002 3254 6002 3231 6002 3231 6003 3254 6003 3255 6003 3231 6004 3255 6004 3256 6004 3231 6005 3256 6005 3229 6005 3229 6006 3256 6006 3257 6006 3229 6007 3257 6007 3227 6007 3227 6008 3257 6008 3258 6008 3227 6009 3258 6009 3224 6009 3224 6010 3258 6010 3246 6010 3224 6011 3246 6011 3222 6011 3259 6012 3260 6012 3261 6012 3261 6013 3260 6013 3262 6013 3261 6014 3262 6014 3263 6014 3261 6015 3263 6015 3264 6015 3264 6016 3263 6016 3265 6016 3264 6017 3265 6017 3266 6017 3266 6018 3265 6018 3267 6018 3266 6019 3267 6019 3268 6019 3268 6020 3267 6020 3269 6020 3268 6021 3269 6021 3270 6021 3270 6022 3269 6022 3271 6022 3270 6023 3271 6023 3272 6023 3272 6024 3271 6024 3273 6024 3272 6025 3273 6025 3274 6025 3274 6026 3273 6026 3275 6026 3275 6027 3273 6027 3276 6027 3275 6028 3276 6028 3277 6028 3277 6029 3276 6029 3278 6029 3277 6030 3278 6030 3279 6030 3279 6031 3278 6031 3280 6031 3279 6032 3280 6032 3259 6032 3259 6033 3280 6033 3260 6033 3282 6034 3272 6034 3284 6034 3284 6035 3272 6035 3274 6035 3284 6036 3274 6036 3275 6036 3284 6037 3275 6037 3285 6037 3285 6038 3275 6038 3277 6038 3285 6039 3277 6039 3286 6039 3286 6040 3277 6040 3279 6040 3286 6041 3279 6041 3281 6041 3281 6042 3279 6042 3259 6042 3270 6043 3283 6043 3268 6043 3287 6044 3288 6044 3261 6044 3261 6045 3288 6045 3259 6045 3259 6046 3288 6046 3281 6046 3272 6047 3282 6047 3270 6047 3270 6048 3282 6048 3283 6048 3287 6049 3261 6049 3264 6049 3287 6050 3264 6050 3289 6050 3289 6051 3264 6051 3290 6051 3290 6052 3264 6052 3266 6052 3290 6053 3266 6053 3268 6053 3290 6054 3268 6054 3291 6054 3291 6055 3268 6055 3283 6055 12 6056 16 6056 1564 6056 3220 6057 1181 6057 2606 6057 2606 6058 1181 6058 1182 6058 1182 6059 2607 6059 2606 6059 1756 6060 2591 6060 1566 6060 1566 6061 2591 6061 2609 6061 2609 6062 2608 6062 1182 6062 1756 6063 2590 6063 2591 6063 1564 6064 1566 6064 12 6064 12 6065 1566 6065 2609 6065 12 6066 2609 6066 1182 6066 1182 6067 2608 6067 2607 6067 3292 6068 3293 6068 3294 6068 3294 6069 3293 6069 3295 6069 3295 6070 3293 6070 3296 6070 3295 6071 3296 6071 3297 6071 3297 6072 3296 6072 3298 6072 3297 6073 3298 6073 3299 6073 3299 6074 3298 6074 3300 6074 3299 6075 3300 6075 3301 6075 3301 6076 3300 6076 3302 6076 3301 6077 3302 6077 3303 6077 3303 6078 3302 6078 3304 6078 3303 6079 3304 6079 3305 6079 3305 6080 3304 6080 3306 6080 3305 6081 3306 6081 3307 6081 3307 6082 3306 6082 3308 6082 3307 6083 3308 6083 3309 6083 3309 6084 3308 6084 3310 6084 3310 6085 3308 6085 3311 6085 3310 6086 3311 6086 3312 6086 3312 6087 3311 6087 3313 6087 3312 6088 3313 6088 3314 6088 3314 6089 3313 6089 3315 6089 3315 6090 3313 6090 3292 6090 3315 6091 3292 6091 3294 6091 3307 6092 3316 6092 3305 6092 3305 6093 3316 6093 3317 6093 3305 6094 3317 6094 3303 6094 3303 6095 3317 6095 3318 6095 3303 6096 3318 6096 3301 6096 3301 6097 3318 6097 3299 6097 3299 6098 3318 6098 3319 6098 3299 6099 3319 6099 3297 6099 3297 6100 3319 6100 3320 6100 3297 6101 3320 6101 3295 6101 3295 6102 3320 6102 3321 6102 3295 6103 3321 6103 3294 6103 3294 6104 3321 6104 3322 6104 3294 6105 3322 6105 3315 6105 3315 6106 3322 6106 3314 6106 3314 6107 3322 6107 3323 6107 3314 6108 3323 6108 3312 6108 3312 6109 3323 6109 3324 6109 3312 6110 3324 6110 3310 6110 3310 6111 3324 6111 3325 6111 3310 6112 3325 6112 3309 6112 3309 6113 3325 6113 3326 6113 3309 6114 3326 6114 3307 6114 3307 6115 3326 6115 3316 6115 30 6116 29 6116 3327 6116 3327 6117 29 6117 28 6117 1178 6118 1179 6118 3221 6118 1723 6119 1725 6119 3327 6119 1178 6120 2612 6120 28 6120 28 6121 2612 6121 2595 6121 3221 6122 2610 6122 1178 6122 28 6123 2595 6123 2596 6123 28 6124 2596 6124 3327 6124 3327 6125 2596 6125 1723 6125 1178 6126 2610 6126 2611 6126 1178 6127 2611 6127 2612 6127 1847 6128 2073 6128 1818 6128 1818 6129 2073 6129 2077 6129 3336 6130 3328 6130 2073 6130 1568 6131 3329 6131 1567 6131 3331 6132 3330 6132 2077 6132 3328 6133 3331 6133 2073 6133 2073 6134 3331 6134 2077 6134 2077 6135 3332 6135 1565 6135 1565 6136 3332 6136 3333 6136 1577 6137 1565 6137 3334 6137 3333 6138 3334 6138 1565 6138 1577 6139 3334 6139 3335 6139 1577 6140 3335 6140 3329 6140 1577 6141 3329 6141 1568 6141 3329 6142 3336 6142 1567 6142 1567 6143 3336 6143 2073 6143 3330 6144 3332 6144 2077 6144 2076 6145 2077 6145 17 6145 17 6146 2077 6146 1565 6146 1180 6147 2074 6147 17 6147 17 6148 2074 6148 2076 6148 1864 6149 2091 6149 1917 6149 1917 6150 2091 6150 2095 6150 3349 6151 3337 6151 2091 6151 2095 6152 3338 6152 3339 6152 2095 6153 3339 6153 3340 6153 3340 6154 3339 6154 3341 6154 2091 6155 3337 6155 2095 6155 2095 6156 3337 6156 3338 6156 3340 6157 3341 6157 3342 6157 3340 6158 3342 6158 1575 6158 1575 6159 3342 6159 3343 6159 1575 6160 3343 6160 1576 6160 1576 6161 3343 6161 3344 6161 1576 6162 3344 6162 3346 6162 3346 6163 3344 6163 3347 6163 3346 6164 3347 6164 3345 6164 3345 6165 3348 6165 3346 6165 3346 6166 3348 6166 2091 6166 2091 6167 3348 6167 3349 6167 3337 6168 3360 6168 3350 6168 3337 6169 3350 6169 3338 6169 3338 6170 3350 6170 3351 6170 3338 6171 3351 6171 3339 6171 3339 6172 3351 6172 3352 6172 3339 6173 3352 6173 3341 6173 3341 6174 3352 6174 3353 6174 3341 6175 3353 6175 3342 6175 3342 6176 3353 6176 3354 6176 3342 6177 3354 6177 3343 6177 3343 6178 3354 6178 3344 6178 3344 6179 3354 6179 3355 6179 3344 6180 3355 6180 3356 6180 3344 6181 3356 6181 3347 6181 3347 6182 3356 6182 3357 6182 3347 6183 3357 6183 3345 6183 3345 6184 3357 6184 3348 6184 3348 6185 3357 6185 3358 6185 3348 6186 3358 6186 3349 6186 3349 6187 3358 6187 3359 6187 3349 6188 3359 6188 3360 6188 3349 6189 3360 6189 3337 6189 3362 6190 3361 6190 3363 6190 3363 6191 3361 6191 3364 6191 3363 6192 3364 6192 3365 6192 3365 6193 3364 6193 3366 6193 3365 6194 3366 6194 3367 6194 3365 6195 3367 6195 3368 6195 3368 6196 3367 6196 3369 6196 3368 6197 3369 6197 3370 6197 3370 6198 3369 6198 3371 6198 3370 6199 3371 6199 3372 6199 3372 6200 3371 6200 3373 6200 3372 6201 3373 6201 3374 6201 3374 6202 3373 6202 3375 6202 3374 6203 3375 6203 3376 6203 3376 6204 3375 6204 3377 6204 3376 6205 3377 6205 3378 6205 3376 6206 3378 6206 3379 6206 3379 6207 3378 6207 3380 6207 3379 6208 3380 6208 3381 6208 3381 6209 3380 6209 3382 6209 3381 6210 3382 6210 3383 6210 3383 6211 3382 6211 3362 6211 3362 6212 3382 6212 3361 6212 3384 6213 3331 6213 3385 6213 3385 6214 3331 6214 3328 6214 3385 6215 3328 6215 3386 6215 3386 6216 3328 6216 3336 6216 3386 6217 3336 6217 3387 6217 3387 6218 3336 6218 3329 6218 3387 6219 3329 6219 3388 6219 3388 6220 3329 6220 3389 6220 3389 6221 3329 6221 3335 6221 3389 6222 3335 6222 3390 6222 3390 6223 3335 6223 3334 6223 3390 6224 3334 6224 3391 6224 3391 6225 3334 6225 3392 6225 3392 6226 3334 6226 3333 6226 3392 6227 3333 6227 3393 6227 3393 6228 3333 6228 3332 6228 3393 6229 3332 6229 3394 6229 3394 6230 3332 6230 3330 6230 3394 6231 3330 6231 3395 6231 3395 6232 3330 6232 3331 6232 3395 6233 3331 6233 3384 6233 3306 6234 3396 6234 3397 6234 3306 6235 3397 6235 3308 6235 3308 6236 3397 6236 3398 6236 3308 6237 3398 6237 3311 6237 3311 6238 3398 6238 3399 6238 3311 6239 3399 6239 3313 6239 3313 6240 3399 6240 3400 6240 3313 6241 3400 6241 3292 6241 3292 6242 3400 6242 3401 6242 3292 6243 3401 6243 3402 6243 3292 6244 3402 6244 3293 6244 3293 6245 3402 6245 3403 6245 3293 6246 3403 6246 3296 6246 3296 6247 3403 6247 3404 6247 3296 6248 3404 6248 3298 6248 3298 6249 3404 6249 3405 6249 3298 6250 3405 6250 3300 6250 3300 6251 3405 6251 3406 6251 3300 6252 3406 6252 3302 6252 3302 6253 3406 6253 3407 6253 3302 6254 3407 6254 3304 6254 3304 6255 3407 6255 3396 6255 3304 6256 3396 6256 3306 6256 3408 6257 3288 6257 3419 6257 3288 6258 3408 6258 3281 6258 3281 6259 3408 6259 3409 6259 3281 6260 3409 6260 3286 6260 3286 6261 3409 6261 3410 6261 3286 6262 3410 6262 3285 6262 3285 6263 3410 6263 3411 6263 3285 6264 3411 6264 3284 6264 3284 6265 3411 6265 3412 6265 3284 6266 3412 6266 3413 6266 3284 6267 3413 6267 3282 6267 3282 6268 3413 6268 3414 6268 3282 6269 3414 6269 3415 6269 3282 6270 3415 6270 3283 6270 3283 6271 3415 6271 3291 6271 3291 6272 3415 6272 3416 6272 3291 6273 3416 6273 3290 6273 3290 6274 3416 6274 3417 6274 3290 6275 3417 6275 3289 6275 3289 6276 3417 6276 3418 6276 3289 6277 3418 6277 3287 6277 3287 6278 3418 6278 3419 6278 3287 6279 3419 6279 3288 6279 2256 6280 3273 6280 3271 6280 3239 6281 3269 6281 3267 6281 2282 6282 2277 6282 2283 6282 1886 6283 2210 6283 1882 6283 3260 6284 1846 6284 1844 6284 3273 6285 2259 6285 3276 6285 3273 6286 2256 6286 2259 6286 2256 6287 3271 6287 3269 6287 2256 6288 3269 6288 2244 6288 3278 6289 2283 6289 3280 6289 2260 6290 3278 6290 3276 6290 2260 6291 3276 6291 2259 6291 3239 6292 3267 6292 3241 6292 3241 6293 3267 6293 3265 6293 3241 6294 3265 6294 3243 6294 3260 6295 1844 6295 3262 6295 3262 6296 1844 6296 1845 6296 3262 6297 1845 6297 3263 6297 3263 6298 1845 6298 3223 6298 3223 6299 3245 6299 3263 6299 3263 6300 3245 6300 3243 6300 3269 6301 3239 6301 3237 6301 2283 6302 2277 6302 1610 6302 3243 6303 3265 6303 3263 6303 1884 6304 3316 6304 1885 6304 1846 6305 2304 6305 1812 6305 2304 6306 1846 6306 3260 6306 2304 6307 3260 6307 2284 6307 2284 6308 3260 6308 3280 6308 2284 6309 3280 6309 2283 6309 2271 6310 2282 6310 3278 6310 3278 6311 2282 6311 2283 6311 1885 6312 3316 6312 3326 6312 1885 6313 3326 6313 1845 6313 1845 6314 3326 6314 3325 6314 2215 6315 1648 6315 2239 6315 3317 6316 2215 6316 2238 6316 3317 6317 2238 6317 3318 6317 2215 6318 3317 6318 2210 6318 2210 6319 3317 6319 3316 6319 3278 6320 2260 6320 2271 6320 3225 6321 3223 6321 1845 6321 3320 6322 3319 6322 2243 6322 3319 6323 3318 6323 2242 6323 2242 6324 3318 6324 2238 6324 2215 6325 2239 6325 2238 6325 1884 6326 1883 6326 3316 6326 3316 6327 1883 6327 2210 6327 2210 6328 1883 6328 1882 6328 2244 6329 3235 6329 3233 6329 3325 6330 3226 6330 1845 6330 1845 6331 3226 6331 3225 6331 3319 6332 2242 6332 2243 6332 3226 6333 3325 6333 3228 6333 3228 6334 3325 6334 3324 6334 3269 6335 3237 6335 2244 6335 2244 6336 3237 6336 3235 6336 2244 6337 3320 6337 2243 6337 3233 6338 3232 6338 2244 6338 3322 6339 3321 6339 2244 6339 2244 6340 3321 6340 3320 6340 3230 6341 3323 6341 3232 6341 3228 6342 3324 6342 3230 6342 3230 6343 3324 6343 3323 6343 3323 6344 3322 6344 3232 6344 3232 6345 3322 6345 2244 6345 33 6346 1019 6346 1785 6346 59 6347 1571 6347 108 6347 108 6348 1571 6348 1774 6348 108 6349 1774 6349 1019 6349 1774 6350 1776 6350 1019 6350 1019 6351 1776 6351 1782 6351 1019 6352 1782 6352 1785 6352 1985 6353 2052 6353 1964 6353 1964 6354 2052 6354 2059 6354 1173 6355 1172 6355 1735 6355 1173 6356 1735 6356 113 6356 113 6357 1735 6357 1736 6357 113 6358 1736 6358 1739 6358 113 6359 1739 6359 1740 6359 3129 6360 69 6360 1740 6360 1740 6361 69 6361 113 6361 1826 6362 2025 6362 1852 6362 1852 6363 2025 6363 2008 6363 2609 6364 2591 6364 2266 6364 2591 6365 2273 6365 2266 6365 2981 6366 3015 6366 2960 6366 2960 6367 3015 6367 2952 6367 2952 6368 3015 6368 2997 6368 2952 6369 2997 6369 2953 6369 2953 6370 2997 6370 2977 6370 2953 6371 2977 6371 2956 6371 2956 6372 2977 6372 2986 6372 2956 6373 2986 6373 2945 6373 2945 6374 2986 6374 2982 6374 2945 6375 2982 6375 2947 6375 2947 6376 2982 6376 2989 6376 2947 6377 2989 6377 2949 6377 2949 6378 2989 6378 3012 6378 2949 6379 3012 6379 2942 6379 2942 6380 3012 6380 3017 6380 2942 6381 3017 6381 2950 6381 2950 6382 3017 6382 3016 6382 2950 6383 3016 6383 2938 6383 2938 6384 3016 6384 3005 6384 2938 6385 3005 6385 2941 6385 2941 6386 3005 6386 3018 6386 2941 6387 3018 6387 2959 6387 2959 6388 3018 6388 2981 6388 2959 6389 2981 6389 2960 6389 2988 6390 3002 6390 2926 6390 2926 6391 3002 6391 2922 6391 2922 6392 3002 6392 2998 6392 2922 6393 2998 6393 2920 6393 2920 6394 2998 6394 2995 6394 2920 6395 2995 6395 2980 6395 2920 6396 2980 6396 2918 6396 2918 6397 2980 6397 2994 6397 2918 6398 2994 6398 2916 6398 2916 6399 2994 6399 2913 6399 2913 6400 2994 6400 2975 6400 2913 6401 2975 6401 2908 6401 2908 6402 2975 6402 2974 6402 2908 6403 2974 6403 2910 6403 2910 6404 2974 6404 2992 6404 2910 6405 2992 6405 2907 6405 2907 6406 2992 6406 2990 6406 2907 6407 2990 6407 2905 6407 2905 6408 2990 6408 2983 6408 2905 6409 2983 6409 2987 6409 2905 6410 2987 6410 2924 6410 2924 6411 2987 6411 2988 6411 2924 6412 2988 6412 2926 6412 2876 6413 2993 6413 2889 6413 2889 6414 2993 6414 2979 6414 2889 6415 2979 6415 2978 6415 2889 6416 2978 6416 2887 6416 2887 6417 2978 6417 2976 6417 2887 6418 2976 6418 2885 6418 2885 6419 2976 6419 3004 6419 2885 6420 3004 6420 2883 6420 2883 6421 3004 6421 2882 6421 2882 6422 3004 6422 2991 6422 2882 6423 2991 6423 2877 6423 2877 6424 2991 6424 3003 6424 2877 6425 3003 6425 2879 6425 2879 6426 3003 6426 2999 6426 2879 6427 2999 6427 3020 6427 2879 6428 3020 6428 2873 6428 2873 6429 3020 6429 3009 6429 2873 6430 3009 6430 2871 6430 2871 6431 3009 6431 3019 6431 2871 6432 3019 6432 2874 6432 2874 6433 3019 6433 2984 6433 2874 6434 2984 6434 2876 6434 2876 6435 2984 6435 2993 6435 2857 6436 3006 6436 2853 6436 2853 6437 3006 6437 3011 6437 2853 6438 3011 6438 2985 6438 2853 6439 2985 6439 2851 6439 2851 6440 2985 6440 2996 6440 2851 6441 2996 6441 2850 6441 2850 6442 2996 6442 2847 6442 2847 6443 2996 6443 3010 6443 2847 6444 3010 6444 3001 6444 2847 6445 3001 6445 2840 6445 2840 6446 3001 6446 2841 6446 2841 6447 3001 6447 3000 6447 2841 6448 3000 6448 3014 6448 2841 6449 3014 6449 2844 6449 2844 6450 3014 6450 3013 6450 2844 6451 3013 6451 2839 6451 2839 6452 3013 6452 3008 6452 2839 6453 3008 6453 2837 6453 2837 6454 3008 6454 2855 6454 2855 6455 3008 6455 3007 6455 2855 6456 3007 6456 2857 6456 2857 6457 3007 6457 3006 6457 2602 6458 2593 6458 2159 6458 2159 6459 2593 6459 2594 6459 2241 6460 2231 6460 2612 6460 2612 6461 2231 6461 2595 6461 2211 6462 1657 6462 1647 6462 2807 6463 2784 6463 2785 6463 2807 6464 2785 6464 2786 6464 2807 6465 2786 6465 2813 6465 2813 6466 2786 6466 2787 6466 2813 6467 2787 6467 2806 6467 2806 6468 2787 6468 2791 6468 2791 6469 2787 6469 2788 6469 2791 6470 2788 6470 2790 6470 2790 6471 2788 6471 2789 6471 2790 6472 2789 6472 2793 6472 2793 6473 2789 6473 2779 6473 2793 6474 2779 6474 2780 6474 2793 6475 2780 6475 2804 6475 2804 6476 2780 6476 2781 6476 2804 6477 2781 6477 2805 6477 2805 6478 2781 6478 2817 6478 2817 6479 2781 6479 2782 6479 2817 6480 2782 6480 2827 6480 2827 6481 2782 6481 2783 6481 2827 6482 2783 6482 2801 6482 2801 6483 2783 6483 2784 6483 2801 6484 2784 6484 2807 6484 2815 6485 2742 6485 2745 6485 2815 6486 2745 6486 2792 6486 2792 6487 2745 6487 2816 6487 2816 6488 2745 6488 2753 6488 2816 6489 2753 6489 2802 6489 2802 6490 2753 6490 2752 6490 2802 6491 2752 6491 2750 6491 2802 6492 2750 6492 2821 6492 2821 6493 2750 6493 2751 6493 2821 6494 2751 6494 2803 6494 2803 6495 2751 6495 2749 6495 2803 6496 2749 6496 2818 6496 2818 6497 2749 6497 2748 6497 2818 6498 2748 6498 2819 6498 2819 6499 2748 6499 2747 6499 2819 6500 2747 6500 2829 6500 2829 6501 2747 6501 2746 6501 2829 6502 2746 6502 2824 6502 2824 6503 2746 6503 2823 6503 2823 6504 2746 6504 2744 6504 2823 6505 2744 6505 2743 6505 2823 6506 2743 6506 2812 6506 2812 6507 2743 6507 2742 6507 2812 6508 2742 6508 2815 6508 2828 6509 2709 6509 2716 6509 2828 6510 2716 6510 2832 6510 2832 6511 2716 6511 2715 6511 2832 6512 2715 6512 2835 6512 2835 6513 2715 6513 2810 6513 2810 6514 2715 6514 2714 6514 2810 6515 2714 6515 2811 6515 2811 6516 2714 6516 2713 6516 2811 6517 2713 6517 2826 6517 2826 6518 2713 6518 2707 6518 2826 6519 2707 6519 2800 6519 2800 6520 2707 6520 2708 6520 2800 6521 2708 6521 2825 6521 2825 6522 2708 6522 2710 6522 2825 6523 2710 6523 2831 6523 2831 6524 2710 6524 2711 6524 2831 6525 2711 6525 2834 6525 2834 6526 2711 6526 2833 6526 2833 6527 2711 6527 2712 6527 2833 6528 2712 6528 2830 6528 2830 6529 2712 6529 2828 6529 2828 6530 2712 6530 2709 6530 2822 6531 2674 6531 2673 6531 2822 6532 2673 6532 2820 6532 2820 6533 2673 6533 2680 6533 2820 6534 2680 6534 2794 6534 2794 6535 2680 6535 2795 6535 2795 6536 2680 6536 2681 6536 2795 6537 2681 6537 2682 6537 2795 6538 2682 6538 2796 6538 2796 6539 2682 6539 2677 6539 2796 6540 2677 6540 2797 6540 2797 6541 2677 6541 2798 6541 2798 6542 2677 6542 2679 6542 2798 6543 2679 6543 2814 6543 2814 6544 2679 6544 2678 6544 2814 6545 2678 6545 2808 6545 2808 6546 2678 6546 2676 6546 2808 6547 2676 6547 2799 6547 2799 6548 2676 6548 2675 6548 2799 6549 2675 6549 2809 6549 2809 6550 2675 6550 2674 6550 2809 6551 2674 6551 2822 6551 2723 6552 2721 6552 1800 6552 1800 6553 2721 6553 2719 6553 2766 6554 2764 6554 2718 6554 2723 6555 1800 6555 1801 6555 2655 6556 2768 6556 2766 6556 2770 6557 2768 6557 2654 6557 2654 6558 2768 6558 2655 6558 2689 6559 2687 6559 2731 6559 1801 6560 2730 6560 2727 6560 1801 6561 2727 6561 2725 6561 2762 6562 2760 6562 2719 6562 2719 6563 2760 6563 1800 6563 1800 6564 2760 6564 2758 6564 1801 6565 2725 6565 2723 6565 2758 6566 2756 6566 1800 6566 1806 6567 2671 6567 2669 6567 2739 6568 2655 6568 2718 6568 2718 6569 2655 6569 2766 6569 2571 6570 2695 6570 2693 6570 2775 6571 2773 6571 2652 6571 2770 6572 2654 6572 2652 6572 2686 6573 2737 6573 2735 6573 1806 6574 2755 6574 2777 6574 1806 6575 2777 6575 2775 6575 2652 6576 2773 6576 2770 6576 2687 6577 2734 6577 2731 6577 2775 6578 2652 6578 2651 6578 2718 6579 2764 6579 2762 6579 2718 6580 2762 6580 2719 6580 2686 6581 2735 6581 2734 6581 2686 6582 2734 6582 2687 6582 1806 6583 2651 6583 2671 6583 2571 6584 2693 6584 2692 6584 2571 6585 2692 6585 2554 6585 1800 6586 2756 6586 1806 6586 1806 6587 2756 6587 2755 6587 2775 6588 2651 6588 1806 6588 1806 6589 2669 6589 2667 6589 1806 6590 2667 6590 1811 6590 2705 6591 2657 6591 2655 6591 2554 6592 2692 6592 2689 6592 2554 6593 2689 6593 1801 6593 1801 6594 2689 6594 2731 6594 1801 6595 2731 6595 2730 6595 2737 6596 2686 6596 2684 6596 2737 6597 2684 6597 2739 6597 2705 6598 2659 6598 2657 6598 2661 6599 2703 6599 2701 6599 2568 6600 2701 6600 2699 6600 2568 6601 2699 6601 2697 6601 2568 6602 2697 6602 2571 6602 2571 6603 2697 6603 2695 6603 2705 6604 2703 6604 2659 6604 2659 6605 2703 6605 2661 6605 2667 6606 2665 6606 1811 6606 1811 6607 2665 6607 2560 6607 2560 6608 2665 6608 2663 6608 2560 6609 2663 6609 2567 6609 2567 6610 2663 6610 2661 6610 2567 6611 2661 6611 2568 6611 2568 6612 2661 6612 2701 6612 2739 6613 2684 6613 2655 6613 2655 6614 2684 6614 2705 6614 16 6615 15 6615 1564 6615 3128 6616 37 6616 36 6616 36 6617 42 6617 3146 6617 1573 6618 71 6618 3146 6618 3146 6619 71 6619 69 6619 3146 6620 69 6620 36 6620 36 6621 69 6621 3129 6621 36 6622 3129 6622 3128 6622 1566 6623 87 6623 1756 6623 1756 6624 87 6624 86 6624 1751 6625 1020 6625 31 6625 1020 6626 1751 6626 86 6626 1751 6627 1754 6627 86 6627 86 6628 1754 6628 1756 6628 3387 6629 1036 6629 1046 6629 3387 6630 1046 6630 3386 6630 3386 6631 1046 6631 1045 6631 3386 6632 1045 6632 3385 6632 3385 6633 1045 6633 3384 6633 3384 6634 1045 6634 1044 6634 3384 6635 1044 6635 3395 6635 3395 6636 1044 6636 1043 6636 3395 6637 1043 6637 3394 6637 3394 6638 1043 6638 1042 6638 3394 6639 1042 6639 3393 6639 3393 6640 1042 6640 1041 6640 3393 6641 1041 6641 3392 6641 3392 6642 1041 6642 1040 6642 3392 6643 1040 6643 3391 6643 3391 6644 1040 6644 3390 6644 3390 6645 1040 6645 1039 6645 3390 6646 1039 6646 3389 6646 3389 6647 1039 6647 1038 6647 3389 6648 1038 6648 1037 6648 3389 6649 1037 6649 3388 6649 3388 6650 1037 6650 1036 6650 3388 6651 1036 6651 3387 6651 1025 6652 1024 6652 3191 6652 3191 6653 1024 6653 3190 6653 3190 6654 1024 6654 1035 6654 3190 6655 1035 6655 3189 6655 3189 6656 1035 6656 1034 6656 3189 6657 1034 6657 3188 6657 3188 6658 1034 6658 1033 6658 3188 6659 1033 6659 3198 6659 3198 6660 1033 6660 1032 6660 3198 6661 1032 6661 1031 6661 3198 6662 1031 6662 3197 6662 3197 6663 1031 6663 1030 6663 3197 6664 1030 6664 3196 6664 3196 6665 1030 6665 1029 6665 3196 6666 1029 6666 3195 6666 3195 6667 1029 6667 1028 6667 3195 6668 1028 6668 3194 6668 3194 6669 1028 6669 1027 6669 3194 6670 1027 6670 3193 6670 3193 6671 1027 6671 1026 6671 3193 6672 1026 6672 3192 6672 3192 6673 1026 6673 1025 6673 3192 6674 1025 6674 3191 6674 79 6675 3327 6675 80 6675 80 6676 3327 6676 1725 6676 1727 6677 1175 6677 1174 6677 80 6678 1734 6678 1728 6678 1727 6679 1174 6679 80 6679 1727 6680 80 6680 1728 6680 80 6681 1725 6681 1734 6681 3356 6682 1090 6682 1088 6682 3356 6683 1088 6683 3357 6683 3357 6684 1088 6684 1086 6684 3357 6685 1086 6685 1085 6685 3357 6686 1085 6686 3358 6686 3358 6687 1085 6687 3359 6687 3359 6688 1085 6688 1107 6688 3359 6689 1107 6689 1105 6689 3359 6690 1105 6690 3360 6690 3360 6691 1105 6691 1103 6691 3360 6692 1103 6692 3350 6692 3350 6693 1103 6693 1100 6693 3350 6694 1100 6694 3351 6694 3351 6695 1100 6695 1099 6695 3351 6696 1099 6696 3352 6696 3352 6697 1099 6697 1097 6697 3352 6698 1097 6698 3353 6698 3353 6699 1097 6699 1095 6699 3353 6700 1095 6700 1093 6700 3353 6701 1093 6701 3354 6701 3354 6702 1093 6702 1092 6702 3354 6703 1092 6703 3355 6703 3355 6704 1092 6704 1090 6704 3355 6705 1090 6705 3356 6705 3160 6706 1067 6706 1065 6706 3160 6707 1065 6707 3161 6707 3161 6708 1065 6708 3162 6708 3162 6709 1065 6709 1063 6709 3162 6710 1063 6710 3163 6710 3163 6711 1063 6711 1083 6711 3163 6712 1083 6712 3164 6712 3164 6713 1083 6713 1082 6713 3164 6714 1082 6714 1080 6714 3164 6715 1080 6715 3154 6715 3154 6716 1080 6716 3155 6716 3155 6717 1080 6717 1078 6717 3155 6718 1078 6718 3156 6718 3156 6719 1078 6719 1076 6719 3156 6720 1076 6720 3157 6720 3157 6721 1076 6721 1074 6721 3157 6722 1074 6722 3158 6722 3158 6723 1074 6723 1071 6723 3158 6724 1071 6724 3159 6724 3159 6725 1071 6725 1070 6725 3159 6726 1070 6726 1067 6726 3159 6727 1067 6727 3160 6727 112 6728 3021 6728 126 6728 126 6729 3021 6729 1187 6729 37 6730 3128 6730 38 6730 124 6731 123 6731 1136 6731 1136 6732 123 6732 1189 6732 1136 6733 1189 6733 1134 6733 1134 6734 1189 6734 3022 6734 1191 6735 1576 6735 79 6735 79 6736 1576 6736 3346 6736 3346 6737 24 6737 79 6737 79 6738 24 6738 25 6738 79 6739 25 6739 3327 6739 3327 6740 25 6740 30 6740 3220 6741 91 6741 1181 6741 1181 6742 91 6742 90 6742 969 6743 3221 6743 967 6743 967 6744 3221 6744 1179 6744 967 6745 1179 6745 75 6745 75 6746 1179 6746 76 6746 1575 6747 1192 6747 3340 6747 3340 6748 1192 6748 1061 6748 3340 6749 1061 6749 5 6749 3151 6750 40 6750 67 6750 3151 6751 67 6751 1574 6751 1574 6752 67 6752 66 6752 1572 6753 58 6753 3131 6753 3131 6754 58 6754 57 6754 3131 6755 57 6755 8 6755 3420 6756 3199 6756 3421 6756 3421 6757 3199 6757 3208 6757 3421 6758 3208 6758 3422 6758 3422 6759 3208 6759 3207 6759 3422 6760 3207 6760 3423 6760 3423 6761 3207 6761 3206 6761 3423 6762 3206 6762 3424 6762 3424 6763 3206 6763 3205 6763 3424 6764 3205 6764 3204 6764 3424 6765 3204 6765 3425 6765 3425 6766 3204 6766 3426 6766 3426 6767 3204 6767 3203 6767 3426 6768 3203 6768 3427 6768 3427 6769 3203 6769 3428 6769 3428 6770 3203 6770 3202 6770 3428 6771 3202 6771 3429 6771 3429 6772 3202 6772 3201 6772 3429 6773 3201 6773 3430 6773 3430 6774 3201 6774 3200 6774 3430 6775 3200 6775 3420 6775 3420 6776 3200 6776 3199 6776 3184 6777 2081 6777 3182 6777 3180 6778 3182 6778 2080 6778 2080 6779 3182 6779 2081 6779 3184 6780 3186 6780 2081 6780 3187 6781 3167 6781 1188 6781 1188 6782 3167 6782 3168 6782 11 6783 3174 6783 10 6783 3186 6784 3187 6784 2081 6784 2081 6785 3187 6785 1188 6785 1188 6786 3168 6786 46 6786 46 6787 3168 6787 3170 6787 46 6788 3170 6788 11 6788 11 6789 3170 6789 3172 6789 11 6790 3172 6790 3174 6790 10 6791 3174 6791 3176 6791 10 6792 3176 6792 2080 6792 2080 6793 3176 6793 3178 6793 2080 6794 3178 6794 3180 6794 3175 6795 904 6795 2087 6795 904 6796 3175 6796 903 6796 903 6797 3175 6797 3173 6797 903 6798 3173 6798 3171 6798 903 6799 3171 6799 1047 6799 3181 6800 2087 6800 3183 6800 3183 6801 2087 6801 2086 6801 2087 6802 3181 6802 3179 6802 3171 6803 3169 6803 1047 6803 1047 6804 3169 6804 64 6804 64 6805 3169 6805 3166 6805 2087 6806 3179 6806 3177 6806 2087 6807 3177 6807 3175 6807 2086 6808 3165 6808 3185 6808 2086 6809 3185 6809 3183 6809 3166 6810 3165 6810 64 6810 64 6811 3165 6811 2086 6811 2088 6812 2089 6812 42 6812 42 6813 2089 6813 3146 6813 64 6814 2086 6814 42 6814 42 6815 2086 6815 2088 6815 3210 6816 3209 6816 3431 6816 3431 6817 3209 6817 3219 6817 3431 6818 3219 6818 3432 6818 3432 6819 3219 6819 3218 6819 3432 6820 3218 6820 3433 6820 3433 6821 3218 6821 3217 6821 3433 6822 3217 6822 3434 6822 3434 6823 3217 6823 3216 6823 3434 6824 3216 6824 3435 6824 3435 6825 3216 6825 3215 6825 3435 6826 3215 6826 3436 6826 3436 6827 3215 6827 3214 6827 3436 6828 3214 6828 3437 6828 3437 6829 3214 6829 3213 6829 3437 6830 3213 6830 3438 6830 3438 6831 3213 6831 3212 6831 3438 6832 3212 6832 3439 6832 3439 6833 3212 6833 3211 6833 3439 6834 3211 6834 3440 6834 3440 6835 3211 6835 3210 6835 3440 6836 3210 6836 3441 6836 3441 6837 3210 6837 3431 6837 33 6838 1785 6838 1779 6838 3442 6839 3419 6839 3443 6839 3443 6840 3419 6840 3444 6840 3444 6841 3419 6841 3418 6841 3444 6842 3418 6842 3417 6842 3444 6843 3417 6843 3445 6843 3445 6844 3417 6844 3416 6844 3445 6845 3416 6845 3446 6845 3446 6846 3416 6846 3415 6846 3446 6847 3415 6847 3447 6847 3447 6848 3415 6848 3448 6848 3448 6849 3415 6849 3414 6849 3448 6850 3414 6850 3449 6850 3449 6851 3414 6851 3413 6851 3449 6852 3413 6852 3412 6852 3449 6853 3412 6853 3450 6853 3450 6854 3412 6854 3411 6854 3450 6855 3411 6855 3451 6855 3451 6856 3411 6856 3410 6856 3451 6857 3410 6857 3452 6857 3452 6858 3410 6858 3409 6858 3452 6859 3409 6859 3408 6859 3452 6860 3408 6860 3442 6860 3442 6861 3408 6861 3419 6861 3374 6862 2 6862 3372 6862 3368 6863 3370 6863 2075 6863 2075 6864 3370 6864 3372 6864 2075 6865 3372 6865 3 6865 3 6866 3372 6866 2 6866 2 6867 3374 6867 21 6867 21 6868 3374 6868 3376 6868 21 6869 3376 6869 3379 6869 3381 6870 1180 6870 3379 6870 3379 6871 1180 6871 21 6871 1180 6872 3381 6872 3383 6872 2074 6873 3363 6873 3365 6873 1180 6874 3383 6874 3362 6874 2074 6875 3365 6875 3368 6875 2074 6876 3368 6876 2075 6876 1180 6877 3362 6877 2074 6877 2074 6878 3362 6878 3363 6878 2092 6879 3371 6879 3369 6879 3366 6880 3364 6880 2093 6880 3361 6881 3382 6881 55 6881 56 6882 55 6882 3380 6882 6 6883 3373 6883 4 6883 3382 6884 3380 6884 55 6884 4 6885 3373 6885 2092 6885 2092 6886 3373 6886 3371 6886 3369 6887 3367 6887 2092 6887 2092 6888 3367 6888 2093 6888 2093 6889 3367 6889 3366 6889 3364 6890 3361 6890 2093 6890 2093 6891 3361 6891 55 6891 3380 6892 3378 6892 56 6892 56 6893 3378 6893 3377 6893 56 6894 3377 6894 3375 6894 56 6895 3375 6895 6 6895 6 6896 3375 6896 3373 6896 3346 6897 2091 6897 24 6897 24 6898 2091 6898 2090 6898 2093 6899 55 6899 24 6899 2093 6900 24 6900 2090 6900 3453 6901 3396 6901 3407 6901 3453 6902 3407 6902 3454 6902 3454 6903 3407 6903 3406 6903 3454 6904 3406 6904 3455 6904 3455 6905 3406 6905 3405 6905 3455 6906 3405 6906 3456 6906 3456 6907 3405 6907 3404 6907 3456 6908 3404 6908 3457 6908 3457 6909 3404 6909 3403 6909 3457 6910 3403 6910 3458 6910 3458 6911 3403 6911 3402 6911 3458 6912 3402 6912 3459 6912 3459 6913 3402 6913 3460 6913 3460 6914 3402 6914 3401 6914 3460 6915 3401 6915 3400 6915 3460 6916 3400 6916 3461 6916 3461 6917 3400 6917 3399 6917 3461 6918 3399 6918 3462 6918 3462 6919 3399 6919 3398 6919 3462 6920 3398 6920 3463 6920 3463 6921 3398 6921 3397 6921 3463 6922 3397 6922 3464 6922 3464 6923 3397 6923 3396 6923 3464 6924 3396 6924 3453 6924 2082 6925 2083 6925 8 6925 8 6926 2083 6926 3131 6926 10 6927 2080 6927 8 6927 8 6928 2080 6928 2082 6928 3151 6929 2085 6929 40 6929 40 6930 2085 6930 2084 6930 2087 6931 904 6931 40 6931 2087 6932 40 6932 2084 6932 2094 6933 2095 6933 5 6933 5 6934 2095 6934 3340 6934 4 6935 2092 6935 5 6935 5 6936 2092 6936 2094 6936 1567 6937 2073 6937 1 6937 1 6938 2073 6938 2072 6938 2075 6939 3 6939 1 6939 2075 6940 1 6940 2072 6940 3466 6941 3465 6941 3473 6941 3467 6942 3465 6942 3469 6942 3467 6943 3469 6943 3468 6943 3468 6944 3470 6944 3471 6944 3468 6945 3471 6945 3467 6945 3467 6946 3472 6946 3465 6946 3465 6947 3472 6947 3473 6947 3466 6948 3474 6948 3465 6948 3466 6949 3475 6949 3474 6949 3473 6950 3047 6950 3057 6950 3473 6951 3057 6951 3466 6951 3466 6952 3057 6952 3056 6952 3466 6953 3056 6953 3475 6953 3475 6954 3056 6954 3055 6954 3475 6955 3055 6955 3474 6955 3474 6956 3055 6956 3054 6956 3474 6957 3054 6957 3465 6957 3465 6958 3054 6958 3053 6958 3465 6959 3053 6959 3469 6959 3469 6960 3053 6960 3052 6960 3469 6961 3052 6961 3468 6961 3468 6962 3052 6962 3051 6962 3468 6963 3051 6963 3050 6963 3468 6964 3050 6964 3470 6964 3470 6965 3050 6965 3471 6965 3471 6966 3050 6966 3049 6966 3471 6967 3049 6967 3467 6967 3467 6968 3049 6968 3048 6968 3467 6969 3048 6969 3472 6969 3472 6970 3048 6970 3047 6970 3472 6971 3047 6971 3473 6971 3480 6972 3476 6972 3477 6972 3477 6973 3478 6973 3479 6973 3477 6974 3476 6974 3478 6974 3480 6975 3481 6975 3484 6975 3480 6976 3484 6976 3485 6976 3481 6977 3480 6977 3477 6977 3477 6978 3479 6978 3486 6978 3477 6979 3486 6979 3482 6979 3477 6980 3482 6980 3483 6980 3483 6981 3247 6981 3246 6981 3483 6982 3246 6982 3477 6982 3477 6983 3246 6983 3258 6983 3477 6984 3258 6984 3481 6984 3481 6985 3258 6985 3257 6985 3481 6986 3257 6986 3484 6986 3484 6987 3257 6987 3256 6987 3484 6988 3256 6988 3485 6988 3485 6989 3256 6989 3255 6989 3485 6990 3255 6990 3254 6990 3485 6991 3254 6991 3480 6991 3480 6992 3254 6992 3253 6992 3480 6993 3253 6993 3476 6993 3476 6994 3253 6994 3252 6994 3476 6995 3252 6995 3251 6995 3476 6996 3251 6996 3478 6996 3478 6997 3251 6997 3250 6997 3478 6998 3250 6998 3479 6998 3479 6999 3250 6999 3249 6999 3479 7000 3249 7000 3486 7000 3486 7001 3249 7001 3248 7001 3486 7002 3248 7002 3482 7002 3482 7003 3248 7003 3247 7003 3482 7004 3247 7004 3483 7004 3488 7005 3489 7005 3490 7005 3488 7006 3490 7006 3492 7006 3488 7007 3487 7007 3493 7007 3488 7008 3492 7008 3494 7008 3487 7009 3488 7009 3491 7009 3491 7010 3495 7010 3487 7010 3488 7011 3493 7011 3489 7011 3494 7012 3496 7012 3488 7012 3495 7013 3497 7013 3487 7013 3508 7014 3496 7014 3498 7014 3498 7015 3496 7015 3494 7015 3498 7016 3494 7016 3499 7016 3499 7017 3494 7017 3492 7017 3499 7018 3492 7018 3500 7018 3500 7019 3492 7019 3490 7019 3500 7020 3490 7020 3501 7020 3501 7021 3490 7021 3489 7021 3501 7022 3489 7022 3493 7022 3501 7023 3493 7023 3502 7023 3502 7024 3493 7024 3487 7024 3502 7025 3487 7025 3503 7025 3503 7026 3487 7026 3504 7026 3504 7027 3487 7027 3497 7027 3504 7028 3497 7028 3505 7028 3505 7029 3497 7029 3495 7029 3505 7030 3495 7030 3506 7030 3506 7031 3495 7031 3491 7031 3506 7032 3491 7032 3507 7032 3507 7033 3491 7033 3488 7033 3507 7034 3488 7034 3508 7034 3508 7035 3488 7035 3496 7035 3506 7036 3509 7036 3505 7036 3505 7037 3509 7037 3510 7037 3505 7038 3510 7038 3504 7038 3504 7039 3510 7039 3511 7039 3504 7040 3511 7040 3503 7040 3503 7041 3511 7041 3502 7041 3502 7042 3511 7042 3512 7042 3502 7043 3512 7043 3513 7043 3502 7044 3513 7044 3501 7044 3501 7045 3513 7045 3514 7045 3501 7046 3514 7046 3500 7046 3500 7047 3514 7047 3515 7047 3500 7048 3515 7048 3499 7048 3499 7049 3515 7049 3516 7049 3499 7050 3516 7050 3517 7050 3499 7051 3517 7051 3498 7051 3498 7052 3517 7052 3518 7052 3498 7053 3518 7053 3508 7053 3508 7054 3518 7054 3519 7054 3508 7055 3519 7055 3507 7055 3507 7056 3519 7056 3520 7056 3507 7057 3520 7057 3506 7057 3506 7058 3520 7058 3509 7058 3429 7059 3518 7059 3428 7059 3428 7060 3518 7060 3517 7060 3428 7061 3517 7061 3427 7061 3427 7062 3517 7062 3516 7062 3427 7063 3516 7063 3515 7063 3427 7064 3515 7064 3426 7064 3426 7065 3515 7065 3425 7065 3425 7066 3515 7066 3514 7066 3425 7067 3514 7067 3513 7067 3425 7068 3513 7068 3424 7068 3424 7069 3513 7069 3512 7069 3424 7070 3512 7070 3423 7070 3423 7071 3512 7071 3511 7071 3423 7072 3511 7072 3422 7072 3422 7073 3511 7073 3510 7073 3422 7074 3510 7074 3421 7074 3421 7075 3510 7075 3509 7075 3421 7076 3509 7076 3420 7076 3420 7077 3509 7077 3520 7077 3420 7078 3520 7078 3430 7078 3430 7079 3520 7079 3519 7079 3430 7080 3519 7080 3429 7080 3429 7081 3519 7081 3518 7081 3524 7082 3525 7082 3523 7082 3524 7083 3523 7083 3522 7083 3521 7084 3523 7084 3526 7084 3524 7085 3527 7085 3525 7085 3525 7086 3527 7086 3528 7086 3525 7087 3531 7087 3529 7087 3525 7088 3529 7088 3530 7088 3521 7089 3522 7089 3523 7089 3525 7090 3528 7090 3531 7090 3543 7091 3528 7091 3532 7091 3532 7092 3528 7092 3527 7092 3532 7093 3527 7093 3533 7093 3533 7094 3527 7094 3524 7094 3533 7095 3524 7095 3534 7095 3534 7096 3524 7096 3522 7096 3534 7097 3522 7097 3535 7097 3535 7098 3522 7098 3521 7098 3535 7099 3521 7099 3536 7099 3536 7100 3521 7100 3537 7100 3537 7101 3521 7101 3526 7101 3537 7102 3526 7102 3538 7102 3538 7103 3526 7103 3523 7103 3538 7104 3523 7104 3539 7104 3539 7105 3523 7105 3525 7105 3539 7106 3525 7106 3540 7106 3540 7107 3525 7107 3541 7107 3541 7108 3525 7108 3530 7108 3541 7109 3530 7109 3529 7109 3541 7110 3529 7110 3542 7110 3542 7111 3529 7111 3543 7111 3543 7112 3529 7112 3531 7112 3543 7113 3531 7113 3528 7113 3543 7114 3544 7114 3542 7114 3542 7115 3544 7115 3545 7115 3542 7116 3545 7116 3541 7116 3541 7117 3545 7117 3546 7117 3541 7118 3546 7118 3540 7118 3540 7119 3546 7119 3539 7119 3539 7120 3546 7120 3547 7120 3539 7121 3547 7121 3538 7121 3538 7122 3547 7122 3548 7122 3538 7123 3548 7123 3537 7123 3537 7124 3548 7124 3549 7124 3537 7125 3549 7125 3550 7125 3537 7126 3550 7126 3536 7126 3536 7127 3550 7127 3551 7127 3536 7128 3551 7128 3535 7128 3535 7129 3551 7129 3552 7129 3535 7130 3552 7130 3534 7130 3534 7131 3552 7131 3533 7131 3533 7132 3552 7132 3553 7132 3533 7133 3553 7133 3532 7133 3532 7134 3553 7134 3554 7134 3532 7135 3554 7135 3543 7135 3543 7136 3554 7136 3544 7136 3439 7137 3554 7137 3438 7137 3438 7138 3554 7138 3553 7138 3438 7139 3553 7139 3437 7139 3437 7140 3553 7140 3552 7140 3437 7141 3552 7141 3436 7141 3436 7142 3552 7142 3551 7142 3436 7143 3551 7143 3435 7143 3435 7144 3551 7144 3550 7144 3435 7145 3550 7145 3434 7145 3434 7146 3550 7146 3549 7146 3434 7147 3549 7147 3548 7147 3434 7148 3548 7148 3433 7148 3433 7149 3548 7149 3547 7149 3433 7150 3547 7150 3432 7150 3432 7151 3547 7151 3546 7151 3432 7152 3546 7152 3431 7152 3431 7153 3546 7153 3545 7153 3431 7154 3545 7154 3441 7154 3441 7155 3545 7155 3440 7155 3440 7156 3545 7156 3544 7156 3440 7157 3544 7157 3439 7157 3439 7158 3544 7158 3554 7158 3557 7159 3556 7159 3558 7159 3557 7160 3559 7160 3556 7160 3556 7161 3559 7161 3560 7161 3560 7162 3561 7162 3562 7162 3562 7163 3563 7163 3560 7163 3560 7164 3563 7164 3556 7164 3564 7165 3555 7165 3558 7165 3558 7166 3555 7166 3557 7166 3564 7167 3565 7167 3555 7167 3561 7168 3566 7168 3567 7168 3561 7169 3567 7169 3562 7169 3562 7170 3567 7170 3568 7170 3562 7171 3568 7171 3563 7171 3563 7172 3568 7172 3569 7172 3563 7173 3569 7173 3556 7173 3556 7174 3569 7174 3570 7174 3556 7175 3570 7175 3558 7175 3558 7176 3570 7176 3571 7176 3558 7177 3571 7177 3564 7177 3564 7178 3571 7178 3572 7178 3564 7179 3572 7179 3565 7179 3565 7180 3572 7180 3555 7180 3555 7181 3572 7181 3573 7181 3555 7182 3573 7182 3557 7182 3557 7183 3573 7183 3574 7183 3557 7184 3574 7184 3559 7184 3559 7185 3574 7185 3575 7185 3559 7186 3575 7186 3560 7186 3560 7187 3575 7187 3566 7187 3560 7188 3566 7188 3561 7188 3575 7189 3576 7189 3566 7189 3566 7190 3576 7190 3577 7190 3566 7191 3577 7191 3567 7191 3567 7192 3577 7192 3578 7192 3567 7193 3578 7193 3568 7193 3568 7194 3578 7194 3569 7194 3569 7195 3578 7195 3579 7195 3569 7196 3579 7196 3570 7196 3570 7197 3579 7197 3580 7197 3570 7198 3580 7198 3571 7198 3571 7199 3580 7199 3581 7199 3571 7200 3581 7200 3572 7200 3572 7201 3581 7201 3582 7201 3572 7202 3582 7202 3573 7202 3573 7203 3582 7203 3583 7203 3573 7204 3583 7204 3584 7204 3573 7205 3584 7205 3574 7205 3574 7206 3584 7206 3585 7206 3574 7207 3585 7207 3575 7207 3575 7208 3585 7208 3586 7208 3575 7209 3586 7209 3576 7209 3576 7210 3445 7210 3446 7210 3576 7211 3446 7211 3577 7211 3577 7212 3446 7212 3447 7212 3577 7213 3447 7213 3578 7213 3578 7214 3447 7214 3448 7214 3578 7215 3448 7215 3579 7215 3579 7216 3448 7216 3449 7216 3579 7217 3449 7217 3580 7217 3580 7218 3449 7218 3450 7218 3580 7219 3450 7219 3581 7219 3581 7220 3450 7220 3451 7220 3581 7221 3451 7221 3582 7221 3582 7222 3451 7222 3452 7222 3582 7223 3452 7223 3583 7223 3583 7224 3452 7224 3584 7224 3584 7225 3452 7225 3442 7225 3584 7226 3442 7226 3585 7226 3585 7227 3442 7227 3443 7227 3585 7228 3443 7228 3444 7228 3585 7229 3444 7229 3586 7229 3586 7230 3444 7230 3445 7230 3586 7231 3445 7231 3576 7231 3587 7232 3588 7232 3589 7232 3589 7233 3588 7233 3590 7233 3591 7234 3589 7234 3590 7234 3592 7235 3593 7235 3589 7235 3589 7236 3591 7236 3592 7236 3597 7237 3596 7237 3594 7237 3596 7238 3597 7238 3589 7238 3589 7239 3597 7239 3587 7239 3596 7240 3595 7240 3594 7240 3595 7241 3607 7241 3598 7241 3595 7242 3598 7242 3594 7242 3594 7243 3598 7243 3599 7243 3594 7244 3599 7244 3597 7244 3597 7245 3599 7245 3587 7245 3587 7246 3599 7246 3600 7246 3587 7247 3600 7247 3588 7247 3588 7248 3600 7248 3601 7248 3588 7249 3601 7249 3590 7249 3590 7250 3601 7250 3602 7250 3590 7251 3602 7251 3591 7251 3591 7252 3602 7252 3603 7252 3591 7253 3603 7253 3592 7253 3592 7254 3603 7254 3604 7254 3592 7255 3604 7255 3593 7255 3593 7256 3604 7256 3605 7256 3593 7257 3605 7257 3589 7257 3589 7258 3605 7258 3606 7258 3589 7259 3606 7259 3596 7259 3596 7260 3606 7260 3607 7260 3596 7261 3607 7261 3595 7261 3604 7262 3608 7262 3609 7262 3604 7263 3609 7263 3605 7263 3605 7264 3609 7264 3606 7264 3606 7265 3609 7265 3610 7265 3606 7266 3610 7266 3607 7266 3607 7267 3610 7267 3611 7267 3607 7268 3611 7268 3598 7268 3598 7269 3611 7269 3612 7269 3598 7270 3612 7270 3599 7270 3599 7271 3612 7271 3613 7271 3599 7272 3613 7272 3614 7272 3599 7273 3614 7273 3600 7273 3600 7274 3614 7274 3615 7274 3600 7275 3615 7275 3601 7275 3601 7276 3615 7276 3616 7276 3601 7277 3616 7277 3602 7277 3602 7278 3616 7278 3617 7278 3602 7279 3617 7279 3603 7279 3603 7280 3617 7280 3618 7280 3603 7281 3618 7281 3608 7281 3603 7282 3608 7282 3604 7282 3611 7283 3456 7283 3457 7283 3611 7284 3457 7284 3612 7284 3612 7285 3457 7285 3458 7285 3612 7286 3458 7286 3613 7286 3613 7287 3458 7287 3614 7287 3614 7288 3458 7288 3459 7288 3614 7289 3459 7289 3460 7289 3614 7290 3460 7290 3615 7290 3615 7291 3460 7291 3461 7291 3615 7292 3461 7292 3616 7292 3616 7293 3461 7293 3462 7293 3616 7294 3462 7294 3617 7294 3617 7295 3462 7295 3463 7295 3617 7296 3463 7296 3618 7296 3618 7297 3463 7297 3464 7297 3618 7298 3464 7298 3608 7298 3608 7299 3464 7299 3453 7299 3608 7300 3453 7300 3609 7300 3609 7301 3453 7301 3454 7301 3609 7302 3454 7302 3610 7302 3610 7303 3454 7303 3455 7303 3610 7304 3455 7304 3611 7304 3611 7305 3455 7305 3456 7305 3619 7306 3620 7306 3621 7306 3619 7307 3622 7307 3623 7307 3619 7308 3623 7308 3624 7308 3619 7309 3624 7309 3625 7309 3619 7310 3621 7310 3622 7310 3619 7311 3625 7311 3626 7311 3619 7312 3626 7312 3627 7312 3619 7313 3627 7313 3628 7313 3628 7314 3629 7314 3619 7314 3621 7315 3630 7315 3622 7315 3622 7316 3630 7316 3631 7316 3622 7317 3631 7317 3632 7317 3622 7318 3632 7318 3623 7318 3623 7319 3632 7319 3633 7319 3623 7320 3633 7320 3624 7320 3624 7321 3633 7321 3634 7321 3624 7322 3634 7322 3625 7322 3625 7323 3634 7323 3635 7323 3625 7324 3635 7324 3626 7324 3626 7325 3635 7325 3636 7325 3626 7326 3636 7326 3627 7326 3627 7327 3636 7327 3637 7327 3627 7328 3637 7328 3628 7328 3628 7329 3637 7329 3638 7329 3628 7330 3638 7330 3629 7330 3629 7331 3638 7331 3639 7331 3629 7332 3639 7332 3619 7332 3619 7333 3639 7333 3640 7333 3619 7334 3640 7334 3620 7334 3620 7335 3640 7335 3641 7335 3620 7336 3641 7336 3621 7336 3621 7337 3641 7337 3630 7337 3640 7338 3642 7338 3641 7338 3641 7339 3642 7339 3643 7339 3641 7340 3643 7340 3630 7340 3630 7341 3643 7341 3631 7341 3631 7342 3643 7342 3644 7342 3631 7343 3644 7343 3632 7343 3632 7344 3644 7344 3645 7344 3632 7345 3645 7345 3633 7345 3633 7346 3645 7346 3646 7346 3633 7347 3646 7347 3647 7347 3633 7348 3647 7348 3634 7348 3634 7349 3647 7349 3648 7349 3634 7350 3648 7350 3635 7350 3635 7351 3648 7351 3649 7351 3635 7352 3649 7352 3636 7352 3636 7353 3649 7353 3650 7353 3636 7354 3650 7354 3637 7354 3637 7355 3650 7355 3651 7355 3637 7356 3651 7356 3638 7356 3638 7357 3651 7357 3639 7357 3639 7358 3651 7358 3652 7358 3639 7359 3652 7359 3653 7359 3639 7360 3653 7360 3640 7360 3640 7361 3653 7361 3642 7361 3665 7362 3654 7362 3649 7362 3649 7363 3654 7363 3650 7363 3650 7364 3654 7364 3651 7364 3651 7365 3654 7365 3655 7365 3651 7366 3655 7366 3656 7366 3651 7367 3656 7367 3652 7367 3652 7368 3656 7368 3657 7368 3652 7369 3657 7369 3653 7369 3653 7370 3657 7370 3642 7370 3642 7371 3657 7371 3658 7371 3642 7372 3658 7372 3659 7372 3642 7373 3659 7373 3643 7373 3643 7374 3659 7374 3660 7374 3643 7375 3660 7375 3644 7375 3644 7376 3660 7376 3661 7376 3644 7377 3661 7377 3662 7377 3644 7378 3662 7378 3645 7378 3645 7379 3662 7379 3663 7379 3645 7380 3663 7380 3646 7380 3646 7381 3663 7381 3647 7381 3647 7382 3663 7382 3664 7382 3647 7383 3664 7383 3648 7383 3648 7384 3664 7384 3665 7384 3648 7385 3665 7385 3649 7385 3654 7386 3665 7386 3660 7386 3660 7387 3659 7387 3654 7387 3654 7388 3659 7388 3658 7388 3654 7389 3658 7389 3657 7389 3660 7390 3665 7390 3664 7390 3662 7391 3661 7391 3663 7391 3663 7392 3661 7392 3660 7392 3654 7393 3657 7393 3656 7393 3660 7394 3664 7394 3663 7394 3654 7395 3656 7395 3655 7395</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Link3" name="Link3" type="NODE"> + <matrix sid="transform">0.001 0 0 -0.0149 0 0.001 0 -0.0719 0 0 0.001 -0.019 0 0 0 1</matrix> + <instance_geometry url="#Link3-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="Material_001-material" target="#Material_001-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/arm/link3.stl b/kinton_description/meshes/arm/link3.stl new file mode 100644 index 0000000000000000000000000000000000000000..3c49a4ca0c3e3d0008fa4e5136107f468e1f0a67 Binary files /dev/null and b/kinton_description/meshes/arm/link3.stl differ diff --git a/kinton_description/meshes/arm/link4.dae b/kinton_description/meshes/arm/link4.dae new file mode 100644 index 0000000000000000000000000000000000000000..b2024ed32850b7f34ff4b5019f0b275eef39ea13 --- /dev/null +++ b/kinton_description/meshes/arm/link4.dae @@ -0,0 +1,199 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2015-07-29T19:30:12</created> + <modified>2015-07-29T19:30:12</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera_003-camera" name="Camera.005"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp_003-light" name="Lamp.005"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>9.99987e-4</adapt_thresh> + <area_shape>1</area_shape> + <area_size>0.1</area_size> + <area_sizey>0.1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <shadspotsize>45</shadspotsize> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_images/> + <library_effects> + <effect id="Material_002_001-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.03699346 0.03699346 0.03699346 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="Material_002_001-material" name="Material_002_001"> + <instance_effect url="#Material_002_001-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Link4-mesh" name="Link4"> + <mesh> + <source id="Link4-mesh-positions"> + <float_array id="Link4-mesh-positions-array" count="10998">18.98499 31.48527 11.74262 18.44672 31.43685 11.74262 18.98644 31.49595 12.29262 18.45 31.50078 12.29262 18.45 31.50078 24.69262 18.43377 31.41105 25.24262 18.97756 31.49279 24.69261 18.9908 31.49131 25.24262 11.55387 31.41926 11.74262 11.01356 31.49596 11.74262 11.55 31.50078 12.29262 10.98868 31.41356 12.29262 26.98095 29.92629 9.492624 26.91268 29.97578 11.74262 26.63668 30.40078 11.74262 26.63668 30.40078 15.49262 27 29.84132 15.49262 23.55 30.46745 11.74262 20.13377 30.04785 11.74262 18.8764 30.83289 11.74262 20.18025 30.5896 11.74262 20.15875 30.58331 12.29262 20.39227 30.02053 25.24262 26.91268 29.97578 25.24262 23.55 30.45078 25.24262 26.63668 30.40078 25.24262 19.34662 30.45593 25.24263 20.12445 30.60121 25.24262 26.98799 29.92118 27.49262 27 29.84132 21.49262 26.85821 30.37008 21.49262 22.25149 35.97222 9.489992 22.18439 35.97204 6.665726 7.562274 35.96385 9.492029 3.019055 29.92628 27.49262 3.087318 29.97578 25.24262 3.363317 30.40078 25.24262 3.363317 30.40078 21.49262 3 29.84132 21.49262 11.12366 30.83292 25.24262 11.55246 31.4221 25.24262 11.02245 31.49281 25.24262 6.449998 30.45078 25.24262 9.866227 30.04786 25.24262 9.785202 30.57299 25.24262 9.841233 30.58331 11.74262 9.636734 30.5558 12.29262 9.84195 30.05548 11.74262 3.087318 29.97578 11.74262 6.449998 30.43411 11.74262 3.363317 30.40078 11.74262 11.05753 30.77008 11.74262 3.012011 29.92118 9.492624 3 29.84132 15.49262 3.141792 30.37009 15.49262 23.55 30.50078 24.69262 20.2148 30.57299 24.69262 11.6113 31.35427 9.492625 11.04939 31.40077 9.492624 4.5 30.40078 9.492624 4.5 29.97578 9.492624 9.468079 30.43162 9.492623 9.866288 30.04788 9.492626 10.44885 30.81917 9.492624 6.449999 30.50078 24.69262 11.05753 30.77002 27.49259 11.05854 31.39135 27.49262 11.56722 31.40077 27.49262 4.5 29.97578 27.49262 4.5 30.40078 27.49262 9.841965 30.05548 27.49262 9.856507 30.48299 27.49262 25.5 12.00078 27.49262 25.48002 32.13657 30.34083 25.5 23.70078 27.49262 25.5 23.70078 21.49262 25.5 24.00078 21.49262 25.5 24.00078 27.49262 25.5 29.97578 27.49262 25.5 30.40078 27.49262 25.5 32.15111 27.49262 25.5 12.00078 9.492624 25.5 5.500775 9.492624 25.5 22.00078 21.49262 25.5 12.10078 21.49262 25.5 12.00078 15.49262 25.5 32.15111 9.492624 25.5 30.40078 9.492624 25.5 29.97578 9.492624 25.5 24.00078 9.492624 25.5 24.00078 15.49262 25.5 22.00078 15.49262 25.5 9.400303 20.50947 25.5 10.54405 19.79331 25.5 12.30078 27.49262 25.5 5.500775 15.49262 25.5 5.500775 21.49262 25.5 5.500775 27.49262 25.5 10.92801 19.05106 25.5 7.684387 16.94099 25.5 9.640503 16.59084 25.5 10.97891 18.01577 25.5 8.786538 16.48579 25.5 10.36571 17.00592 25.5 7.127861 17.77277 25.5 7.902618 20.20566 25.5 7.223 19.42299 25.5 6.986648 18.62149 4.5 32.15111 9.492624 4.517052 32.14197 6.662336 4.5 12.30078 21.49262 4.5 22.00078 21.49262 4.5 22.00078 15.49262 4.5 32.15111 27.49262 4.5 24.00078 27.49262 4.5 7.019165 18.87542 4.5 5.500775 21.49262 4.5 12.00078 15.49262 4.5 12.30078 27.49262 4.5 12.00078 9.492624 4.5 5.500775 9.492624 4.5 5.500775 15.49262 4.510668 3.856644 30.29801 4.5 24.00078 21.49262 4.5 23.70078 21.49262 4.5 23.70078 27.49262 4.5 24.00078 15.49262 4.5 24.00078 9.492624 4.5 12.00078 27.49262 4.5 5.500775 27.49262 4.5 7.045917 18.0403 4.5 7.404236 17.25798 4.5 10.03598 16.74083 4.5 10.82198 17.62283 4.5 8.048829 16.72635 4.5 11.0149 18.62151 4.5 12.00078 21.49262 4.5 10.69629 19.5874 4.5 7.557548 19.92703 4.5 8.872765 16.47844 4.5 9.793641 20.36659 4.5 8.617112 20.47407 9.596131 35.47342 30.49262 16.72632 34.86871 30.49262 19.9104 35.29906 30.49262 6.471644 33.27794 30.49263 4.727554 32.09275 30.48883 15.56537 35.44437 30.49264 7.20697 34.80479 30.49261 8.301941 35.40979 30.49262 21.1443 35.50474 30.49262 14.52151 35.47779 30.49262 22.18378 35.22861 30.49261 23.46534 32.53953 30.49262 23.45447 33.584 30.49263 22.97593 34.546 30.49666 9.799729 16.25909 30.49265 19.63159 30.88135 30.49264 8.075483 14.59193 30.49262 18.45404 17.23453 30.49264 20.83891 30.48312 30.49263 15.04621 30.4577 30.49262 13.53918 35.03961 30.49262 23.86794 8.246005 30.49262 23.37293 5.89917 30.49262 25.30634 3.910667 30.48269 7.837097 30.77853 30.49262 6.858734 31.62805 30.49262 4.686272 3.909325 30.48141 11.01714 34.55018 30.49262 12.82444 34.27807 30.49263 18.82445 34.27807 30.49263 17.51661 33.36964 30.49262 16.87617 0.3007753 30.49262 18.4812 0.7960205 30.49262 22.86002 13.237 30.49262 11.51772 33.16078 30.49262 12.47777 33.05487 30.49262 7.527557 4.11322 30.49262 6.326151 6.88179 30.49262 22.93958 31.35535 30.49263 23.80811 10.44188 30.49251 12.51485 17.57688 30.49262 20.99982 15.61353 30.49262 16.28256 30.84537 30.49261 6.920236 12.80119 30.49266 13.6315 30.88141 30.49262 10.28061 30.80318 30.49261 20.79709 2.209656 30.4926 22.37374 4.017 30.49262 15.51378 17.91491 30.49262 18.50441 33.25126 30.49262 8.838906 30.48312 30.49262 6.115704 9.89243 30.49262 21.89987 30.65965 30.49263 18.65753 32.00967 30.49262 17.18972 31.70675 30.4926 12.7717 31.8179 30.49261 11.27605 31.91258 30.49262 13.12423 0.3006592 30.49259 10.85985 1.089729 30.49264 9.119997 2.319792 30.49262 7.708405 0.2325592 30.48618 19.20004 8.051804 6.492623 23.02268 8.779019 6.492622 18.99373 9.031117 6.492622 19.17918 9.871384 6.492619 22.71301 10.09892 6.492619 19.97552 10.75886 6.492621 20.9451 11.00652 6.492622 22.43442 7.557556 6.492622 20.19567 7.131699 6.492621 21.79248 10.85692 6.492621 21.38278 7.01916 6.492621 14.78662 5.00771 6.492622 14.36779 1.084105 6.49262 15.38279 1.019163 6.492621 16.91694 3.632172 6.492621 16.98145 2.617165 6.492622 16.4344 1.557533 6.492623 13.97392 4.725079 6.492621 13.02771 3.369705 6.492622 13.6517 1.51474 6.492622 13.35246 4.166527 6.492617 15.61647 4.910217 6.492621 16.36556 4.486877 6.492623 13.06553 2.36969 6.492621 7.386291 7.761276 6.492623 10.3656 10.48686 6.492621 10.84065 9.79953 6.492622 6.985817 8.872767 6.492621 10.16989 7.335914 6.492622 8.367791 7.08411 6.492621 10.81568 8.146744 6.49263 9.224747 7.006901 6.492622 7.118437 9.697743 6.492622 7.693151 10.56045 6.492621 8.786601 11.00771 6.492622 9.616486 10.91022 6.492622 11.01778 8.957509 6.492621 15.87166 13.16213 6.492622 16.78264 15.94708 6.49262 14.13018 16.82197 6.492619 14.52312 13.02264 6.492621 17.01778 14.9575 6.492622 16.74044 13.9789 6.492623 15.30739 17.01223 6.492621 16.21735 16.5958 6.492621 12.98581 14.87278 6.492621 13.24819 16.03594 6.492621 13.38626 13.76132 6.49262 22.99607 8.702424 4.292622 22.67922 7.902405 4.292623 22.09481 7.305279 4.292622 21.28492 7.014605 4.292623 20.28737 7.094841 4.292622 19.35246 7.835052 4.292627 18.99315 8.786614 4.292623 19.20002 9.949723 4.292622 19.92223 10.69325 4.292623 20.86431 11.03105 4.292622 22.16991 10.66562 4.292623 22.88812 9.713776 4.29262 17.03106 2.87752 4.292622 16.59711 1.766861 4.292622 15.64291 1.070209 4.292622 14.45052 1.058765 4.292622 13.57317 1.573349 4.292625 13.11842 2.303864 4.292623 12.98581 3.128775 4.292622 13.38628 4.240257 4.292623 14.36776 4.917439 4.292621 15.3828 4.982386 4.292623 16.16861 4.631866 4.292617 16.74045 4.022583 4.292623 10.87397 8.207898 4.292623 10.21742 7.405805 4.292619 9.4674 7.037396 4.292623 8.287377 7.094841 4.292621 7.35247 7.835007 4.292622 6.965798 8.951369 4.292623 7.304016 10.09483 4.292624 8.195694 10.86987 4.292622 9.382843 10.98237 4.292621 10.43444 10.44395 4.292621 10.98145 9.3844 4.292621 16.99647 15.20117 4.292622 16.91694 14.3694 4.292622 16.46944 13.63445 4.292617 15.64291 13.07021 4.292623 14.28739 13.09484 4.292621 13.24818 13.96559 4.292621 12.9867 15.29587 4.292623 13.51333 16.36573 4.292624 14.52312 16.97891 4.292623 15.87166 16.83942 4.292621 16.74043 16.02264 4.292621 24.8 9.050177 22.45843 24.8 7.978943 26.23309 24.8 9.124054 26.52369 24.8 7.162149 25.36433 24.8 10.16649 22.84506 24.8 10.90672 23.78002 24.8 10.93134 25.13552 24.8 10.23474 26.08972 24.8 7.02264 24.01576 24.8 7.761291 22.87888 24.8 8.051819 10.69265 24.8 7.852219 14.13788 24.8 9.214985 10.48578 24.8 10.16648 10.84506 24.8 8.779019 14.5153 24.8 10.96416 12.96001 24.8 10.25079 14.12503 24.8 10.90672 11.78001 24.8 7.162144 13.36432 24.8 7.004829 12.19342 24.8 7.308289 11.41492 18.82912 10.2569 4.292621 19.54368 11.0608 4.292623 20.73328 11.50945 4.292622 22.20118 11.2424 4.292622 23.22833 10.18365 4.292623 23.52836 8.72361 4.292621 22.79302 7.196762 4.29262 21.26006 6.47096 4.292623 19.81619 6.772957 4.292623 18.88004 7.633179 4.292623 18.45726 9.062541 4.292623 16.36853 5.120148 4.292622 17.34247 3.991852 4.292623 17.47533 2.527542 4.292621 17.05658 1.565094 4.29262 16.27638 0.8246765 4.292623 15.28092 0.5084311 4.292621 13.99462 0.6644077 4.292623 12.88005 1.633207 4.292624 12.52462 2.576337 4.292621 12.62307 3.906082 4.292621 13.5437 5.06081 4.292624 14.95378 5.543856 4.292621 6.504263 9.491377 4.292623 7.366443 10.95036 4.292623 8.4709 11.45592 4.292622 9.803643 11.41398 4.292622 11.14127 10.3735 4.292622 11.52223 8.946688 4.292622 11.26958 7.933228 4.292621 10.62578 7.07168 4.292624 9.261711 6.470774 4.292622 8.026061 6.692163 4.292624 7.141632 7.294601 4.292622 6.62278 8.201096 4.292625 17.14127 16.37349 4.292622 17.50246 15.2138 4.292622 17.29158 13.89711 4.292623 16.27639 12.82468 4.292627 15.28094 12.50844 4.292621 14.2097 12.60494 4.292623 12.98284 13.45143 4.292623 12.45726 15.06253 4.292622 13.0149 16.60365 4.292623 14.31317 17.4283 4.292623 15.80366 17.41399 4.292621 12.85237 7.189086 3.983241 17.59194 7.909645 3.991733 16.68781 9.012175 3.648001 17.59247 10.09036 3.992238 17.81988 9.001044 3.992952 17.03305 10.95252 3.983537 15.83398 11.71156 3.98728 15.00711 10.3095 3.555026 13.15234 11.11009 3.983938 14.22821 11.71178 3.990588 13.31879 8.987289 3.644188 12.17153 9.171231 3.994139 12.55685 10.40082 3.993494 12.35689 8.067059 3.990644 14.81084 6.195604 3.993011 14.41102 7.279389 3.699854 13.72345 6.488767 3.990835 16.11395 6.393009 3.994101 15.58478 7.818085 3.576845 17.06612 7.094201 3.984292 14.40747 9.008075 3.49367 18.9209 4.010506 6.492621 19.22942 5.590767 6.492619 19.90572 4.28611 6.492624 19.46201 3.974333 6.492622 18.45037 4.501705 6.492622 19.84377 5.306885 6.492622 20.05506 4.807449 6.492621 18.57336 5.236069 6.492622 11.051 3.965977 6.492622 10.88503 5.581026 6.492622 10.25145 4.109737 6.492622 9.924919 4.780264 6.492622 11.44256 5.197421 6.49262 11.56983 4.620679 6.492622 10.23461 5.381995 6.492622 19.89559 13.74342 6.492619 19.81641 12.66612 6.492622 19.3656 14.04799 6.492622 18.63443 12.68983 6.492619 19.25902 12.42099 6.492621 18.42896 13.26315 6.492621 20.05171 13.15472 6.492621 18.70927 13.88292 6.492623 11.48482 13.62653 6.492622 10.95127 14.04264 6.492622 10.06437 12.80054 6.492622 11.52342 12.94789 6.492621 11.10762 12.5094 6.492621 10.56607 12.45366 6.492621 9.967082 13.47106 6.492622 10.34758 13.94665 6.492621 5.199998 9.95279 22.72633 5.199999 10.98238 24.87548 5.199998 8.536011 26.47363 5.199998 9.128769 22.47844 5.199998 9.713746 26.38075 5.199999 7.965561 22.74085 5.199999 10.54404 25.79324 5.199999 7.179565 23.62288 5.199999 10.59737 23.25804 5.199999 6.989326 24.80001 5.199999 10.95563 24.0403 5.199998 7.514709 25.85823 5.199999 7.902637 14.20566 5.199999 7.684448 10.94095 5.199999 10.66563 13.66254 5.199999 11.03105 12.35693 5.199998 10.59736 11.25802 5.199998 9.952736 10.72631 5.199999 8.95138 10.45843 5.199999 7.070206 13.13552 5.199998 7.058767 11.94313 5.199998 8.860886 14.49424 5.199998 9.713822 14.38074 26.2 9.384507 26.47407 26.2 8.369431 26.40958 26.2 7.278334 25.61533 26.2 7.00182 24.11237 26.2 7.684463 22.94098 26.2 9.122356 22.44019 26.2 10.49516 23.1116 26.2 11.05653 24.52699 26.2 10.44392 25.92708 26.2 8.207901 14.3666 26.2 7.305273 13.58742 26.2 7.014606 12.77755 26.2 7.058771 11.94312 26.2 7.573379 11.06581 26.2 8.303803 10.61108 26.2 9.295857 10.47933 26.2 10.36568 11.00589 26.2 10.85105 11.7164 26.2 11.01857 12.53503 26.2 10.66563 13.66252 26.2 9.561173 14.44873 21.01235 6.449021 3.492622 19.5437 6.940735 3.492618 18.8291 7.74469 3.492622 18.49145 8.732964 3.492622 18.62279 9.800507 3.492622 19.14164 10.70695 3.492624 20.40393 11.47345 3.492622 21.8985 11.35307 3.492623 22.78436 10.76343 3.492619 23.36013 9.891968 3.492622 23.49509 8.627839 3.492622 23.09894 7.627808 3.492617 22.36852 6.881405 3.492622 17.25276 1.854202 3.492621 16.19993 0.7580986 3.492621 14.93145 0.4935862 3.492622 13.9128 0.7242622 3.492621 12.87476 1.619964 3.492622 12.49136 2.787258 3.492622 12.62279 3.800476 3.492622 13.27373 4.868755 3.492622 14.43457 5.444335 3.492622 15.47849 5.477787 3.492621 16.62576 4.929886 3.492621 17.26955 4.06839 3.492622 17.52223 3.054867 3.492622 7.737424 6.831102 3.492617 6.810268 7.706764 3.492621 6.492162 8.962856 3.492622 6.67939 9.990387 3.49262 7.612154 11.13152 3.492622 9.261691 11.53078 3.492622 10.62579 10.92986 3.49262 11.36013 9.891983 3.492621 11.49509 8.627835 3.492622 10.87847 7.285917 3.492622 9.7706 6.613964 3.492622 8.733294 6.492106 3.492622 12.77867 16.17002 3.492624 13.6142 17.13361 3.492623 15.05296 17.52303 3.492622 16.46236 17.08186 3.492623 17.35263 15.90323 3.492621 17.50202 14.82586 3.492622 17.14127 13.62806 3.492622 15.99062 12.68059 3.49262 14.52467 12.50208 3.492621 13.06046 13.3553 3.492622 12.45725 14.939 3.492622 12.69444 10.68239 3.492622 13.27858 6.763893 3.492622 17.65693 8.040973 3.492622 17.03077 7.054418 3.492622 16.12164 6.411093 3.49262 14.59286 6.194846 3.492621 12.56863 7.593882 3.492622 12.14788 8.872307 3.492622 14.12144 11.6792 3.492621 15.5209 11.77444 3.492622 16.87517 11.1192 3.492622 17.72488 9.789613 3.492622 19.94472 4.310322 3.492622 19.36559 3.953556 3.492621 18.83285 4.054893 3.492622 18.45236 4.530495 3.492622 18.52267 5.137741 3.492622 18.9209 5.505767 3.492622 19.59765 5.511406 3.492622 20.02509 4.982269 3.492622 10.95765 3.93739 3.492621 10.07049 4.266254 3.492622 9.999484 5.077488 3.492621 10.56035 5.567233 3.492622 11.28463 5.389278 3.492623 11.59244 4.647443 3.492622 18.95449 12.48339 3.492621 18.43114 13.00847 3.492622 18.72205 13.9088 3.492622 19.66594 13.97455 3.492622 20.07888 13.12326 3.492622 19.57175 12.4924 3.492622 11.58752 13.20105 3.492622 11.25708 12.60096 3.492622 10.79192 12.43096 3.492622 10.27009 12.58458 3.492621 9.980648 13.02332 3.492622 9.999485 13.56278 3.492621 10.43565 13.99106 3.492622 11.18066 13.97455 3.492622 3.8 8.617066 26.47406 3.8 7.557556 25.92703 3.8 6.976775 24.702 3.8 7.294502 23.38402 3.8 8.209046 22.63617 3.8 9.031117 22.48636 3.8 10.03599 22.74082 3.8 10.90672 23.78002 3.8 10.98694 24.77762 3.8 10.69629 25.58734 3.8 9.79361 26.3666 3.799999 8.957508 14.5104 3.8 8.146759 14.3083 3.8 7.335896 13.66249 3.8 6.982973 12.53503 3.8 7.294495 11.384 3.8 8.369652 10.55818 3.8 9.369721 10.52033 3.8 10.31711 10.94095 3.8 10.99972 12.11233 3.8 10.85693 13.28509 3.8 10.09891 14.20565 26.2 6.470774 24.75433 26.2 6.86792 23.10687 26.20001 8.011139 22.17201 26.2 9.038712 21.98479 26.2 10.29477 22.30288 26.2 11.27727 23.40538 26.2 11.50796 24.42404 26.2 11.32096 25.48328 26.2 10.3735 26.6339 26.2 8.723572 27.02097 26.2 7.196739 26.28563 26.2 6.702486 13.58224 26.2 6.505847 12.11862 26.2 7.005066 10.94933 26.2 7.810822 10.28476 26.2 9.062535 9.949872 26.2 10.64624 10.55307 26.2 11.42829 11.8058 26.2 11.48348 12.84879 26.2 11.00841 14.05429 26.2 9.581734 14.96889 26.2 7.897163 14.78423 17.94458 11.85611 3.492622 12.14467 12.1641 3.492622 7.029304 12.60244 3.492526 10.92676 16.69788 3.492541 13.16712 17.50549 3.492616 22.67473 4.779802 3.492568 17.54759 0.6821339 3.492624 6.593668 6.642211 3.492554 6.300525 9.5914 3.492461 7.882675 3.982777 3.492474 12.61475 0.6253629 3.492563 9.941368 1.884822 3.492437 15.37055 0.2778726 3.492395 21.2811 2.980961 3.49264 19.36181 1.441684 3.492355 17.94458 6.17403 3.492622 23.55372 10.74318 3.492506 23.62826 7.728049 3.491641 20.86491 15.46477 3.49248 22.66047 13.20211 3.492561 18.91708 16.76917 3.492616 16.69103 17.55474 3.492458 14.63076 17.69294 3.492622 8.872291 15.2154 3.492496 10.78266 32.0545 7.292621 10.46234 30.91967 7.292623 10.09479 31.30527 7.292625 8.963058 30.96631 7.292622 9.2809 30.50843 7.292623 8.209656 30.60496 7.292622 7.834869 31.35275 7.292621 7.314636 31.14331 7.292628 7.098442 32.27653 7.292623 6.67939 32.01114 7.292624 6.491446 33.26857 7.292623 7.036424 33.46735 7.292623 6.829147 34.25702 7.292628 7.618942 34.49512 7.292619 7.543701 35.06079 7.292622 8.700776 34.99673 7.292624 8.733269 35.50943 7.292623 9.558472 34.92801 7.292619 9.990693 35.32094 7.292621 10.30063 34.54401 7.292625 10.83673 34.70874 7.292642 10.81564 33.8548 7.29263 11.47627 33.5817 7.292623 11.01778 33.04406 7.292623 11.36014 32.10956 7.292625 16.81564 33.85474 7.292626 17.2283 34.18368 7.292627 17.03106 32.87752 7.292623 17.52223 32.94668 7.292623 17.26953 31.93311 7.292621 16.5028 31.62891 7.292623 16.46234 30.91969 7.292624 15.3074 30.98933 7.292623 14.83038 30.46294 7.292623 14.28021 31.12787 7.292619 13.45673 31.00501 7.292622 13.44836 31.68445 7.292621 12.6794 32.01117 7.292624 12.9658 32.95138 7.292623 12.50427 33.49137 7.292623 13.4795 34.38474 7.292623 13.36645 34.95036 7.292629 14.70073 34.99671 7.292623 14.50864 35.4603 7.292623 15.58426 35.45499 7.292623 16.03258 34.77871 7.292623 16.52173 34.99451 7.292628 20.96307 30.96632 7.292623 20.62596 30.50585 7.292623 19.69321 31.4411 7.292621 19.45667 31.00507 7.292622 18.67938 32.01117 7.292622 19.0034 32.60833 7.292623 18.50427 33.49139 7.292623 19.14355 33.79255 7.292627 19.21649 34.78505 7.292617 19.6517 34.48678 7.292623 20.36789 34.91749 7.292625 20.31316 35.42827 7.292625 21.38284 34.98237 7.292624 21.80365 35.41399 7.292623 22.3006 34.54401 7.292623 22.83679 34.70862 7.292613 22.95611 33.56116 7.292623 23.47627 33.58169 7.292623 22.94917 32.52455 7.292623 23.29159 31.89715 7.292623 22.39763 31.49283 7.292623 22.08965 30.7025 7.292623 17.02269 32.77907 8.692624 16.54273 31.6995 8.692625 15.54841 31.04126 8.692624 14.19566 31.13169 8.692627 13.20001 32.05186 8.692624 12.99372 33.03112 8.692624 13.17915 33.87129 8.692618 13.8349 34.6488 8.692626 14.96303 35.03525 8.692624 16.24933 34.60687 8.692625 16.84064 33.79956 8.692621 11.03106 33.12406 8.692623 10.81564 32.14669 8.692621 10.16989 31.33592 8.692624 9.04245 30.98298 8.692625 8.223816 31.15045 8.692628 7.386291 31.76128 8.692625 6.985816 32.87277 8.692624 7.118431 33.69774 8.692614 7.820358 34.68473 8.692621 9.128899 35.0149 8.692624 10.09485 34.69623 8.692618 10.6792 34.09912 8.692628 22.88811 32.28776 8.692627 22.42745 31.59065 8.692646 21.54839 31.04127 8.692625 20.54773 31.04593 8.692626 19.76544 31.40418 8.692639 19.2338 32.04877 8.692623 18.98581 32.87283 8.692624 19.24821 34.03598 8.692625 20.13019 34.82197 8.692618 20.9451 35.00653 8.692625 21.95996 34.79489 8.692622 22.95559 33.63558 8.692623 15.69806 30.59175 9.492624 16.70703 34.8584 9.492622 12.82912 34.25694 9.492624 14.62598 30.50586 9.492625 13.54367 35.06077 9.492624 14.73329 35.50944 9.492625 15.77057 35.38757 9.492623 17.47626 33.58172 9.492624 13.65295 30.88507 9.492624 12.88004 31.63324 9.492624 12.45726 33.06254 9.492624 17.41738 32.33222 9.492628 16.79303 31.19676 9.492625 3.8 7.292877 26.32938 3.8 8.419808 26.96888 3.799999 9.89209 26.85277 3.8 10.76349 26.27692 3.8 11.45014 25.17817 3.8 11.39661 23.70235 3.8 10.55012 22.47547 3.799999 9.160786 21.9749 3.8 8.129578 22.14063 3.8 7.216492 22.70917 3.8 6.573269 23.80575 3.8 6.587561 25.29623 3.8 11.49571 12.11863 3.8 11.11639 11.14545 3.8 10.36833 10.37263 3.8 9.387223 10.01445 3.8 8.312851 10.06542 3.8 7.395782 10.56525 3.8 6.724251 11.40543 3.8 6.493586 12.42408 3.8 6.680588 13.48322 3.8 7.292831 14.32936 3.8 8.419804 14.96889 3.8 9.669373 14.91 3.8 10.62733 14.42101 3.8 11.3613 13.38287 16.46234 35.08186 27.49262 14.73329 30.4921 27.49262 15.28098 35.49311 27.49262 14.20969 35.39659 27.49262 13.31467 34.85828 27.49262 12.6794 33.9904 27.49262 15.77054 30.61392 27.4926 16.8785 31.28595 27.49262 17.26959 34.0683 27.49263 12.50427 32.51015 27.49262 13.36642 31.05121 27.49263 17.53883 32.84671 27.49262 27 8.211487 26.88879 27 7.143143 26.19962 27 6.546553 25.07687 27 6.573273 23.80576 27 7.216492 22.70911 27 8.510193 21.99688 27 9.800477 22.1154 27 10.70699 22.63428 27 11.39661 23.70235 27 11.47778 24.97115 27 10.92987 26.11841 27 9.701279 26.93776 27 9.27797 15.02097 27 7.62809 14.63392 27 6.680593 13.48323 27 6.492105 12.22591 27 6.940758 11.03632 27 7.744659 10.32172 27 8.939017 9.949872 27 10.55013 10.47548 27 11.31362 11.52234 27 11.53078 12.75432 27 10.80478 14.28564 6.608408 11.96577 3.692616 6.121622 9.817096 3.693676 7.613263 13.99343 3.708682 12.32774 17.50675 3.698947 9.119932 15.6817 3.692589 10.33366 16.57938 3.69259 15.16184 17.92628 3.695915 17.60613 17.51069 3.692574 19.72617 16.56098 3.693657 21.80244 14.78151 3.700947 23.10998 12.66668 3.692574 23.77308 10.5617 3.691122 23.89449 8.441905 3.689848 23.61282 6.758217 3.692575 22.75394 4.599903 3.693642 21.06422 2.449789 3.70085 19.00678 1.05373 3.692669 16.92836 0.3060709 3.683954 14.69767 0.1049249 3.697124 13.21607 0.2887358 3.68771 11.72731 0.7211339 3.69681 10.33372 1.422164 3.692644 8.39921 2.990995 3.692635 6.849355 5.386951 3.698969 6.228026 7.496659 3.692621 11.43648 32.40557 6.492621 10.87849 31.28594 6.492624 9.770569 30.61394 6.492622 8.524659 30.50209 6.492622 7.06041 31.35535 6.492625 6.457249 32.93902 6.492621 6.982834 34.55011 6.492621 8.403885 35.47343 6.492621 9.69806 35.40979 6.492619 10.62573 34.9299 6.492619 11.44515 33.70122 6.492622 17.34246 32.00967 6.492622 16.36852 30.88139 6.492626 15.16109 30.48312 6.492621 13.91275 30.72427 6.492621 12.81026 31.70677 6.492617 12.48339 33.36964 6.492622 13.02501 34.54678 6.49262 13.81625 35.22862 6.492626 14.85571 35.50474 6.492621 15.69806 35.40976 6.492624 16.62567 34.92987 6.492614 17.44514 33.70126 6.492621 23.52223 33.05487 6.492622 23.30082 32.0023 6.492622 22.707 31.14317 6.492621 21.7706 30.61397 6.49262 20.7333 30.49211 6.492621 19.36646 31.05124 6.492625 18.50427 32.51015 6.492622 18.67941 33.99042 6.492619 19.45674 34.9965 6.492625 20.83057 35.53868 6.491474 22.09522 35.2572 6.492622 23.07208 34.47589 6.492623 12.49145 32.73299 8.692622 12.82916 31.74457 8.692621 13.71939 30.80316 8.692622 15.16108 30.48312 8.692622 16.36839 30.88135 8.692617 17.09905 31.62792 8.692618 17.53883 32.84671 8.692624 17.26959 34.06836 8.692629 16.46231 35.08188 8.692627 14.83037 35.5386 8.692624 13.4567 34.99646 8.692625 12.67939 33.99039 8.692624 7.422975 35.8836 6.693169 6.893772 35.58732 6.634464 6.51197 35.22929 6.716881 6.627501 35.12732 6.511025 7.89698 35.97957 6.671989 7.58865 35.76534 6.5002 22.23261 35.80294 6.508675 23.1933 35.53615 6.683136 22.6183 35.86617 6.651283 23.16366 35.31966 6.497334 23.47868 35.22553 6.669922 9.80365 30.58757 8.692623 10.83679 31.29291 8.692612 11.39618 32.21158 8.692627 11.47681 33.48032 8.692625 11.05658 34.43634 8.692623 10.27634 35.17685 8.69262 9.053029 35.52302 8.692625 7.816254 35.22862 8.692632 6.750027 34.18695 8.692624 6.501854 32.5176 8.692638 7.36644 31.05121 8.692625 8.508728 30.54125 8.692623 21.35617 30.51806 8.692624 22.3685 30.88139 8.692624 23.22831 31.81792 8.692627 23.50202 32.82587 8.692625 23.36011 33.892 8.692626 22.62579 34.92987 8.692616 21.26174 35.53076 8.692623 19.81616 35.22858 8.692625 19.02501 34.54675 8.692614 18.55209 33.60437 8.692568 18.52908 32.55855 8.692585 19.06044 31.35535 8.692624 20.31308 30.57328 8.692622 11.00138 31.44179 24.69263 11.55 31.50078 24.69262 3 9.1549 27.03144 3 7.72348 26.66821 3 6.702482 25.58224 3 6.496805 24.34829 3 6.772964 23.30881 3 7.454773 22.51758 3 8.417557 22.03816 3 9.906113 22.1157 3 11.19837 23.212 3 11.51843 24.65367 3 11.22305 25.65558 3 10.54324 26.48898 3 9.581727 14.96889 3 7.897156 14.78423 3 6.824666 13.76898 3 6.462935 12.32301 3 6.885178 11.14545 3 7.814606 10.24263 3 9.491383 9.996886 3 10.95036 10.85907 3 11.50944 12.22591 3 11.32094 13.48328 3 10.70859 14.32947 6.525009 35.23021 30.31799 7.79776 35.98197 30.27396 7.897888 35.83197 30.47533 6.715118 35.19865 30.47845 7.378662 35.86349 30.3103 7.15844 35.58586 30.47537 6.860336 35.5729 30.30672 23.11454 35.6049 30.24201 23.482 35.2256 30.30542 23.15384 35.42468 30.45914 22.2094 35.9774 30.29652 22.38238 35.79119 30.48179 22.71203 35.82694 30.28656 25.30896 32.09169 6.504056 25.48763 32.14501 6.680572 26.57174 5.500775 21.49262 27 6.160235 21.49262 26.57174 5.500775 27.49262 27 6.160235 27.49262 27 12.00078 27.49262 27 12.00078 21.49262 26.57174 5.500775 9.492624 27 6.160235 9.492624 26.57174 5.500775 15.49262 27 6.160235 15.49262 27 12.00078 15.49262 27 12.00078 9.492624 24.7 7.699524 20.03536 24.7 10.00577 16.75595 24.7 9.215012 16.48578 24.7 8.360993 16.59086 24.7 7.506424 17.11156 24.7 7.19566 19.36875 24.7 9.793656 20.3666 24.7 10.64882 17.3276 24.7 8.617112 20.47406 24.7 6.970504 18.35693 24.7 11.00771 18.27923 24.7 10.79493 19.45255 26.2 23.70078 21.49262 26.2 23.70078 27.49262 26.2 22.00078 21.49262 26.2 12.30078 27.49262 26.2 12.30078 21.49262 23.12407 0.4187222 30.31507 22.60263 0.1210384 30.26341 22.09664 0.01093673 30.25777 22.5722 0.3114166 30.49059 23.30544 0.8166275 30.47614 23.46411 0.7526398 30.30547 22.30267 0.1056518 30.41164 23.38535 0.639534 6.707954 23.26632 0.5856133 6.591896 23.16794 0.7204857 6.496222 22.39049 0.2308692 6.505374 22.12103 0.03195714 6.639213 22.7259 0.1724483 6.670567 13.31005 0.2363424 6.494009 16.10705 0.1535348 6.524626 18.31842 0.7425631 6.492622 20.31125 1.819536 6.492619 22.40026 3.999192 6.492624 23.64376 6.750223 6.492618 23.9 9.000777 6.492622 23.64375 11.25135 6.492619 22.40014 14.00246 6.49263 20.88001 15.68176 6.492622 19.02112 16.97637 6.492618 16.13452 17.86038 6.492622 13.86954 17.82869 6.492622 11.66966 17.28864 6.492628 9.098863 15.70573 6.492632 7.20228 13.35683 6.492611 6.196533 10.51028 6.492621 6.196536 7.491256 6.492619 7.202295 4.644731 6.492631 9.098855 2.295817 6.492629 10.99319 1.053736 6.492622 7.277571 0.1868724 30.31474 6.86727 0.4092574 30.25665 6.580616 0.7121887 30.34503 7.740631 0.03737068 30.33196 6.910812 0.5680475 30.47831 7.882041 0.02974081 6.645524 7.63981 0.2521095 6.497309 6.693995 0.7730675 6.513912 6.516312 0.7667275 6.717525 7.421242 0.1232461 6.670181 6.898209 0.4047245 6.650299 4.723289 3.912426 6.497998 4.707903 32.09075 6.500954 6.654747 35.41624 9.492625 23.1482 35.63636 9.492633 20.3923 30.02054 9.492622 19.34662 30.45593 9.492628 18.39835 31.39288 9.492624 6.489514 33.25755 9.492634 6.622787 32.20099 9.492618 7.141602 31.29465 9.492626 8.209717 30.60496 9.492622 9.685517 30.5514 9.492626 10.92847 31.37424 9.49263 11.52835 32.7236 9.492623 11.30083 33.99927 9.492628 10.70694 34.85852 9.492627 9.77063 35.3876 9.492621 8.524674 35.49945 9.492624 7.060471 34.64625 9.492633 18.4829 32.84402 9.49264 18.88004 31.63318 9.492627 19.65283 30.88519 9.492637 20.62598 30.50585 9.492624 22.08965 30.7025 9.492624 23.17554 31.72346 9.492629 23.53883 33.15487 9.492624 22.87845 34.71561 9.492622 21.38425 35.51507 9.492623 19.71941 35.19839 9.492623 18.72393 34.08891 9.492621 9.687546 30.56362 24.69262 17.53883 33.15485 28.29262 17.07211 31.52573 28.29262 15.8903 30.64029 28.29263 14.85571 30.4968 28.29262 13.61423 30.86795 28.29262 12.58192 32.21191 28.29262 12.5728 33.68869 28.29263 13.21652 34.78503 28.29263 14.31311 35.42825 28.29262 15.35617 35.48347 28.29262 16.36847 35.12012 28.29261 17.099 34.37372 28.29261 20.13376 30.04786 27.49262 18.3887 31.35427 27.49262 11.47627 33.58171 28.29262 11.47627 32.41984 27.49262 11.29158 31.89713 28.29262 10.56166 30.99314 27.49263 10.27634 30.82462 28.29262 9.161103 30.48312 27.49262 9.280915 30.50843 28.29262 8.209717 30.60497 28.29261 8.100098 30.65962 27.4926 7.216492 31.21649 27.49262 7.314636 31.14331 28.29268 6.581928 32.21189 28.29262 6.504263 32.51016 27.49262 6.623072 33.90609 28.29262 6.750027 34.18695 27.49263 7.719421 35.19839 28.29262 7.994553 35.3371 27.49263 9.384255 35.51508 28.29262 9.685532 35.45014 27.49261 10.70703 34.85837 28.29262 10.7843 34.76343 27.49258 11.36014 33.89203 27.49263 23.53883 33.15486 28.29262 23.52836 33.27794 27.49262 23.30082 32.00233 27.49261 23.0721 31.52573 28.29262 22.70699 31.14317 27.49262 22.09515 30.74435 28.29262 21.58426 30.54657 27.49262 20.83039 30.46294 28.29262 20.5087 30.54123 27.49263 19.5437 30.94071 27.4926 19.27368 31.13281 28.29262 18.8291 31.74457 27.4926 18.54553 32.41757 28.29261 18.49145 32.73299 27.49262 18.62307 33.90608 28.29261 18.62277 33.80044 27.49264 19.27373 34.86876 27.49261 19.37161 34.90839 28.29268 20.3132 35.4283 28.29262 20.83038 35.53861 27.49262 21.3562 35.48348 28.29262 22.27631 35.17691 27.49263 22.36847 35.12015 28.29261 23.05646 34.43652 27.49258 23.099 34.37378 28.2926 3.428258 5.500775 27.49262 3 6.160235 27.49262 3.428258 5.500775 21.49262 3 6.160235 21.49262 3 12.00078 21.49262 3 12.00078 27.49262 3.428258 5.500775 15.49262 3 6.160235 15.49262 3.428258 5.500775 9.492624 3 6.160235 9.492624 3 12.00078 15.49262 3 12.00078 9.492624 5.299999 7.902618 20.20566 5.299999 9.044041 20.5104 5.299999 9.631867 16.55816 5.299999 8.450501 16.55086 5.299999 7.441116 17.18576 5.299999 6.993837 18.27926 5.299999 10.02258 20.23309 5.299999 10.83942 19.36429 5.299999 10.59737 17.25803 5.299999 10.99672 18.1934 5.299999 7.144635 19.28513 3.8 12.30078 21.49262 3.8 12.30078 27.49262 3.8 22.00078 21.49262 3.8 23.70078 27.49262 3.8 23.70078 21.49262 10.71302 31.9026 28.29262 9.642838 31.0702 28.29262 8.287369 31.09485 28.29262 7.352447 31.83505 28.29264 7.027714 32.63179 28.29262 7.065538 33.63187 28.29263 7.651794 34.48688 28.2926 8.523163 34.97892 28.29262 9.712128 34.88922 28.29261 10.65765 34.18085 28.29263 11.01778 33.04407 28.29262 17.02269 33.2225 28.29262 16.78265 32.05448 28.29261 16.21726 31.4057 28.29266 15.46736 31.03738 28.29263 14.28734 31.09483 28.29262 13.45813 31.71686 28.29256 13.05823 32.45047 28.29262 13.03641 33.46733 28.29262 13.41995 34.23749 28.29263 14.05295 34.78299 28.29263 15.20935 35.02478 28.29262 16.43442 34.444 28.29262 20.96307 30.96632 28.29262 19.97394 31.27643 28.2926 19.35248 31.83505 28.29261 19.0277 32.63187 28.29262 19.03643 33.46733 28.29262 19.61897 34.49515 28.29259 20.70076 34.99672 28.29261 21.8717 34.83942 28.29261 22.64526 34.14941 28.29258 22.98144 33.38444 28.29262 22.87397 32.2079 28.29261 22.0948 31.30527 28.29262 7.676711 35.97107 27.49415 6.740056 35.52019 27.49262 23.23783 35.53563 27.49263 22.32237 35.97102 27.49365 25.30106 3.907417 6.501658 25.4884 3.85871 6.679268 27 24.00078 27.49262 27 24.00078 21.49262 23.55 30.50078 12.29262 27 24.00078 15.49262 27 24.00078 9.492624 4.518375 3.860979 6.653831 20.33331 30.45033 9.492623 18.95012 31.34204 9.492624 3 24.00078 9.492624 3 24.00078 15.49262 6.449999 30.50078 12.29262 3 24.00078 21.49262 3 24.00078 27.49262 20.16521 30.48927 27.49262 18.92799 31.39285 27.49263 10.99607 33.29911 29.69262 10.83327 32.11787 29.69262 10.16864 31.36975 29.69262 9.382798 31.01916 29.69262 8.195679 31.13168 29.69262 7.304016 31.90677 29.69262 6.985817 32.87278 29.69262 7.248203 34.03597 29.69263 8.28743 34.90672 29.69262 9.467408 34.96414 29.69262 10.50279 34.37263 29.69263 16.95611 32.4404 29.69262 16.3006 31.45747 29.69263 15.20941 30.97678 29.69262 14.05295 31.21851 29.69262 13.41998 31.76404 29.69264 13.03642 32.53419 29.69262 13.09845 33.72502 29.69263 13.8349 34.64876 29.69263 14.60696 34.96842 29.69262 15.46741 34.96415 29.69262 16.21741 34.59576 29.69262 16.87396 33.79365 29.69262 22.99647 32.80044 29.69262 22.65769 31.82074 29.69264 21.87637 31.19571 29.69261 21.04244 30.98298 29.69262 19.89139 31.29446 29.69262 19.06554 32.36966 29.69261 19.09847 33.72507 29.69262 19.6973 34.52688 29.69262 20.45059 34.9428 29.69262 21.28507 34.98692 29.69262 22.09479 34.69632 29.69263 22.87398 33.79362 29.69261 11.45446 32.41756 29.69262 6.497978 33.17568 29.69262 6.77169 34.18364 29.69262 7.800079 35.24346 29.69262 9.790345 30.60496 29.69263 9.475342 35.49945 29.69262 10.78351 34.785 29.69261 11.4272 33.68867 29.69262 10.85835 31.29456 29.69263 6.63987 32.1095 29.6926 7.215759 31.2381 29.6927 8.314469 30.55139 29.69262 17.3772 32.20102 29.69262 15.56549 30.55725 29.69263 16.72627 31.13278 29.69262 14.52151 30.52375 29.69263 13.37421 31.07169 29.6926 12.63985 32.10956 29.69263 12.77169 34.18365 29.69264 13.6315 35.12018 29.69261 14.6438 35.48347 29.69261 15.6868 35.42827 29.69262 16.78348 34.78509 29.6926 17.49574 33.49136 29.69262 12.49798 33.17568 29.69262 23.51661 32.6319 29.69262 19.00364 34.54321 29.69266 22.97496 31.45474 29.69261 23.3519 33.87195 29.69264 22.78351 34.78503 29.6926 21.89978 35.34198 29.69261 20.83892 35.51843 29.69262 19.83716 35.22299 29.69256 22.0054 30.66441 29.69262 18.50491 33.37371 29.69262 18.63988 32.10953 29.69262 19.21564 31.23822 29.6926 20.31448 30.55139 29.69261 4.516617 32.13922 30.32975 25.26839 32.08628 30.48791 25.48761 3.856565 30.30467 14.12832 4.839412 32.29264 14.62597 5.495703 32.29262 17.52223 3.054872 32.29262 16.82085 2.130203 32.29262 17.30081 2.002319 32.29261 16.70696 1.143143 32.29258 16.16502 1.352737 32.29262 15.38423 0.4864631 32.29262 15.03696 0.9663098 32.29262 13.71941 0.8031616 32.29263 13.9052 1.30529 32.29262 15.29921 4.996717 32.29262 15.89025 5.361282 32.29261 16.38103 4.495163 32.29264 17.07211 4.47583 32.29263 17.01226 3.293671 32.29262 13.04442 2.365955 32.29262 12.62307 2.095459 32.29262 12.58193 3.789638 32.29261 13.16671 3.883659 32.29261 13.45671 4.996471 32.2926 17.43647 3.595978 33.49263 16.87849 4.715607 33.49261 15.58425 5.455 33.49262 14.10922 5.383194 33.49262 12.9406 4.458 33.49262 12.53465 3.461975 33.49261 12.54553 2.417541 33.49262 13.27372 1.13279 33.49261 14.83038 0.4629364 33.49262 16.46236 0.9196816 33.49262 17.44515 2.300285 33.49261 18.96894 8.877507 32.29262 19.25956 10.0226 32.29263 18.67941 9.990403 32.29262 19.61422 11.13361 32.29264 23.01226 9.293671 32.29262 23.49509 8.627823 32.29262 22.75182 7.965599 32.29261 23.099 7.627899 32.29263 22.36848 6.881374 32.29262 21.71263 7.094844 32.29262 20.95379 6.457693 32.29262 20.53262 7.037392 32.29261 19.54367 6.94075 32.2926 18.49217 8.962857 32.29262 18.72394 7.912598 32.29262 19.49719 7.628906 32.29263 21.63222 10.91745 32.29261 22.27631 11.17693 32.29261 22.48666 10.36569 32.29263 23.29158 10.10445 32.29262 20.28276 10.92765 32.29262 21.05297 11.52303 32.29262 23.52223 8.946681 33.49262 23.14124 10.3735 33.49262 21.99063 11.32094 33.49262 20.73327 11.50944 33.49261 19.54369 11.06081 33.49264 18.8291 10.25693 33.49261 18.49145 9.268574 33.49261 18.67938 8.011124 33.49263 19.31461 7.14328 33.49262 20.20972 6.604946 33.49262 21.68552 6.551397 33.49262 23.0721 7.525711 33.49264 11.01226 9.293625 32.29262 11.53883 8.846676 32.29262 10.7518 7.965584 32.29261 10.99633 7.458317 32.29262 9.869786 7.179568 32.29262 9.990612 6.680593 32.29261 8.87113 6.986648 32.29262 8.931452 6.493585 32.29261 7.912796 6.724266 32.29261 8.069642 7.222992 32.29262 7.286983 7.902611 32.29261 6.810261 7.706772 32.29262 6.982217 9.044045 32.29262 6.48227 9.160783 32.29261 7.342321 10.18083 32.29263 6.792114 10.19071 32.29258 7.456726 10.99648 32.2926 8.123826 10.80588 32.29265 8.434586 11.44434 32.2926 9.135691 11.03105 32.29262 9.478524 11.47778 32.29262 10.38103 10.49516 32.29261 10.46072 11.03961 32.29257 11.17557 10.27808 32.29262 11.52835 8.723603 33.49262 11.22831 10.18365 33.49261 10.52173 10.99451 33.49258 9.384236 11.51508 33.49262 8.100098 11.34189 33.49266 7.060451 10.64624 33.49261 6.534646 9.461998 33.49261 6.545526 8.417572 33.49263 7.141647 7.294556 33.4926 8.209717 6.604938 33.49259 9.68552 6.551396 33.49262 10.9284 7.374168 33.49261 15.97258 16.81223 32.29262 16.46236 17.08185 32.2926 17.44513 15.70129 32.29261 14.61716 16.98238 32.29262 14.83036 17.53861 32.29262 16.8565 15.79245 32.29261 17.00667 14.97454 32.29262 17.39617 14.21151 32.29261 16.56166 12.99313 32.29261 16.16502 13.35273 32.2926 16.82084 14.13022 32.29261 15.2134 12.99384 32.29262 15.16105 12.48311 32.29262 14.04008 13.20663 32.29262 13.71939 12.80318 32.29262 13.3208 13.90247 32.29266 12.82907 13.74466 32.2926 12.96894 14.87748 32.29262 12.49145 14.73299 32.29262 12.75001 16.18692 32.29263 13.43411 16.33317 32.29262 13.65282 17.11638 32.2926 17.34247 15.99185 33.49262 16.3685 17.12018 33.49264 15.16106 17.51843 33.49262 13.91275 17.27727 33.49261 13.07266 16.60577 33.49266 12.5728 15.6887 33.49261 12.54553 14.41756 33.49262 13.14168 13.29459 33.49261 14.20973 12.60493 33.49262 15.68555 12.55141 33.49262 16.78438 13.23819 33.49261 17.44514 14.30029 33.49263 13.12495 0.3005341 33.49262 15.09376 0.08025646 30.49262 15.44696 0.08674931 33.49269 17.60612 0.4908918 33.49262 19.79599 1.469223 33.49261 22.03107 3.497131 33.49257 23.10993 5.334854 33.49262 23.86507 7.826681 33.49258 23.74001 10.7886 33.49261 22.72833 13.47284 33.49261 20.79712 15.79193 33.4926 18.20361 17.33521 33.49261 16.13046 17.82869 33.49262 13.7321 17.83923 33.49262 10.86002 16.91191 33.49259 8.460999 15.08084 33.49258 6.809017 12.55515 33.49261 6.092806 9.623394 33.49261 6.394188 6.620514 33.49264 7.230174 4.66029 33.49262 8.647873 2.725723 33.49259 11.10104 0.9680941 33.49261 17.01226 14.70788 30.49262 16.381 13.50637 30.49262 15.45229 13.04591 30.49262 14.61716 13.01917 30.49261 13.83142 13.36972 30.49259 13.16672 14.11787 30.49262 13 15.00078 30.49262 13.12603 15.79365 30.49262 13.90517 16.69625 30.49261 14.8711 17.0149 30.49262 16.02446 16.75887 30.49262 16.82085 15.87134 30.49263 10.97854 9.45324 30.49263 10.93915 8.462265 30.49261 10.38103 7.506399 30.49263 9.135694 6.970503 30.49262 7.978912 7.259888 30.49263 7.079685 8.266152 30.49262 7.12603 9.793653 30.49263 8.184552 10.88819 30.49263 9.712609 10.90672 30.49263 10.54196 10.2847 30.49258 23.02858 9.052578 30.49262 22.76633 8.048798 30.49268 22.23464 7.404205 30.49261 20.96566 6.945026 30.49262 19.69937 7.457504 30.49262 19.1843 8.146729 30.49259 18.98222 8.957509 30.49262 19.15932 9.79953 30.49259 19.75065 10.60686 30.49262 20.8711 11.0149 30.49262 22.02446 10.75888 30.49261 22.73666 10.00574 30.49258 17.00768 3.206028 30.49262 16.8 2.051865 30.49262 15.80432 1.131691 30.49262 14.6172 1.019164 30.49262 13.83136 1.369705 30.49263 13.16673 2.117859 30.49262 13 3.000775 30.49262 13.12602 3.793632 30.49262 14.04007 4.794922 30.49262 15.38026 4.999727 30.49262 16.55164 4.317154 30.49262 18.52319 9.480332 30.49262 19.20699 10.80481 30.49261 20.3019 11.40979 30.49263 21.59606 11.47345 30.49262 23.01715 10.55009 30.49262 23.53839 8.937213 30.49265 23.05939 7.543564 30.49261 21.89076 6.618354 30.49261 20.64384 6.518066 30.49263 19.63152 6.881393 30.49261 18.65753 8.009705 30.49262 7.72364 11.17689 30.49263 8.947035 11.52303 30.49262 10.38578 11.13361 30.49261 11.37827 9.875618 30.49262 11.48786 8.62697 30.4926 11.17088 7.744614 30.49259 10.28059 6.803168 30.49263 9.068549 6.493587 30.49263 7.80011 6.758083 30.49263 6.657534 8.009697 30.49263 6.523191 9.480343 30.49262 6.943467 10.43652 30.49261 22.85111 9.8956 27.49262 19.08307 9.632187 27.49263 21.1357 6.970503 27.49262 22.38104 7.506409 27.49262 22.96357 8.534195 27.49263 21.86981 10.82198 27.49262 19.8773 10.72322 27.49262 19.07969 8.266137 27.49262 19.9789 7.259903 27.49264 21.05489 11.00652 27.49262 18.98222 9.044057 29.69262 19.15935 8.202057 29.69263 19.63437 7.514664 29.6926 20.69263 6.989325 29.69262 21.86976 7.179552 29.69261 22.75181 7.965607 29.6926 23.01417 9.128823 29.69262 22.61372 10.24026 29.69263 21.63222 10.91743 29.69262 20.77519 10.99464 29.69262 19.83009 10.66562 29.69263 19.18436 9.854889 29.69263 23.18976 10.29475 29.69264 22.08722 11.27727 29.69261 20.83895 11.51843 29.69262 19.43833 11.00841 29.69262 18.60382 9.790009 29.69261 18.5232 8.52121 29.69262 18.94345 7.565002 29.69264 19.7236 6.824676 29.69262 21.16963 6.462937 29.69262 22.72628 7.132797 29.69263 23.51609 8.632654 29.69267 11.03419 9.050181 27.49262 7.083059 9.632166 27.49263 10.16502 10.64882 27.4926 7.634405 10.48687 27.49264 10.73669 10.00577 27.49262 9.213414 11.00771 27.49262 8.383576 10.91024 27.49262 7.043884 8.440392 27.49262 9.135697 6.970505 27.49262 10.23461 7.404195 27.49262 10.7663 8.048798 27.49262 7.830109 7.335907 27.49262 6.998382 8.860871 29.69262 7.217339 8.054505 29.69261 8.040085 7.206623 29.69261 9.054839 6.995024 29.69262 9.869788 7.17957 29.69262 10.64754 7.835037 29.69262 11.00684 8.786568 29.69262 10.90176 9.640625 29.69261 10.38102 10.49516 29.69262 9.135697 11.03105 29.69262 7.830091 10.66562 29.6926 7.111892 9.713772 29.69262 10.92737 10.60577 29.69264 10.08726 11.27727 29.69262 8.838952 11.51843 29.69262 7.438337 11.00842 29.69262 6.699163 9.999188 29.69264 6.47777 8.946684 29.69262 6.82444 7.72348 29.69262 7.910393 6.702476 29.69261 9.596081 6.528107 29.69261 10.85835 7.294586 29.69264 11.4479 8.397183 29.69257 11.44002 9.657325 29.69255 27 30.40078 15.49262 23.55 30.40078 11.29262 27 30.40078 9.492624 18.45 31.40077 11.29262 18.92799 31.39285 11.29262 9.666657 30.45032 11.29262 6.449999 30.40078 11.29262 3 30.40078 9.492624 11.0499 31.34207 11.29262 9.64853 30.45565 25.69262 11.08065 31.35231 25.69262 18.95009 31.34209 25.69263 20.33331 30.45032 25.69262 20.16522 30.48927 11.29262 25.13443 41.57873 0.9053955 26.03455 40.9624 1.507446 25.6964 41.70605 1.055115 25.08131 43.00143 0.6448517 25.47614 42.47308 0.8582764 24.99477 42.47558 0.6810837 25.17786 39.55664 1.823975 25.61792 39.70068 1.705322 25.52426 40.65442 1.242004 26.43311 39.43384 2.238403 26.41205 38.59888 2.461975 26.8059 36.22812 3.781433 26.93147 35.72089 3.984009 27.94423 36.52834 3.348186 27.27875 35.95283 3.474426 27.61088 36.33552 3.306076 26.41284 36.98877 3.540649 27.42682 37.49798 3.116211 26.86086 36.78332 3.351074 26.49359 37.61645 2.980225 27.00906 37.46783 3.02977 26.91422 38.30401 2.770172 29.1526 35.93234 3.854767 29.19804 36.15698 3.664246 28.22463 36.09366 3.6586 28.03284 35.89447 3.838623 27.68988 35.57922 4.417725 28.58064 36.47341 3.493092 29.17558 36.49321 3.516375 29.25673 35.69079 4.359131 29.65263 36.12407 3.965702 29.79284 36.16894 4.186638 29.97722 36.54483 4.299973 29.78951 36.53715 3.878693 29.4901 36.50944 3.629684 4.483566 40.46301 1.315613 5.279587 43.93318 0.5333405 5.543327 43.36703 0.5050783 4.672615 42.62794 0.7519493 5.005829 41.84381 0.8165894 4.104919 41.40933 1.273682 4.356476 41.32129 1.093811 3.556457 39.44696 2.253357 3.630859 38.61426 2.437256 4.395508 39.42334 1.858887 2.654419 36.01906 3.428856 3.028175 36.22058 3.599518 3.074242 35.71188 3.998535 3.320932 36.40716 3.877869 2.538116 37.35547 3.137985 2.324738 36.42742 3.284019 3.873291 37.54272 3.213867 4.76416 39.23047 2.047852 3.002869 38.12524 2.840454 3.100052 37.20117 3.138 3.434051 37.13159 3.303955 1.747665 36.50989 3.444168 0.9441834 36.32907 3.565475 1.8172 36.21149 3.562683 2.053955 35.91791 3.762207 0.9890747 36.06464 3.727478 0.8429566 35.90637 3.89386 0.5326996 35.93921 4.028564 0.05177116 36.56864 4.129906 0.1172163 36.3075 4.202026 0.6063538 36.27493 3.667908 0.2844963 36.04016 4.243042 0.3514404 36.41913 3.7547 0.7621384 36.5762 3.514265 29.14295 36.48669 33.47165 29.96858 36.51273 32.71643 29.75613 36.1382 32.81686 29.53424 36.53683 33.33496 29.25882 36.31232 33.38266 29.13061 36.07992 33.27352 29.82208 36.55846 33.06158 29.17642 35.85791 32.99975 29.62573 36.26169 33.15179 28.55358 36.00794 33.22264 28.32752 36.53229 33.52209 27.14296 35.86484 33.34863 27.87012 35.87755 33.16644 27.41145 36.10354 33.59627 27.69904 36.43636 33.69726 27.16184 36.81152 33.74499 26.92653 35.71382 32.979 26.701 36.43378 33.20846 27.25391 37.59302 33.95117 25.98865 37.71387 33.83533 26.79761 38.5542 34.33154 26.3877 39.5957 34.81787 26.67969 37.47815 33.96924 26.22632 38.00928 34.23035 26.25342 38.94336 34.72363 25.61389 39.28662 35.04834 25.33801 40.55517 35.70489 25.55048 41.14368 35.89136 25.88617 41.43396 35.72461 24.72119 43.82959 36.45056 25.06946 42.82153 36.33743 25.51758 42.24121 36.08783 24.8385 41.77014 36.15576 0.7857361 36.625 33.47225 0.2531128 36.17556 32.90858 0.4909287 35.94183 32.89526 0.8595886 45.9064 33.4707 0.8042288 36.08999 33.26879 0.4461975 36.5611 33.32681 0.09563446 36.43022 32.9013 0.4686356 36.31319 33.2664 0.01479196 36.62274 32.68473 0.9402924 36.3688 33.43997 0.8495979 35.90878 33.09805 2.657989 36.03265 33.54559 1.549103 36.45976 33.4897 2.337547 36.39044 33.69393 2.061279 35.57153 32.51391 1.565506 36.00621 33.25019 3.533813 39.48572 34.7135 3.657471 38.9834 34.70532 3.074245 35.6864 32.9169 2.873888 35.86245 33.35492 2.603516 37.29639 33.86011 3.407525 36.61891 33.25947 3.860802 37.49968 33.73227 3.033691 38.20239 34.1676 4.540162 38.67972 34.53056 4.264404 39.04492 34.9032 3.152435 37.10834 33.81412 3.618957 37.9956 34.24432 4.236786 41.4743 35.85095 3.907471 41.09082 35.39429 4.555176 40.349 35.62488 5.243774 42.75378 36.37094 4.870239 43.06103 36.31723 4.73407 42.38232 36.24036 4.789124 41.70557 36.11029 5.252624 40.74316 35.79742 25.12982 39.44495 35.08032 25.45146 38.65002 34.50134 25.20981 37.75598 33.50622 26.04154 36.60895 32.27612 26.85108 34.87345 30.09192 26.91531 35.44739 32.43359 26.51909 35.79294 31.40369 27.01025 34.13745 31.08405 26.99413 34.6641 31.47853 26.96369 34.40301 27.49282 25.35949 36.06008 29.60657 25.36147 35.96042 27.49404 25.94071 35.75627 27.49565 25.38055 36.62964 31.66357 25.19357 36.28564 30.63538 25.91616 36.0932 30.67847 26.316 35.56382 29.27515 25.34483 37.13702 32.63281 26.60101 35.20123 27.49351 4.688002 35.96152 27.49488 4.049499 35.77826 27.49263 3.960991 35.75631 29.38269 3.564369 35.44334 29.34528 3.341874 35.12194 27.49361 3.015393 34.32165 27.4929 4.61618 37.75586 33.52722 3.00776 34.61116 31.43174 3.188521 35.04751 30.32532 3.068214 35.27161 32.17578 3.575409 35.87863 31.31329 4.923614 39.4837 35.1037 4.08535 36.67697 32.22797 4.834076 36.86429 32.14184 4.498276 36.24475 30.58948 4.641047 36.05209 29.55274 25.53244 35.95965 9.492626 25.38138 36.00893 7.674194 26.05193 35.74045 7.668457 26.58723 35.26389 9.492494 26.71473 35.13003 7.513428 26.9826 34.33382 9.492438 25.52942 37.7793 3.400391 26.99549 34.66388 5.506348 26.93121 35.26501 4.825317 26.71338 35.53931 5.486084 25.50354 38.82324 2.297852 25.51007 37.13647 4.314697 25.37897 36.63037 5.321777 26.20114 36.08331 5.681885 25.50163 36.24475 6.395752 24.87631 40.6477 1.239136 5.171143 40.51343 1.289734 4.768677 38.4873 2.68335 4.581039 37.71387 3.499023 4.049665 36.92895 4.309326 3.175785 35.08328 6.453125 3.051445 35.1344 5.00415 3.544739 35.88269 5.578247 3.00951 34.11129 9.491402 2.998436 34.3728 5.72583 3.143671 34.74499 9.492202 3.293026 35.09057 7.589691 4.512299 36.04698 7.39917 4.458773 35.95352 8.434998 4.515648 36.63135 5.309326 4.619202 36.26922 6.345337 3.568426 35.38972 9.490637 4.790161 37.13721 4.366699 3.8237 35.793 6.768616 4.361465 35.94103 9.492624 24.58488 43.85748 0.5073724 26.02258 46.47888 1.444397 26.34796 46.30406 2.121338 25.86075 72.98036 1.220402 25.90864 47.65008 1.285263 25.64801 73.88135 0.9972229 25.22583 74.76673 0.7025604 24.53764 75.51442 0.499732 4.138833 72.96737 1.219731 5.134857 75.39543 0.5810013 4.547485 74.4442 0.836606 4.06695 47.12376 1.312386 3.758003 46.11345 1.894012 25.86235 72.91782 35.76758 24.27289 43.47494 36.48942 24.45477 75.81893 36.48619 25.26648 74.74762 36.26349 25.65442 73.8479 35.98059 25.93565 47.09369 35.66882 26.3523 45.91748 34.88367 5.427643 43.88019 36.4811 4.139503 72.98667 35.76373 4.072451 47.19018 35.6815 4.404724 74.08118 36.03989 4.820923 74.82556 36.30292 5.485443 75.59777 36.48612 29.98559 41.7082 10.0058 29.46011 42.31375 10.47168 29.50693 42.4137 10.24853 29.04834 42.40631 10.57898 29.86112 42.01651 10.22058 29.85715 41.73797 10.42334 28.73364 41.37805 11.27145 29.13507 41.45618 11.15683 29.51038 41.5758 10.91354 29.0047 41.86413 11.07971 29.18543 42.06836 10.89453 29.53705 42.01282 10.70764 17.26685 42.07727 10.95398 17.24886 41.61185 11.22731 28.85963 36.00052 15.69952 28.89486 36.22589 14.70166 28.78425 36.54101 13.99219 28.79396 37.17889 13.01355 28.90555 38.05566 12.20703 28.78313 39.06659 11.64658 29.00771 40.26044 11.29333 29.51044 35.66109 15.69867 29.48352 36.05224 14.23047 29.489 36.66699 13.16553 29.38943 37.26221 12.56812 29.2804 39.00452 11.4585 29.57806 38.12915 11.6499 29.63965 39.72058 10.90832 29.84809 35.80469 13.68311 29.84261 36.92322 12.10474 29.88762 35.15657 15.14453 29.88565 39.19397 10.6106 29.9832 35.90942 12.63818 29.99217 34.6297 15.60645 29.99159 38.64392 10.32269 17.20575 41.20966 11.31882 16.65588 41.99278 11.18262 16.76453 42.3612 10.68555 29.79901 35.32672 21.36969 29.28886 35.80896 21.29346 28.78632 36.00875 21.27063 16.49921 40.70877 12.14426 16.34996 41.22199 12.37958 15.84649 41.78197 12.52747 15.25512 42.02557 12.52161 15.81787 41.97543 11.8252 16.55042 40.89432 11.92123 15.54663 42.22406 11.32153 16.44092 41.27254 11.94031 16.78076 41.26576 11.54541 16.17002 41.60724 12.00058 16.73853 41.64928 11.39813 28.72076 41.2984 25.70727 28.77382 39.81183 25.58211 28.78428 38.70059 25.15231 28.85807 37.73056 24.52887 28.89496 36.9068 23.62024 28.78305 36.35461 22.62665 29.18391 41.38718 25.84794 29.18702 40.19955 25.78281 29.28032 38.99354 25.52173 29.3778 36.9884 24.13855 29.48972 36.24744 23.13501 29.38947 35.98456 22.33081 29.56128 38.12683 25.31531 29.64606 41.74019 26.23398 29.72168 39.68051 26.16171 29.80951 37.66431 25.40161 29.78003 36.63708 24.40064 29.78717 35.65314 22.77441 29.97969 39.78204 26.81375 29.9851 37.79101 26.07593 29.97817 35.92346 24.33838 29.98011 34.85818 21.91516 29.97255 41.8352 26.95258 14.75076 42.01059 12.68347 14.11428 41.77101 12.38815 13.71772 41.35625 12.22127 13.50514 40.85633 12.11431 15.12927 42.03438 24.28034 15.71878 41.85971 24.55927 16.01151 41.69581 24.78696 16.48006 40.9252 24.81575 28.84917 41.66678 25.79749 29.0842 42.18907 26.14813 29.2182 41.80379 25.95659 29.67105 42.08829 26.48267 29.18558 42.43078 26.50012 29.87308 41.71314 26.59808 29.61676 42.3136 26.69898 29.86043 42.68994 28.26025 13.02234 42.23859 10.81421 13.30929 41.13818 11.6608 14.67614 42.08758 11.9989 13.97217 42.25751 11.09497 14.0899 41.94357 11.82373 13.548 41.5614 11.70642 13.20935 41.61249 11.38721 13.01343 42.46863 10.43774 13.36551 41.92035 11.23981 14.66104 42.00199 24.41492 14.22225 41.8188 24.40671 13.78755 41.46358 24.70379 13.5084 40.82423 24.78398 15.36287 42.06567 24.95007 17.31271 41.24461 25.68764 17.23122 41.73793 25.80849 12.63635 41.25609 11.29193 12.98323 41.21589 11.39451 12.70819 41.78116 11.15585 16.32988 41.39014 24.95026 16.58158 40.91589 25.12914 14.71863 42.10818 25.00562 15.78592 42.27289 25.88721 15.98694 42.08203 25.53394 16.69873 41.7493 25.62592 16.74887 41.26391 25.40961 16.36749 42.01849 25.68457 16.9942 41.30426 25.5818 17.09613 42.09579 26.02835 17.08862 42.41608 26.42517 1.351532 41.35316 11.27789 0.8122559 42.39957 10.55695 13.37201 41.73196 25.57984 13.41246 41.03693 25.17268 13.55265 41.50772 25.26749 14.0531 41.866 25.06479 13.67129 42.12421 25.81397 13.07391 41.19543 25.53488 14.30493 42.20203 25.61377 13.60889 42.35553 26.21387 0.1657257 42.00044 10.29327 0.3998413 42.26578 10.36414 0.3162842 41.80325 10.69775 0.4672546 41.57045 10.8811 1.071411 41.5408 11.21974 0.7889404 41.60208 11.10074 0.9049378 42.05109 10.94543 12.70654 41.24774 25.68504 12.76469 42.02771 25.98866 12.872 41.61752 25.74768 12.98352 42.38463 26.36563 0.04089164 41.74391 10.15974 0.1456756 40.25165 10.50777 1.023537 42.0592 26.0228 1.264221 41.30838 25.70999 1.136642 39.83182 11.38728 1.104935 38.68225 11.82544 1.113693 38.01648 12.24451 0.9929962 37.39294 12.75391 1.10572 36.90686 13.36523 1.136749 36.34515 14.35522 1.213615 36.00876 15.71469 0.5935364 39.72076 11.14145 0.4878235 36.02661 14.23437 0.7113342 35.80901 15.69174 0.5297241 38.19012 11.72119 0.4381714 36.83868 12.78223 0.2010302 35.32677 15.61578 0.2199401 38.79437 11.00769 0.1482238 37.74341 11.45837 0.1565704 36.54034 12.53613 0.1188659 35.61229 13.79559 0.01886558 37.99745 10.67789 0.007296919 34.86933 14.24092 0.5754395 42.37619 26.58936 0.2837982 42.19095 26.68399 0.05057716 41.81424 26.80373 0.2588348 41.75209 26.36697 0.5692139 41.60336 26.01465 0.8282471 41.27331 25.84174 1.121246 41.58121 25.77116 0.6749363 41.99723 26.10387 1.131676 35.99506 21.21756 0.731247 35.85049 21.38428 0.2854004 35.42766 21.35297 0.1153278 35.19416 21.95035 0.007959604 34.92872 22.91898 0.3563233 40.4155 26.19461 0.8683319 42.42633 26.46887 1.216923 36.3477 22.61005 1.206402 37.1788 23.97165 1.244025 38.33711 24.95712 1.104935 39.48163 25.49072 0.9923477 40.26041 25.69186 0.8130608 38.65692 25.28157 0.7196865 36.17206 22.70007 0.5104694 36.66803 23.81836 0.6383991 37.56344 24.69461 0.4388428 38.94961 25.73465 0.3605156 35.8931 22.82202 0.2634776 37.36601 25.01733 0.1562442 38.80775 26.09491 0.1114306 35.94775 23.81226 0.02642583 39.38876 26.66851 0.01919376 36.95166 25.42625 17.29876 36.04019 21.25742 17.25742 36.35998 22.54273 17.16148 36.96478 23.58362 17.1742 37.48724 24.20917 17.18153 38.4373 24.96518 17.24955 39.86606 25.55947 16.8806 39.83377 25.35828 16.67864 39.20398 24.92224 16.52289 38.96069 24.46362 16.84023 38.20563 24.55963 16.68269 37.51227 23.69714 16.50924 37.85974 23.47168 16.81873 36.6344 22.59705 16.51863 36.9237 22.0318 16.77434 36.30453 21.26044 16.52453 36.74585 15.86609 16.87516 36.20647 15.86609 17.27012 36.04904 15.65289 17.26277 39.90845 11.41559 16.89911 39.82239 11.61536 16.61475 39.91333 11.93182 17.16156 38.77734 11.85425 17.1676 38.10693 12.25525 17.26392 37.25024 12.98901 17.23628 36.5769 14.01074 17.1613 36.28992 14.72595 16.9068 37.10205 13.46851 16.66958 37.62463 13.16516 16.72609 36.70636 14.47119 16.68265 38.57776 12.37634 16.51502 37.22504 14.33362 16.51082 38.73511 12.75745 12.85983 40.26007 25.59566 13.32919 39.81555 25.14609 13.48456 36.82263 21.71467 13.48189 37.87558 23.61755 13.45283 39.30701 24.68726 13.37239 36.86741 22.53718 13.23032 38.36066 24.60721 13.21227 36.31064 21.22579 13.15972 36.45917 22.15552 13.17956 37.41778 23.8344 12.8385 36.59265 22.97607 12.83834 38.77771 25.13147 12.75661 36.04725 21.28119 12.76303 36.98791 23.63861 12.76337 39.4862 25.43483 12.68922 36.26193 22.25 12.69233 37.77602 24.51722 13.48079 36.77735 15.69276 13.12188 36.20912 15.8078 12.67266 36.04034 15.69177 13.47657 37.87804 13.29491 12.91829 40.17184 11.41795 13.48302 39.23035 12.40077 13.35332 36.79097 14.5415 13.31965 39.43318 11.93106 13.16083 37.14783 13.47888 12.83843 39.43445 11.58173 12.8387 36.26904 14.79077 12.83903 36.56219 14.06885 13.19844 37.96051 12.65686 12.7729 38.38251 12.04468 12.72138 37.23004 13.0025 18.45 39.01733 11.68762 18.45 40.52414 11.29763 23.55 37.99981 12.29235 18.45 37.99903 12.29252 23.55 39.14691 11.63397 23.55 40.582 11.29675 6.449998 39.01745 11.68765 6.449999 40.52591 11.2973 11.54997 37.99951 12.29239 6.449999 37.99942 12.29251 11.55 39.14691 11.63397 11.55 40.58012 11.29704 11.55 39.01767 25.29771 11.55 40.52408 25.68761 6.450004 37.99981 24.69289 11.55 37.99902 24.69271 6.449999 39.14697 25.35127 6.449999 40.58194 25.6885 23.55 39.01752 25.29764 23.55 40.52589 25.68795 18.45003 37.9995 24.69285 23.55 37.9994 24.69273 18.45 39.14697 25.35127 18.45 40.58009 25.6882 0.01838302 44.49341 5.789307 0.01003432 45.8659 4.58989 0.2838593 44.66296 6.244751 0.7366943 43.66846 7.92334 0.7780762 42.98901 9.138428 0.7392273 44.41479 6.943359 0.7468872 45.31177 6.034424 0.4243622 46.30597 5.042908 0.2898712 43.09314 8.315674 0.02574396 43.00458 7.557129 0.8179932 46.44574 5.126648 0.5722294 46.55437 4.770874 1.008207 46.65781 4.732391 0.1704101 46.21754 4.747803 0.7749443 46.65852 4.368103 0.04146575 45.93163 4.254219 0.2878647 46.37147 4.293594 0.8675804 46.51446 3.942444 0.2120361 45.93801 3.896332 0.5042191 46.43614 4.018799 0.840992 46.15536 3.611206 0.5293884 45.92267 3.62323 0.8132305 45.81724 3.511209 0.7595062 35.41382 4.815796 0.8701782 34.61725 5.648437 1.648499 34.84778 5.415039 0.9002228 33.66797 6.195038 0.7588348 33.19635 6.366211 0.7677994 32.54774 6.484474 0.4375153 35.37756 5.114502 0.5352173 34.51294 5.841919 0.4720154 33.7138 6.315765 0.2575379 32.80803 6.771782 0.1910858 34.49512 6.220093 0.1221313 35.66431 5.319031 0.01787757 35.66986 5.741882 0.01543903 33.53996 7.152008 0.6789703 25.56089 6.538006 0.1342487 25.61989 6.977993 0.003669023 24.97286 7.486675 0.003834843 23.29137 8.831238 0.04091173 22.72159 9.964417 0.1173992 24.82941 7.186142 0.1149978 23.51083 8.018616 0.2267818 22.61768 9.071961 0.3195458 24.10275 7.245056 0.3389411 22.25114 10.0437 0.4063377 22.91626 8.245972 0.6615448 24.74347 6.732773 0.6614952 23.17371 7.713257 0.7573261 23.86524 7.118622 0.7577591 22.56613 8.455994 0.7366467 22.20963 9.286988 0.8095715 22.031 10.05511 0.6940045 22.04443 26.91618 0.2657709 22.36408 27.23128 0.01563835 22.78639 27.08237 0.005239963 24.40849 29.34263 0.1335091 22.96892 28.31999 0.1211547 25.48241 29.97635 0.226715 23.60411 29.27087 0.3391571 24.54199 29.98218 0.5171852 22.70653 28.57087 0.6773377 25.61221 30.45143 0.7364693 22.22513 27.74603 0.7357178 23.42857 29.543 0.8324967 22.58255 28.57641 0.8092346 24.49359 30.19789 0.689621 33.25561 30.62555 0.8065071 34.04648 30.95975 0.7853766 34.82042 31.51317 0.9040833 35.33346 32.06821 0.5365296 35.26555 31.80966 0.0100733 35.48766 30.8789 0.153553 35.48499 31.53441 0.4243088 34.15314 30.83582 0.1327991 34.08172 30.44824 0.3426819 32.65379 30.2878 0.02649688 32.85661 29.8051 0.007982254 45.8194 32.65545 0.2982483 45.83907 33.21994 0.6330567 45.96344 33.40033 0.07828807 46.11032 32.36108 0.283659 46.22807 32.02388 0.9029541 46.45129 33.13135 0.7635803 46.58929 32.875 0.6303101 46.26623 33.22229 0.9305287 46.68226 32.52156 0.3561554 46.40751 32.81067 0.1676025 46.11154 32.87439 0.7599945 46.56875 32.0639 0.7463913 46.42966 31.84737 0.4904251 46.54942 32.35016 0.8540192 42.97558 27.7981 0.8264923 45.34582 30.97302 0.5871267 44.38159 30.05029 1.227356 46.33743 31.73792 0.8197479 43.68494 29.06421 0.4015408 45.16998 31.05371 0.102169 44.49457 30.92712 0.00573796 43.34352 30.24709 0.3405228 43.48767 29.16382 0.07461524 42.83063 28.87512 0.3397179 42.85535 28.07617 29.94323 46.08856 32.44365 29.89476 44.94287 31.31885 29.79173 46.11603 32.05298 29.70825 44.65967 30.73071 29.48761 46.27551 31.84674 29.2518 45.31055 30.94983 29.18152 43.06177 27.99732 29.2522 43.68542 29.07764 29.26361 44.41406 30.04126 29.5813 43.16406 28.58814 29.96784 43.6438 30.2085 29.11133 45.86212 33.47615 29.39807 45.85333 33.41012 29.82153 45.8223 33.07635 29.13437 46.51559 33.04816 29.98539 45.84842 32.67883 29.25836 46.64981 32.65027 29.17851 46.66928 32.37637 29.55078 46.01904 33.27313 29.75513 46.32846 32.71496 29.56958 46.30969 33.06012 29.14781 46.44842 31.853 28.66203 46.60365 32.07672 29.6001 46.4451 32.1962 29.18182 46.25439 33.30621 29.44734 35.95445 32.98552 29.23335 35.41444 32.17444 29.21945 34.82516 31.51115 29.18239 34.11084 30.99455 29.21948 33.1991 30.62302 29.38202 32.50992 30.44751 28.99814 32.58288 30.51223 29.45471 33.6991 30.69873 29.67478 35.22552 31.57513 29.58798 34.54614 31.07275 29.86142 34.54175 30.71167 29.80978 32.95911 30.14295 29.92269 35.74585 31.61145 29.9881 33.12793 29.76248 29.99297 35.3374 30.7016 29.70453 25.62048 30.21738 29.16435 25.55432 30.46844 29.98389 25.23004 29.66544 29.99201 23.68854 28.78406 29.99487 22.88004 27.17987 29.83759 22.79379 28.11206 29.86565 22.5137 27.03717 29.76981 24.19739 29.70252 29.73129 23.14795 28.85388 29.61411 24.60651 30.03632 29.62186 22.24455 27.17135 29.31439 23.37122 29.48169 29.24257 24.41925 30.15915 29.26334 22.7675 28.81049 29.2644 22.30491 27.99656 29.19046 22.03101 26.93016 29.98206 22.75899 10.17505 29.72497 22.31514 10.13005 29.302 22.05081 9.998169 29.99175 23.04349 9.154908 29.98567 24.68466 7.468842 29.81911 23.51955 7.840485 29.77445 24.47861 7.150024 29.786 25.65306 6.865723 29.67824 22.54509 9.001576 29.59274 22.91089 8.254273 29.29703 25.57545 6.53241 29.26337 22.22507 9.239136 29.26474 23.42856 7.442383 29.26434 24.49701 6.796722 29.19124 22.60361 8.381104 29.96625 32.60974 7.172516 29.70778 32.47854 6.763763 29.21541 32.62901 6.477406 29.19034 34.10351 5.994141 29.64971 35.49603 5.06189 29.14663 34.98541 5.317627 29.97676 35.57544 5.753906 29.51164 34.54961 5.88652 29.85655 34.6037 6.215027 29.75882 33.58227 6.586914 29.22331 33.32587 6.321304 29.98951 34.3612 6.836914 29.99364 45.83098 4.38205 29.97651 45.99655 4.437019 29.78356 46.19488 4.898804 29.56213 46.34296 5.010986 29.26172 46.45312 5.108398 29.22762 46.65649 4.672119 28.58847 46.67538 4.702148 29.67025 46.45001 4.494531 29.2919 46.63102 4.255371 29.26785 46.40683 3.842834 28.64447 46.58044 4.023804 29.70078 46.19391 3.965088 29.81136 45.80239 3.882843 29.18166 46.19067 3.64267 29.11865 45.86451 3.510109 29.42307 45.89622 3.594986 29.1754 43.06201 8.9917 29.32452 44.38281 6.97168 29.24094 45.25732 6.089844 29.19034 43.67602 7.930176 29.7194 44.71411 6.189697 29.97532 43.87158 6.394287 29.65972 43.48926 7.821777 29.92728 42.71985 8.274415 29.6595 42.85791 8.907715 25.1872 49.2439 3.858948 25.89533 49.11016 3.008514 28.81177 46.39343 5.201843 28.60828 46.54852 5.013306 28.15372 46.77464 4.506256 27.75464 46.82952 4.062988 27.20807 47.08104 3.923218 26.59261 47.58881 3.756134 27.48282 46.96586 4.420105 26.55139 47.50769 4.268433 28.21045 46.49805 5.121338 27.79102 46.80029 4.739746 26.99878 46.99463 4.753906 26.59082 47.05493 4.784424 25.7655 48.01037 4.278748 26.27918 47.93713 3.883423 26.11025 48.32576 3.410801 25.85127 48.62762 3.700806 25.47208 49.04968 3.808044 25.78453 49.28973 3.424988 25.23407 51.1132 3.500401 25.53748 51.04834 3.35852 25.79993 51.06207 3.050293 24.96058 72.62744 3.492622 25.69533 71.97376 3.186356 25.83888 73.08075 2.811127 25.54392 74.71248 2.810974 25.07452 76.06185 2.950027 24.534 77.24297 2.829071 23.76086 78.48751 2.767242 22.91733 79.47002 2.818909 21.92951 80.37424 2.897827 20.84995 81.18009 2.817383 19.63742 81.85326 2.761719 18.43961 82.29169 2.967895 17.7023 82.58073 1.234802 17.03854 82.68857 2.829834 15.72098 82.85152 2.884705 14.29083 82.86228 2.818329 12.97168 82.66122 2.96582 11.67502 82.35524 2.884491 10.33157 81.84585 2.838959 9.123925 81.13668 2.948456 8.087052 80.36469 2.966705 7.078461 79.46588 2.818085 6.193527 78.40877 2.755157 5.450406 77.2378 2.753723 4.883572 76.00579 2.829559 4.460424 74.69978 2.874458 4.156929 73.02079 2.831692 5.870182 77.45548 3.275009 6.723 78.79108 3.191589 19.55826 81.6261 3.246155 4.387161 73.04917 3.219482 4.958435 75.39569 3.294312 14.37978 82.5239 3.338837 16.48901 82.48468 3.304871 20.69405 80.935 3.287994 23.23026 78.77545 3.235107 24.45264 76.66495 3.349701 25.30948 74.64057 3.235107 25.455 73.18077 3.357803 10.91019 81.62799 3.390076 12.19371 81.96299 3.471085 21.89484 79.78803 3.427719 4.747006 72.73471 3.470176 8.862915 80.50989 3.365234 18.98847 81.49706 3.475784 5.76479 76.46547 3.485804 8.301659 79.7842 3.4758 23.75523 77.30539 3.48247 25.0331 74.04831 3.476955 16.17468 82.11591 3.486877 4.797037 51.14987 3.500184 4.408577 51.07659 3.321747 4.120903 51.06044 2.865708 4.808212 49.27966 3.848389 4.113185 49.17104 3.207348 4.42263 49.32223 3.665283 3.843654 48.1484 3.244965 3.438738 47.59864 3.633865 4.322754 48.01807 4.293213 2.931564 47.21279 4.008354 2.224426 46.82088 4.070862 1.755096 46.74055 4.540802 1.306396 46.43628 5.158142 1.37677 46.60916 4.894897 0.848999 45.98437 5.508789 2.218018 46.8573 4.531433 2.685791 46.91394 4.733643 3.068848 46.91992 4.853394 3.253723 47.35052 4.341858 3.757568 47.44092 4.544312 3.848 48.01257 3.967133 3.973474 48.47071 3.458862 4.327698 48.38769 4.063293 4.216495 48.69534 3.755432 4.468878 74.74506 1.15844 11.63643 82.36097 1.237854 21.87412 80.41098 1.033142 5.628328 75.80254 0.4945173 24.80106 75.86832 0.660492 25.52897 74.74394 1.161194 7.259411 78.69151 0.5059834 5.911102 77.34101 0.641037 8.732636 80.08135 0.5015068 4.904949 76.04523 1.102226 25.12778 75.96305 1.101852 23.80153 78.39678 1.158478 24.54998 77.22274 1.167603 19.61575 81.858 1.165405 20.82878 81.188 1.156067 22.92154 79.46457 1.165894 23.15888 78.78745 0.696167 24.21796 77.11366 0.6462555 22.75755 78.6083 0.4971466 21.09177 80.46683 0.5832214 20.03008 81.36518 0.7145386 18.33936 82.30658 1.04834 15.72718 82.85147 1.101807 14.25345 82.83678 1.034088 19.19239 81.24832 0.495801 17.93866 82.10416 0.6229248 16.9859 82.45502 0.7510986 10.38453 81.83737 1.118225 15.14926 82.18506 0.4992218 15.11581 82.52747 0.6421509 12.6498 81.95729 0.5072937 12.9837 82.50379 0.7991943 11.68706 82.12436 0.7399902 10.0237 81.2887 0.6337738 9.171929 81.17392 1.088959 7.745544 79.85971 0.7801209 8.066674 80.40132 1.231842 7.066188 79.45618 1.173309 6.217396 78.37509 1.01944 5.465247 77.24323 1.156189 12.95772 82.6968 1.221374 25.89554 49.08471 33.7665 26.06733 48.40451 33.55549 26.41028 47.72174 33.58911 25.77571 47.79782 32.58751 26.98436 47.23673 33.13779 28.7879 46.35751 31.75537 28.68359 46.48572 31.88879 28.52818 46.67175 32.23981 27.75153 46.80835 32.24646 27.66943 46.55798 31.89429 28.19605 46.75469 32.56889 27.44223 47.00024 32.58922 26.8385 46.98849 32.17238 27.68875 46.80653 33.06854 26.74951 47.36412 32.65945 26.27072 47.94774 33.13949 25.96779 48.01227 32.83087 25.8187 48.54758 33.1655 25.18884 49.09927 33.08526 25.62506 49.26716 33.35137 25.86514 50.8725 34.04261 25.28227 51.103 33.48987 25.62426 51.02081 33.69893 25.23828 72.76056 33.5243 25.55908 72.92076 33.69926 25.88044 72.00131 34.15546 4.159895 73.12773 34.19031 4.870503 76.00248 34.23027 4.473062 74.70226 34.08805 5.452076 77.22669 34.16499 6.217809 78.37593 34.0193 7.052574 79.43737 34.16543 8.066052 80.39403 34.17418 9.165253 81.19396 34.22058 10.37265 81.83429 34.08761 11.64318 82.34975 34.11056 13.0292 82.68244 34.03529 14.28632 82.80365 33.98099 14.34571 82.88514 35.8212 15.67635 82.83142 34.01944 17.15653 82.70168 34.50116 18.38876 82.35668 34.14752 19.59403 81.85721 34.10123 20.86513 81.15849 34.10254 21.92778 80.34919 34.05102 21.93171 80.41397 35.76358 22.94122 79.44815 34.17615 23.77268 78.38912 34.02019 24.50697 77.23186 34.01807 25.12409 76.00415 34.17386 25.52631 74.70494 34.0881 25.78411 73.40155 34.10066 17.02228 82.61847 33.98083 9.257828 81.02375 33.79776 5.08699 75.89727 33.74032 4.301117 72.8963 33.85132 25.04114 75.39723 33.69084 22.75052 79.29295 33.7511 8.473748 80.25067 33.6222 7.003937 78.86971 33.63604 5.707443 77.08567 33.69759 21.14867 80.59342 33.66867 18.81635 81.85477 33.66943 16.39882 82.39397 33.61098 11.0741 81.84955 33.70184 4.928635 74.43914 33.53365 23.65867 77.61674 33.52227 14.44418 82.25196 33.50464 13.02409 82.22292 33.58393 4.739609 72.86307 33.51479 24.59514 75.47455 33.49795 21.99828 79.55553 33.52887 18.72503 81.56298 33.50107 11.15409 81.48226 33.49956 7.5448 78.99515 33.50635 5.849625 76.46677 33.49834 4.715271 51.09738 33.48993 4.354462 51.04144 33.71982 4.120628 51.01019 34.11755 4.827965 49.41138 33.16717 4.100779 49.15177 33.85237 1.353485 46.51889 31.92239 1.607544 46.6983 32.28039 1.368713 46.67508 32.28339 2.505951 46.96965 32.83288 1.777908 46.64517 32.98178 2.846985 46.94844 33.43866 3.256744 47.44533 33.20495 1.871094 46.69446 32.15271 2.768524 47.09097 32.61096 3.348846 47.39746 32.60528 2.76001 46.84912 32.11053 3.569006 47.16957 32.26356 4.549713 48.2507 32.78665 4.071562 47.99019 32.78639 3.670822 47.85531 33.05249 3.6791 47.90048 33.56421 4.028853 48.38679 33.21897 4.447693 49.12186 33.25397 4.230041 49.12071 33.49734 3.992037 48.61474 33.66046 25.54891 74.70298 35.7684 9.4516 81.3821 35.81622 8.087784 80.36717 35.96472 24.6077 76.62853 36.24771 5.469452 76.47641 36.35058 4.472519 74.76255 35.81392 23.41164 78.11249 36.43082 20.88931 80.31281 36.48601 25.12091 76.01334 35.81177 4.902763 76.03891 35.88428 6.251053 78.43758 35.95151 5.476379 77.2365 35.89714 10.36023 81.85968 35.68872 6.732391 78.12383 36.4696 9.213685 80.80632 36.34799 7.543549 79.56555 36.26721 10.48752 81.65073 36.24426 11.73209 82.13886 36.24567 12.95581 82.6944 35.81131 15.6832 82.87429 35.69714 7.884018 79.34027 36.48135 11.71829 81.68625 36.48498 14.33213 82.61619 36.22902 16.05451 82.72931 36.08581 15.74582 82.26102 36.47845 16.99561 82.39575 36.27856 19.06165 81.60559 36.41348 18.32566 82.30442 36.00366 19.58901 81.86082 35.88275 20.82689 81.17447 35.89508 22.84315 79.34467 36.13324 22.94479 79.45447 35.68835 23.77179 78.42932 35.88364 20.64102 80.82324 36.37051 21.99976 79.87207 36.35165 24.54249 77.24469 35.76312 7.078003 79.46504 35.81756 11.63635 82.35733 35.76263 17.0136 82.69783 35.81805 13.35939 82.46454 36.29663 2.999734 32.81195 6.433914 2.997713 33.82593 6.058838 2.127136 35.57483 4.452393 27.00696 33.57373 6.184875 27.00042 32.5021 6.468948 2.99976 33.50909 30.76616 2.999855 32.53989 30.52438 0.8400421 32.47586 30.50026 27.00205 32.51327 30.51931 27.0003 33.24872 30.6868 27.91009 35.39863 32.22195 3 25.33623 6.52231 3 23.95288 7.04364 3 22.98731 7.845337 3 22.10471 9.374451 3 24.9359 30.4104 3 23.35338 29.50603 3 22.55176 28.54044 3 22.05192 27.24011 27 22.09178 9.457047 27 22.91455 7.93042 27 23.85748 7.102081 27 25.26643 6.527343 27 22.1047 27.61079 27 23.20727 29.39908 27 25.07811 30.44331 1.371071 46.59598 4.049469 4.081412 48.80001 2.579971 2.866211 46.88019 3.451904 3.410614 46.19529 2.450348 2.724829 45.84237 3.031532 3.871597 47.49187 2.292084 3.386703 47.09445 3.010376 2.237091 46.36539 3.467102 1.566803 46.19388 3.583435 3.051941 46.38129 2.927887 1.842773 45.7854 3.413245 26.63788 47.18368 3.128784 26.14163 47.71655 2.518433 28.60639 46.35254 3.739441 28.20607 45.96051 3.44117 27.30847 45.94658 3.059601 26.80676 46.18318 2.679321 27.74182 46.47314 3.551392 27.15234 46.67054 3.270874 25.94526 48.3363 34.67139 26.96741 45.96582 34.17651 27.56567 45.92978 33.79065 28.20142 45.93521 33.54816 28.24814 46.62555 32.97717 28.25223 46.35559 33.31897 26.12451 47.26007 34.8977 27.32489 46.55664 33.63989 26.61939 46.67297 34.29126 4.054573 48.01276 35.01761 2.421875 46.68172 33.35046 3.155884 46.94296 33.8291 3.644501 46.13554 34.86279 1.598145 46.2359 33.35742 1.815063 45.86511 33.5594 3.021423 45.9752 34.16095 2.650635 46.10126 33.8706 3.664459 47.03796 34.50989 9.481583 69.4494 35.29262 9.160477 69.43485 36.49261 10.21374 69.74878 36.49264 10.98862 70.3346 35.29264 11.03561 70.42667 36.49263 11.54483 71.6193 36.49261 11.59394 71.95363 35.29262 11.45718 72.71283 36.49262 11.04776 73.59369 35.29262 10.84012 73.82965 36.49263 10.01855 74.3476 35.29263 9.489197 74.52714 36.49262 8.944886 74.57346 35.29262 8.392945 74.48592 36.49261 7.495483 74.11432 35.29261 7.250885 73.91681 36.49263 6.698456 73.1178 35.29262 6.4354 72.39269 36.49262 6.427303 72.05484 35.29262 6.677978 70.89176 36.4926 6.824554 70.58725 35.29263 7.680237 69.76721 36.49262 7.990601 69.63373 35.2926 7.378967 73.26552 35.29262 8.707777 74.01403 35.29262 10.03516 73.75263 35.29262 10.82123 72.87055 35.29261 9.464692 70.01974 35.29262 11.01413 71.87191 35.29262 10.60608 70.75144 35.29261 6.976001 71.79141 35.29262 7.368896 70.83216 35.2926 8.117127 70.16751 35.29263 14.83965 75.43484 35.29262 15.16034 75.43483 36.49262 16.31998 75.76731 35.29262 16.3949 75.83841 36.49264 17.38311 76.97534 36.49262 17.43009 77.09223 35.29261 17.49838 78.70001 36.49261 17.5033 78.59674 35.29262 16.89484 79.74195 35.29261 16.7981 79.82056 36.49261 15.90912 80.40811 36.49261 15.80505 80.44483 35.29261 14.61963 80.5458 36.49261 14.5108 80.52714 35.29262 13.59961 80.14173 36.4926 13.53589 80.09851 35.29261 12.83817 79.39655 36.4926 12.65574 79.11219 35.29263 12.46764 78.36411 36.49263 12.44596 77.85353 35.29262 12.56992 77.09221 36.49261 12.82443 76.58734 35.29264 13.68011 75.76725 36.49262 13.78625 75.74884 35.2926 14.46497 76.06693 35.29264 15.6348 76.0452 35.29262 15.20538 80.00918 35.29262 16.6955 76.90601 35.29259 17.04543 78.20937 35.29262 16.31641 79.55237 35.29259 13.55673 76.56647 35.29262 12.976 77.79142 35.29262 13.29375 79.10947 35.29262 14.20825 79.85724 35.29262 21.69293 69.52017 35.29262 20.73831 69.441 36.49262 22.20993 69.70578 36.49263 22.63721 70.03485 35.29259 23.15793 70.62671 36.49258 23.43009 71.09223 35.29261 23.54483 71.61927 36.49263 23.53236 72.36408 35.29262 23.3443 73.11206 36.49261 23.1618 73.39649 35.29261 22.30298 74.21991 36.49264 22.40039 74.14173 35.29255 21.38046 74.54578 35.29262 21.25543 74.54627 36.49261 20.19501 74.44492 36.49262 20.31775 74.4664 35.29262 19.34088 73.96768 35.29264 19.25781 73.87409 36.49261 18.53854 72.8205 36.49263 18.50164 72.70003 35.29262 18.52393 71.3003 36.49262 18.55628 71.19474 35.29262 19.32172 70.02237 36.4926 19.41968 69.9433 35.29263 20.64905 69.46427 35.29261 21.02577 74.0083 35.29262 21.87061 73.82166 35.29263 22.52612 73.30347 35.29264 19.89295 73.73334 35.29263 22.99896 72.38106 35.29262 22.79416 71.04087 35.29262 22.09802 70.32147 35.29258 21.2984 70.00471 35.29262 19.25909 70.97974 35.29262 20.11713 70.16748 35.29261 19.00612 71.77603 35.29262 19.08333 72.63301 35.29264 15.0335 63.44227 35.29262 14.63519 63.4599 36.49261 16.09976 63.63415 36.49261 16.31982 63.76723 35.29261 17.27236 64.79329 36.49262 17.43009 65.09223 35.29261 17.55405 65.85354 36.49262 17.53235 66.36408 35.29262 17.40775 66.90872 36.49262 17.16168 67.39673 35.29264 16.65906 67.96784 36.4926 16.40027 68.14173 35.29262 15.68213 68.46646 36.49265 15.38037 68.54578 35.29261 14.4075 68.5266 36.49263 14.09088 68.40811 35.29262 13.10513 67.74179 36.49262 13.20184 67.82074 35.29257 12.59228 66.90888 35.29264 12.43541 66.39273 36.49261 12.47788 65.39276 35.29262 12.67795 64.89188 36.49261 13.10522 64.28174 35.29264 13.51373 63.90002 36.49262 13.99054 63.63379 35.29263 15.47626 64.05161 35.29262 16.23395 64.40363 35.29263 16.93058 65.35791 35.29261 16.90594 66.71341 35.29262 16.28394 67.54273 35.2926 15.37971 68.00164 35.29262 14.36011 67.90253 35.29262 13.50568 67.38184 35.29262 12.94425 65.96641 35.29262 13.45673 64.70014 35.29265 14.43967 64.04464 35.29262 14.20712 64.12682 33.49261 13.20586 65.04084 33.49261 19.71594 73.54261 33.49261 15.56027 64.04464 33.49262 6.994248 72.05562 33.49262 7.205856 71.04084 33.49262 8.207184 70.12677 33.49262 9.20044 70.00429 33.49261 10.18005 70.34308 33.49261 10.49438 73.38178 33.49262 15.22179 75.97811 33.49261 15.79169 67.85727 33.49263 18.98587 71.87191 33.49261 20.20715 70.1268 33.49261 16.54334 64.70017 33.49262 16.92721 65.44229 33.49261 12.99306 66.21411 33.49261 14.61347 67.99929 33.49262 11.03028 72.13648 33.49262 9.48298 73.9591 33.49259 12.99306 78.21413 33.49262 13.20581 77.0409 33.49261 21.64602 73.92871 33.4926 13.44025 67.30753 33.49261 10.8051 71.12461 33.49261 20.47471 73.95281 33.49259 19.1788 72.87059 33.49263 16.99594 66.29998 33.49261 21.38373 70.01936 33.49261 22.30133 70.45822 33.49262 7.316025 73.18044 33.49262 19.30451 70.90607 33.49261 8.474674 73.95278 33.4926 22.59656 73.2356 33.49263 22.99595 72.30001 33.49262 16.30127 76.45813 33.49261 14.05383 76.21808 33.49261 16.59644 67.23548 33.49262 15.29446 80.01366 33.49263 22.88841 71.28859 33.49261 16.23718 79.58057 33.49259 16.80516 77.1247 33.49267 14.12946 79.8216 33.49262 16.78226 78.94782 33.4926 17.0178 77.95838 33.49262 13.35193 79.1659 33.49257 6.92041 70.51087 1.692622 7.217743 71.05371 1.692623 6.4194 71.73384 1.692623 6.996821 71.88533 1.692623 8.799683 73.99726 1.692623 7.820007 73.65854 1.692622 8.184327 74.4256 1.692624 7.259766 73.8963 1.692624 7.11158 72.71294 1.692623 6.64093 72.99054 1.692624 9.500489 74.54643 1.692623 9.956147 73.82094 1.692623 10.63721 73.96668 1.692624 11.43006 72.9094 1.692623 10.85612 72.79334 1.692623 10.99895 71.62053 1.692623 11.46148 71.18109 1.692623 10.19482 70.32756 1.692624 10.40021 69.81668 1.692623 7.763428 70.42078 1.692621 7.874329 69.66335 1.692623 8.70723 69.98851 1.692623 9.178498 69.44871 1.692623 8.619538 69.4558 0.492623 7.250885 70.08466 0.492623 6.4354 71.60887 0.492623 6.677948 73.10977 0.492623 7.680054 74.23426 0.4926229 9.163208 74.56887 0.4926231 10.39502 74.16315 0.4926233 11.15784 73.37512 0.4926242 11.58859 72.1738 0.492623 11.12271 70.50922 0.4926231 9.909119 69.59345 0.4926231 12.87732 76.50916 1.692623 13.13092 77.19644 1.692623 12.4114 78.17382 1.692623 13.01838 78.38355 1.692623 13.90601 76.30487 1.692623 14.28549 75.50675 1.692623 15.0518 75.97221 1.692623 14.77824 80.02347 1.692623 14.40527 80.5044 1.692623 13.55679 79.43524 1.692623 13.09467 79.7616 1.692622 15.9234 80.42525 1.692623 15.79834 79.84156 1.692624 16.48602 79.36634 1.692624 17.10138 79.48621 1.692624 16.96339 78.46817 1.692623 17.59394 78.04794 1.692623 16.942 77.45127 1.692623 17.1618 76.60498 1.692623 16.31638 76.4491 1.692623 16.01096 75.61151 1.692623 14.61957 75.4558 0.492623 13.42694 75.96436 0.4926231 12.63338 76.99048 0.4926229 12.45134 78.48567 0.492623 13.17999 79.82001 0.4926231 14.49954 80.54642 0.492623 15.8158 80.42554 0.4926231 16.90527 79.76166 0.492623 17.49243 78.57752 0.4926231 17.49838 77.30158 0.4926231 16.79797 76.18079 0.4926231 15.90912 75.59348 0.4926229 19.34076 70.03382 1.692622 18.59229 71.09272 1.692623 19.13092 71.19647 1.692623 18.44595 72.14803 1.692623 19.0405 72.54922 1.692623 20.46484 73.93451 1.692623 19.6051 74.16315 1.692624 19.69867 73.54349 1.692623 18.72762 73.20824 1.692623 20.60577 74.5285 1.692623 21.46475 73.98179 1.692623 21.70154 74.47657 1.692623 22.82007 73.81989 1.692625 22.48602 73.36634 1.692623 23.47605 72.70145 1.692623 22.96339 72.46814 1.692623 23.46149 71.18112 1.692623 22.90593 71.28816 1.692623 22.74201 70.12726 1.692625 22.03525 70.24901 1.692624 21.59259 69.47499 1.692623 19.90595 70.30487 1.692623 20.31836 69.53498 1.692623 20.87425 69.98828 1.692623 20.4075 69.47498 0.492623 18.95218 70.40793 0.4926231 18.40606 72.04795 0.4926231 18.8988 73.48624 0.492623 20.07663 74.42528 0.4926232 21.59479 74.50437 0.4926233 22.74036 73.8963 0.4926232 23.35907 72.99048 0.4926231 23.5806 71.73383 0.4926231 23.07956 70.51068 0.4926231 22.12564 69.66335 0.492623 12.99682 65.88534 1.692623 12.47346 65.51268 1.692623 12.92041 64.51087 1.692623 13.29373 64.89212 1.692623 13.58984 67.42823 1.692624 13.2597 67.89633 1.692623 12.55625 66.80686 1.692622 16.36621 67.47046 1.692626 15.92343 68.42523 1.692623 15.46472 67.9818 1.692623 14.40521 68.50438 1.692623 14.28699 67.8889 1.692623 13.11158 66.71294 1.692623 16.20648 63.72784 1.692623 15.87048 64.1799 1.692623 16.75813 64.97638 1.692623 17.16177 64.60495 1.692623 17.56801 65.83647 1.692623 16.99807 66.48558 1.692623 17.24158 67.30698 1.692623 13.69727 63.78155 1.692622 14.04797 64.23456 1.692623 14.87414 63.98827 1.692623 14.94483 63.42809 1.692623 15.25555 63.45529 0.4926231 14.19489 63.55669 0.4926229 13.25806 64.1272 0.4926231 12.53852 65.18106 0.4926231 12.52394 66.7014 0.492623 13.0542 67.66168 0.492623 13.89001 68.32236 0.492623 15.37627 68.56771 0.492623 16.74036 67.8963 0.4926231 17.52213 66.60877 0.4926231 17.40776 65.09281 0.492623 16.50446 63.88719 0.4926231 20.20129 73.84149 3.492622 21.04328 74.01856 3.492622 17.0178 78.04322 3.492622 16.94978 65.34835 3.492622 16.85031 77.22464 3.492622 16.36481 76.5141 3.492622 22.98161 72.38356 3.492622 14.45654 64.05518 3.492622 16.02179 67.7414 3.492626 19.1788 71.13105 3.492622 14.12952 76.17993 3.492623 10.97814 71.52394 3.492622 16.83865 66.8725 3.492622 19.83423 70.35321 3.492619 20.62695 70.02873 3.492622 14.87677 68.03186 3.492622 18.98587 72.12963 3.492622 15.22174 80.02347 3.492622 19.3938 73.24999 3.492622 15.29288 75.98851 3.492622 22.33237 73.56668 3.492621 22.91667 71.36856 3.492622 10.83861 72.8725 3.492623 16.09399 64.30481 3.492622 22.36499 70.51416 3.492626 13.40491 79.21802 3.492622 7.766052 73.5979 3.492621 8.70163 73.99684 3.492621 21.43512 70.02667 3.492622 14.05377 79.78357 3.492623 16.57785 79.31897 3.492621 13.09407 65.28818 3.492622 9.292832 69.98851 3.492622 8.129273 70.17993 3.492622 7.241913 70.97632 3.49262 13.03237 77.60782 3.492622 9.882874 73.83408 3.492623 10.36499 70.51416 3.492623 13.90173 67.67993 3.492622 6.98587 72.12965 3.492621 7.222198 72.93122 3.492625 15.27533 64.0114 3.492622 13.01383 66.28569 3.492622 13.30444 67.09552 3.492622 13.71594 64.45886 3.492622 13.35199 76.83576 3.492622 13.03661 78.46815 3.492621 3 22.00078 15.49262 3 22.00078 21.49262 1.2 29.54577 18.87299 0 29.44485 17.68761 1.2 29.3382 17.36691 0 28.74183 16.59779 1.2 28.11221 16.14838 0 27.59669 15.98931 1.2 26.85355 15.93857 0 26.09219 16.06256 1.2 25.79321 16.22026 0 25.03491 16.85553 1.2 24.98627 16.91565 0 24.45513 17.9922 1.2 24.49721 17.89774 1.2 24.48611 18.96301 0 24.57602 19.30835 1.2 25.02243 20.171 0 25.10526 20.23295 0 26.3928 21.01475 1.2 26.30023 20.96869 1.2 27.59676 20.99592 0 27.90878 20.90038 1.2 28.91681 20.24176 0 28.82074 20.29047 0 29.49482 19.20709 1.199998 29.00814 18.28186 1.2 28.72324 19.61533 1.2 27.46555 20.47362 1.2 26.11787 20.32589 1.2 25.2599 19.51375 1.2 24.98298 18.53507 1.2 25.15042 17.71655 1.2 25.76128 16.87892 1.2 27.05019 16.45843 1.2 28.00573 16.75592 1.2 28.64879 17.32758 1.2 29.54577 12.87305 0 29.59039 12.33546 1.2 29.4081 11.58356 0 28.91684 10.74349 1.2 28.82077 10.69476 1.2 27.90884 10.0849 0 27.3927 9.928023 1.2 26.85355 9.938573 0 25.89175 10.17059 1.2 25.79334 10.22025 0 24.76721 11.17278 1.2 24.98627 10.91577 1.2 24.49722 11.89778 0 24.43269 12.6558 1.2 24.57632 13.41607 0 24.7487 13.70627 0 25.42659 14.52821 1.2 25.51531 14.59382 0 26.82774 15.08122 1.2 26.49969 15.00136 1.2 27.59673 14.99593 0 28.3027 14.71223 1.2 28.91683 14.24176 0 29.21985 13.79547 1.2 25.34309 11.31261 1.2 26.28854 10.6042 1.2 27.47763 10.51448 1.2 24.98299 12.44932 1.2 25.28775 13.59078 1.2 26.35787 14.42319 1.2 27.55023 14.43463 1.2 28.55241 13.80905 1.2 28.61453 11.25316 1.2 29.02936 12.54443 1.2 27.80508 22.62353 1.2 28.65898 22.52487 1.2 27.71283 22.03545 1.2 26.39276 21.97051 1.2 26.45238 22.53312 1.2 25.28186 22.5979 1.2 25.34308 23.31262 1.2 24.63377 23.48322 1.2 24.98299 24.44933 1.2 24.44278 24.53131 1.2 24.67922 25.60259 1.2 25.21811 25.43889 1.2 25.51542 26.59391 1.2 25.78333 26.08759 1.2 26.69339 26.50407 1.2 26.95366 27.08657 1.2 28.02527 26.25072 1.2 28.18689 26.75928 1.2 29.03702 26.06592 1.2 28.82156 25.36325 1.2 29.59039 24.6498 1.2 28.80075 23.54367 1.2 29.31577 23.40378 1.2 29.00745 24.51886 0 29.54577 24.11224 0 28.91681 22.74346 0 27.7868 22.05808 0 26.72878 21.93378 0 25.51535 22.39139 0 24.6792 23.38266 0 24.43383 24.86885 0 24.98625 26.06949 0 25.79332 26.765 0 27.26772 27.07323 0 28.49072 26.57221 0 29.33817 25.61838 3 30.40078 21.49262 3 30.40078 27.49262 10.97813 32.52392 11.29262 11.55 31.40077 11.29262 7.834259 31.3533 11.29262 7.205841 33.96067 11.29262 8.860016 35.00238 11.29262 9.882905 34.83403 11.29262 10.36491 31.51408 11.29263 9.121562 30.94833 11.29262 7.275757 31.97473 11.29262 6.993064 32.7874 11.29262 8.053772 34.78343 11.29263 10.83864 33.87245 11.29262 9.631287 34.91774 25.69262 7.456757 34.30142 25.69264 6.944252 33.03513 25.69262 8.439621 34.9569 25.69262 6.449999 30.40078 25.69262 7.505661 31.61969 25.69262 8.704934 30.98749 25.69262 9.870545 31.17995 25.69263 10.64799 31.83571 25.69259 11.55 31.40077 25.69262 11.03447 32.9638 25.69262 10.60611 34.25009 25.69262 9.383667 34.98223 27.49262 8.207154 34.87476 27.49262 7.304504 34.09558 27.49264 7.01383 33.28569 27.49262 7.094063 32.28815 27.49263 8.105149 31.14967 27.49261 9.631089 31.06632 27.49262 10.48599 31.65247 27.49258 10.97813 32.52392 27.49262 10.9272 33.55929 27.49261 10.44322 34.43516 27.49261 7.011626 33.39388 24.69262 7.176437 32.06923 24.69263 7.217728 32.0538 12.29263 8.051011 31.20082 12.29262 8.275727 31.09926 24.69262 9.392457 31.00418 12.29262 9.631089 31.06632 24.69262 10.42737 31.57391 12.29262 10.70627 31.89216 24.69261 10.942 32.45128 12.29262 11.00318 32.88533 24.69262 10.98617 33.28567 12.29262 10.88841 33.713 24.69262 10.60611 34.25011 12.29262 10.18008 34.65845 24.69262 9.798707 34.8414 12.29262 9.20047 34.99724 24.69262 8.778222 35.02346 12.29262 8.368622 34.91772 24.69262 7.851257 34.64584 12.29262 7.513885 34.36629 24.69261 7.259109 34.02183 12.29262 6.985322 33.04037 12.29262 9.123295 35.03184 9.492625 7.978149 34.74123 9.492622 7.259117 34.02188 9.492629 6.982198 33.04317 9.492622 7.149719 32.22458 9.49262 7.760529 31.38704 9.492622 8.871987 30.9866 9.492623 10.03525 31.24902 9.492628 10.90593 32.28815 9.492626 10.96337 33.4682 9.492623 10.37192 34.50354 9.492626 3 29.02936 24.44083 3 28.6145 25.73209 3 27.63306 26.40927 3 26.45236 26.45212 3 25.23223 25.54119 3 25.0452 23.85779 3 25.78339 22.89764 3 26.53345 22.52924 3 27.71338 22.58668 3 28.64832 23.32687 3 29.00745 12.46639 3 28.80075 13.44162 3 27.94779 14.27487 3 26.79138 14.51661 3 25.70017 14.03591 3 25.11267 13.20561 3 25.01977 12.02782 3 25.63519 11.00656 3 26.69339 10.48117 3 28.02525 10.73454 3 28.82159 11.62198 27 22.00078 15.49262 27 22.00078 21.49262 28.8 29.54577 18.11225 30 29.57971 18.20992 28.8 29.40813 19.40164 30 29.34763 19.51093 30 28.74194 20.38745 28.8 28.49237 20.61534 30 27.59674 20.99592 28.8 27.05483 21.06532 30 26.4997 21.00136 28.8 25.58728 20.66812 30 25.5153 20.59382 30 24.78648 19.77396 28.8 24.63377 19.50206 30 24.44205 18.76574 28.8 24.44278 18.45394 30 24.70578 17.28273 28.8 24.76726 17.17273 30 25.79321 16.22026 28.8 26.09218 16.06255 30 26.85353 15.93857 28.8 27.59669 15.98932 30 28.1122 16.14838 28.8 28.91684 16.74348 30 29.09836 17.02808 28.8 28.92801 19.05109 28.8 28.98796 18.03793 28.8 28.36567 17.00589 28.8 27.29585 16.47933 28.8 26.13019 16.67181 28.8 25.47455 17.18988 28.8 25.05875 17.94312 28.8 25.01461 18.77759 28.8 25.30526 19.58742 28.8 25.9024 20.17179 28.8 26.70239 20.48869 28.8 27.53577 20.4265 28.8 28.44397 19.927 28.8 29.52658 11.90009 30 29.5797 12.20991 28.8 29.40811 13.40167 30 29.34766 13.51086 30 28.74191 14.38739 28.8 28.49243 14.61533 30 27.3927 15.05722 28.8 27.05484 15.06532 30 25.89184 14.81468 28.8 25.5873 14.66813 30 24.76724 13.81252 28.8 24.53433 13.29727 30 24.43269 12.32944 28.8 24.52505 11.79089 30 24.94328 10.91231 28.8 25.03491 10.85559 28.8 25.89179 10.17058 30 26.19469 10.04887 28.8 27.39269 9.928022 30 27.70003 9.99426 28.8 28.74187 10.59781 30 28.96771 10.83345 28.8 28.82163 11.62207 28.8 24.96605 12.19741 28.8 25.18509 13.34671 28.8 25.75145 10.8865 28.8 27.03775 10.45815 28.8 28.16581 10.84459 28.8 28.76715 13.44452 28.8 29.01328 12.6184 28.8 28.23541 14.08917 28.8 27.1365 14.52289 28.8 25.83089 14.15749 28.8 25.08385 23.86121 28.8 25.01934 24.87633 28.8 24.43269 24.6558 28.8 24.74874 25.70635 28.8 25.4581 25.79394 28.8 25.58731 26.66814 28.8 26.45235 26.45212 28.8 27.05486 27.06532 28.8 27.633 26.40929 28.8 28.11792 26.79416 28.8 28.48746 25.85767 28.8 28.96771 26.15173 28.8 28.93995 25.0311 28.8 29.52711 24.98177 28.8 28.99362 24.20647 28.8 29.44487 23.68759 28.8 28.55246 23.1763 28.8 28.8743 22.75053 28.8 28.01124 22.12606 28.8 27.20935 22.4472 28.8 26.51598 21.94396 28.8 25.7515 22.88652 28.8 25.18161 22.67267 28.8 24.60187 23.60376 30 29.55284 24.67104 30 29.18483 25.89282 30 27.82048 26.9541 30 26.09216 26.92268 30 24.90019 25.97899 30 24.4861 24.96303 30 24.53435 23.68794 30 25.42664 22.457 30 26.82778 21.90403 30 28.49241 22.36994 30 29.40811 23.58354 27 30.40078 27.49262 19.62814 34.50358 11.29262 19.31604 31.82114 11.29262 22.33241 34.56663 11.29262 20.8767 35.03184 11.29262 22.98162 33.38359 11.29262 22.8691 32.19649 11.29262 21.94897 31.20081 11.29262 20.60758 31.00417 11.29262 18.98855 33.30816 11.29262 21.1233 35.03184 25.69262 19.82001 34.65847 25.69263 19.0405 33.54921 25.69262 18.45 31.40077 25.69262 19.04516 32.54843 25.69262 19.40341 31.76618 25.69264 20.04797 31.2345 25.69261 21.04942 30.96657 25.69262 22.8729 32.28082 25.69262 23.55 30.40078 25.69262 22.31638 31.44915 25.69262 23.01413 33.12963 25.69262 22.50792 34.39844 25.69263 20.36865 34.91772 27.49262 19.39389 34.25011 27.49262 18.96553 32.96379 27.49262 19.35199 31.83569 27.49262 20.1294 31.17992 27.49263 20.96967 30.99451 27.49262 21.94896 31.2008 27.49261 22.8691 32.19649 27.49261 22.98161 33.38356 27.49262 22.54324 34.30145 27.49263 21.56035 34.95691 27.49262 23.01468 33.04036 24.69262 23.00675 32.7902 12.29262 22.79416 33.96066 12.29262 22.66487 34.17065 24.69262 21.94635 34.78345 12.29262 21.85413 34.81637 24.69262 21.04328 35.01856 24.69262 20.95672 35.01856 12.29262 19.90184 34.71379 24.69262 19.6676 34.56665 12.29262 19.14386 33.79328 24.69261 18.976 33.21014 12.29262 19.00104 32.62054 24.69262 19.29373 31.89215 12.29262 19.5726 31.57394 24.69262 20.20828 31.14432 12.29263 20.3031 31.11911 24.69261 21.12802 30.98659 24.69262 21.21425 30.99394 12.29262 22.09409 31.30482 24.69263 22.16577 31.35327 12.29262 22.78228 32.05378 24.69261 22.72435 31.97479 12.29262 20.95672 35.01855 9.492623 20.146 34.81644 9.492618 19.33514 34.17067 9.49263 18.9822 33.04317 9.492625 19.21773 32.05377 9.492615 20.05106 31.20082 9.492626 21.21426 30.99393 9.492625 22.00488 31.26401 9.492617 22.64804 31.83575 9.49263 22.96763 32.60774 9.49262 22.93058 33.64368 9.492628 22.09818 34.7138 9.492622 27 29.02936 24.5444 27 28.61451 23.25316 27 27.47766 22.5145 27 26.44241 22.56542 27 25.56635 23.04941 27 25.06688 23.9577 27 25.00472 24.79105 27 25.40369 25.72657 27 26.35787 26.42318 27 27.39383 26.46026 27 28.16583 26.14063 27 28.73743 25.49744 27 28.97485 12.05739 27 28.58069 11.25574 27 27.80508 10.62353 27 26.618 10.511 27 25.70017 10.94937 27 25.18509 11.63849 27 24.983 12.44933 27 25.28775 13.59076 27 26.35786 14.42318 27 27.71341 14.39855 27 28.54273 13.77655 27 28.94636 13.03613 3 29.45499 25.07694 3 29.38319 23.60185 3 28.29475 22.30287 3 26.63192 21.97601 3 25.29459 22.63428 3 24.5281 23.89655 3 24.59177 25.19077 3 25.07171 26.11844 3 26.30028 26.93776 3 27.79007 26.8888 3 28.8584 26.19965 3 29.50945 12.22591 3 28.95037 10.85907 3 27.68869 10.06541 3 26.21193 10.07455 3 24.86794 11.10684 3 24.47077 12.75431 3 25.07166 14.11839 3 25.93328 14.76224 3 27.15489 15.03145 3 28.71567 14.37108 3 29.38756 13.26324 27 29.49571 12.11864 27 29.40978 13.1908 27 28.92987 14.11838 27 27.70127 14.93777 27 26.00967 14.83508 27 24.88134 13.86105 27 24.48312 12.65367 27 24.72427 11.4054 27 25.70679 10.30288 27 27.36964 9.97601 27 28.86877 10.76635 27 29.47778 24.97113 27 29.03967 25.95349 27 28.10437 26.78424 27 26.8259 26.99464 27 25.81795 26.72098 27 24.88138 25.86111 27 24.51807 24.84882 27 24.57327 23.80579 27 25.35532 22.55307 27 26.73299 21.98407 27 28.18693 22.24264 27 29.33715 23.48723 5.299999 25.5733 17.06589 5.299999 28.36572 17.00593 5.299999 28.444 19.92703 5.3 25.20662 19.45254 5.299999 25.00183 18.11234 5.299999 26.05451 20.2753 5.299999 27.22255 20.5153 5.299999 28.92801 19.05103 5.299996 28.98378 18.02776 5.299999 26.60831 16.49603 5.299999 27.64047 16.59082 24.7 25.05102 17.84015 24.70001 28.69632 19.58743 24.7 25.90674 16.79663 24.7 27.05018 16.45842 24.7 25.16214 19.36431 24.7 27.94705 20.2753 24.7 28.82198 17.62285 24.70001 29.01401 18.62135 24.7 26.95753 20.5104 24.7 25.97895 20.23308 24.7 28.16653 16.84509 5.199999 27.29586 22.47934 5.199998 28.44397 25.92703 5.199999 25.27649 23.46661 5.199998 24.99385 24.27921 5.199998 28.98237 24.87541 5.199999 25.09129 25.10898 5.199999 25.96561 22.7408 5.199999 25.6289 25.99542 5.199999 28.91744 23.8604 5.199999 27.0537 26.54798 5.199999 28.36568 23.00591 3.8 26.61709 26.47407 3.8 25.55757 25.92706 3.8 25.01916 24.87541 3.8 25.13168 23.68834 3.8 26.05185 22.69264 3.8 27.03112 22.48635 3.8 27.87138 22.6718 3.8 28.64877 23.32756 3.8 29.00771 24.27924 3.799999 28.85693 25.28516 3.799999 27.95693 26.3128 3.8 29.47345 23.89657 3.8 28.70693 22.63425 3.8 27.36965 21.97601 3.8 25.91257 22.2166 3.8 25.09308 22.86426 3.799999 24.57326 23.80582 3.8 24.54656 25.07691 3.8 25.00707 26.0144 3.8 25.81793 26.72095 3.8 27.05486 27.01485 3.8 28.4758 26.56474 3.8 29.36128 25.38287 5.199998 25.44112 11.18581 5.199999 24.96632 12.45568 5.199998 27.94972 10.69264 5.199999 25.39469 13.74196 5.199998 28.86985 11.68829 5.199999 26.60827 10.49604 5.199999 26.2021 14.33331 5.199999 27.04405 14.5104 5.199999 28.66562 13.66254 5.199999 28.99464 12.71744 5.199999 27.8548 14.30832 3.8 26.61709 14.47406 3.8 25.69947 14.03533 3.8 25.19568 13.36877 3.8 24.9705 12.35692 3.8 25.40427 11.25806 3.8 26.36965 10.55817 3.799999 27.5511 10.55086 3.8 28.28467 10.95068 3.8 28.82198 11.62286 3.8 29.0149 12.62152 3.799999 28.69629 13.5874 3.8 27.79363 14.36659 3.8 28.47582 14.56474 3.8 29.45014 13.17815 3.8 29.33714 11.48721 3.8 28.36833 10.37265 3.8 27.38723 10.01445 3.799999 26.31285 10.06541 3.8 25.21649 10.70908 3.8 24.57326 11.80586 3.8 24.58757 13.29629 3.8 25.4584 14.48902 3.8 26.84666 15.03145 24.8 28.1665 10.84508 24.8 25.02264 12.01575 24.8 28.98153 11.94136 24.8 25.51483 11.14429 24.8 28.91026 13.10901 24.8 28.37271 13.99539 24.8 26.94784 14.54797 24.8 25.55755 13.92704 24.8 25.07353 13.05099 24.8 26.36967 10.55817 24.8 27.36971 10.52033 26.2 27.05371 14.54797 26.2 25.7668 14.08969 26.2 25.14462 13.28508 26.2 25.00183 12.11233 26.2 25.47467 11.18988 26.2 26.13025 10.67175 26.2 27.29586 10.47933 26.2 28.62183 11.22792 26.2 29.02478 12.70197 26.2 28.44405 13.927 26.2 27.58175 14.96889 26.2 25.89715 14.78422 26.2 24.70249 13.58224 26.2 24.5281 11.89656 26.2 25.14319 10.80725 26.2 26.0112 10.172 26.2 27.49139 9.996888 26.2 28.60574 10.56531 26.20001 29.27725 11.4053 26.2 29.51509 12.87685 26.2 28.8584 14.19962 24.8 25.01916 24.87544 24.8 25.13168 23.68836 24.8 28.85689 25.2851 24.8 26.05182 22.69264 24.8 27.215 22.48579 24.8 28.46115 23.04535 24.8 29.0077 24.27922 24.8 25.97885 26.23302 24.8 27.12408 26.52369 24.8 28.23468 26.08972 24.8 25.36964 25.66116 26.2 26.36942 26.40958 26.2 25.27834 25.61534 26.2 25.00183 24.11234 26.2 25.57336 23.06577 26.2 26.77371 22.44917 26.2 28.24022 22.87887 26.2 28.97891 24.01575 26.2 28.88922 25.20474 26.2 28.302 26.03531 26.2 27.38445 26.47406 26.2 29.3832 23.60187 26.2 29.41397 25.29625 26.2 28.54315 26.48901 26.2 27.1549 27.03145 26.2 25.72347 26.66819 26.2 24.96188 25.95332 26.2 24.52378 24.97115 26.2 24.66442 23.48727 26.2 25.81464 22.24262 26.20001 27.49139 21.99689 26.2 28.60573 22.56524 14.69261 11.01223 27.49262 13.63439 10.48686 27.4926 13.01899 9.465554 27.49262 13.23146 7.952179 27.49263 14.28783 7.112362 27.49262 15.2992 7.00483 27.49262 16.23463 7.404209 27.49262 16.7663 8.048798 27.49262 17.0342 9.0502 27.49262 16.64754 10.16647 27.49263 15.86984 10.82198 27.49262 12.99838 8.860901 29.69262 13.21732 8.054505 29.69261 14.04006 7.206634 29.69262 15.21336 6.993838 29.69262 16.16504 7.352745 29.69261 16.73671 7.99588 29.69261 17.0342 8.951358 29.69262 16.7663 9.95279 29.69264 16.23462 10.59737 29.69262 15.13568 11.03105 29.69262 13.97888 10.74164 29.69259 13.16672 9.883679 29.69261 13.12149 10.71561 29.69262 12.46117 9.154862 29.69262 12.82443 7.72348 29.69263 13.91038 6.702476 29.69261 15.14433 6.496807 29.69262 16.1838 6.772957 29.69263 16.97502 7.454819 29.69264 17.51609 8.632643 29.69266 17.35198 9.871949 29.69262 16.63355 10.95035 29.69263 15.26673 11.50944 29.69262 14.22936 11.38758 29.69262 17.37827 9.875641 30.49262 16.6853 10.85828 30.49266 15.79028 11.3966 30.49262 14.31445 11.45015 30.49263 13.0716 10.62739 30.4926 12.58263 9.669388 30.49262 12.50491 8.627846 30.49262 12.90097 7.627869 30.49262 13.63153 6.881363 30.49259 15.04621 6.457694 30.49262 16.45631 6.940746 30.49262 17.43513 8.208235 30.49255</float_array> + <technique_common> + <accessor source="#Link4-mesh-positions-array" count="3666" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Link4-mesh-normals"> + <float_array id="Link4-mesh-normals-array" count="22188">-0.08957082 0.9957974 -0.01909434 0.008952796 0.9932667 -0.1155047 0.01493918 0.9867722 0.1614233 -0.1426048 0.9897609 0.006102383 0.1390774 0.9797221 -0.1442297 -0.1520364 0.9784501 0.1397157 0.8386694 0.5446409 0 0.8386691 0.5446411 0 0.7333598 0.6798016 0.007298409 -3.1336e-7 -2.03499e-7 -1 4.77379e-7 5.20463e-6 -1 -4.0938e-6 -2.91247e-6 -1 -3.36155e-6 -2.02309e-6 -1 6.91495e-7 3.46138e-6 -1 3.22854e-6 3.24372e-6 -1 0.5993467 0.7998267 0.03257077 0.6142026 0.7889664 -0.01694369 -3.07457e-7 -2.17659e-6 1 0 0 1 -2.60871e-7 1.8106e-6 1 1.44773e-6 5.37761e-6 1 2.73857e-7 -6.443e-6 1 3.38732e-6 -5.00702e-6 1 0.7271539 0.6864315 -0.007680654 0.8386694 0.5446409 0 0.9644201 0.2586212 0.05485445 -5.69515e-4 0.9999998 -4.9951e-5 5.3005e-4 0.999984 0.005638659 -0.8386694 0.5446409 0 -0.8386709 0.5446387 -3.57407e-7 -0.7333984 0.6797599 -0.007296502 0 0 1 3.04267e-7 -2.15401e-6 1 6.34397e-6 -6.39633e-6 1 -1.01891e-5 1.38902e-5 1 1.00499e-6 3.78715e-6 1 -5.18831e-6 2.83158e-6 1 -0.6117977 0.7858708 0.09005886 -0.5292516 0.8341739 -0.1550694 0 2.27794e-6 -1 3.11146e-7 -2.02062e-7 -1 0 0 -1 2.50918e-7 1.76758e-6 -1 2.8756e-6 -3.60967e-6 -1 -6.84637e-7 -3.61451e-6 -1 -0.7271656 0.6864191 0.007680416 -0.8386694 0.5446409 4.74402e-7 -0.9644212 0.2586169 -0.05485463 0.02155816 0.9956616 0.0905165 0.04383003 0.9980694 -0.04400503 1.9196e-7 0 1 -4.49336e-7 6.98936e-6 1 -2.77895e-6 4.57191e-6 1 -3.00275e-6 4.74095e-6 1 -1.56358e-6 1.61448e-6 1 -0.0364691 0.9952306 0.09047728 -0.01940351 0.9997192 -0.01359832 2.78361e-6 5.21814e-5 -1 -3.5705e-7 0 -1 -9.31775e-7 -8.89122e-6 -1 -2.18669e-5 -8.17913e-6 -1 -3.63074e-5 5.22451e-5 -1 0.9999867 2.61827e-4 0.005162954 1 0 0 0.9999753 0 0.007013857 0.9999754 0 0.007013857 0.9999754 0 0.007013857 0.9999915 0 -0.004123985 1 0 0 0.9999904 0 -0.00440061 0.9999904 0 -0.00440061 0.9999904 0 -0.00440061 1 0 0 1 -4.46621e-7 -7.13276e-7 1 0 0 0.9999754 0 0.007013857 0.9999755 0 0.007013857 0.9999753 0 0.007013857 1 0 0 1 0 0 1 0 0 1 0 0 0.9999915 0 -0.004123985 0.9999907 2.75082e-5 -0.004320919 0.999975 -0.007065534 0 0.999975 -0.007065534 0 0.9999728 -0.007358789 3.25123e-5 0.9999716 -0.007533073 0 0.9999903 0 0.004404664 1 -2.57581e-6 1.23725e-6 1 1.17934e-6 2.53463e-6 1 1.76649e-6 3.79652e-6 1 0 -1.92048e-6 1 -1.06649e-6 1.60787e-6 1 3.47937e-6 -1.67127e-6 1 -1.79275e-6 0 1 -7.46813e-7 4.53483e-7 1 0 0 1 2.11151e-6 1.75707e-6 1 0 0 1 2.55385e-6 -1.8224e-6 1 -1.28366e-6 0 1 0 0 1 3.76474e-6 -1.22809e-5 -0.9999819 0 -0.006024599 -1 0 0 -0.9999828 0 0.005856812 -0.9999829 0 0.005856812 -0.9999829 0 0.005856812 -1 0 0 -1 0 0 -0.9999372 -0.01120519 0 -0.9999554 -0.009438991 -3.27699e-4 -1 0 0 -1 0 0 -0.9999829 0 0.005856812 -0.9999829 0 0.005856812 -1 0 0 -1 0 0 -1 0 0 -0.9999791 0 -0.006472826 -0.9999791 0 -0.006472826 -0.9999811 -4.49539e-5 -0.006153881 -0.9999818 0 -0.006024599 -0.9999819 0 -0.006024599 -0.9999928 0 0.003802537 -0.9999789 -0.006488263 0 -0.9999789 -0.006488263 0 -1 -3.14041e-7 0 -1 8.94212e-7 -5.42331e-7 -1 -5.7258e-7 3.47264e-7 -1 1.54961e-7 -1.38094e-7 -1 2.73638e-7 -5.65152e-7 -1 9.39409e-7 2.95997e-7 -0.9999903 2.05404e-4 0.004398822 -0.9999828 0 0.005856752 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.48365e-7 3.26285e-7 -1 -2.68152e-7 -3.5228e-7 -1 -3.56929e-7 7.37176e-7 -1 0 -4.83695e-7 -1 0 -2.81919e-7 -1 0 0 -1 0 4.68152e-7 -1 3.43742e-7 -6.73772e-7 -3.14005e-4 0.04666692 0.9989104 4.57929e-6 -2.0585e-5 1 -0.001872658 -4.45142e-4 0.9999982 -0.003243386 0.001571953 0.9999935 -0.01726329 0.01438963 0.9997474 -0.001923382 0.03905957 0.999235 -3.13393e-5 0.03530895 0.9993764 6.03227e-4 0.01940727 0.9998115 -4.25123e-4 0.03960138 0.9992155 3.87085e-6 -4.17699e-5 1 -0.01170068 0.02133458 0.999704 -0.01478958 0.02675801 0.9995325 -0.007143676 0.02161854 0.9997407 0.002616941 1.62832e-5 0.9999966 0.004675447 0.01757967 0.9998345 0.008788704 0.01612752 0.9998313 -0.001451909 -0.004911601 0.9999869 -4.49851e-5 3.05085e-5 1 0 4.12624e-6 1 -1.56546e-7 4.70381e-6 1 0.004219532 -8.9084e-4 0.9999908 -3.32364e-4 -3.78283e-4 0.9999998 -0.001832425 -2.60711e-4 0.9999983 -1.45243e-6 1.13816e-5 1 -5.11115e-6 -5.23921e-6 1 0 1.30402e-5 1 3.58786e-4 -0.001158893 0.9999994 -3.5662e-6 -2.65764e-6 1 -6.67219e-7 -6.04812e-6 1 -0.003825247 -0.0016613 0.9999914 0.002353072 -0.001033425 0.9999967 0.002085924 -1.82404e-4 0.9999978 0.007684707 2.58904e-4 0.9999705 1.6497e-5 -1.08315e-5 1 7.3797e-6 -1.76688e-7 1 7.07375e-7 -2.48889e-7 1 -9.74104e-6 5.50543e-6 1 7.11315e-6 -3.00499e-6 1 9.77662e-5 -4.2834e-5 1 5.68689e-7 1.89878e-6 1 0.004418075 -0.003864705 0.9999828 0.003233909 -0.004209458 0.9999859 0.00332266 -0.001762866 0.9999929 -4.36072e-7 -1.7738e-6 1 1.37293e-5 -6.27236e-6 1 -6.5945e-6 2.3388e-6 1 -1.77224e-6 2.76772e-6 1 4.16652e-4 -6.70436e-4 0.9999997 -2.93433e-6 -8.37309e-6 1 4.95633e-6 1.51172e-6 1 -9.02198e-5 1.18393e-5 1 2.2746e-4 -3.42677e-4 0.9999999 0.0110957 0.001041352 0.999938 -4.35171e-6 -6.25982e-6 1 1.70636e-4 1.96653e-5 1 -0.006067752 -4.24145e-4 0.9999815 0.01243072 0.0105645 0.9998669 -9.86283e-6 1.6842e-5 1 -1.903e-5 3.55414e-5 1 -1.90454e-6 8.43489e-6 1 7.93215e-6 -1.57136e-5 1 -0.001141428 -0.003331124 0.9999939 -0.001481056 -0.002082467 0.9999967 -0.008698701 0.002798855 0.9999583 -0.01756513 0.002322971 0.999843 -1.2077e-4 -4.03096e-4 1 -1.04811e-6 -9.50077e-6 1 8.91432e-6 -1.97897e-7 1 -0.003701031 -0.003392219 0.9999874 -0.003803849 -0.003374338 0.9999871 -2.33359e-6 -3.36024e-6 1 -9.7223e-6 -9.55891e-6 1 0 -1.48024e-6 -1 1.85332e-7 -2.87832e-6 -1 0 -1.83324e-6 -1 -1.46868e-7 2.28096e-6 -1 -1.19661e-7 2.39382e-6 -1 -1.50795e-7 2.33318e-6 -1 1.46888e-6 -1.09781e-6 -1 0 2.48959e-7 -1 -6.37372e-7 1.38327e-6 -1 1.4307e-6 3.33399e-7 -1 8.78469e-7 -1.35353e-6 -1 4.33779e-7 4.39817e-7 -1 -8.04386e-6 -2.70588e-6 -1 -2.5962e-6 0 -1 7.73702e-6 -9.25092e-7 -1 -5.7058e-7 0 -1 1.84699e-6 0 -1 -1.95911e-6 9.67742e-7 -1 2.72678e-6 -1.78343e-6 -1 1.59706e-6 5.37237e-7 -1 3.85434e-7 -1.12111e-6 -1 6.99215e-7 -1.4641e-6 -1 1.46973e-6 4.24275e-6 -1 -3.55069e-6 1.16493e-5 -1 1.02996e-6 5.25581e-6 -1 3.15895e-6 -1.07857e-5 -1 -5.97985e-7 1.25213e-6 -1 -1.90158e-7 -4.26044e-7 -1 -5.42845e-7 4.52106e-7 -1 -1.39669e-7 1.40758e-6 -1 3.3404e-7 2.84368e-6 -1 7.63928e-7 -5.48519e-7 -1 0 -1.45297e-6 -1 3.07522e-6 -1.51958e-6 -1 2.39366e-6 2.26968e-7 -1 0 -1.32755e-7 -1 -1.65519e-6 0 -1 -2.19687e-6 4.95548e-7 -1 4.62183e-7 -5.79727e-7 -1 -3.60905e-6 4.09825e-7 -1 -0.9297329 0.3682313 -0.001574218 -0.9004898 0.4336819 -0.03221923 -0.7143552 0.6991356 0.03010183 -0.4554818 0.8896802 -0.03170961 -0.3377765 0.9411354 0.01307743 0.08017301 0.996765 -0.005630373 0.09436923 0.9954557 -0.01274389 0.6206926 0.7839505 0.01273703 0.678483 0.7341794 -0.02532482 0.9351038 0.3531017 0.03000026 0.9782593 0.2060883 -0.02316117 0.9843661 -0.1750846 0.0191999 0.9764967 -0.2155269 0.00157535 0.7441867 -0.6677622 -0.01672863 0.7173141 -0.6967417 0.003402292 0.337456 -0.9411311 0.01989352 0.2474368 -0.9686999 -0.01988452 -0.1738607 -0.9847595 -0.004592061 -0.2693458 -0.9623144 0.03746908 -0.6351045 -0.7712895 -0.0418899 -0.797555 -0.601791 0.0418747 -0.9728805 -0.2282525 -0.03747397 -0.9942281 -0.106128 0.0157212 -0.9975373 -0.06340003 -0.03000009 -0.9312014 0.3638371 0.02205651 -0.8883551 0.4586266 -0.02206492 -0.5893346 0.8072059 0.03321754 -0.455453 0.8896402 -0.03320842 -0.009594798 0.9997106 0.02206182 0.06384837 0.9979181 -0.009092688 0.5058982 0.8625453 0.009090185 0.5153575 0.8569639 0.00443232 0.824681 0.5654154 -0.01437705 0.8489394 0.5284703 0.004593431 0.9871473 0.1586818 0.01898002 0.9990173 0.0377869 -0.02316343 0.940623 -0.3389095 0.01920205 0.9260417 -0.3774178 0.00158751 0.668389 -0.7436677 -0.0146479 0.5676524 -0.8227331 0.02968358 0.328381 -0.9442461 -0.02377516 0.06382745 -0.9975458 0.02877974 -0.1166565 -0.9929673 -0.0201826 -0.4073354 -0.9131817 0.01330858 -0.4919644 -0.8705132 -0.01332938 -0.7290098 -0.6842063 0.02016925 -0.8399679 -0.5418726 -0.02877718 -0.9687073 -0.2458546 0.03408175 -0.9952743 0.09092628 0.03408044 -0.9701337 0.2418268 -0.01897966 -0.7822148 0.6229997 -0.00340569 -0.7738164 0.6334009 0.003404557 -0.4408029 0.8974031 0.01898604 -0.3286703 0.9441606 -0.02316403 0.04861468 0.998633 0.01920431 0.08973318 0.9959647 0.001577973 0.5678069 0.8229915 -0.01674008 0.6206324 0.783923 0.01673108 0.9449176 0.3272893 -0.003557682 0.9407903 0.3389706 0.003550171 0.9872179 -0.1587012 -0.01465314 0.9585096 -0.2835111 0.02968174 0.8318673 -0.5541712 -0.02985405 0.6553931 -0.7540252 0.04365831 0.3782297 -0.9246817 -0.04365611 0.09427851 -0.9948578 0.0370081 -0.1166416 -0.9929691 -0.02017706 -0.4556554 -0.8899491 0.01920509 -0.4920125 -0.8705866 0.001583933 -0.8225482 -0.5685069 -0.0146504 -0.8881807 -0.4585344 0.0296812 -0.9783055 -0.2057986 -0.02377671 -0.9952578 0.09515571 0.02018177 -0.9617086 0.2725585 -0.02877932 -0.8538814 0.5199243 0.02377849 -0.684666 0.7282522 -0.02968323 -0.5636498 0.8256618 0.02411162 -0.10284 0.9942196 -0.03084528 0.01815468 0.9993591 0.0308513 0.5445851 0.8381382 -0.03084731 0.6419432 0.7661314 0.03084534 0.9404423 0.3388339 -0.02756357 0.9805354 0.1927351 0.03746283 0.9746345 -0.2198485 -0.04188466 0.8964086 -0.4412446 0.0418896 0.6649917 -0.7461772 -0.03171241 0.5187738 -0.8543232 0.03171247 0.1594094 -0.9863234 -0.04188925 -0.1027471 -0.9933645 0.05167275 -0.4158747 -0.9087371 -0.03528738 -0.6847203 -0.728308 0.0269373 -0.7538928 -0.6569476 -0.008100569 -0.9546718 -0.2975503 0.008095145 -0.972783 -0.2311528 -0.01617723 1 -4.18908e-6 -2.70475e-6 1 2.8623e-6 1.84809e-6 1 9.32977e-7 1.30137e-6 1 -5.55214e-7 -1.67348e-6 1 1.06592e-6 1.38775e-6 1 -3.49526e-6 -4.55056e-6 1 3.62081e-6 1.03978e-6 1 3.06121e-6 3.11217e-7 1 -2.23081e-6 4.24377e-7 1 1.38334e-6 -1.44194e-6 1 -4.04843e-6 0 1 -1.23372e-6 2.34695e-7 1 2.56602e-6 0 1 2.01266e-6 6.70224e-7 1 -3.8303e-6 -3.94306e-6 1 7.66627e-6 -1.98956e-6 1 3.48548e-6 1.16068e-6 3.63621e-6 -2.66354e-7 -1 -3.27809e-7 9.59726e-7 -1 -7.09368e-7 5.66753e-7 -1 -7.49214e-7 -1.20195e-6 -1 1.51038e-7 -9.55365e-7 -1 1.31831e-7 -8.33871e-7 -1 -3.67387e-7 -8.06806e-7 -1 1.73761e-6 3.81592e-6 -1 4.40461e-6 1.88487e-6 -1 -8.3598e-7 -1.50369e-6 -1 -8.61973e-7 -8.50671e-7 -1 -4.84942e-6 3.27242e-6 -1 -2.15567e-6 3.70685e-6 -1 -2.51791e-6 1.37615e-6 -1 -2.11581e-6 9.73851e-7 -1 1.49906e-6 8.08571e-7 -1 -1.45455e-6 -3.7964e-6 -1 -5.00796e-6 1.40511e-6 -1 5.5116e-6 5.99813e-6 -1 8.7966e-6 -1.68945e-6 -1 -4.05258e-7 -7.87071e-7 -1 -1.9338e-7 -3.75572e-7 -1 2.01473e-6 -2.22425e-6 -1 1.53729e-5 3.4714e-6 -1 -1.70228e-6 -2.31463e-6 -1 -1.54031e-6 8.58361e-7 -1 -1.48305e-6 8.42362e-7 -1 -1.64142e-6 6.41332e-7 -1 -3.80861e-6 3.14339e-6 -1 -5.0942e-6 2.15799e-7 -1 2.14009e-6 -2.24679e-6 -1 2.67247e-6 -8.73247e-7 -1 -4.10586e-7 1.11337e-6 -1 -1.10397e-6 0 -1 -2.36593e-6 1.52602e-6 -1 1.6693e-6 3.39705e-6 -1 1.15623e-6 -2.54395e-6 -1 1.22977e-6 -2.57008e-6 -1 2.02821e-6 -8.30062e-7 -1 1.13454e-6 0 -1 1.77935e-6 2.16913e-7 -1 1.21288e-6 1.51067e-6 -1 -3.0662e-6 2.33158e-6 -1 -2.98587e-6 2.79331e-6 -1 2.49842e-6 -2.3373e-6 -1 -1.21208e-6 -5.17246e-6 -1 -3.50005e-6 1.11987e-5 -1 1.08741e-6 9.29393e-7 -1 3.22809e-6 -1.90762e-6 -1 -7.32137e-7 -1.61865e-6 -1 -5.49953e-7 2.58257e-7 -1 -8.40746e-7 3.94812e-7 -1 0 2.14383e-6 -1 7.54624e-7 1.47387e-6 -1 1.54751e-6 1.98948e-6 -1 1.42241e-6 7.34338e-7 -1 2.2497e-6 6.00661e-7 -1 7.25696e-7 -1.2822e-6 -1 -3.27447e-6 2.2278e-6 -1 -4.94532e-6 -1.78797e-7 -1 9.03244e-6 -3.23199e-6 -1 1.59945e-6 -1.23164e-5 -1 1.22316e-6 3.97525e-7 -1 1.23148e-6 3.94505e-7 -1 -3.05898e-6 -6.30405e-6 -1 -1.6722e-6 -7.204e-6 -1 -3.89675e-7 1.52031e-7 -1 -3.82554e-6 1.49253e-6 -1 -5.01771e-6 -8.83704e-7 -1 -2.42231e-6 -2.0703e-6 -1 1.10366e-6 9.6052e-7 -1 8.80685e-7 3.52946e-7 -1 1.33382e-6 -1.64746e-7 -1 0 0 -1 0 -5.7465e-7 -1 2.99278e-7 -7.72231e-7 -1 5.81008e-6 3.59912e-6 -1 1.18101e-5 -1.51814e-5 -1 1.81399e-6 -1.27984e-5 -1 6.2105e-6 -1.45524e-6 -1 1.08884e-6 1.84483e-6 -1 -1.57592e-6 -2.6701e-6 -1 -2.16634e-6 -2.57647e-6 -1 -2.39214e-6 -3.40253e-6 -1 -4.80246e-6 -2.15864e-6 -1 2.47297e-7 1.48241e-6 -1 7.47034e-7 3.48508e-7 -1 2.06614e-6 3.20064e-7 -1 4.4779e-7 -3.07038e-6 -1 -2.83236e-7 -1.32323e-7 -1 -9.64081e-7 -4.50402e-7 -1 -1.345e-6 6.70748e-7 -1 0.2904221 -0.05958741 -0.9550415 0.2914889 0.06022727 -0.9546763 0.2143153 0.1292886 -0.9681701 -0.001926124 0.2956529 -0.9552935 -0.1233557 0.2312341 -0.9650463 -0.2779376 0.08659654 -0.956688 -0.1838718 0.1412684 -0.9727458 -0.2983343 -0.04706346 -0.9533005 -0.230838 -0.1221325 -0.9652966 -0.07523185 -0.2861381 -0.9552304 0.04119819 -0.2666397 -0.9629154 0.2122205 -0.1280071 -0.9688017 -0.1628213 -0.212971 -0.9633963 -0.1710858 -0.1170328 -0.9782807 -0.1325804 -0.1503355 -0.9797049 -0.1381837 0.1100721 -0.984271 -0.1638207 0.1433643 -0.9760171 0.0159915 -0.2555754 -0.9666568 -0.04959821 -0.1183872 -0.991728 0.08044683 0.009923994 -0.9967095 0.1551251 -0.2241085 -0.9621391 0.2033747 -0.1300369 -0.9704273 0.05904084 0.004947245 -0.9982434 0.1621458 0.1400593 -0.9767764 0.1351481 0.2182632 -0.9664865 7.70312e-7 -1.65912e-6 -1 -1.14099e-6 -4.24634e-6 -1 5.03343e-6 -1.04571e-6 -1 -2.992e-6 -9.24584e-7 -1 6.3371e-6 3.63579e-6 -1 -4.40905e-6 0 -1 -6.07604e-7 0 -1 -3.53197e-7 -1.71997e-7 -1 -2.76105e-6 -2.8374e-7 -1 3.98304e-6 -2.42812e-6 -1 2.87817e-7 -9.40572e-7 -1 -1.93409e-6 -9.76024e-7 -1 2.3896e-6 -1.54304e-6 -1 2.50527e-6 4.22466e-6 -1 -5.78048e-6 -2.23084e-6 -1 1.72477e-6 -2.78251e-6 -1 1.68392e-6 2.31592e-6 -1 1.46355e-6 7.30686e-7 -1 -8.61564e-7 2.05892e-6 -1 -7.22852e-7 6.85448e-7 -1 0 7.00724e-7 -1 3.356e-7 -3.27636e-6 -1 -8.89565e-7 0 -1 -1 0 0 -1 4.06976e-7 0 -1 -4.51986e-7 -1.86413e-7 -1 6.02172e-7 0 -1 -2.44732e-7 -2.18086e-7 -1 1.00692e-6 0 -1 6.17911e-7 1.47724e-7 -1 -1.34036e-6 6.13866e-7 -1 -6.84713e-7 0 -1 -3.71959e-7 -1.57549e-7 -1 6.35113e-7 1.77759e-7 -1 6.40382e-7 1.81188e-7 -1 0 0 -1 -4.68006e-7 0 -1 -6.26666e-7 0 -1 2.01227e-6 7.80498e-7 -1 -5.07834e-7 0 -1 0 -1.28533e-7 -1 0 0 -0.04711318 0.06332772 -0.9968801 0.05350816 0.2456205 -0.9678881 -0.06211024 0.5873888 -0.806918 0.06222337 0.7271504 -0.6836524 -0.04911893 0.9823064 -0.1807248 0.02188861 0.9944533 -0.102876 -0.02189111 0.8637867 0.5033819 0.0218442 0.8383532 0.5446898 -0.02383542 0.3288088 0.9440957 -0.003605365 0.310125 0.9506889 0.02916884 -0.3271313 0.9445286 -0.0677278 -0.4383351 0.8962563 0.06574308 -0.7823298 0.6193851 -0.09678053 -0.9251947 0.3669444 0.09683996 -0.9951357 0.01807969 -0.09192818 -0.9122631 -0.3991556 0.05210864 -0.8065754 -0.58883 -0.03465807 -0.4584952 -0.8880208 0.03467053 -0.3637071 -0.9308679 -0.08104288 0.06037944 -0.9948801 0.055399 0.3765789 -0.9247266 -0.04230761 0.6528574 -0.7562985 0.02978157 0.7458965 -0.6653956 -0.04235398 0.9403713 -0.3375024 0.04857915 0.9899249 -0.133 -0.02901422 0.9981818 0.05283164 0.02901989 0.9313259 0.363029 -0.03713482 0.8619647 0.5056062 0.04687732 0.6960101 0.7165002 -0.04561388 0.5279607 0.848043 0.03404581 0.1315656 0.9907226 -0.005582392 0.1751011 0.9845346 0.02470463 -0.3531415 0.9352437 -0.04020887 -0.441244 0.896486 0.04020708 -0.7833861 0.6202337 -0.007205367 -0.8257009 0.5640622 -0.02983617 -0.9792599 0.2003998 0.05350518 -0.9973868 0.04854756 -0.05351388 -0.9529664 -0.298314 0.07992762 -0.8500955 -0.5205279 -0.0968436 -0.5771974 -0.8108418 0.09677535 -0.2551092 -0.9620571 0.2038996 0.9748581 -0.08986979 0.3161866 0.944384 0.09036028 0.6746647 0.7342202 -0.07581746 0.7466658 0.6636775 0.04497104 0.9461854 0.3232687 -0.01518088 0.9561851 0.2828232 -0.07563966 0.9882771 -0.1215826 0.09233582 0.9519988 -0.2964047 -0.0764364 0.8663435 -0.4958963 0.05946284 0.7449297 -0.6621466 -0.08149623 0.5154979 -0.8489444 0.1164271 0.3510177 -0.9307281 -0.102625 -0.08003914 -0.9937613 0.0776689 -0.1785702 -0.9815586 -0.06822979 -0.5516372 -0.828764 0.0940569 -0.7137097 -0.6924169 -0.1057233 -0.8326648 -0.5501356 0.06340497 -0.9757636 -0.2005079 -0.08764731 -0.9928998 -0.1060033 0.05397516 -0.9296952 0.3682898 -0.005432784 -0.8954837 0.431271 -0.1100646 -0.7109191 0.6956924 0.102985 -0.4243969 0.8963618 -0.1281517 -0.3030627 0.9505577 0.06777179 -0.9139986 0.3976656 -0.08042746 -0.719258 0.6908668 0.07328718 -0.688363 0.7253461 0.005423486 -0.3023918 0.9518548 -0.05031514 -0.2036243 0.9764837 0.07083082 0.1200755 0.9902349 -0.07082825 0.2205797 0.9740701 0.05031782 0.65326 0.7570654 -0.01017105 0.6559363 0.7546287 -0.01682788 0.9356873 0.3526256 -0.01202231 0.9491969 0.3117677 0.0427348 0.9954246 -0.07369774 -0.06081575 0.9915551 -0.1286159 0.01662606 0.8519662 -0.5191328 0.06822687 0.7768589 -0.6193658 -0.1134739 0.4432825 -0.8940199 0.06503248 0.3226953 -0.9419966 -0.09225106 0.03185784 -0.9941711 0.1029999 -0.2852124 -0.9523128 -0.108417 -0.4297058 -0.8997797 0.07582414 -0.7540746 -0.6509125 -0.08766096 -0.8009432 -0.5985333 0.01574444 -0.9682372 -0.2413933 0.06516212 -0.9890528 -0.08973628 -0.1171403 -0.9720449 0.2181585 0.08680766 0.5619698 0.8250171 -0.05947136 0.6838565 0.7240709 0.0897873 0.8632736 0.4941144 -0.1030024 0.966646 0.2448042 0.07527542 0.9929826 0.09120881 -0.0752775 0.9785697 -0.1783066 0.1029962 0.8538516 -0.5045781 -0.127821 0.77082 -0.630069 0.09407281 0.4149464 -0.906511 -0.0778287 0.2329255 -0.9623363 0.1401951 -0.03121244 -0.9918334 -0.1236622 -0.3992754 -0.9063618 0.1381571 -0.6068844 -0.7802094 -0.1515411 -0.8100929 -0.5731735 0.1233761 -0.9604623 -0.2564392 -0.1084032 -0.9914872 -0.1058509 0.0758208 -0.9683551 0.2413986 -0.06336581 -0.9035606 0.4151929 0.1057972 -0.7976293 0.5960403 -0.09232276 -0.5174957 0.8532112 0.06502974 -0.4014214 0.9112359 -0.09224903 -0.1160523 0.9878883 0.1029973 0.175646 0.9803421 -0.08987665 0.3218709 0.9455615 0.04808932 0.7490257 -0.6494891 0.1308605 0.5296408 -0.8338278 -0.1556018 0.259175 -0.9575397 0.1262772 -0.009522914 -0.9919501 -0.1262705 -0.2954088 -0.9437479 0.1485714 -0.6045059 -0.7771168 -0.1751061 -0.7898604 -0.5966161 0.1420204 -0.951912 -0.29648 -0.0772221 -0.9882974 -0.1370396 0.06699627 -0.9845654 0.157689 -0.07592797 -0.95424 0.2873985 0.08263301 -0.722984 0.6843941 -0.09433382 -0.633207 0.7689995 0.08768498 -0.3021678 0.9511457 -0.06337374 -0.1201994 0.9870975 0.1057865 0.0893383 0.9917123 -0.09233242 0.501571 0.8607502 0.08680742 0.5673626 0.8223041 -0.04376643 0.9334403 0.3555286 0.04783838 0.9496018 0.3097878 -0.04783266 0.9668285 -0.2524356 0.03897511 0.9362716 -0.3387859 -0.09284251 -0.8400996 0.5414229 0.03307223 -0.8441714 0.535793 0.01733845 -0.5929756 0.8049061 -0.02249664 -0.5775102 0.8161242 0.02057331 -0.1399779 0.9895865 0.03353816 -0.1495276 0.9867072 0.06364178 0.2588178 0.9591517 -0.1141988 0.3928174 0.907259 0.1502519 0.6220272 0.7723057 -0.128942 0.7563821 0.6469908 0.09637957 0.8664335 0.4897852 -0.0969718 0.9445035 0.3108524 0.1062269 0.9758569 0.164269 -0.1439406 0.9496645 -0.2867578 0.1261243 0.9500634 -0.2976758 0.09364223 0.756166 -0.6368843 -0.1503046 0.5636051 -0.8068352 0.177105 0.4877855 -0.8716679 -0.04754352 0.06781244 -0.9964109 0.05066573 -3.98267e-4 -0.9920485 -0.1258562 -0.4299782 -0.888697 0.1591745 -0.531633 -0.83927 -0.1139839 -0.9762193 0.2039646 -0.07344514 -0.9691975 0.03765827 0.2433887 -0.969903 -0.2025718 -0.1351032 -0.8347954 -0.5406119 0.1041892 -0.8393691 -0.5364213 0.08781677 -0.9927815 0.1187497 0.01683849 -0.9612824 0.2753735 -0.01027405 -0.5749225 0.8182075 -8.7046e-4 -0.5244745 0.8513556 0.0109592 0.066697 0.9977322 -0.009053707 0.18686 0.9823449 0.009050309 0.7220926 0.6917095 -0.01095908 0.7808425 0.624694 0.006512165 0.9933623 -0.1150267 -4.45767e-4 0.9862015 -0.1651669 -0.01124864 0.6786518 -0.7343521 0.01260298 0.4754512 -0.8794152 -0.02397853 0.008329153 -0.9995881 0.0274651 -0.4193127 -0.9074265 -0.02746319 -0.7777289 -0.6282498 0.02097284 -0.9208856 -0.389599 -0.01350289 -0.783739 0.6210901 -3.65671e-4 -0.7454071 0.6663965 0.01684409 0.1769434 0.9841085 -0.01488339 0.3474429 0.9372846 0.02794259 0.8986208 0.4376031 -0.03137391 0.9956364 0.08714276 0.03338015 0.8889098 -0.4574928 -0.0232321 0.6575289 -0.7530178 0.02489894 0.2925005 -0.9558767 -0.02726155 -0.2384914 -0.9706726 0.03027397 -0.5666881 -0.8236157 -0.02284139 -0.923377 -0.3831371 0.02410477 -0.9764621 -0.215489 -0.009281635 -0.01457989 0.9996456 0.02227509 0.395273 0.9183232 -0.02102011 0.7080104 0.7056866 0.02697682 0.9410035 0.3372409 -0.02794635 0.9512172 -0.3073573 0.02678328 0.9111432 -0.4120898 3.2824e-4 0.2439015 -0.9697723 -0.007324695 0.06946241 -0.9970914 0.03136271 -0.4980469 -0.8666768 -0.02864474 -0.8991733 -0.4361723 0.03522962 -0.96657 -0.2563313 -0.00606513 -0.9008867 0.4338686 -0.01270854 -0.779103 0.6263027 0.02726942 -0.4025002 0.9151976 -0.02017295 -0.9980458 -0.05676901 -0.02611458 -0.8757612 0.4822438 0.0219835 -0.7255482 0.6880047 -0.01514804 -0.3432409 0.9391762 0.01156306 -0.1023743 0.9946293 -0.01523393 0.2823762 0.9592015 0.01399981 0.568592 0.8223713 -0.02020972 0.83459 0.5505905 0.01759451 0.9894946 0.1435721 -0.01695352 0.9993437 -0.03489518 0.00972712 0.7808065 -0.6246818 -0.01066362 0.7005959 -0.7134881 0.01000672 0.1570148 -0.9875455 -0.01000827 -0.0221529 -0.9995342 0.02099198 -0.6147155 -0.7882114 -0.02911412 -0.8844695 -0.4652301 0.03570342 -0.005572557 -0.09095525 -0.9958394 0.02627837 0.4586115 -0.8882483 -0.02628397 0.5159307 -0.856227 0.005560696 0.8956716 -0.4446814 0.02188485 0.9033771 -0.4282882 -0.02001613 0.9869933 0.1595102 0.0397948 0.9713804 0.2341722 -0.05214589 0.7455642 0.6643905 0.05213928 0.6321668 0.7730761 -0.03464698 0.2199302 0.9749001 -0.006944477 0.1792832 0.9837729 0.02259677 -0.2454218 0.9691529 -0.007209658 -0.2880719 0.9575815 -0.02981936 -0.6360513 0.7710704 0.06991231 -0.7646262 0.6406708 -0.04560202 -0.9082385 0.4159606 0.02895414 -0.9990684 0.03199958 -0.00884813 -0.9967436 0.0801503 0.02054667 -0.9410043 -0.3377706 -0.03472596 -0.9018152 -0.4307243 0.04023057 -0.6529332 -0.7563463 -0.0246911 -0.5774391 -0.8160604 0.005592823 -0.07861495 -0.9968894 0.008844375 0.2883481 -0.9574848 -0.02895355 0.2417705 -0.9699014 0.05121588 0.6221842 -0.7811939 -0.08104658 0.7867195 -0.6119672 0.06850683 0.9520952 -0.2980297 -0.05809366 0.9982652 -0.009576499 0.05809468 0.9636415 0.2608064 -0.06851518 0.8462646 0.5283387 0.0810393 0.607142 0.79045 -0.08103877 0.3547483 0.9314432 0.05540162 0.03775787 0.99775 -0.03448796 -0.2582832 0.9654535 0.03449171 -0.4055428 0.913425 -0.04728496 -0.6355953 0.770573 0.05882072 -0.8625035 0.5026212 -0.04328781 -0.9293099 0.3667552 0.04328668 -0.9917382 -0.1207549 -0.05881875 -0.9613254 -0.269061 0.06574994 -0.7702951 -0.634289 -0.06570523 -0.601029 -0.7965219 0.04981231 -0.2576411 -0.9649559 -0.02054524 -0.1318777 -0.9910531 1 -2.09055e-6 -2.54479e-7 1 -2.93821e-6 5.40573e-7 1 -5.0688e-6 -1.22192e-6 1 -2.64958e-6 -1.54408e-6 1 -2.005e-6 1.62862e-6 1 2.57071e-6 3.57247e-6 1 3.59213e-6 -6.59763e-7 1 -1.5926e-6 2.9251e-7 1 -1.58097e-6 3.91751e-7 1 2.689e-6 -6.6631e-7 1 2.27084e-6 4.46933e-7 1 8.84719e-6 1.74125e-6 1 7.52105e-6 -4.07426e-6 1 -8.85391e-7 -1.7497e-6 1 0 0 1 0 0 1 -4.71524e-7 2.91773e-6 1 -2.05755e-7 3.23892e-6 1 -3.51267e-7 3.32321e-6 1 0 0 1 -9.46107e-6 -3.66975e-6 1 7.48622e-6 2.90375e-6 1 2.21376e-6 6.97463e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 1.08517e-6 -1.63942e-6 1 -4.51946e-7 -3.40327e-6 1 2.01563e-7 -3.69125e-6 1 0 0 1 4.12138e-6 2.55353e-6 1 2.87476e-6 2.773e-6 1 3.03972e-6 1.70788e-6 1 0 0 1 2.82768e-6 -4.18984e-6 1 3.74026e-6 -3.27264e-6 1 -1.06415e-6 9.31107e-7 1 6.73571e-7 7.30706e-6 1 9.66671e-7 7.29548e-6 1 3.14059e-6 2.33674e-6 1 0 0 1 -9.53323e-6 4.71474e-6 3.92312e-5 -1.58368e-5 -1 1.44627e-5 -5.97529e-5 -1 1.36336e-4 -1.14608e-5 -1 0.00301975 -0.002467095 -0.9999925 5.2356e-4 -9.6791e-5 -0.9999998 0.001094341 7.72527e-5 -0.9999994 1.38434e-4 3.54383e-5 -1 2.78589e-5 7.58789e-5 -1 -1.19779e-5 1.17156e-5 -1 1.35214e-5 -1.35377e-5 -1 6.68126e-5 4.96607e-6 -1 4.30938e-5 5.08304e-5 -1 5.78349e-5 7.42536e-5 -1 -1.45755e-4 -6.01269e-4 -0.9999998 7.22926e-5 5.38785e-5 -1 4.12935e-5 4.86537e-5 -1 -1.54002e-4 7.37617e-4 -0.9999997 2.58393e-5 4.27022e-4 -1 5.11034e-6 5.23553e-4 -0.9999999 4.42431e-4 0.001951634 -0.999998 1.64336e-6 -2.23104e-6 -1 -4.72674e-4 7.74927e-4 -0.9999996 -9.63094e-7 -2.692e-7 -1 -5.3012e-7 -4.34193e-7 -1 7.47746e-6 -4.88418e-6 -1 5.6445e-6 -8.49418e-6 -1 -1.46761e-5 -2.89221e-5 -1 0 0 -1 -2.01248e-5 2.76201e-6 -1 -2.17104e-5 -1.79882e-5 -1 0 0 -1 -9.10981e-7 -2.81452e-7 -1 -8.11289e-6 2.43433e-5 -1 -7.24624e-4 -8.00532e-5 -0.9999998 -4.07896e-4 -4.33589e-5 -0.9999999 -0.006512999 1.25849e-4 -0.9999788 -0.002260804 0.002205669 -0.999995 -0.001993596 7.9476e-4 -0.9999977 -1.49269e-4 -1.02177e-4 -1 -1.52414e-4 -2.21705e-4 -1 -7.20838e-5 -3.69093e-6 -1 -7.36898e-5 -3.57456e-5 -1 -1.45419e-6 8.20896e-7 -1 -2.39417e-5 1.88683e-5 -1 -2.17411e-5 -5.31844e-5 -1 -8.67777e-5 -2.52155e-5 -1 -6.09699e-7 -2.12559e-6 -1 9.5395e-6 -2.81759e-6 -1 6.11519e-6 -2.37512e-6 -1 -9.41489e-5 -3.0186e-4 -0.9999999 -9.53773e-5 -2.38398e-4 -1 3.2256e-6 6.6118e-6 -1 3.42761e-6 -1.51125e-5 -1 -2.70203e-6 -6.24974e-7 -1 -4.41546e-5 -3.26037e-4 -0.9999999 3.00461e-5 9.89595e-5 -1 3.30531e-5 -2.92198e-6 -1 4.05075e-5 -2.59018e-5 -1 -2.34073e-6 -1.05613e-4 -1 2.96175e-5 2.11693e-5 -1 -6.71536e-5 -3.59392e-5 -1 4.54381e-5 -4.46042e-5 -1 4.63327e-5 -4.3994e-5 -1 -3.46735e-7 -2.22845e-6 -1 2.62345e-6 8.65561e-7 -1 0 0 -1 -1.83137e-6 -3.26413e-5 -1 0 0 -1 0 0 -1 -3.06358e-6 1.72527e-6 -1 6.09853e-7 -5.93646e-6 -1 -8.28036e-7 -2.71972e-7 -1 8.66736e-5 3.67903e-5 -1 -4.70734e-7 9.49385e-7 -1 2.16478e-5 1.05893e-5 -1 -9.26353e-7 1.20159e-7 -1 -6.20271e-7 3.77953e-7 -1 7.22446e-6 -8.27116e-7 -1 6.71338e-6 -8.3258e-7 -1 -4.12774e-7 1.32328e-7 -1 -5.76414e-7 3.06896e-6 -1 -1.76922e-7 -1.58604e-5 -1 5.18322e-7 -1.66165e-7 -1 2.59488e-7 0 -1 4.65067e-5 5.41424e-5 -1 3.88208e-5 1.00681e-4 -1 4.04876e-7 -6.67531e-7 -1 3.77837e-5 8.58974e-5 -1 3.20514e-7 -7.71824e-7 -1 8.55873e-7 -5.7095e-7 -1 1.60815e-6 -2.40481e-7 -1 4.90921e-6 -8.34356e-7 -1 1.5308e-6 -2.13773e-7 -1 -5.23412e-7 2.38264e-6 -1 9.05532e-6 -8.34683e-6 -1 5.61496e-5 -2.20453e-5 -1 -7.62009e-6 3.53899e-6 -1 -4.85955e-7 0 -1 1.05616e-6 4.78809e-7 -1 1.30946e-7 0 -1 -3.37358e-7 2.59359e-7 -1 0 -1.5403e-6 -1 -3.1357e-7 -2.76736e-6 -1 2.63803e-7 1.19595e-7 -1 -3.58811e-6 -4.54422e-7 -1 -2.2619e-6 -1.42012e-6 -1 -7.06719e-7 0 -1 1.0852e-6 0 -1 0 0 -1 1.20957e-6 1.25549e-6 -1 1.24389e-7 -2.87854e-6 -1 0 -7.30042e-6 -1 -4.513e-7 -3.86031e-7 -1 8.69619e-7 0 -1 -1.65065e-6 0 -1 -7.1185e-7 -2.34282e-7 -1 -4.84907e-7 -5.01732e-7 -1 3.2151e-7 2.7857e-6 -1 0 0 -1 -5.66921e-7 1.75646e-7 -1 0 -6.8035e-7 -1 -4.53059e-6 -2.91179e-5 -1 -4.7542e-5 1.21579e-4 -1 1.60489e-6 -4.10416e-6 -1 2.94142e-7 5.97637e-7 -1 1.53847e-7 3.12585e-7 -1 1.35459e-5 -6.16627e-5 -1 3.31552e-5 1.67178e-4 -1 -2.59681e-6 2.98368e-5 -1 -4.26395e-5 -1.06015e-4 -1 -3.48062e-7 -5.08515e-7 -1 -4.99611e-7 -3.15953e-7 -1 7.84278e-6 -4.3146e-6 -1 -5.70424e-6 -4.90841e-7 -1 1.46962e-6 6.34733e-6 -1 1.16781e-6 -3.35496e-6 -1 1.4989e-6 -3.12514e-6 -1 4.93133e-7 -1.02816e-6 -1 -1.10131e-5 -6.79498e-6 -1 -1.10376e-5 -6.73429e-6 -1 -1.44553e-6 -4.90435e-6 -1 -3.28039e-6 -2.00717e-6 -1 1.43065e-6 8.75367e-7 -1 -2.11997e-7 5.37895e-6 -1 -1.15888e-5 2.39271e-6 -1 -1.16701e-5 2.66251e-6 -1 2.31091e-6 4.52215e-6 -1 2.00201e-6 -1.05693e-6 -1 -6.1587e-6 -5.39725e-7 -1 -8.46873e-7 6.99928e-6 -1 7.73318e-6 -2.43875e-6 -1 2.92434e-5 6.1422e-6 -1 2.70464e-5 1.3292e-5 -1 -5.00501e-6 1.40835e-5 -1 -7.73388e-6 7.48221e-6 -1 3.23873e-6 -1.87502e-6 -1 7.46265e-6 -3.27561e-7 -1 9.63454e-7 3.1401e-6 -1 -4.72686e-7 3.35697e-6 -1 -3.43266e-7 2.43784e-6 -1 -4.30207e-6 1.43823e-6 -1 -3.27203e-6 -1.15801e-6 -1 7.42088e-7 -1.38701e-6 -1 8.86539e-7 1.00834e-6 -1 3.94069e-6 -1.75929e-6 -1 -2.42585e-6 -7.02704e-6 -1 -3.25888e-6 -1.44372e-6 -1 -4.33967e-6 -1.45702e-6 -1 -3.48504e-6 5.54422e-7 -1 1.08593e-6 -8.37946e-7 -1 9.07391e-7 -9.90537e-7 -1 -8.48592e-6 9.2635e-6 -1 -4.63701e-6 1.00327e-5 -1 -4.19243e-6 -2.76578e-6 -1 8.83359e-7 -6.62554e-7 -1 1.29458e-7 7.90903e-7 -1 7.30176e-6 5.54552e-6 -1 6.85387e-6 6.56075e-6 -1 3.54199e-6 0 -1 1.778e-6 -2.6614e-7 -1 0 -2.13509e-6 -1 -1.66317e-6 -1.28491e-6 -1 3.11332e-7 2.22659e-6 -1 3.13718e-6 6.93281e-7 -1 6.29219e-6 2.47661e-6 -1 1.26498e-5 -1.10189e-5 -1 4.89128e-6 -1.04487e-5 -1 7.40599e-6 -6.77936e-6 -1 6.54553e-6 7.01383e-7 -1 -9.33231e-7 0 -1 -9.61362e-7 -1.67486e-7 -1 -1.06901e-6 0 -1 -1.52755e-5 -8.17753e-6 -1 -1.47632e-5 -9.84633e-6 -1 -5.8615e-7 -8.37212e-6 -1 -9.35135e-7 4.66262e-7 -1 1.45544e-6 -7.2569e-7 -1 1.40697e-6 -7.52144e-7 -1 1.95756e-6 -1.96951e-6 -1 -2.58951e-7 -1.10577e-6 -1 2.07014e-7 8.83988e-7 -1 -0.9207456 0.3895493 0.02188539 -0.9137489 0.4062409 0.005574345 -0.5518126 0.8335536 -0.02629309 -0.4711979 0.8806958 0.04845035 0.06662005 0.9966021 -0.04843521 0.1336563 0.9910132 0.005366027 0.5558202 0.8307132 0.03129893 0.676954 0.7324811 -0.07214462 0.9320684 0.3550212 0.07217162 0.9780455 0.2060361 -0.03124451 0.9764763 -0.2155039 -0.007203936 0.938503 -0.3363479 0.07798796 0.7624233 -0.6430309 -0.07226324 0.4473319 -0.8926868 0.05481427 0.323872 -0.9454661 -0.03465515 -0.1612687 -0.9852437 0.05733448 -0.31525 -0.9466136 -0.06738013 -0.762308 -0.6460548 0.03872501 -0.8067162 -0.5908722 -0.008884906 -0.9765151 -0.2152628 0.008949756 -0.9842942 -0.1755913 -0.0182361 -0.9729057 0.2311676 -0.003979921 -0.9765213 0.2152399 0.008829772 -0.7820181 0.6228461 -0.02259159 -0.7364054 0.6760895 0.02470099 -0.2869083 0.9579418 -0.005584061 -0.2987469 0.9543161 0.005578219 0.2003716 0.9794494 -0.02302539 0.3236993 0.9450106 0.04662466 0.5886054 0.8070586 -0.04690492 0.7801046 0.6218892 0.06848639 0.9385855 0.3381752 -0.06851667 0.9969602 0.05192184 0.05808991 0.9868283 -0.158635 -0.03169953 0.8695839 -0.4928628 0.03017026 0.8143185 -0.5791254 -0.03871917 0.4198336 -0.905465 0.0622335 0.2441791 -0.9677391 -0.06210851 -0.07980734 -0.9961109 0.03733569 -0.3130803 -0.9489993 -0.03716498 -0.4593509 -0.887781 0.02901035 -0.7143992 -0.6991376 -0.02898955 -0.8007755 -0.5983831 0.02638435 -0.9401345 -0.3392583 -0.03241926 -0.9700384 -0.2418583 0.02302092 -0.9999772 0.006697416 -7.32051e-4 -0.9981346 0.04996842 -0.03508007 -0.8811445 0.4710453 0.04123979 -0.8341152 0.5511999 -0.0207495 -0.5293743 0.8470344 -0.047912 -0.3430399 0.9346675 0.09338223 0.004651188 0.9984536 -0.05539691 0.3497587 0.9354741 0.05056875 0.4163628 0.9091951 0.002497911 0.7712526 0.636113 -0.02301555 0.8592687 0.507807 0.06155776 0.956721 0.2879056 -0.04237145 0.9924728 -0.1174573 0.03466343 0.9748997 -0.2199336 -0.03463757 0.8062115 -0.5901103 0.04233908 0.6645305 -0.7456799 -0.04858851 0.5151496 -0.8566087 0.02902519 0.2207824 -0.9748912 -0.02902436 0.06375402 -0.9972743 0.0371406 -0.2039199 -0.977864 -0.04688936 -0.4303125 -0.9008947 0.05674326 -0.7568928 -0.6500258 -0.06767439 -0.8315864 -0.5546287 0.02917164 -8.70224e-7 -2.41247e-7 -1 1.85855e-7 -1.65211e-7 -1 8.082e-7 0 -1 -1.83418e-6 0 -1 -1.09419e-6 -1.34163e-7 -1 1.24786e-6 -7.4213e-7 -1 1.64069e-6 1.69497e-6 -1 6.75183e-7 1.99715e-7 -1 3.21673e-7 0 -1 5.57522e-6 -3.31571e-6 -1 -7.48755e-7 2.93142e-6 -1 -1 4.42039e-7 -3.01776e-7 -1 2.44859e-7 -4.31488e-7 -1 -1.86617e-7 0 -1 2.103e-7 0 -1 -2.35528e-7 -9.33098e-7 -1 0 -9.62774e-7 -1 0 3.42659e-7 -1 1.78235e-7 3.28378e-7 -1 0 0 -1 2.22109e-7 -2.56852e-7 -1 -4.83892e-7 0 -1 -4.38687e-7 3.02673e-7 -1 0 1.60164e-7 -1 0 1.95807e-7 -1 -4.44798e-7 8.19541e-7 -1 4.82206e-7 1.05456e-6 -1 -5.26168e-7 -3.96746e-7 -1 0 -4.75516e-7 -1 0 3.50313e-7 -1 1.93502e-7 3.30923e-7 -1 -1.23134e-7 -2.10581e-7 -1 -2.40697e-7 -1.57652e-7 -1 1.72373e-7 0 -1 -4.79962e-7 0 -1 0 0 -1 0 4.1006e-7 -1 0 4.25182e-7 -1 0 0 -1 -2.38715e-7 0 -1 0 4.81212e-7 -1 0 4.83439e-7 -1 0 0 -1 4.20052e-7 0 -1 4.14532e-7 0 -1 -5.13861e-7 0 -1 -4.54329e-7 -1.44889e-7 -1 3.34632e-7 0 -1 4.53617e-7 -3.28225e-7 -1 2.70818e-7 -3.40029e-7 -1 2.76385e-7 0 -1 -6.55705e-7 2.71028e-7 -1 -1.50081e-7 8.64016e-7 -1 2.49509e-7 1.52159e-7 -1 0 0 -1 0 -1.93919e-7 -1 0 -2.01978e-7 -1 0 0 -1 -4.82442e-7 1.37294e-7 -1.27891e-7 -3.67387e-7 1 -1.76346e-6 -1.88268e-7 1 0 0 1 -2.07943e-6 -6.75633e-7 1 2.12149e-5 -8.4076e-6 1 2.8803e-6 2.23628e-6 1 1.96585e-5 2.07685e-5 1 -1.72542e-5 -2.45116e-6 1 -1.75195e-5 -2.33606e-6 1 1.26594e-5 -6.57804e-6 1 -0.1426251 0.03251373 -0.9892426 0.1278392 0.4303488 -0.8935643 -0.05395352 0.5412953 -0.8390998 0.008710741 0.8830392 -0.4692184 0.08679288 0.9001881 -0.4267651 -0.102631 0.9944999 0.02090519 0.1515479 0.9609231 0.2316458 -0.1233389 0.8559913 0.5020622 0.1084321 0.629305 0.7695568 -0.1084461 0.4794328 0.8708523 0.1029921 0.1782923 0.9785726 -0.07526952 -0.09120595 0.9929834 0.07528215 -0.2447987 0.9666469 -0.1029995 -0.4941298 0.8632652 0.108434 -0.7421643 0.661388 -0.07582414 -0.837683 0.5408678 0.06336551 -0.9733437 0.2204243 -0.08104807 -0.994677 0.0636326 0.08146739 -0.9814976 -0.1732789 -0.09851574 -0.8979846 -0.4288572 0.1262573 -0.7657897 -0.6305754 -0.14855 -0.5486801 -0.822729 0.1751239 -0.2248671 -0.958523 0.1055017 0.1083568 -0.988498 -0.1055077 0.2271181 -0.9681351 0.1055153 0.7053025 -0.7010099 -0.05744367 0.7706985 -0.6346054 0.008715689 0.9889115 -0.1482504 0.03486084 0.9904928 -0.1330743 -0.03123992 0.9352107 0.3527112 0.03121811 0.9192394 0.3924597 -0.0278542 0.6641167 0.74711 0.0169813 0.6361873 0.7713477 -0.01951986 0.2972043 0.9546144 0.03987282 0.2582478 0.9652556 -0.04783147 -0.3097941 0.9495998 0.04782909 -0.3555289 0.9334407 -0.03987252 -0.8073109 0.5887779 0.06589627 -0.8464264 0.5284128 -0.07941091 -0.9817076 0.1730436 0.06513959 -0.9964824 0.05272281 0.01170927 -0.9303005 -0.3666112 -0.1055262 -0.8985486 -0.4259984 0.1054932 -0.5366789 -0.8371661 -0.1055067 -0.4314887 -0.8959274 -0.6447404 0.1560665 -0.7483002 -0.5803763 0.1310888 -0.8037282 -0.812833 0.406127 -0.4175685 -0.4530194 0.3195166 -0.8322756 -0.6374251 0.5638559 -0.5251246 -0.3925749 0.5307888 -0.7510981 -0.3647377 0.50549 -0.7819503 -0.3427924 0.7410468 -0.5773587 -0.1984774 0.5506588 -0.8107907 -0.1258676 0.8465523 -0.5172102 -0.09887021 0.772028 -0.6278514 0.04035705 0.6025615 -0.7970515 0.1464697 0.865319 -0.4793432 0.2015252 0.5708996 -0.7959027 0.3349177 0.7469769 -0.5743306 0.3266791 0.4879056 -0.8094621 0.5954522 0.6931081 -0.4062486 0.4374071 0.3470799 -0.8295845 0.7605814 0.4720092 -0.445784 0.6022263 0.2187868 -0.7677602 0.7525866 0.2374992 -0.6141722 0.6787847 0.01699256 -0.7341408 0.5411568 0.03150147 -0.8403316 0.7979251 -0.1344392 -0.5875726 0.5492795 -0.1779071 -0.8164809 0.762131 -0.3035655 -0.571843 0.5939939 -0.4689975 -0.653615 0.6357348 -0.4925499 -0.5943365 0.3746081 -0.4669433 -0.8010198 0.4823637 -0.7078589 -0.5160049 0.2593774 -0.6197949 -0.7406604 0.2739033 -0.7544699 -0.5964496 0.1092168 -0.5877052 -0.8016696 0.07560217 -0.8702868 -0.4867086 -0.07325887 -0.6300916 -0.7730574 -0.07538634 -0.5974709 -0.7983391 -0.2232544 -0.7557135 -0.6156741 -0.2445138 -0.5190976 -0.8189937 -0.286908 -0.5749019 -0.7662712 -0.5494593 -0.6775374 -0.4889147 -0.3735184 -0.3665133 -0.8521456 -0.7461072 -0.481413 -0.4599626 -0.4906498 -0.237789 -0.8382835 -0.8438823 -0.2499595 -0.4747453 -0.579479 -0.05762463 -0.8129473 -0.7659552 -0.03483128 -0.6419498 -0.9991825 0.006686747 0.03986984 -0.9947374 0.07846844 -0.06588196 -0.8921844 0.4446394 0.0793901 -0.7906097 0.5965339 -0.1381436 -0.5148085 0.8487519 0.1207987 -0.3277764 0.9416581 -0.07643604 -0.08914875 0.9930833 0.07640677 0.0893625 0.9917104 -0.0923289 0.5015778 0.8607449 0.08682191 0.5144097 0.8552126 0.06319892 0.8029252 0.5877372 -0.099379 0.9237218 0.3518095 0.1515528 0.9837918 0.1470437 -0.1026255 0.947102 -0.3089739 0.08679205 0.944403 -0.3226551 0.06321793 0.7436702 -0.6611241 -0.09934586 0.5385445 -0.8288584 0.1515379 0.3510185 -0.9307262 -0.1026381 -0.0490083 -0.996679 0.06503242 -0.1480183 -0.9874248 -0.05552428 -0.4583635 -0.8860624 0.06925475 -0.5848208 -0.8082069 -0.06918227 -0.8301503 -0.5536319 0.06589657 -0.869038 -0.4931369 -0.03986316 -0.9866312 0.05989009 0.1515656 -0.9682357 0.2413995 -0.06516158 -0.7821496 0.6229813 -0.01167607 -0.7557338 0.6523576 0.0574097 -0.3132421 0.9496333 -0.008716166 -0.2685026 0.9593607 -0.08679604 0.1886746 0.9766623 0.1026277 0.3645746 0.9238727 -0.1163812 0.6607825 0.7414861 0.116468 0.7871677 0.6081392 -0.1026338 0.9775211 0.192148 0.08678472 0.9921225 0.1173831 -0.04374945 0.9077303 -0.4176552 0.03987085 0.8556762 -0.5056609 -0.1101146 0.6493206 -0.7535091 0.1029903 0.4060877 -0.9095821 -0.08805215 0.2563112 -0.9648772 0.05758976 -0.004921317 -0.9983274 -0.05760312 -0.1119629 -0.9928984 0.04021507 -0.459438 -0.8880809 -0.01513999 -0.4408343 -0.8974593 0.01523321 -0.7531514 -0.6563181 -0.04482769 -0.8270172 -0.551612 0.1084745 -0.9654818 -0.2294114 -0.1233501 -0.9858905 0.108083 -0.1278198 -0.9784625 0.2058217 0.01576417 -0.820881 0.5673758 0.06510871 -0.6968089 0.7010632 -0.151551 -0.4895704 0.8662818 0.0993815 -0.1164391 0.991182 -0.06324672 -0.1330738 0.9904928 -0.03486239 0.3783817 0.924992 0.03488534 0.3926352 0.9196522 0.0088045 0.7901972 0.6104806 -0.05387002 0.8538379 0.504597 0.1278388 0.9829231 0.1162837 -0.1426196 0.9829186 -0.1162919 0.1426436 0.8708485 -0.4794452 -0.1084212 0.7890442 -0.6096398 0.0758199 0.5044701 -0.8600918 -0.07584196 0.3650134 -0.9246808 0.1083086 -0.009489119 -0.9897453 -0.142528 -0.2160069 -0.9700185 0.111379 -0.6228753 -0.7787768 -0.07438588 -0.5623015 -0.8235957 0.07421183 -0.8643032 -0.4904503 -0.1115279 -0.9435666 -0.2988989 0.1426238 1.24196e-5 4.06956e-6 1 -3.17911e-6 -1.04171e-6 1 -3.37537e-6 -7.11058e-7 1 -5.38943e-6 -2.80627e-6 1 -4.79608e-6 -3.52232e-6 1 -8.51699e-6 -5.06997e-6 1 -2.92508e-6 -1.31766e-5 1 2.47664e-6 -5.13598e-6 1 6.58379e-6 -7.98615e-6 1 5.85214e-6 -1.17378e-5 1 1.20341e-5 -1.3055e-5 1 1.3187e-5 -4.09598e-6 1 6.4581e-7 -4.92787e-6 1 -3.59022e-7 2.73952e-6 1 -1.50023e-5 -7.99023e-6 1 -1.16851e-5 -1.32838e-5 1 -6.34998e-6 -3.17594e-6 1 -2.39035e-6 -4.95135e-6 1 -2.52366e-6 -6.65122e-7 1 2.32607e-6 6.13047e-7 1 -1.02915e-6 4.36672e-6 1 -8.55679e-6 -3.82236e-6 1 9.47866e-6 -8.27126e-6 1 -0.1819199 0.7610868 -0.6226171 -0.3028863 0.6744211 -0.6733618 -0.2704031 0.392432 -0.8791356 -0.6126598 0.5154165 -0.599161 3.77997e-5 0.6805222 -0.7327275 4.16452e-4 0.06275337 -0.998029 -0.001157581 0.6266014 -0.7793391 0.5253682 0.5115893 -0.6799005 0.3705248 0.5751838 -0.7292976 0.2358569 0.4742896 -0.8481867 0.1462132 0.6952676 -0.703722 1.47003e-6 -1.99379e-6 1 1.65553e-5 -9.3765e-6 1 1.65381e-5 -9.64318e-6 1 -1.03467e-5 -1.03094e-5 1 -1.15658e-5 5.97756e-7 1 -6.40666e-6 2.66215e-6 1 3.19262e-7 -5.75317e-6 1 9.60645e-6 6.21779e-6 1 -2.86222e-7 1.72886e-5 1 -5.47213e-6 -1.90217e-6 1 4.10334e-6 -5.51797e-6 1 3.51535e-6 -1.35198e-6 1 -1.65066e-6 -2.12335e-6 1 1.11573e-5 -2.09569e-5 1 1.24151e-5 -2.09474e-5 1 8.69422e-6 -1.29468e-5 1 3.39833e-5 6.09727e-6 1 2.61192e-5 4.6863e-6 1 2.23811e-5 9.77999e-6 1 1.36904e-5 -3.82748e-7 1 -3.34779e-6 0 1 -2.1342e-6 -1.03907e-5 1 3.02804e-6 -7.97647e-6 1 1.6145e-7 -4.51293e-6 1 1.50712e-6 -4.19922e-6 1 -3.90197e-6 -3.19463e-5 1 3.37701e-5 -3.50771e-5 1 1.97565e-5 1.43052e-5 1 2.85095e-6 2.0643e-6 1 1.63092e-6 3.4562e-6 1 -7.65059e-6 -2.80741e-6 1 -1.09336e-5 2.37188e-6 1 7.17746e-6 6.98669e-6 1 7.42781e-6 5.75175e-6 1 3.1776e-6 1.71902e-6 1 -1.04447e-5 9.94699e-6 1 4.09109e-6 -1.32587e-5 1 1.31499e-5 -6.26241e-6 1 -2.249e-5 1.07104e-5 1 -7.36175e-5 -1.16317e-5 1 -9.33832e-5 2.0247e-5 1 -9.62747e-5 1.85326e-5 1 -6.85344e-5 -2.17813e-5 1 -4.38523e-5 1.23384e-5 1 -2.21219e-5 6.9058e-6 1 -1.93303e-5 -3.34003e-5 1 9.1482e-6 -1.46303e-5 1 9.03954e-7 -1.05374e-5 1 -1.98297e-6 -2.91698e-6 1 -0.1065006 0.990429 -0.08779627 0.1309472 0.9814788 0.1398295 0.1485385 0.2432311 -0.9585275 -0.1021763 0.4909619 -0.8651684 0.1015089 0.7248038 -0.6814363 -0.08264619 0.8230664 -0.5618998 0.08263474 0.9830178 -0.1638518 -0.1015506 0.9947847 -0.00953865 0.08148354 0.9632604 0.2559099 -0.0984928 0.8583668 0.5034934 0.06913745 0.7557325 0.6512207 -0.04581421 0.528015 0.8479983 0.04575097 0.4452822 0.8942207 -0.06917983 0.1582958 0.9849654 0.1262751 -0.05160468 0.990652 -0.1485554 -0.3352053 0.9303596 0.1751023 -0.6369305 0.750772 -0.1426411 -0.814682 0.5620915 0.1084281 -0.9704748 0.2154573 -0.1084304 -0.9934507 0.03603613 0.1029712 -0.9540844 -0.2812824 -0.07532596 -0.8456106 -0.5284589 0.0457313 -0.7740875 -0.6314246 -0.06920546 -0.5500059 -0.8322886 0.1263101 -0.3610158 -0.9239661 -0.1485364 -0.07775014 -0.9858458 0.1563155 0.1076295 -0.9818255 -0.1207909 0.4899291 -0.8633534 0.1057963 0.6836005 -0.7221478 -0.06336092 0.8085321 -0.585031 0.087686 0.9663681 -0.2417515 -0.01576328 0.9846462 -0.1738487 -0.0651291 0.9732371 0.2203809 0.07941377 0.9383422 0.3364632 -0.04571485 0.7803296 0.6236953 0.07529699 0.6947839 0.7152662 -0.1029961 0.4760186 0.8733831 0.1278074 0.1438217 0.9813157 -0.01575303 0.04738521 0.9987524 -0.06513208 -0.3422186 0.9373603 0.1515567 -0.5028773 0.8509672 -0.09936618 -0.7149643 0.6920639 0.06323522 -0.9298622 0.3624329 0.03485548 -0.9250042 0.3783548 -0.03123688 -0.9939107 -0.1056687 0.03126877 -0.9884641 -0.1481917 -0.03124344 -0.8161377 -0.5770124 -0.01519978 -0.8100344 -0.5861853 0.04933148 -0.492919 -0.8686757 -0.01575851 -0.454587 -0.8905629 -0.06822037 -0.04696661 -0.9965642 -0.1574226 0.752869 0.6390669 -0.2046782 0.6150856 0.7614306 -0.38423 0.6776176 0.627058 -0.4402709 0.5099433 0.738999 -0.5018555 0.5139654 0.6956872 0.04522591 0.03347939 0.9984157 0.6073527 0.661851 0.4394041 0.3311595 0.6550762 0.6791235 0.4564406 0.7235017 0.5178872 0.247369 0.7891433 0.5621933 0.5956594 0.8012305 0.05674082 0.6175022 0.7864661 -0.01273947 0.528355 0.3495311 -0.773737 0.5893607 0.3818883 -0.7119095 0.8386692 -0.5446412 0 0.8386692 -0.5446412 0 1 1.32275e-6 -1.03081e-6 1 -3.64692e-6 0 1 4.45562e-6 1.21823e-6 1 0 0 1 3.77285e-6 1.39289e-6 1 -4.93725e-6 0 1 7.51841e-6 -1.3425e-6 1 0 0 1 -5.59415e-7 -1.90038e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.8386691 -0.5446412 0 0.8386691 -0.5446412 0 1 -4.05815e-6 0 1 3.00727e-6 1.01811e-6 1 0 0 1 -5.52195e-7 3.35579e-6 1 8.50204e-7 -8.42473e-7 1 1.53141e-6 3.9658e-7 1 -4.53224e-7 -2.99595e-6 1 0 0 1 0 0 1 7.57748e-7 8.52442e-7 1 3.71016e-6 9.60797e-7 1 -5.74727e-6 0 1 0 0 1 0 0 1 5.03223e-6 -1.30882e-6 1 -1.34752e-6 -1.52925e-6 1 4.04978e-6 2.26639e-6 1 3.20218e-6 4.40867e-7 1 0 5.67137e-7 1 3.82109e-7 6.27115e-7 1 -8.45661e-6 -4.96795e-7 1 3.25978e-6 1.915e-7 1 1.84398e-7 1.93476e-6 1 3.55683e-6 3.89623e-6 1 -5.23334e-6 -7.20512e-7 1 0 0 1 0 0 1 0 0 0.5237122 -0.5137704 0.6795333 0.3492877 -0.4839802 0.8023474 0.3421863 -0.7068278 0.6191147 0.3379226 -0.6887621 0.6414166 0.1991316 -0.9308555 0.306357 0.5721416 -0.7901836 -0.2196905 0.2583644 -0.4264564 -0.8668234 0.295576 -0.5370478 -0.7900725 0.2016484 -0.7199798 -0.6640534 -0.1230152 -0.9923003 -0.01440656 -0.02992856 -0.9990367 0.03209322 0.08961224 -0.9955955 -0.02755129 0.2576287 -0.9659793 0.0226171 0.3384932 -0.9407271 -0.0213285 0.4753507 -0.8795888 0.01911181 0.5612309 -0.8269058 -0.03530812 0.7214244 -0.6914231 0.03848326 0.7857668 -0.6176279 -0.03326427 0.9109088 -0.4117406 0.02673566 0.9290736 -0.3697218 -0.01131999 0.9862269 -0.1650074 -0.01136702 0.9933698 -0.113102 0.02060079 0.998274 0.05718719 -0.01336437 0.9934192 0.1131096 0.01801419 0.9533616 0.3003435 -0.02992665 0.9106823 0.4116659 0.03447902 0.849969 0.5256495 -0.03528845 0.7410668 0.6708247 0.02854049 0.6505209 0.7589043 -0.02978122 0.5713628 0.8203982 0.02216726 0.4086231 0.9121266 -0.03243964 0.2926458 0.9555996 0.03446477 0.1674692 0.9852548 -0.03502726 -0.01398283 0.9994984 0.02841639 -0.1463876 0.988672 -0.0331428 -0.2383672 0.9709761 0.01965886 -0.4214445 0.906406 -0.0285083 -0.5239973 0.8510227 0.03445196 -0.5946007 0.8039406 -0.01137387 -0.7460992 0.6657385 -0.01132768 -0.7777168 0.6279554 0.02878314 -0.8954901 0.444024 -0.03066313 -0.9423179 0.3329411 0.03445565 -0.9748886 0.2208484 -0.02860319 -0.999642 -1.11762e-6 0.02675455 -0.9988865 -0.04579907 -0.01132237 -0.9591929 -0.2825252 -0.01133269 -0.9424342 -0.332989 0.03059506 -0.8390793 -0.5426684 -0.03816992 -0.7774707 -0.627745 0.03841394 -0.6294806 -0.7762084 -0.03542506 -0.5482242 -0.8361133 0.01910275 -0.2789546 -0.9602659 -0.008586287 -0.3326148 -0.9427363 0.02481424 -0.449326 -0.8932911 -0.0117138 -0.2067766 -0.5470408 0.8111658 -0.269721 -0.6240165 0.7333852 -0.4509103 -0.6813007 0.5766362 -0.5108785 -0.648176 0.5646867 -0.1746773 -0.6707356 -0.720834 -0.2694081 -0.4621921 -0.8448656 -0.2768442 -0.5691117 -0.7742539 -0.6203337 -0.55071 -0.5584841 -0.003652036 4.69869e-7 -0.9999934 5.03848e-6 0 -1 -0.004019618 -0.001532971 -0.9999908 -0.00350821 1.02967e-4 -0.9999938 -2.64894e-6 1.94995e-7 -1 -4.56388e-7 -3.85182e-7 -1 -1.54397e-6 -2.03608e-7 -1 1.97794e-5 -7.03838e-6 -1 -1.22658e-5 -1.73147e-6 -1 3.21318e-6 2.80711e-5 -1 -0.02288544 0.01778268 -0.9995799 -0.00565803 0.001845777 -0.9999823 -1.10568e-4 -1.86389e-4 -1 -0.007628679 8.8844e-4 -0.9999705 -1.50527e-5 1.80065e-6 -1 -0.001959383 -6.9633e-4 -0.9999977 -5.63196e-4 -0.005422592 -0.9999851 -0.005856454 -0.004727602 -0.9999717 0 6.44126e-7 -1 2.30212e-6 0 -1 -1.507e-6 4.73148e-7 -1 -2.15236e-6 7.08102e-7 -1 2.08713e-7 1.29608e-7 -1 0.005747556 -0.001208961 -0.9999827 -9.19403e-4 0.003443777 -0.9999936 -0.001025259 -0.001558244 -0.9999983 -5.91313e-4 -0.003373563 -0.9999941 3.29596e-6 -6.69474e-7 -1 -1.89878e-6 9.18108e-7 -1 -6.35737e-6 1.33195e-5 -1 4.52119e-6 -5.36808e-7 -1 2.90049e-5 6.19842e-4 -0.9999998 0.001344621 0.02970784 -0.9995578 -0.02301096 0.01770532 -0.9995784 -5.01228e-7 4.24747e-7 -1 -3.72121e-7 -1.85413e-6 -1 0.004364132 8.38602e-5 -0.9999904 0.005874395 -0.004059135 -0.9999745 0.007056236 0.02762645 -0.9995934 0.002729833 0.02871537 -0.9995839 -3.08305e-4 0.02047908 -0.9997902 -1.82589e-4 -0.001659512 -0.9999986 -1.27481e-4 -0.001160621 -0.9999992 3.8093e-6 2.74424e-6 -1 4.46597e-6 -4.35515e-6 -1 -0.005993604 0.009224057 -0.9999395 -0.003681123 -0.01284611 -0.9999107 0.00771743 0.00244534 -0.9999673 0.009914755 0.004507005 -0.9999406 3.26184e-6 -6.61926e-6 -1 5.46135e-7 -3.15038e-7 -1 -1.44341e-6 -2.08414e-6 -1 -4.12436e-7 -6.48488e-6 -1 -3.91289e-6 2.09842e-6 -1 2.00371e-6 6.06686e-6 -1 3.45453e-7 -3.25846e-7 -1 1.89511e-7 -1.30243e-6 -1 -0.00250864 -0.04486018 -0.9989901 0.002540409 -0.004703938 -0.9999858 0.004109799 0.005137264 -0.9999784 0 3.67245e-7 -1 -7.87424e-7 -2.46558e-6 -1 -0.01350343 0.007350385 -0.9998818 9.22207e-4 -8.8123e-4 -0.9999992 0.003102421 -3.70739e-4 -0.9999951 0.003070175 -0.00138998 -0.9999943 0.004565715 -5.18144e-4 -0.9999895 0.01099574 0.001250684 -0.9999388 -1.3693e-6 0 -1 0.00954616 9.23555e-4 -0.9999541 1.78906e-4 -3.14767e-4 -1 -0.6698651 0.4433649 -0.5955739 -0.5485864 0.3493139 -0.7596266 -0.9916139 0.04673004 -0.1204915 -0.9379684 0.3384535 0.0752623 -0.8737788 0.480459 -0.07529729 -0.7108802 0.6957259 0.1030289 -0.481744 0.8718779 -0.08804488 -0.3122161 0.9465488 0.0810346 -0.07959884 0.9934915 -0.08147656 0.2152411 0.9695972 0.1164153 0.362356 0.9297633 -0.06510281 0.6954225 0.7184273 -0.01580512 0.7256953 0.6862441 0.04934996 0.9461804 0.3232836 -0.01518028 0.9561817 0.2828328 -0.0756452 0.9837911 -0.147049 0.1026238 0.9517788 -0.2963312 -0.07940346 0.7901085 -0.6104479 0.0555157 0.7471069 -0.664121 -0.0278328 0.3668883 -0.9296121 0.03484827 0.3528758 -0.9356297 0.008716702 -0.1165419 -0.9919115 -0.05029636 -0.2670903 -0.9543478 0.1337275 -0.4898648 -0.8668967 -0.09231853 -0.7805386 -0.6217092 0.06509298 -0.8528831 -0.5138854 -0.09226238 -0.969451 -0.213658 0.1204786 -0.7938395 0.6069517 -0.03779435 -0.5982147 0.7990689 0.0602343 -0.5067697 0.8620406 -0.008392989 -0.0117979 0.9999243 -0.003504633 -0.01343357 0.9998741 -0.008434414 -0.03666049 0.9990626 -0.02301764 -0.1991948 0.9797914 -0.01817893 -0.4884511 0.872591 -7.08963e-4 -0.5166206 0.8561766 0.008043885 -0.6855463 0.727899 -0.01376152 0.7360839 0.6767781 -0.01232349 0.4986079 0.8665249 -0.02290439 0.3507003 0.9364308 0.01033347 0.2368509 0.9715294 -0.005689024 0.008761167 0.9998996 -0.01113128 0.01063024 0.9999212 -0.006674289 0.03339177 0.9992224 -0.02096527 0.3841783 0.922671 0.03294241 0.5293405 0.8478276 -0.03141677 0.7025792 0.7110663 0.02769982 0.8144923 0.5794575 -0.02883404 0.9871701 0.1245218 -0.09994733 0.8660181 0.4957324 0.0652849 0.8581383 0.5059565 0.08721607 0.5395856 0.8356512 -0.1026379 0.4063734 0.9102512 0.07939422 0.03618854 0.9971705 -0.06589007 -0.03572356 0.998566 0.03987348 -0.5514764 0.8330414 -0.04376977 -0.5637348 0.8257293 -0.01934427 -0.8532519 0.5195577 0.04495704 -0.9083853 0.4038395 -0.1083956 -0.9903669 0.06293851 0.1233385 -0.979316 -0.1746709 -0.102128 -0.9138365 -0.4016935 0.05954074 -0.8211798 -0.5675725 -0.05937385 -0.686099 -0.722913 0.08163952 -0.4903307 -0.867731 -0.08135664 -0.2713882 -0.9590471 0.08110052 -0.08906441 -0.992127 -0.0880444 0.2297977 -0.9653921 0.1233336 0.4976496 -0.8540346 -0.1515576 0.6921206 -0.708437 0.1381532 0.9158741 -0.3765549 -0.1392158 0.9780037 -0.145393 0.1495649 0.948693 0.3111526 -0.05626481 0.9127827 0.4031034 0.06584376 0.6925092 0.7154785 -0.09231334 0.5266233 0.843495 0.1057544 0.3624633 0.9298398 -0.06339013 0.05275624 0.9965949 0.06336921 -0.1324087 0.9855317 -0.1058076 -0.3363646 0.9371946 0.09233164 -0.6830259 0.7264684 -0.07562637 -0.736273 0.6759627 0.03125005 -0.9686815 0.2458463 -0.034868 -0.9631201 0.2615339 -0.06324344 -0.9863501 -0.1312929 0.09937667 -0.9103171 -0.3851736 -0.1515385 -0.8120322 -0.5745269 0.1025788 -0.4699828 -0.8783943 -0.08683019 -0.4027528 -0.914263 0.04374331 0.1866568 -0.9812602 -0.04782778 0.2046051 -0.9787687 -0.01218974 0.6520003 -0.7565481 0.05030649 0.7404626 -0.6643813 -0.1015507 0.8909475 -0.4471059 0.07942944 0.977299 -0.1892187 -0.09530472 0.9976167 -0.0219506 0.06541424 -0.5958303 0.801456 -0.05152171 -0.5537257 0.8284317 0.08419501 -0.9559632 0.2738725 -0.1054909 -0.9158262 0.3874695 0.1054984 -0.5969317 0.7967258 -0.09434282 -0.5179688 0.8539721 0.04939603 -0.1166291 0.9930582 -0.01526927 -0.1373579 0.9904049 0.01520115 0.2860785 0.956932 -0.04939925 0.3769062 0.9214357 0.09432888 0.7886286 0.6057476 -0.1055216 0.8561078 0.505914 0.1055015 0.9955207 0.006152749 -0.09434407 0.9892489 -0.1170431 0.08767926 0.8598586 -0.5048698 -0.07582658 0.8061128 -0.5900583 0.04487216 0.5153532 -0.8568427 -0.01522213 0.5057011 -0.8621424 -0.03125572 0.08969479 -0.995581 0.02780687 0.05285286 -0.9984577 -0.016999 -0.3286958 -0.9442342 0.01951783 -0.3378275 -0.9411928 0.005364537 -0.7137568 -0.6985816 -0.05034857 -0.7802565 -0.6214323 0.07086598 -0.9382701 -0.338576 -0.07082027 -0.9732236 -0.2144997 0.0826174 -0.8084837 0.588418 0.01087892 -0.7777845 0.6285088 -0.005291163 -0.529577 0.8482227 0.008146166 -0.5067425 0.8620567 -0.008384287 -0.01491719 0.9998825 -0.003547847 -0.01063138 0.9999212 0.006675004 -0.03339701 0.9992221 0.02096855 0.006861865 0.999912 -0.0113582 0.01343017 0.9998743 0.008432209 0.03666174 0.9990626 0.02301836 0.3841937 0.9226649 0.03293377 0.5980577 0.7988665 -0.06433737 0.7225535 0.6905786 0.03190147 -0.9818213 0.1076428 -0.1563329 -0.8315134 0.5330548 0.1563267 -0.7215413 0.6830114 -0.1134622 -0.341193 0.9369412 0.07568639 -0.3026988 0.9529653 0.0151835 0.08966463 0.9949591 -0.04490697 0.1639328 0.9854509 0.04486376 0.5331109 0.8459078 -0.01525521 0.5153501 0.8568457 0.01515662 0.8237357 0.5648191 -0.0493853 0.8721051 0.4801365 0.09434831 0.9941248 -0.02414196 -0.1055124 0.9839057 -0.1442102 0.1055125 0.7582941 -0.6433164 -0.1055181 0.6749273 -0.7303054 0.1054855 0.1858334 -0.976903 -0.1054827 0.06632673 -0.9922026 0.1055215 -0.4426972 -0.8916953 -0.09433269 -0.5293419 -0.8469702 0.04938393 -0.8341993 -0.5512549 -0.01515275 -0.8540778 -0.5146162 -0.07563889 -0.990464 -0.07813131 0.1134746 -0.9836783 0.1754629 0.0398736 -0.9554843 0.2737342 -0.1100883 -0.8182547 0.5655542 0.1029943 -0.6221808 0.7779077 -0.08803832 -0.4677052 0.880158 0.08107954 -0.2160605 0.9710278 -0.1020926 -0.004936814 0.9950384 0.09936928 0.3817234 0.9221099 -0.06325089 0.3937807 0.9150938 -0.086833 0.7441928 0.6615546 0.09231787 0.8651029 0.4903043 -0.1058235 0.9444074 0.3226159 0.06335282 0.9947996 -0.05181837 -0.08768552 0.9923939 -0.1220909 0.01575583 0.8519681 -0.5191279 0.06823807 0.7993536 -0.5969745 -0.06823009 0.4833123 -0.8753057 -0.01577782 0.3920314 -0.91103 0.1278114 0.05255293 -0.9932928 -0.1029927 -0.2416394 -0.9659704 0.09225809 -0.3376979 -0.9408424 -0.02785229 -0.688112 -0.7250708 0.02782744 -0.7145476 -0.6993839 -0.01685488 -0.9259468 -0.3771418 0.01965904 -0.9398878 -0.3391482 -0.03986823 -0.8386708 -0.5446386 0 -0.8386708 -0.5446386 0 -1 0 0 -1 -5.9803e-7 0 -1 -1.32169e-7 0 -1 0 0 -1 -1.26139e-7 1.83186e-7 -1 -7.05883e-7 0 -1 1.41819e-7 -1.7912e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 1.46772e-7 -1 -2.40129e-7 0 -1 4.9429e-7 0 -1 1.80713e-7 0 -1 2.04177e-7 -8.44849e-7 -1 0 3.82648e-7 -0.8386709 -0.5446386 0 -0.8386709 -0.5446386 0 -1 0 0 -1 0 5.3877e-7 -1 -1.62871e-7 0 -1 0 0 -1 1.48105e-7 0 -1 2.53979e-7 0 -1 2.59397e-7 0 -1 -7.8764e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 -4.85246e-7 0 -1 3.88352e-7 -1.31395e-7 -1 0 0 -1 0 0 -1 0 0 -1 -4.03258e-7 0 -1 0 0 -1 -4.73041e-7 0 -1 9.08259e-7 1.22012e-7 -1 0 0 -1 0 0 -1 0 0 -1 7.34741e-7 1.41953e-7 -1 0 0 -1 0 0 -1 0 0 9.86915e-6 -2.22856e-6 -1 -2.00935e-6 2.58335e-6 -1 -5.56865e-6 -6.59814e-6 -1 1.20776e-6 -1.09639e-5 -1 9.12343e-6 2.44731e-6 -1 -6.2062e-5 1.3731e-5 -1 -6.50416e-5 -4.60764e-5 -1 7.70103e-6 -5.00526e-5 -1 1.97198e-5 -2.54779e-5 -1 -1.93392e-5 1.5989e-5 -1 2.26088e-5 1.70257e-6 -1 -3.97962e-7 -3.54199e-5 -1 -3.43457e-5 2.47101e-5 -1 8.0208e-6 2.06833e-5 -1 1.64965e-6 -2.64939e-6 -1 -2.86169e-6 4.59594e-6 -1 7.98725e-6 1.02794e-5 -1 7.47697e-6 -6.1753e-6 -1 -1.27601e-5 -4.70043e-6 -1 -7.33704e-6 2.7092e-6 -1 -2.03049e-7 -3.37445e-6 -1 9.88106e-6 -9.67192e-7 -1 -2.11681e-5 -1.01944e-5 -1 -5.17062e-6 -1.12549e-5 -1 -2.13946e-6 1.18705e-5 -1 2.59538e-5 -7.43547e-6 -1 -3.44727e-5 -4.05159e-5 -1 -4.83074e-5 5.80137e-5 -1 2.82675e-5 2.53043e-5 -1 8.61192e-6 4.36924e-6 -1 3.71519e-6 9.90973e-6 -1 -3.77452e-6 2.79142e-6 -1 2.0865e-5 -7.03086e-5 -1 -1.17196e-4 -9.56953e-5 -1 -2.9664e-5 5.92284e-5 -1 -1.85889e-6 3.71154e-6 -1 -1.98096e-5 1.02101e-5 -1 -1.42107e-5 2.19365e-5 -1 -1.81886e-6 2.80769e-6 -1 -4.55633e-6 1.79063e-6 -1 -4.60675e-6 -1.88341e-5 -1 -7.88395e-6 -1.75127e-5 -1 0 0 -1 -3.38002e-6 1.0819e-6 -1 -1.88375e-6 -1.71099e-5 -1 -2.21081e-5 -1.90826e-5 -1 2.11031e-5 5.80497e-6 -1 -2.18728e-5 -3.94403e-5 -1 -2.78166e-5 -1.04592e-5 -1 -9.0689e-6 -1.25629e-5 -1 1.2242e-5 1.69585e-5 -1 2.29296e-5 -7.08856e-6 -1 8.74503e-6 -4.55523e-7 -1 -1.02261e-5 -1.83287e-5 -1 -1.02257e-4 1.37263e-4 -1 -1.23473e-4 1.24564e-4 -1 6.45961e-6 2.7898e-5 -1 -6.35342e-6 1.63919e-5 -1 8.91524e-7 6.6364e-6 -1 -4.94841e-6 1.96219e-6 -1 -2.05198e-5 2.95164e-5 -1 2.51987e-5 4.25525e-5 -1 5.92551e-5 -2.63201e-5 -1 -1.04572e-6 -1.91549e-5 -1 9.81329e-6 7.20932e-6 -1 3.67408e-5 -1.16966e-5 -1 4.73559e-6 -2.09925e-5 -1 -2.30094e-6 1.01999e-5 -1 -1.36969e-6 1.02004e-5 -1 -1.08486e-6 1.16532e-5 -1 -0.2713952 0.9624343 0.008044779 -0.4336904 0.9009888 -0.01147925 -0.4890398 0.8722495 0.004566669 -0.7143476 0.699574 0.01743078 0.7169358 0.6969865 0.01458847 0.4829876 0.8756271 -4.03194e-4 0.4294465 0.9029939 -0.01333266 0.2869282 0.9579061 0.009383738 0.6880034 -1.30967e-4 -0.7257075 0.7028047 5.20036e-5 -0.7113829 0 0 1 0 0 1 0 -1 0 0 -1 0 0.03622287 0.9992613 0.0128377 0.02428525 0.9978741 -0.06047636 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0.8374475 0.5462028 0.01854866 0.828921 0.5593446 -0.004861056 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0.06651926 0.9977852 0 0 0.9998611 0.01666438 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0.1319573 -0.09016245 -0.9871464 -0.1495522 0.1965681 -0.9690176 0.08226597 0.4298762 -0.8991323 -0.05204838 0.7540419 -0.6547609 0.01361626 0.7976766 -0.6029317 -0.01360207 0.9590766 -0.2828198 0.05206423 0.9748007 -0.216917 -0.07398021 0.9837361 0.1636772 0.1073351 0.9132523 0.3930004 -0.06618046 0.8292993 0.5548719 0.06617325 0.5191903 0.8520931 -0.0813933 0.3804749 0.9212024 0.06526261 0.1218557 0.9903999 -0.06525623 -0.1218351 0.9904029 0.04763847 -0.3229416 0.9452192 -0.04762667 -0.4961907 0.8669062 0.0652582 -0.6629766 0.7457904 -0.09338283 -0.8510217 0.5167608 0.08224809 -0.9325023 0.3516741 -0.05205386 -0.9974393 -0.04904234 0.07392573 -0.9812589 -0.1779491 -0.08254885 -0.8851689 -0.4578883 0.1026069 -0.6706498 -0.7346433 -0.1089279 -0.5275444 -0.842515 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0.2745797 -0.9610307 0.03203427 0 -1 0 0.715681 -0.4721319 -0.5146768 0.5837163 -0.3770856 -0.7190839 0.4338532 -0.2889367 -0.8533974 0.7006673 -0.7134874 0.001081168 0.578045 -0.816004 -0.001234829 0.495735 -0.8684737 6.97714e-4 0.2262884 -0.9740599 -9.40191e-4 0.2126269 -0.9771333 -6.50097e-4 -0.005251169 -0.4979875 -0.8671684 0.004387378 -0.5623277 -0.8269029 -2.12603e-4 -0.691424 -0.7224493 -0.002030074 -0.556149 -0.8310801 -0.1989117 -0.980017 -8.71836e-4 -0.3072636 -0.9516242 6.93757e-4 -0.4738825 -0.8805879 -5.09818e-4 -0.4764626 -0.8791946 -4.5563e-4 -0.6880213 -0.7256901 -7.62377e-4 -0.726295 -0.687383 3.90009e-4 -0.5178707 -0.3290917 -0.7896257 -0.6682955 -0.4438029 -0.5970093 -0.6456608 1.99409e-4 -0.7636243 -0.6052865 -2.47025e-4 -0.7960076 -0.8398385 0.5427937 -0.006813347 -0.8346232 0.5507904 0.005834817 -3.73426e-7 0 1 -2.06131e-7 -2.24722e-6 1 4.82383e-6 -1.55684e-6 1 4.86952e-6 6.48393e-6 1 4.13739e-7 4.49013e-6 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 -0.01724672 0.9989029 0.04353988 -0.04363244 0.991788 -0.1202186 0 -1 0 0 -1 0 0 3.21888e-7 1 -1.28793e-6 0 1 1.07259e-6 0 -1 -1.73954e-7 -1.29508e-5 -1 -7.13798e-6 -1.24547e-5 -1 1.52809e-5 3.35883e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0.09336215 -0.09057492 -0.9915037 -0.0933727 0.2568215 -0.9619377 0.1109104 0.4559276 -0.8830793 -0.1108976 0.7672093 -0.6317369 0.09337055 0.8862376 -0.4537234 -0.0789287 0.985863 -0.1477983 0.05541765 0.9979513 0.03196907 -0.05275648 0.9242762 0.3780612 -0.004321098 0.9091637 0.4164164 0.04027867 0.6357547 0.7708396 -0.08137494 0.5306637 0.8436671 0.06525528 0.2875065 0.9555531 -0.09337264 -0.006151676 0.9956123 0.1108962 -0.2186809 0.9694744 -0.1109105 -0.5832812 0.8046627 0.09335863 -0.743308 0.6624028 -0.0789209 -0.9168183 0.3914279 0.07893335 -0.9787848 0.1890764 -0.09336745 -0.9867677 -0.1325591 0.08226746 -0.946448 -0.3121989 -0.06057238 -0.727221 -0.6837255 0.06057006 -0.6522422 -0.7555868 -0.08224558 -0.2717261 -0.9588538 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 -0.9898346 0.1364231 -0.04020237 -0.9652518 0.2577127 0.04327875 -0.7470558 0.6636807 -0.03788828 -0.6127908 0.7878426 0.06157594 -0.4070634 0.9124178 -0.04234457 0.0181685 0.9990426 0.0397973 0.09434098 0.9953389 -0.02000379 0.6206087 0.7838647 0.02002584 0.6559671 0.7546207 -0.01596403 0.925962 0.3774033 0.01269996 0.9494926 0.3127581 -0.02542191 0.9986238 -0.03777009 0.0363866 0.9735128 -0.2195987 -0.06363302 0.8234725 -0.5646317 0.05553531 0.6410198 -0.7650477 -0.06160855 0.4913482 -0.87014 0.0378611 0.04855793 -0.9978821 -0.04328387 -0.07516807 -0.996361 0.0401805 -0.4956477 -0.8675923 -0.0402103 -0.5990212 -0.7995631 0.04327201 -0.9078134 -0.4171357 -0.04327392 -0.9525358 -0.3017607 0.0402013 -0.9948781 -0.06039994 -0.08105152 -0.9774107 0.2008666 0.06573414 -0.8309283 0.5541464 -0.04979914 -0.7537326 0.656859 0.02057975 -0.4408429 0.8975574 -0.00694859 -0.4028981 0.914589 -0.03464269 0.04856103 0.9974591 0.05212616 0.2043216 0.977514 -0.05214333 0.5998053 0.7995913 0.02978652 0.6528326 0.7574627 -0.007737874 0.8779986 0.4785998 0.00779426 0.8950597 0.4457651 -0.01271295 0.9996678 0.02145099 0.01429224 0.9980463 -0.05198603 -0.03465563 0.8943383 -0.4453824 0.04234981 0.7809926 -0.622649 -0.04856723 0.6525381 -0.7571997 0.02903187 0.3823839 -0.9235486 -0.02899378 0.2044215 -0.9776757 0.04860037 -0.004960715 -0.9990904 -0.04235374 -0.4280394 -0.9028834 0.03979688 -0.4406846 -0.8971951 0.02894908 -0.7728108 -0.6325662 -0.05121964 -0.8979988 -0.4324715 0.08103466 -0.9916712 -0.1223032 -0.04037499 -0.994678 0.09086197 0.04857867 -0.9436308 0.3263074 -0.05553668 -0.7554491 0.6521103 0.06363064 -0.6242711 0.7803624 -0.03633195 -0.2867761 0.9575219 0.03018879 -0.2471772 0.9689671 0.002480447 0.2611231 0.9649474 -0.02629107 0.2991594 0.9541881 0.005347073 0.6682116 0.7433733 0.0298236 0.7911226 0.6076507 -0.06989616 0.9250657 0.3770585 0.04561054 0.9995254 -0.01044666 -0.0289793 0.9989128 -0.02426755 -0.03980296 0.8687987 -0.492412 0.05214649 0.8008257 -0.5980818 -0.03124755 0.4833365 -0.8754051 -0.00719726 0.4202945 -0.9064972 0.04019159 0.05277645 -0.9981849 -0.02901124 -0.1329852 -0.9899269 0.04857587 -0.3374933 -0.9403753 -0.04233932 -0.665357 -0.7459312 0.02977806 -0.7563142 -0.6528363 -0.0423507 -0.914473 -0.4018774 0.04726248 -0.8385241 0.5448071 -0.007905244 -0.8327126 0.5536588 0.007197499 3.23264e-4 0.9999921 -0.003934681 3.56733e-6 0.9999974 -0.002276778 0.839587 0.5431563 0.00866127 0.8313397 0.5556575 -0.01091974 0.8371836 -0.5469219 -2.18731e-5 0.8377091 -0.5461168 -1.78437e-4 1.55259e-4 -0.9999996 -8.89835e-4 -0.001839697 -0.9999983 3.11136e-4 -0.8401024 -0.542427 0.001034319 -0.8352647 -0.549848 -3.73092e-4 -1.62022e-6 -3.00611e-6 1 6.07559e-7 -1.16153e-5 1 -2.47625e-5 1.05089e-5 1 -2.23991e-5 1.81354e-5 1 -5.71079e-6 1.28005e-5 1 1.30706e-5 1.92414e-6 1 3.99101e-6 -1.12165e-5 1 -1.61759e-6 0 1 -1.27869e-5 1.89532e-7 1 2.16034e-5 3.15472e-5 1 3.23646e-5 2.42216e-5 1 1.39161e-5 -7.12501e-7 1 1.03597e-5 3.22327e-6 1 -7.43171e-6 9.04022e-6 1 -1.00849e-5 8.95939e-6 1 -9.46375e-6 1.46569e-5 1 1.94261e-5 1.20091e-4 1 9.56464e-5 1.10031e-4 1 8.59648e-5 2.08847e-5 1 -2.37346e-6 -1.64164e-5 1 -1.98276e-5 -8.50556e-6 1 -6.88443e-6 1.16457e-5 1 -2.95928e-6 2.68113e-6 1 -1.38355e-5 1.55354e-5 1 -4.11808e-6 7.23833e-7 1 1.58042e-5 -2.77789e-6 1 1.30358e-5 -6.4073e-6 1 -7.96632e-6 2.05169e-5 1 0 8.29281e-6 1 -2.11736e-5 -6.04416e-6 1 -1.31342e-5 -4.32097e-5 1 -2.84683e-5 -4.21959e-5 1 1.10381e-5 -1.29299e-5 1 -1.33396e-5 4.2796e-5 1 -4.47928e-6 4.66189e-5 1 -8.75395e-6 1.91421e-5 1 -4.33993e-6 1.88264e-5 1 -1.44849e-5 2.73739e-6 1 4.25753e-7 -4.3108e-6 1 3.18145e-5 1.56951e-5 1 2.97223e-5 2.19506e-5 1 1.57348e-7 1.92525e-5 1 -8.07036e-6 2.32894e-6 1 -4.30475e-6 3.95457e-7 1 -1.28896e-6 1.91706e-5 1 6.77853e-6 1.16364e-5 1 -1.20608e-5 -4.17686e-6 1 1.90203e-6 -1.94392e-5 1 6.2401e-6 1.92579e-5 1 5.40233e-5 -3.13392e-5 1 1.94454e-6 6.00112e-6 1 -5.1969e-5 -2.38222e-5 1 -5.78456e-5 1.20363e-5 1 4.43285e-5 2.136e-5 1 4.23867e-5 3.64348e-5 1 -3.69685e-6 2.25163e-5 1 9.06092e-6 4.28548e-7 1 6.92904e-6 -1.36093e-6 1 -8.20344e-5 5.86551e-5 1 -6.29955e-5 1.00338e-4 1 5.67892e-5 7.62707e-5 1 5.3989e-5 -4.26994e-5 1 4.07947e-5 -4.28062e-5 1 -3.78754e-5 1.57172e-6 1 3.61401e-5 -4.47683e-5 1 1.23162e-5 -4.52085e-6 1 2.18976e-5 8.29117e-7 1 2.64419e-5 -6.60694e-6 1 -2.70847e-5 -1.37076e-5 1 -2.63366e-5 -2.26962e-5 1 -5.0452e-7 -7.98779e-6 1 3.87417e-6 1.17108e-5 1 -1.87679e-6 -5.67317e-6 1 -0.5192155 0.3348909 0.7862973 -0.5630596 0.3686653 0.7396281 -6.81524e-4 0.8018056 0.5975846 0.001672148 0.7060902 0.7081199 0.5706234 0.3774474 0.72933 0.4893202 0.3169376 0.8124755 0.04072099 0.03439843 0.9985783 0.5705857 6.16395e-4 0.8212379 0.7005488 -7.24286e-4 0.7136041 0.5872865 -0.3813075 0.7139322 0.5972989 -0.3892101 0.7012485 0.001133918 -0.8522704 0.5231004 0.001633882 -0.3601022 0.9329115 -0.001385033 -0.6201114 0.7845126 -4.70411e-6 -0.09332227 0.995636 6.99067e-4 -0.1866576 0.9824247 -0.6069393 -0.3891783 0.6929392 -0.4699541 -0.3136498 0.8250859 -0.7221972 -6.24339e-4 0.691687 -0.6020289 6.71528e-4 0.7984741 0.9911372 0.131904 0.01576471 0.9655773 0.2265405 -0.1278278 0.8298279 0.5484272 0.103021 0.653778 0.7529353 -0.07525104 0.5285063 0.8455849 0.07528179 0.2813373 0.9540644 -0.1030074 -0.03605735 0.9934511 0.1084199 -0.2154468 0.9704771 -0.1084284 -0.5382975 0.833683 0.1233225 -0.738341 0.6624967 -0.1262958 -0.8789786 0.4665806 0.098486 -0.9769943 0.1891633 -0.09848517 -0.9949087 -0.02133977 0.09849554 -0.9344037 -0.3366554 -0.1164162 -0.8577916 -0.5036382 0.1026742 -0.5427638 -0.8353983 -0.08670091 -0.4788587 -0.8767999 0.04377436 0.04906988 -0.9979988 -0.03987824 0.150134 -0.9825168 0.1100933 0.4800882 -0.8689019 -0.1205194 0.709706 -0.6886574 0.1485542 0.8905553 -0.4288884 -0.1515449 0.9630026 -0.2615048 0.06512439 0.9902608 0.1317806 0.04491192 0.9701087 0.2305154 -0.07584083 0.8139748 0.5759306 0.07582235 0.734504 0.6743537 -0.0758351 0.4297145 0.8997774 0.07580387 0.2852187 0.9523086 -0.1084368 -0.03189951 0.9941686 0.1030105 -0.2983476 0.9514859 -0.07525473 -0.4429489 0.8933801 0.07528775 -0.6835573 0.7198817 -0.1204977 -0.8477297 0.5165624 0.1204892 -0.9752548 0.1917149 -0.1101068 -0.9950153 0.09140741 0.03986406 -0.8835892 -0.4658137 -0.04782921 -0.8759482 -0.4822516 -0.01217925 -0.5051577 -0.8613401 0.05393493 -0.4436937 -0.8948189 -0.04934841 -0.03200393 -0.9993715 0.01524227 -0.05284273 -0.9984876 -0.0151664 0.3374476 -0.9402728 0.04490387 0.4069625 -0.9123398 -0.04491782 0.72907 -0.6842699 0.01521897 0.7362766 -0.6759594 0.03123652 0.9616372 -0.2725393 -0.03124278 0.9649409 -0.2620268 -0.0151959 0.992295 0.1223775 0.01934981 0.9943114 0.1061567 -0.008692383 0.8332453 0.5506073 0.05033725 0.753046 0.6500859 -0.1015381 0.5272529 0.8435457 0.1021506 0.3108502 0.9424214 -0.1233459 -0.066145 0.9895905 0.1278097 -0.1641128 0.9863154 -0.01577866 -0.5548177 0.8291677 -0.06825166 -0.6303535 0.7733072 0.06819498 -0.9083812 0.4179779 0.0117557 -0.9139033 0.4057625 -0.01171886 -0.9978219 -0.01038563 -0.06514149 -0.9881594 -0.1312545 0.07945615 -0.8944933 -0.4447704 -0.0454002 -0.8480552 -0.5279065 0.04601246 -0.6510282 -0.7559183 -0.06891983 -0.5318931 -0.8439781 0.06921446 -0.2564713 -0.9654673 -0.04577583 -0.1639038 -0.9854173 0.04569786 0.1638979 -0.983277 -0.07939672 0.2822702 -0.9571192 0.06516593 0.6319389 -0.7748568 0.01582491 0.6823402 -0.7257552 -0.08769971 0.9172026 -0.3911425 0.07580918 0.9537386 -0.2972639 -0.04490864 1.41377e-5 -6.59825e-6 1 5.43146e-6 -3.92737e-5 1 4.6337e-5 -4.39936e-5 1 4.8239e-5 -3.90756e-5 1 7.60198e-6 -2.4483e-6 1 6.2178e-6 -3.45003e-6 1 3.11096e-6 2.16401e-5 1 1.10321e-5 1.48846e-5 1 7.04522e-6 9.50543e-6 1 -2.51328e-6 2.5002e-5 1 6.35994e-6 3.00299e-5 1 5.24162e-6 -9.94607e-6 1 2.87891e-6 -9.82643e-6 1 6.94518e-6 -1.1426e-6 1 1.92894e-5 1.56542e-5 1 3.40756e-6 8.79462e-6 1 4.64457e-6 6.86772e-6 1 -8.1883e-7 5.09291e-6 1 -2.30099e-6 1.43116e-5 1 -5.05142e-5 2.68759e-5 1 -4.3626e-5 5.63307e-5 1 -0.9976437 -0.006675601 -0.0682829 -0.9511147 -0.3012843 0.06788641 -0.8936482 -0.4453601 -0.05520093 -0.5983987 -0.7987143 0.06304407 -0.4951993 -0.8668022 -0.0585798 -0.1055904 -0.9931198 0.05063474 0.04849547 -0.9961875 -0.07251685 0.3913268 -0.916539 0.08258193 0.6184959 -0.7812263 -0.08454751 0.8067651 -0.5847891 0.0845685 0.9239919 -0.3765987 -0.06642502 0.9990546 0.01041424 0.04220741 0.9980236 0.02423417 0.05797797 0.8674648 0.4916718 -0.07591938 0.7583416 0.6433557 0.1049358 0.3930904 0.9134929 -0.1049312 0.1858483 0.9769595 0.1049308 -0.2680277 0.9576799 -0.1049304 -0.4433888 0.8931072 0.07593321 -0.8132998 0.5789504 -0.05796402 -0.8218876 0.5680843 -0.0422036 -0.9764202 0.2054008 0.06643921 -1.94452e-5 -5.05891e-6 1 -1.96937e-5 -5.80383e-7 1 9.75467e-6 1.34438e-6 1 0 -5.74139e-6 1 -2.36905e-5 2.08292e-5 1 -2.76107e-5 1.6799e-5 1 -3.16219e-6 8.15478e-6 1 -1.38291e-6 1.36213e-5 1 -4.05065e-6 1.67986e-5 1 -1.62077e-5 7.9662e-6 1 0 0 1 6.76955e-7 3.78154e-6 1 -7.69897e-6 5.90828e-6 1 -2.68007e-5 -4.6157e-5 1 -1.10229e-5 -4.50914e-5 1 -4.92873e-6 2.6936e-5 1 3.06978e-5 3.61742e-5 1 1.88542e-5 -1.28857e-5 1 1.63198e-5 -2.1112e-5 1 5.59894e-6 -7.24302e-6 1 7.93885e-6 -5.00482e-6 1 1.8424e-5 -1.64231e-6 1 -0.9889349 -0.1362938 0.05858284 -0.9642255 -0.2574689 -0.06307679 -0.7247654 -0.6861065 0.06303149 -0.6345666 -0.7706449 -0.05858051 -0.2718795 -0.9609998 0.05060511 -0.1480737 -0.9876796 -0.05062818 0.2608116 -0.963611 0.05857723 0.3526476 -0.9350633 -0.03600656 0.7473908 -0.6643747 0.003617823 0.7733873 -0.6324061 0.04398256 0.9452911 -0.3229407 -0.04619574 0.9827491 -0.1790776 0.0462085 0.9883365 0.1477121 -0.03704279 0.9763363 0.2154601 0.01856064 0.8067961 0.5905394 -0.01853001 0.7638688 0.6443061 0.03706961 0.5148373 0.856042 -0.04620164 0.3229154 0.9426433 0.08455401 0.03607982 0.9943684 -0.09964841 -0.2854689 0.953194 0.09964215 -0.5719503 0.8139608 -0.1016892 -0.7140496 0.6987427 0.04349499 -0.9296646 0.3682569 0.01051849 -0.9516751 0.3014681 -0.05857938 -4.18028e-6 -4.92499e-6 1 -1.72318e-5 6.73328e-6 1 -3.32489e-6 1.34374e-5 1 3.56946e-6 -1.44258e-5 1 -8.27377e-7 -1.54905e-5 1 1.33713e-6 -7.57316e-6 1 -1.80196e-6 -7.9572e-6 1 2.27394e-7 -1.53693e-5 1 -2.57483e-5 -7.20013e-6 1 3.06604e-5 2.27583e-5 1 3.97665e-5 5.91712e-7 1 -6.11444e-6 6.49143e-6 1 -9.29347e-6 -7.12315e-6 1 -8.90513e-5 6.01247e-5 1 -8.92345e-5 4.99312e-5 1 -6.66939e-5 4.67696e-5 1 -5.07996e-5 1.02399e-4 1 1.44392e-5 7.06451e-5 1 -2.2197e-5 8.49533e-6 1 6.44867e-6 -1.34878e-5 1 8.40269e-5 5.77646e-5 1 0 7.0073e-5 1 -1.83719e-5 3.04768e-6 1 0 0 1 -0.9791133 -0.2012102 -0.02918487 -0.9690121 -0.2459174 0.02323997 -0.7537879 -0.6568557 -0.01855427 -0.7290587 -0.6843572 0.0113399 -0.4161094 -0.9092214 -0.01302134 -0.4074072 -0.9132395 -0.003623247 0.03200429 -0.998924 0.03356629 0.1335099 -0.9899185 -0.04729223 0.4160946 -0.9085093 0.03842109 0.5551538 -0.829665 -0.05882436 0.7696086 -0.6347908 0.06887096 0.9128061 -0.4052879 -0.05026614 0.9571594 -0.2879504 0.03050249 0.9988775 0.01040542 -0.04620933 0.9719953 0.2192598 0.08455872 0.8802551 0.4672599 -0.08257895 0.6635469 0.7446094 0.07254278 0.5417315 0.8390265 -0.05061107 0.2206661 0.9744318 0.04229742 0.0361669 0.9968382 -0.0707497 -0.1735417 0.9828918 0.06169992 -0.551293 0.8327817 -0.05050176 -0.611598 0.7908944 0.02083599 -0.9135127 0.4061461 -0.02323669 -0.9310224 0.3637939 0.02918249 2.47005e-5 2.5873e-5 1 -4.76575e-6 8.68466e-6 1 8.21363e-7 6.54324e-6 1 1.93244e-5 3.56391e-5 1 -1.33832e-6 -8.64141e-6 1 7.43462e-7 4.80046e-6 1 1.369e-5 -3.01054e-6 1 -7.9705e-6 1.81676e-6 1 -6.85116e-6 1.56162e-6 1 -4.8667e-6 -1.24831e-5 1 1.41605e-5 2.62274e-5 1 1.4142e-5 -8.91862e-6 1 -1.32984e-6 -7.33285e-6 1 2.24914e-6 -1.78779e-6 1 2.99805e-5 -2.38309e-5 1 -1.08159e-4 -7.39188e-5 1 -1.31696e-4 -5.76963e-7 1 1.35918e-5 -1.85154e-5 1 1.01216e-5 -7.04742e-6 1 1.25715e-5 -6.63782e-6 1 5.21643e-6 2.77669e-5 1 -2.96448e-5 3.75017e-5 1 -0.9987258 0.03282564 0.03832983 -0.9956758 -0.06043469 -0.07055032 -0.8126347 -0.5784874 0.07054919 -0.756432 -0.6529496 -0.03830611 -0.3132299 -0.9496595 0.005834579 -0.269069 -0.9613739 0.05798441 0.1892362 -0.9795309 -0.06862276 0.337054 -0.9399912 0.05302083 0.6240768 -0.7807675 -0.03049856 0.7164107 -0.6958659 0.05026406 0.875959 -0.4774441 -0.06886976 0.9819609 -0.1746284 0.07251143 0.9984878 -0.02141946 -0.05062949 0.9454619 0.3229763 0.04228627 0.881961 0.4682011 -0.05415141 0.7248772 0.6854874 0.06826448 0.5406011 0.8372155 -0.08258718 0.2161615 0.9736603 0.07252627 0.03614646 0.9967116 -0.07252341 -0.3405909 0.935335 0.09563648 -0.5285294 0.8456314 -0.0745936 -0.8480458 0.5275914 0.0496546 -0.8250022 0.5650711 -0.008136332 -0.09167379 -0.9957049 0.01294779 0.1227739 -0.9923583 -0.01230669 0.1839532 -0.9827789 0.01752191 0.2948228 -0.9554864 -0.01118403 0.4077588 -0.9127163 0.0261088 0.5206601 -0.8529716 -0.03677856 0.6713746 -0.7399606 0.04140692 0.7532709 -0.6571213 -0.02783101 0.8830849 -0.4688023 0.01963132 0.862209 -0.5061724 -0.01962816 0.956609 -0.2898947 0.02933031 0.9780894 -0.2063077 -0.02789908 0.9996177 0.02723789 0.00476557 0.9989517 0.04217517 0.01779931 0.9468888 0.3211814 -0.01562684 0.9356609 0.352648 0.0133475 0.7873794 0.6163123 -0.01388871 0.7683694 0.6398563 0.01386427 0.5370508 0.8434359 -0.01387166 0.5113176 0.8592803 0.01384598 0.2254235 0.9741621 -0.01387476 0.2315211 0.9726317 -0.01963764 0.004392087 0.9996031 0.0278263 -0.1119113 0.9928548 -0.04141569 -0.3069908 0.950811 0.04141473 -0.4362658 0.8988645 -0.04140961 -0.6062032 0.7942304 0.04142165 -0.6948373 0.7186284 -0.02782505 -0.8401489 0.5420003 0.019634 -0.8368031 0.5473282 0.01386684 -0.9637201 0.2665545 -0.01386642 -0.9713392 0.2372927 0.01386636 -0.9974699 -0.06972432 -0.01386588 -0.9949057 -0.09985274 0.01386696 -0.9172627 -0.3980414 -0.0138635 -0.9196645 -0.3922135 -0.01964157 -0.806288 -0.5908684 0.02782309 -0.7474756 -0.6637061 -0.02782738 -0.5771771 -0.816383 0.01963239 -0.5823596 -0.8128131 0.01386427 -0.3290407 -0.9442418 -0.01183062 -0.3132373 -0.9496748 3.56835e-5 -0.1112121 -0.9937967 -1.47075e-5 7.62736e-6 -6.16505e-5 -1 8.1765e-7 2.18102e-6 1 4.12028e-6 2.47484e-6 1 2.35681e-5 6.28659e-5 1 -3.89111e-5 1.39032e-4 1 -6.79298e-6 6.94031e-6 1 -1.90432e-6 -7.634e-6 1 7.49729e-5 -7.4113e-6 1 -7.5468e-6 -8.83627e-6 1 4.01779e-6 1.09992e-5 1 0 1.21288e-5 1 8.96505e-6 2.99325e-5 1 -4.22636e-6 2.55006e-5 1 -2.33058e-5 4.3387e-5 1 1.31255e-5 -5.57432e-6 1 5.48207e-6 -6.74549e-7 1 4.40548e-5 7.37378e-6 1 -4.51967e-6 -8.24116e-6 1 2.91031e-6 1.19252e-5 1 4.86225e-6 1.87858e-6 1 5.05105e-6 1.90373e-6 1 5.3757e-6 1.43543e-6 1 8.51457e-5 -7.99639e-6 1 7.62307e-5 -1.07253e-5 1 -1.65562e-6 -6.78403e-6 1 2.69951e-6 3.16075e-6 1 -1.67054e-5 1.75428e-4 1 -3.42107e-5 -3.54285e-5 1 5.80249e-6 4.86246e-6 1 3.67608e-6 9.64088e-6 1 -1.52021e-6 -9.90393e-6 1 -1.8323e-7 -3.30547e-5 1 -1.33211e-6 1.39888e-5 1 2.50309e-6 1.33033e-5 1 -2.34117e-6 -1.35468e-5 1 -5.5881e-6 3.59416e-6 1 -5.63625e-6 2.98517e-6 1 4.01426e-6 -6.63238e-6 1 4.36079e-7 -1.10462e-5 1 2.31022e-6 -7.57114e-6 1 -5.62062e-6 1.84917e-5 1 4.27816e-5 -4.54145e-5 1 -8.15121e-6 6.33977e-6 1 4.90151e-5 2.24045e-6 1 -2.59626e-7 5.3332e-6 1 6.26348e-7 7.48255e-6 1 3.51995e-7 -9.70232e-6 1 -1.55109e-6 9.44832e-6 1 1.17252e-5 -3.38685e-5 1 1.22656e-5 -8.75033e-6 1 7.12087e-6 1.09627e-5 1 0 0 1 -1.8542e-6 1.75414e-6 1 -2.34063e-7 5.92898e-6 1 1.27797e-6 -5.62796e-6 1 -2.44947e-5 1.62916e-5 1 -9.65881e-6 7.16684e-6 1 2.31137e-5 1.27166e-7 1 2.33758e-5 3.06725e-5 1 -4.16932e-5 -3.49329e-6 1 -1.58776e-5 2.39783e-5 1 2.70309e-5 1.98366e-5 1 -1.34926e-5 9.34431e-6 1 -4.07461e-6 6.76894e-6 1 -1.12427e-5 1.22453e-5 1 2.46183e-5 -2.68135e-5 1 1.18462e-6 -1.29589e-5 1 3.78959e-7 9.15767e-6 1 4.74599e-7 7.93567e-6 1 -5.0354e-7 1.72025e-7 1 -1.02301e-6 -3.41296e-6 1 5.13172e-6 6.15721e-6 1 -3.45056e-6 2.35294e-7 1 2.03705e-7 -2.28166e-6 1 -1.73497e-5 2.05091e-5 1 -0.9760329 0.214814 -0.03485381 -0.8839144 0.4643985 0.05504018 -0.7638688 0.6443298 -0.0366562 -0.444083 0.8956861 0.02316761 -0.3528017 0.9354894 -0.01976168 -0.03199452 0.9991838 0.02465665 0.1782606 0.9829438 -0.04521638 0.4071733 0.9126611 0.03549182 0.7473066 0.6639519 -0.02647143 0.6950532 0.7184705 0.0264818 0.9398761 0.3391812 -0.03986388 0.9822028 0.1854676 0.02965444 0.9875817 -0.1569802 0.006289064 0.950102 -0.3036082 -0.07161325 0.7553228 -0.6520059 0.06615 0.4804578 -0.8755412 -0.05087023 0.3131721 -0.9493117 0.02702623 -0.1244725 -0.9915887 -0.03547775 -0.216654 -0.9759849 0.02268803 -0.744291 -0.6678534 -0.001653909 -0.7555786 -0.6549139 -0.01373714 -0.9866594 -0.1623235 0.01242846 -0.9832838 -0.180532 0.02369195 -0.9989638 0.03971159 0.02223324 -0.9801276 0.1922276 -0.04897326 -0.8625259 0.5036163 0.04918944 -0.6643648 0.7455031 -0.05333429 -0.3946912 0.9171998 0.05443578 -0.189546 0.9811872 -0.03665989 0.2425972 0.9697524 0.02695882 0.2828366 0.9591529 0.005403995 0.655554 0.7549439 -0.01756858 0.7447684 0.6655476 0.04864716 0.9644671 0.2575162 -0.05906414 0.9972888 -0.03025829 0.06707859 0.9521425 -0.301614 -0.04953473 0.7174045 -0.6937997 0.06302976 0.624535 -0.7808597 -0.01463681 0.2170634 -0.9754453 -0.03728121 0.01209473 -0.9972761 0.07275933 -0.3944873 -0.9167312 -0.06311762 -0.5995253 -0.7993627 0.03985881 -0.8850968 -0.4647461 -0.024796 -0.884999 -0.4649399 -0.02465134 -0.9807206 0.1923183 -0.03465169 -0.9675168 0.2527768 0.00388807 -0.7712237 0.6361418 0.02319008 -0.6413033 0.7653539 -0.05443865 -0.3395856 0.9384754 0.06281304 -0.04853397 0.9968434 -0.0628283 0.3748103 0.9261202 0.0426464 0.4958571 0.8679857 -0.02695679 0.8005909 0.5983044 0.03295093 0.9199082 0.3891913 -0.04794579 0.9701601 0.2418033 0.01790308 0.978587 -0.2058247 -0.001929759 0.9690031 -0.2459297 -0.02348631 0.8064237 -0.5906611 0.02828806 0.6612521 -0.7475765 -0.06225115 0.341435 -0.9375745 0.06615281 -0.007547795 -0.9986765 -0.05087596 -0.2165398 -0.9755045 0.03874939 -0.5419454 -0.8392525 -0.0441634 -0.7260947 -0.6866272 0.03646063 -0.8972872 -0.4399234 -0.03664851 -0.9557178 -0.2926962 0.03053802 -0.9841753 0.1770921 -0.006121873 -0.9867264 0.1623331 0.004361033 -0.7642299 0.6446579 -0.01920682 -0.6779999 0.7336356 0.04577153 -0.3236483 0.9447929 -0.05116796 -0.09424328 0.9942332 0.05117154 0.2867056 0.9572347 -0.03875231 0.4073271 0.9131427 0.01596903 0.7475873 0.6641277 -0.006900012 0.7760255 0.6297805 -0.03407227 0.9818003 0.1854021 0.04115939 0.984478 -0.1564798 -0.0794807 0.9965984 -0.08030515 -0.01851302 0.7384408 -0.6741034 0.01702183 0.7048425 -0.7091596 -0.01702761 0.1510432 -0.9883805 0.01702409 0.1331502 -0.9910864 0.004338264 -0.4205265 -0.9070498 -0.0204522 -0.5031108 -0.8633993 0.03769844 -0.8846273 -0.4647572 -0.03788518 -0.9249092 -0.3796169 0.02083384 -3.66546e-5 -2.85337e-5 -1 -6.19674e-5 2.19118e-5 -1 1.71372e-5 1.81608e-5 -1 1.18799e-5 3.7213e-6 -1 1.04198e-6 1.11622e-5 -1 -7.32485e-6 -8.98106e-7 -1 -6.94693e-6 -1.4956e-6 -1 9.4369e-6 8.32688e-6 -1 2.08967e-5 6.28136e-5 -1 1.43155e-4 -1.81321e-7 -1 4.84317e-5 -9.04112e-7 -1 3.3336e-5 -6.76146e-5 -1 -1.23061e-4 6.83002e-5 -1 -1.93891e-5 1.28435e-4 -1 2.49727e-6 -1.09275e-6 -1 -1.25007e-5 5.47002e-6 -1 -1.26443e-5 5.06329e-6 -1 7.63582e-6 -1.02227e-5 -1 6.71222e-6 9.14161e-6 -1 4.95498e-6 9.34859e-6 -1 -3.64328e-5 -6.8738e-5 -1 -6.02011e-5 2.26352e-5 -1 -1.34021e-6 2.4715e-6 -1 -3.22186e-6 -5.14372e-6 -1 -1.15574e-6 -7.62527e-6 -1 -1.05126e-5 -1.92483e-5 -1 -2.9556e-5 3.72517e-5 -1 7.80834e-5 5.70549e-5 -1 2.97681e-5 -4.17189e-5 -1 -2.6394e-5 1.14313e-5 -1 -1.58166e-5 1.79512e-5 -1 -1.60523e-5 1.87365e-5 -1 -4.83838e-5 8.29638e-6 -1 -4.70922e-5 4.01401e-6 -1 1.10349e-5 -4.2884e-6 -1 8.56284e-6 -2.12022e-5 -1 -4.05082e-6 -1.94264e-5 -1 -8.21033e-6 6.72648e-6 -1 9.10668e-6 5.56096e-7 -1 -8.71912e-6 -7.95953e-6 -1 -9.10952e-6 -7.31688e-6 -1 1.66504e-5 4.48951e-6 -1 2.86352e-5 -1.85705e-5 -1 2.13435e-5 -2.06412e-5 -1 8.74855e-6 1.39671e-5 -1 -6.55713e-6 -9.20127e-6 1 2.9825e-7 -6.01551e-7 1 0 -4.89876e-6 1 -5.61428e-5 -4.96675e-5 1 6.55908e-5 1.23854e-5 1 4.57821e-7 -2.40534e-7 1 -2.04852e-6 4.60898e-6 1 1.74277e-7 7.85086e-7 1 -2.03808e-5 1.98806e-5 1 1.75881e-5 -3.90073e-7 1 -2.72861e-6 -5.1144e-6 1 0 0 1 -1.78252e-7 1.16643e-6 1 2.52663e-6 -4.016e-7 1 2.85067e-5 2.03768e-5 1 -1.82225e-5 -3.44111e-6 1 3.9516e-7 -4.27586e-7 1 0 -1.66795e-6 1 -6.33043e-7 1.70797e-6 1 3.53939e-6 7.29747e-6 1 1.62074e-6 -3.76629e-6 1 -5.39326e-7 -7.11745e-6 1 -2.5346e-6 -6.80273e-6 1 -7.95427e-6 -1.11503e-5 1 -2.35611e-6 -1.0404e-5 1 3.10778e-6 1.34715e-5 1 2.7954e-5 4.58316e-5 1 0.9989778 -0.002474904 0.0451349 0.9781574 0.2057725 -0.02942383 0.8226049 0.5684596 -0.01322764 0.7450637 0.665818 0.03957843 0.4443877 0.8951865 -0.03407061 0.2424944 0.9693053 0.04054474 -0.1594017 0.986381 -0.04054141 -0.3948901 0.9176468 0.04456418 -0.6646799 0.7458516 -0.04365849 -0.869147 0.4926232 0.04365706 -0.974826 0.2198742 -0.03700786 -0.9955897 -0.08224761 0.04512906 -0.9396981 -0.3385701 -0.04835104 -0.6859222 -0.7265844 0.03981959 -0.5676993 -0.8228377 -0.02560687 -0.2208319 -0.9751371 0.01846235 -0.0897119 -0.9958263 -0.01678425 0.2338368 -0.9719677 0.02447903 0.3287263 -0.94426 -0.01766681 0.7822088 -0.6230162 4.73345e-4 0.8082706 -0.5883868 0.02235001 0.9701051 -0.241845 -0.02018034 -8.50724e-6 -1.50778e-5 1 -1.14704e-5 1.62476e-5 1 -4.90448e-7 2.18223e-5 1 9.43199e-6 9.27585e-6 1 2.20141e-6 -2.67943e-7 1 1.47521e-5 -1.79555e-6 1 -2.83806e-6 1.90131e-5 1 -1.14764e-5 9.14074e-6 1 -3.781e-5 1.49386e-5 1 -3.52832e-5 -7.6703e-6 1 -4.75006e-6 7.81818e-6 1 -9.13687e-6 1.16695e-5 1 -6.39386e-6 1.71369e-5 1 5.22519e-5 -2.73802e-6 1 5.45769e-5 2.91728e-5 1 -1.75073e-6 2.18882e-5 1 1.17217e-6 4.68566e-6 1 9.02598e-7 4.44138e-6 1 -1.87511e-5 2.36431e-5 1 -1.81361e-5 3.49098e-5 1 -1.15427e-4 3.7892e-5 1 -8.82861e-5 6.79531e-6 1 -9.67691e-5 -1.78596e-6 1 -0.9763281 -0.1916866 0.1001979 -0.9461266 -0.3057657 -0.1065447 -0.6623392 -0.7432432 0.09432125 -0.5403707 -0.8316615 -0.1278231 -0.1882372 -0.9743462 0.1233541 0.04887115 -0.9935702 -0.102126 0.3403917 -0.9347832 0.1015574 0.4819723 -0.8722815 -0.08263051 0.8213547 -0.5625618 0.09434258 0.8851444 -0.4569808 -0.08768135 0.9951147 -0.06323075 0.07581907 0.989984 0.09043562 -0.1084112 0.9106157 0.4002165 0.1029843 0.7537466 0.6506516 -0.09229671 0.688084 0.7250984 0.02779775 0.3376762 0.9408508 -0.02783346 0.2416486 0.9659687 0.09225213 -0.0795865 0.9895185 -0.1204955 -0.3891693 0.9043681 0.1751155 -0.6143764 0.776013 -0.1426375 -0.8775269 0.4620935 0.1281254 -0.9412463 0.3235146 -0.0969215 1.25146e-6 -1.4445e-5 1 3.84968e-6 3.1945e-6 1 7.70059e-7 3.33116e-5 1 1.67302e-5 -1.40997e-5 1 -3.10984e-6 4.60489e-5 1 1.68073e-5 -1.53051e-5 1 -6.55864e-7 1.66187e-6 1 -1.85059e-7 3.1116e-6 1 -6.93258e-7 -1.71926e-6 1 1.20714e-6 4.31312e-6 1 0.9990974 -0.03284186 0.02694123 0.9646175 0.2619283 -0.03011018 0.8141 0.579515 0.03746294 0.7173916 0.6961248 -0.02756255 0.2693905 0.9625367 0.03085237 0.204131 0.9789376 -0.003407657 -0.2208195 0.9751299 -0.01898378 -0.3668874 0.929641 0.03407853 -0.6441678 0.7643426 -0.02877914 -0.7712744 0.6361829 0.02017676 -0.9354028 0.3532137 -0.01617801 -0.9658563 0.258384 0.0189526 -0.9921544 -0.1220763 -0.02696257 -0.9545617 -0.2971783 0.02229517 -0.8537275 -0.5202425 -0.02229315 -0.747098 -0.6641669 0.0269618 -0.3951466 -0.9182686 -0.02533942 -0.352874 -0.9356673 -0.002538442 0.1166325 -0.993067 0.01465618 0.2693247 -0.9622498 -0.03923738 0.4918172 -0.8702808 0.02696478 0.798066 -0.6021661 -0.02206069 0.840296 -0.5420517 0.009094059 0.9912274 -0.1319195 -0.00809735 -2.27107e-5 -8.52993e-6 1 -5.48063e-6 -2.05848e-6 1 -3.44522e-6 -9.92446e-6 1 -6.86562e-6 -1.2007e-5 1 1.52687e-5 -3.81915e-5 1 3.98868e-5 -1.00575e-5 1 2.7546e-5 -6.94574e-6 1 1.73006e-5 -2.17612e-5 1 -1.07551e-5 1.43136e-6 1 -1.43631e-5 -2.04576e-5 1 2.42502e-5 1.15507e-5 1 1.86966e-5 1.81424e-5 1 8.4502e-6 -5.95714e-6 1 -7.88444e-6 -1.75504e-6 1 -3.20616e-6 -2.00565e-5 1 -7.76792e-7 -1.72404e-5 1 -1.20511e-5 -1.25036e-5 1 -1.64546e-5 2.53441e-5 1 2.92538e-5 4.31737e-5 1 8.49133e-5 -3.60728e-5 1 1.29501e-4 1.44322e-5 1 1.09085e-4 2.45884e-5 1 1.08218e-4 5.25534e-5 1 -5.87995e-6 -9.1663e-5 1 -0.9947727 -0.08730471 -0.05296349 -0.8780345 -0.4746011 0.06171864 -0.7792291 -0.6147692 -0.1219054 -0.6217004 -0.7777965 0.09231078 -0.2605122 -0.9625032 -0.07563567 -0.1895876 -0.9813664 0.03124713 0.2721124 -0.961758 -0.03124326 0.3411791 -0.9369504 0.07563585 0.6854186 -0.7222708 -0.09233814 0.8043995 -0.5891524 0.0764271 0.91385 -0.4016701 -0.05949211 0.9753304 -0.2051617 0.08148193 0.989081 0.09035086 -0.1164281 0.9570267 0.271233 0.1026278 0.7357575 0.6716601 -0.08679705 0.6843287 0.7278603 0.04374378 0.2039685 0.9781651 -0.03987216 0.1022667 0.9886459 0.1100945 -0.2456728 0.9618347 -0.120495 -0.5132717 0.8452736 0.1485427 -0.7227721 0.6834974 -0.102136 -0.8790951 0.4700517 0.07901418 -0.9399372 0.3376587 -0.05004525 -0.9986451 -0.006244242 0.05166298 0 -1 0 -0.02136033 -0.9889776 0.1465167 -0.02612847 -0.9994745 0.0191822 -0.00958836 -0.9999001 -0.01038742 0 -1 0 0 -1 0 0 -1 0 -0.9030365 -0.4286638 0.0277909 -0.01656162 -0.9998511 0.004856169 -0.09172201 -0.9954193 0.02697163 0.00620681 -0.9999337 0.009703278 0.01539635 -0.9997424 -0.0166794 -0.06802976 -0.9949576 0.07369899 0.01079809 -0.9999269 0.005455136 0 -1 0 0.03708738 -0.9992941 -0.005988657 0.3673219 -0.9295817 -0.0308662 0.5407643 -0.8388037 0.06310588 0.6954973 -0.7181406 -0.02361452 0.5300531 -0.846583 -0.0483818 0.6027162 -0.7975732 0.02470463 -0.5897182 -0.8074597 0.01553261 -0.5415707 -0.8400306 -0.03240209 -0.5897127 -0.8074636 0.01554256 -0.5415561 -0.84004 -0.03239947 0.34237 -0.1205525 -0.9317992 0.2925422 -0.1888993 -0.9374093 0.341373 -0.1404706 -0.929372 0.2964479 -0.2139352 -0.9307793 0.5556825 -0.2327951 -0.7981374 0.5558885 -0.2334164 -0.7978125 -0.09555697 -0.4425382 -0.8916439 0.5775434 -0.2247121 -0.7848237 -0.6529412 -0.414753 -0.6337569 -0.5206047 -0.4902826 -0.6989948 -0.2543944 -0.6256832 -0.7374308 -0.04215174 -0.5553622 -0.8305397 -0.5247257 -0.5284011 -0.6674243 -0.0959714 -0.5484334 -0.8306685 -0.6536149 -0.4221865 -0.6281291 0.2173631 -0.4412515 -0.8706609 -0.05056113 -0.4692651 -0.8816087 0.2819708 -0.3966863 -0.8735745 -0.2016769 -0.2424318 -0.9489749 -0.2690438 -0.360895 -0.892956 -0.03349983 -0.4187201 -0.9074972 0.4085185 -0.2280437 -0.8838035 0.2137175 -0.2674535 -0.9395709 0.3975726 -0.2466734 -0.883792 0.1986914 -0.1313921 -0.9712147 0.2094761 -0.120373 -0.9703763 0.2378585 -0.5566053 -0.7959986 0.1299933 -0.9011436 -0.4135723 0.3360294 -0.3941144 -0.8554286 0.1490561 -0.5091754 -0.8476572 0.04970103 -0.4378325 -0.8976818 0.2309238 -0.7653279 -0.6007891 0.03371673 -0.6878072 -0.7251101 0.03137296 -0.4006259 -0.9157044 0.04677945 -0.6515938 -0.7571243 0.4050281 -0.7892297 -0.4615938 0.3919968 -0.639881 -0.6609772 0.4670228 -0.4609701 -0.7545835 0.6174143 -0.352688 -0.7031435 0.3325267 -0.3609684 -0.8712794 0.8373253 -0.2668579 -0.4771512 0.8540073 -0.3617361 -0.3739233 -0.1533907 -0.1457511 -0.9773577 -0.5954449 -0.06542998 -0.8007274 -0.2549437 -0.1865505 -0.9487901 -0.1848044 -0.2714599 -0.9445405 -0.2270567 -0.05724173 -0.9721978 -0.6213388 -0.2810223 -0.7314127 -0.5296414 -0.2478671 -0.8111978 -0.5870863 -0.2242404 -0.777847 0.564715 -0.4770822 -0.6734164 -0.277886 -0.08665037 -0.956698 0.1833419 -0.1938076 -0.9637553 -0.2313157 -0.2260826 -0.946245 -0.3914064 -0.2316536 -0.8905827 0.3315523 -0.4215437 -0.8440225 0.2947083 -0.5110995 -0.8074184 -0.1384013 -0.4860442 -0.8629056 0.753077 -0.3624881 -0.5490695 0.7453066 -0.4816267 -0.4610357 0.4247922 -0.6019886 -0.676137 0.4966788 -0.6553311 -0.5690794 0.1221866 -0.5655484 -0.8156136 0.1489647 -0.2888486 -0.9457145 -0.3221614 -0.3206866 -0.8907144 0.5478531 -0.3887895 -0.7407428 -0.1957604 -0.4410901 -0.8758524 -0.2469115 -0.4948489 -0.8331623 -0.08374196 -0.9015776 -0.4244352 -0.2654768 -0.6791594 -0.6842986 -0.05524039 -0.5913309 -0.8045348 -0.07167088 -0.6905105 -0.7197629 -0.07409644 -0.530077 -0.8447059 -0.297856 -0.4115022 -0.861364 -0.05405825 -0.379427 -0.923641 -0.08602106 -0.2625212 -0.9610844 -0.5332307 -0.5621476 -0.6321829 -0.6833844 -0.5390591 -0.4923424 -0.6728764 -0.5040932 -0.5414125 -0.4262126 -0.2262849 -0.8758642 -0.796442 -0.3380714 -0.5013861 -0.1653128 -0.5354632 -0.8282214 -0.2198445 -0.3505889 -0.9103603 -0.2142969 -0.606817 -0.7654083 -0.3608146 -0.6447571 -0.6738703 0.03005522 -0.4384335 0.8982609 0.6267533 -0.619632 0.4724791 0.2894711 -0.7191751 0.6316595 0.3922226 -0.6034721 0.6942498 0.3854882 -0.5578447 0.7349886 0.7998867 -0.3907659 0.4555034 0.8378632 -0.366864 0.4042226 0.4529407 -0.3847723 0.8042357 0.3471741 -0.2328913 0.9084227 0.6782832 -0.2373877 0.6953984 0.04054152 -0.772728 0.6334413 0.1613329 -0.7921256 0.5886499 0.0783798 -0.7117 0.6980973 0.2397039 -0.4656428 0.8518913 0.08289641 0.7183106 0.6907663 0.1119565 -0.8253405 0.5534246 0.1446163 -0.5908537 0.7937116 -0.02474039 -0.4371545 0.899046 -0.9183391 -0.3478553 0.1888116 -0.08513206 -0.2447801 0.965834 0.4622561 -0.2192721 0.8592084 -0.4310294 -0.5788385 0.6922137 -0.3095585 -0.6627393 0.6818726 -0.2283577 -0.6003203 0.7664648 -0.07448029 -0.2300975 0.9703132 0.0829187 -0.2633389 0.9611333 0.094994 -0.3269883 0.9402419 0.3833762 -0.3321762 0.8617898 -0.03654837 -0.4658383 0.8841149 -0.1016941 -0.3824724 0.9183535 -0.4603689 -0.3350154 0.8220859 0.1911709 -0.462698 0.8656583 -0.2233362 -0.5768946 0.7856929 -0.7170168 -0.4199209 0.5563752 -0.7065315 -0.4060545 0.5795973 0.3024703 -0.3854111 0.8717626 0.2386855 -0.3946393 0.887293 0.5837001 -0.2272246 0.7795275 0.5729214 -0.2315094 0.7862343 0.3164438 -0.1579571 0.9353678 0.5312715 -0.1338308 0.8365644 0.06632828 -0.323062 0.9440507 0.1769278 -0.2051935 0.9625967 -0.7167 -0.2256603 0.6598625 -0.408084 -0.6781149 0.6112509 -0.05683678 -0.1584871 0.9857238 -0.3406842 -0.2515792 0.905893 -0.2991905 -0.2948372 0.9074999 -0.5600187 -0.6022331 0.5689414 -0.4361365 -0.6490924 0.6232687 -0.2739529 -0.4025617 0.873438 -0.6994289 -0.4158852 0.5812391 0.3235582 -0.6047105 0.7277606 -0.03669953 -0.9329323 0.3581766 -0.1327044 -0.8900557 0.4361083 -0.1346854 -0.8100926 0.5706224 -0.2604246 -0.4581992 0.8498426 -0.002449929 -0.467032 0.884237 -0.09243518 -0.5821789 0.8077892 -0.2096016 -0.5287384 0.8224979 0.007984757 -0.858738 0.5123528 -0.2577657 -0.1005874 0.9609574 0.5154689 -0.2606294 0.8163112 0.6003016 -0.4422761 0.6663557 0.4045757 -0.5853717 0.7026084 0.3937621 -0.560347 0.7286718 0.2178536 -0.6115868 0.7605928 0.2449902 -0.6360494 0.7317246 0.7298476 -0.4499218 0.5146774 -0.24675 -0.4019138 0.8818048 0.1156346 -0.290284 0.9499283 0.01869672 -0.1856903 0.9824304 -0.06352812 -0.4081629 0.9106961 -0.2047064 -0.2260344 0.9523674 -0.2568022 -0.4004846 0.8795822 -0.5353093 -0.1453259 0.8320603 -0.6389451 -0.1695078 0.750344 -0.7537755 -0.1216963 0.645765 -0.4292584 -0.2930833 0.8543064 -0.2405433 -0.4283767 0.870995 -0.1935384 -0.064152 0.9789931 -0.1988099 -0.07082599 0.9774755 -0.344729 -0.2041348 0.9162374 -0.04719853 -0.3293041 0.9430435 -0.3135513 -0.2715193 0.9099246 -0.09723532 -0.4740663 0.8751037 -0.9914932 -0.09610849 0.08777511 -0.9796022 -0.1873037 0.07277947 -0.9764745 -0.2156077 -0.003283798 -0.8420187 -0.5181471 0.1500939 -0.9016954 -0.3707174 0.2225177 -0.6330523 -0.7071629 0.3149052 -0.7091917 -0.5863509 0.3914584 -0.8543022 -0.5017976 0.1355249 -0.3321864 -0.9421804 0.04413795 -0.260568 -0.9003242 0.3485978 -0.2630158 -0.9504107 0.1659583 -0.385131 -0.8943444 0.2276445 -0.4602436 -0.887792 0.001051127 -0.4071305 -0.8152793 0.4117817 -0.3187509 -0.8944072 0.3137413 -0.3211024 -0.6643943 0.6748878 -0.2672138 -0.8052343 0.5293341 -0.3135668 -0.7797411 0.5419223 -0.6725542 -0.6872085 0.2746188 -0.5724639 -0.8076187 0.141553 -0.7895745 -0.6136531 -0.001423716 -0.1524758 -0.6214249 0.7684934 -0.9098481 -0.413428 0.03540891 -0.6424514 -0.7645045 0.05281227 0.2758788 -0.9611908 0.001758337 0.6181918 -0.7857772 0.0198251 0.6793568 -0.7323967 0.04549181 0.9786184 -0.1867322 0.0862382 0.8869061 -0.4011415 0.2290918 0.39697 -0.6600117 0.6378083 0.1884317 -0.628083 0.754987 0.693269 -0.583692 0.4227077 0.3960948 -0.7794235 0.4853945 0.2616243 -0.7923731 0.5510877 0.5726364 -0.7486183 0.3341534 0.982908 -0.163941 0.08375698 0.7937492 -0.5815075 0.1783571 0.5652304 -0.7513186 0.3406391 0.2640828 -0.9141056 0.307687 0.8436618 -0.5251839 0.11143 0.6006066 -0.7813802 0.1694601 0.4626922 -0.8741131 0.147791 0.343182 -0.9138397 0.2170782 0.9449965 -0.3260615 0.02579694 0.9251549 -0.3774572 0.04018074 0.7534124 -0.6571272 0.02352869 0.3879537 -0.9203563 0.04935812 0.06535178 -0.4942835 0.8668408 -0.1068665 -0.1960318 0.974757 -0.3716538 -0.9283539 0.005719602 -0.5497525 -0.8334209 -0.05640709 -0.6766443 -0.7362838 0.006210148 -0.9311506 -0.3204741 -0.1739392 -0.9378477 -0.3011001 -0.1725695 -0.4801765 -0.6425476 -0.5971291 -0.5352164 -0.6856487 -0.4933855 -0.8259599 -0.5056766 -0.2491617 -0.7444405 -0.5853852 -0.3211426 -0.4602091 -0.8004724 -0.3839939 -0.3453188 -0.8197465 -0.4569141 -0.9347792 -0.305433 -0.1813791 -0.4561623 -0.8528414 -0.2541207 -0.9495863 -0.3074282 -0.06143265 -0.7449103 -0.6540672 -0.1315479 -0.6888196 -0.7039312 -0.1732297 -0.3963176 -0.8992865 -0.1849765 -0.3655296 -0.9086195 -0.2019869 -0.9999033 -0.01321381 -0.004326105 -0.9168267 -0.3976689 -0.03589147 -0.9198015 -0.3910098 -0.03280967 0.00878185 -0.4705301 -0.8823401 0.007680356 -0.3393148 -0.9406416 0.1217637 -0.08815968 -0.9886362 -0.01078873 -0.336255 -0.9417092 6.03276e-4 -0.4631661 -0.8862712 0.1449874 -0.537043 -0.8310014 -0.5196351 -0.5570948 -0.6477846 0.3879973 -0.7760111 -0.4972571 0.9762985 -0.1965013 -0.09071069 0.4132516 -0.6551092 -0.632499 0.8928409 -0.4408403 -0.0921688 0.9969769 -0.07725423 -0.008296966 0.9782391 -0.2070903 -0.01271522 0.8045189 -0.5665125 -0.1783614 0.9038484 -0.3606437 -0.2302049 0.7175126 -0.693063 -0.06956642 0.6661306 -0.6834971 -0.2984992 0.6802119 -0.5873265 -0.4385879 0.8653948 -0.4936381 -0.08610075 0.4883125 -0.8710362 -0.05335479 0.3430461 -0.8755054 -0.3403084 0.4527919 -0.8805918 -0.139777 0.4194675 -0.9028465 -0.0944209 0.2622172 -0.7733707 -0.5771826 0.2771519 -0.8779264 -0.3904253 0.7879464 -0.6155009 -0.01729357 0.4663552 -0.7645976 -0.4448632 0.5651102 -0.8021537 -0.1928729 0.6487058 -0.7322903 -0.2071994 0.834537 -0.5498787 -0.03437024 0.5702103 -0.8203846 0.04277163 0.9009836 -0.00300461 -0.4338427 0.7954858 -0.004942715 -0.6059522 0.7968214 -0.005177497 -0.6041927 0.7220342 -8.90482e-4 -0.6918569 0.6671826 4.30609e-4 -0.744894 0.7393072 -3.26444e-4 -0.6733682 0.4749483 -5.62034e-4 -0.8800135 0.5730264 4.89772e-4 -0.8195368 0.2677395 5.32318e-4 -0.9634912 0.2828935 1.90668e-4 -0.9591514 -0.1043701 0.001026451 -0.9945381 -0.1727309 1.31956e-4 -0.984969 -0.3984186 -4.43334e-4 -0.9172036 -0.341062 0.001159846 -0.9400401 -0.6825301 -7.39648e-4 -0.7308571 -0.739615 -3.55763e-4 -0.6730302 -0.676051 -5.33183e-4 -0.7368547 -0.8812218 -0.002653539 -0.4726952 0.08666366 -3.87711e-4 0.9962376 0.2659817 0.001141607 0.9639775 0.3097046 2.90985e-4 0.9508328 0.4856458 -9.72373e-4 0.8741551 0.5894921 1.88508e-4 0.8077741 0.7140195 -7.15875e-4 0.7001255 0.7632321 -3.04466e-4 0.6461243 0.7014065 -4.42209e-4 0.7127614 0.8814322 -0.003051221 0.4723007 0.04086983 -0.1788365 0.9830295 0.1362315 -0.06388115 0.9886152 0.06497794 -0.4944146 0.8667941 -0.8874411 0.002300083 0.4609155 -0.8087615 -0.005817353 0.588108 -0.7206387 -3.05683e-4 0.6933107 -0.7232586 -3.21337e-4 0.6905773 -0.6149409 -0.00140202 0.788572 -0.4902204 -3.68365e-4 0.8715984 -0.533981 -2.00882e-4 0.8454964 -0.2820471 -5.60051e-6 0.9594005 -0.2661329 3.32533e-4 0.9639363 -0.001320123 -0.5084212 -0.8611075 9.54508e-4 -0.4722297 -0.8814751 0.001087009 -0.2424771 -0.9701566 -2.56307e-4 -0.3351129 -0.9421779 -1.17964e-4 -0.3374096 -0.941358 0.003307163 -0.123757 -0.9923071 -3.12381e-4 -0.2002558 -0.9797435 0.03331905 -0.9955542 -0.08810085 5.63423e-4 -0.999179 -0.04050916 0.002048969 -0.6498982 -0.7600185 -0.006762981 -0.5448109 -0.8385317 -0.001040101 -0.7255246 -0.6881955 -9.69138e-4 -0.7261496 -0.687536 -4.84491e-6 -0.8328431 -0.5535091 -0.001472413 -0.8180345 -0.5751672 -0.001218557 -0.8809885 -0.4731361 2.26143e-4 -0.8935273 -0.4490087 1.57635e-4 -0.9411637 -0.3379511 -3.09883e-4 -0.9440049 -0.3299313 -6.48467e-4 -0.9784643 -0.2064154 5.96607e-4 -0.9834189 -0.1813477 -0.001522123 -0.999738 -0.02283471 -0.003490447 -0.9988831 0.0471211 -0.00252366 -0.09692597 0.9952884 0.001154363 -0.1917045 0.9814521 -0.001425862 -0.2407295 0.9705911 -0.001004219 -0.3482737 0.9373924 0.001494526 -0.308511 0.9512196 6.78264e-5 -0.4903119 0.8715471 -4.79298e-4 -0.4823684 0.8759683 -2.17883e-6 -0.9991127 0.0421167 0.003202259 -0.9990246 0.04404121 2.81982e-4 -0.99921 0.03974211 -1.79777e-4 -0.9768046 0.2141323 0.001536965 -0.9831292 0.182906 0.001013696 -0.9288423 0.370474 -0.00342977 -0.9481403 0.3178336 6.7841e-4 -0.8859379 0.4638035 -0.001765966 -0.841035 0.5409778 5.94395e-4 -0.8158532 0.5782587 6.94998e-4 -0.7356154 0.6773992 -1.22619e-4 -0.7438598 0.6683356 3.13076e-4 -0.5805767 0.8142054 -1.94253e-4 -0.5887912 0.8082852 0.6947825 0.5906867 0.4103248 0.7307066 0.6337331 0.2538703 0.9424675 0.1878662 0.2765166 -0.01533412 0.6790585 0.733924 0.4487502 0.302374 0.8409479 0.4614469 0.3361207 0.8210297 0.4822037 0.3491372 0.8034817 0.442173 0.6207125 0.6474558 0.3225321 0.7125859 0.6230525 0.7736088 0.3656908 0.5174937 0.7523265 0.2426552 0.6124731 0.6963706 0.544564 0.4674593 0.2208448 0.2488395 0.9430304 0.3047912 0.8437278 0.4418433 0.09128743 -0.9421707 -0.3224607 0.003740012 0.6904715 0.7233499 0.004445075 0.6782726 0.7347969 -4.1414e-5 0.5064047 0.8622959 0.003853619 0.3650828 0.9309671 7.66758e-4 0.2217771 0.9750971 0.4521797 0.8664504 0.2116534 0.4786716 0.8276639 0.2929947 0.3692175 0.7768801 0.510035 0.4663822 0.7650622 0.4440357 0.3704122 0.6881548 0.6238892 0.4348655 0.5790375 0.6896431 0.3616748 0.4851654 0.7961193 0.3683402 0.1993904 0.9080578 0.3917001 0.1139286 0.9130123 0.4364516 0.8713603 0.2241458 0.4768928 0.5880981 0.6532334 0.5727211 0.3561939 0.7383201 0.5129456 0.3461878 0.7855194 0.6444539 0.2355895 0.7274453 0.5418425 0.03539359 0.8397344 0.8023794 0.515082 0.3014597 0.7709996 0.5107558 0.380379 0.7849318 0.361872 0.5029221 0.8536283 0.507007 0.1194254 0.7672797 0.5936833 0.2425323 0.7500609 0.5408356 0.3806647 0.7051377 0.3803812 0.5984069 0.8850608 0.1680281 0.4340899 0.8154738 0.0552017 0.5761556 0.8070191 0.05233746 0.5882014 0.966521 0.2109208 0.1461148 0.9570929 0.2736101 0.09545063 0.9172352 0.3667983 0.1553662 0.8660063 0.32158 0.3829091 0.9797152 0.09686076 0.1754311 0.9563214 0.03210109 0.2905491 0.9559496 0.032045 0.2917764 0.2999649 0.557731 0.7739233 0.3240549 0.1767264 0.9293848 0.1189191 0.7850733 0.60788 0.24735 0.4835408 0.8396465 0.981692 0.190409 -0.005018532 0.9314409 0.3638777 0.003312706 0.7982133 0.6023534 -0.005101859 0.6863009 0.7272742 0.007958114 0.4624266 0.8866428 -0.005120337 0.3692977 0.9293046 0.003486573 0.368422 0.9000087 0.2329152 0.9388297 0.1260604 0.3204803 0.7465932 0.1839182 0.6393533 0.7764674 0.587327 0.2283537 0.6816383 0.4474438 0.5789329 0.6755346 0.3279864 0.660362 0.4875319 0.7089999 0.5095409 0.6698067 0.7224096 0.1717078 0.5039508 0.5427833 0.6718779 0.2319722 0.9160197 0.3272566 0.234167 0.7558646 0.6114201 0.4754505 0.3605259 0.8024762 0.9390158 0.2605559 0.2244105 0.3760055 0.8951599 0.2393923 0.2735242 0.09038662 -0.9576089 0.3969967 0.0512883 -0.916386 0.2483465 0.2232725 -0.9425887 0.4313454 0.3289803 -0.8400675 0.2789089 0.5341316 -0.7980685 0.5016211 0.6509431 -0.5697802 0.4537931 0.7562232 -0.4713791 0.3691712 0.8687943 -0.3300137 0.4264138 0.8767144 -0.2225826 0.370153 0.9093686 -0.1898304 0.5958397 0.363686 -0.716036 0.3948218 0.628795 -0.6698751 0.4189018 0.7521867 -0.5086615 0.6201785 0.04456818 -0.7831937 0.6094175 0.05013734 -0.7912626 0.6899943 0.2037418 -0.6945483 0.5444347 0.3572377 -0.7589283 0.8132669 0.3496839 -0.4651004 0.6895315 0.700128 -0.1853841 0.7312965 0.4651275 -0.4988605 0.735006 0.5820668 -0.3477995 0.7794853 0.5602129 -0.2802931 0.7262085 0.6709576 -0.1497901 0.7245204 0.2705519 -0.6339336 0.7369738 0.5797334 -0.3475325 0.9262859 0.04712653 -0.3738631 0.9036013 0.1850182 -0.3863587 0.9231831 0.2543277 -0.2881849 0.9107996 0.2794011 -0.3039395 0.9468078 0.2771499 -0.1635324 0.8933404 0.4116466 -0.1802499 0.9528512 0.2972357 -0.06103813 0.9578188 0.1021429 -0.2686073 0.7511883 0.6067035 0.2600519 0.8480929 -0.01233774 -0.529704 0.9605721 0.02207708 -0.2771531 -0.4070587 0.9016928 0.1457852 -0.03003931 0.9995481 -0.001069903 0.2830778 0.9590942 0.002311468 0.3808866 0.9246197 -0.001930892 0.488798 0.8723969 -4.48068e-4 0.7429264 0.6693521 -0.005295574 0.8543909 0.5196194 0.003463089 0.9598078 0.2806381 -0.003342807 0.4512445 0.6696771 -0.5898397 0.2626041 0.1422148 -0.9543658 0.3183932 0.2146055 -0.9233474 0.8213105 0.2914073 -0.4904394 0.186132 0.4885361 -0.8524596 0.4950298 0.4812728 -0.72341 0.5181138 0.5184111 -0.6802999 0.5537195 0.1671763 -0.8157491 0.4528954 0.6718275 -0.5861176 0.8353921 0.4718878 -0.2818545 0.8623375 0.3525874 -0.3633955 -0.006420671 0.9818465 0.1895689 -0.3325607 0.8454268 0.4179198 -0.3091974 0.9056257 0.2902397 -0.3632346 0.8329244 0.4174896 -0.2180023 0.6891279 0.69107 -0.5315257 0.5580866 0.6371967 -0.5171898 0.5686103 0.6396853 -0.5762003 0.6760346 0.4593154 -0.7478439 0.6251457 0.2234332 -0.8709481 0.2846584 0.4005235 -0.635509 0.2809309 0.7191703 -0.5496109 0.3275115 0.7685468 -0.7510285 0.3642506 0.5507066 -0.06894624 0.9976204 2.03932e-4 -0.3514744 0.9361954 -0.002001643 -0.3852551 0.9228102 -2.08854e-4 -0.6317002 0.7752084 0.002592027 -0.7223932 0.69148 -0.00190407 -0.9203931 0.3909906 0.001787364 -0.9163943 0.4002748 0.001249849 0.3513861 0.9214652 -0.1656197 5.49006e-4 0.2380325 -0.971257 5.36293e-4 0.2377179 -0.9713341 0.004423499 0.524671 -0.8512935 0.002621948 0.5565714 -0.8307956 2.20737e-4 0.7781603 -0.6280657 0.002508461 0.8240064 -0.566575 -0.1694759 0.8391689 0.5167917 -0.3485557 0.2155233 0.9121725 -0.2433154 0.274394 0.9303254 -0.2141399 0.5080604 0.8342773 -0.2327542 0.6795064 0.6957704 0.6913175 0.3977998 -0.6031877 0.05990362 0.9959239 -0.06743186 0.2090157 0.9307107 -0.30015 0.6943809 0.5288006 -0.4880626 0.1801192 0.415861 -0.8914127 0.2803966 0.9021611 -0.3278458 0.6184702 0.7409158 -0.2617983 0.03846466 0.8881501 -0.4579409 0.3112007 0.84832 -0.4283775 0.724947 0.5045697 -0.4688938 0.4824176 0.3976513 -0.7804785 0.7507468 0.156367 -0.6418167 0.8881038 0.3669416 -0.2768129 0.3083875 0.5487657 -0.7770158 0.3152382 0.2985852 -0.9008173 0.2759769 0.5766182 -0.7689917 0.2077823 0.7630925 -0.6119773 0.1500774 0.802772 -0.5770909 0.3493053 0.2769935 -0.8951315 9.52822e-4 0.250751 0.9680511 -8.44449e-4 0.2948724 0.9555363 -0.004914462 0.4722324 0.8814604 -0.004273235 0.7438843 0.6682949 -5.88936e-4 0.598659 0.8010038 2.6414e-4 0.8533051 0.5214119 -0.3775534 0.9116314 -0.1624245 -0.1151477 0.9795693 -0.1648784 -0.6337346 0.7045956 -0.3192578 -0.593088 0.4511452 -0.6668693 -0.7050743 0.6710195 -0.2293536 -0.5163062 0.6936928 -0.5022135 -0.7002665 0.1144887 -0.7046411 -0.8604373 0.3266284 -0.3911029 -0.8605757 0.3337402 -0.3847426 -0.6145098 0.3275224 -0.7177094 -0.6331923 0.4069807 -0.6583572 -0.3620089 0.2757567 -0.8904536 -0.3398094 0.8222376 -0.4565688 -0.3493379 0.9275529 -0.1326976 -0.2047176 0.936773 -0.2838082 -0.2625744 0.8169153 -0.5135213 -0.8801579 0.2055926 0.4278478 -0.7099686 0.4918219 0.5040394 -0.4926486 0.3954057 0.7752107 -0.5104479 0.5617954 0.6510214 -0.2883583 0.3786863 0.8794579 -0.49128 0.586853 0.6436207 -0.562205 0.2550013 0.7867019 -0.1880691 0.8371614 -0.5136054 -0.2118133 0.6149751 -0.7595662 -0.3723613 0.3957541 -0.8394795 -0.324663 0.2973607 -0.89787 -0.1212598 0.7549894 -0.6444277 -0.8912529 0.04271566 0.4514906 -0.4199799 -0.579343 0.6985546 -0.002764105 0.7716385 -0.6360553 -5.22168e-5 0.7261763 -0.6875085 -0.001325249 0.4656311 -0.884978 -0.003287255 0.5058907 -0.8625913 -0.002489447 0.1680932 -0.985768 -9.70469e-4 0.2183135 -0.9758782 -0.1435282 0.09113001 0.9854415 -0.4444388 0.3297252 0.8329198 -0.463324 0.8537814 0.2374622 -0.3701998 0.9087951 0.1924673 -0.4853466 0.06693768 0.8717557 -0.4268683 0.09739965 0.8990533 -0.4374001 0.3344131 0.8347749 -0.5175737 0.4509135 0.7271826 -0.4109923 0.623158 0.6654018 -0.5631268 0.5931023 0.5754285 -0.4682995 0.762108 0.4470871 -0.4600088 0.7681745 0.4453085 -0.5161961 0.5502572 0.656322 -0.6879051 0.6949775 0.2092677 -0.7437007 0.04312402 0.6671203 -0.8096631 0.01719558 0.5866429 -0.7178398 0.1929038 0.66895 -0.7981272 0.2422178 0.5516554 -0.7545522 0.301455 0.5829029 -0.7917507 0.4094967 0.4532586 -0.8056669 0.5048557 0.3098737 -0.804891 0.3928555 0.444764 -0.8475659 0.439031 0.2981338 -0.8039062 0.5809477 0.1274161 -0.9252811 0.08003103 0.3707423 -0.9649648 0.1562401 0.2107889 -0.777 0.0907216 0.6229292 -0.9564336 0.1910955 0.2207201 0.3414964 0.7517381 0.5641543 -0.9238886 0.2890453 0.2507642 -0.9786931 0.191449 0.07420933 -0.2746732 0.4033644 -0.8728412 -0.5630113 0.5915524 -0.5771344 -0.3749622 0.2993924 -0.8773641 -0.6354628 0.3288241 -0.698614 -0.6525318 0.467761 -0.5961558 -0.3725433 0.692966 -0.6172598 -0.2779345 0.6919987 -0.666251 -0.2931877 0.06030535 -0.9541511 -0.3923713 0.1660264 -0.9046989 -0.8186277 0.3661775 -0.4424508 -0.3694007 0.9292648 -0.003187239 -0.3416504 0.9398101 -0.005653202 -0.6866074 0.7270226 -0.002895951 -0.688035 0.7256727 -0.002642154 -0.806526 0.5911969 0.001464903 -0.9164205 0.4001966 -0.004020392 -0.9300975 0.3673046 -0.002442896 -0.5736536 -0.02124106 -0.8188225 -0.7432472 0.03196501 -0.6682527 -0.4056 0.8916805 -0.2009842 -0.3821229 0.3519387 -0.8544714 -0.3604497 0.9053769 -0.2244294 -0.3679909 0.792396 -0.4865092 -0.4708078 0.7704666 -0.4297922 -0.3569398 0.6788967 -0.6416333 -0.4568269 0.5849881 -0.6701478 -0.2636184 0.4885751 -0.8317449 -0.2948634 0.09294939 -0.951008 -0.573107 0.3861383 -0.7228039 -0.4506 0.1616107 -0.877976 -0.6699153 0.7198339 -0.181804 -0.6425675 0.739294 -0.201374 -0.6423993 0.6487827 -0.4079267 -0.7090036 0.4180908 -0.5679031 -0.5698474 0.3905918 -0.7229884 -0.5725417 0.2159447 -0.7909261 -0.6175915 0.01629716 -0.7863302 -0.6913156 0.553401 -0.4645751 -0.8047987 0.1359836 -0.5777609 -0.8998321 0.4270034 -0.08927702 -0.7920771 0.5652531 -0.2304399 -0.8484186 0.4720602 -0.2394682 -0.7920459 0.4423648 -0.4206861 -0.8027853 0.3175104 -0.5047009 -0.9271965 0.1370059 -0.3486203 -0.8316317 0.01094204 -0.5552198 -0.9213087 0.3043696 -0.2419698 -0.9161609 0.1939999 -0.3507325 -0.9002992 0.03316032 -0.4340067 -0.9852572 0.1578561 -0.06595331 -0.9201182 0.3068068 -0.2434178 -0.8822845 0.2158444 -0.4183124 0.7987291 0.09489637 -0.5941604 0.5635889 0.08141636 -0.8220334 0.4699325 0.09706014 -0.8773499 0.3267188 0.07264202 -0.9423258 0.8291167 0.1131735 -0.547501 0.9257205 0.09667193 -0.3656448 0.949268 0.07542157 -0.3052901 0.4296796 0.3292768 -0.8408045 0.5732702 0.334135 -0.7481411 0.6044369 0.3565803 -0.7123949 0.8443986 0.2982943 -0.4449849 0.4550508 0.5523099 -0.6984859 0.6121332 0.5579464 -0.560347 0.8597802 0.3097126 -0.4060247 0.9166333 0.261232 -0.3025579 0.5818222 0.6183733 -0.5282967 0.4435556 0.7920872 -0.4193522 0.6314268 0.6422967 -0.4344598 0.8685946 0.4340873 -0.2389803 0.9223866 0.3265739 -0.2062823 0.4397611 0.8747562 -0.2034986 0.4968821 0.8385566 -0.2234523 0.8252046 0.5413963 -0.1610203 0.9195693 0.3927891 -0.01045137 0.838401 0.5450235 0.005761861 0.4500651 0.8929615 -0.007821798 0.3700634 0.9290065 -4.24519e-4 0.4772722 0.08153414 0.8749648 0.4040808 0.299088 0.864445 0.3751098 0.7693212 0.5171436 0.46399 0.08590233 0.8816655 0.5448343 0.5799805 0.6056221 0.5480132 0.5918712 0.5910754 0.5418252 0.743893 0.3912142 0.5238728 0.7701305 0.3639456 0.4449725 0.8780906 0.1759444 0.6340054 0.3201428 0.7039502 0.582463 0.4211137 0.6952698 0.6276981 0.4912008 0.603918 0.6094827 0.7647719 0.2089371 0.753767 0.09332633 0.650481 0.7553066 0.241216 0.6093658 0.7576102 0.5489131 0.3531591 0.8235113 0.0600869 0.5641086 0.8686104 0.4222377 0.25929 0.8337683 0.5420119 0.1051363 0.959167 0.06586164 0.2750653 0.9229076 0.1630156 0.3488087 0.9176446 0.2458303 0.3122435 0.9080665 0.4013102 0.1198558 0.9691287 0.07833433 0.2337806 0.9574339 0.2097041 0.1983548 -0.3751052 0.02564382 -0.9266275 -0.6595426 0.06127738 -0.7491654 -0.9956805 0.04175436 -0.0829268 -0.9471737 0.05483645 -0.3159982 -0.958608 0.07135492 -0.2756434 -0.9551929 0.2584105 -0.1443271 -0.90527 0.2423658 -0.3489195 -0.8116164 0.5667862 -0.1415354 -0.8214586 0.5540741 -0.1349366 -0.8547211 0.4198889 -0.3051967 -0.8415496 0.3687984 -0.3946921 -0.8382692 0.2385705 -0.4902945 -0.6442217 0.6738482 -0.3618108 -0.6495721 0.6603956 -0.3767408 -0.6285676 0.3073447 -0.7144522 -0.5085508 0.8453125 -0.1637766 -0.5084702 0.7127603 -0.4831468 -0.5593413 0.2755527 -0.781798 -0.5469003 0.2351588 -0.8034926 -0.4147211 0.8818796 -0.2242645 -0.4195634 0.8555144 -0.3034166 -0.3931695 0.6685079 -0.6312804 -0.5032013 0.5638425 -0.6548817 -0.4370675 0.5156201 -0.7369586 -0.8457808 0.5335192 -0.003482937 -0.8852752 0.4650282 0.006055772 -0.5011572 0.8653206 -0.007853984 -0.3526452 0.9357479 0.004139542 -0.7022671 0.1072907 0.7037825 -0.6234611 0.05629426 0.7798253 -0.9015702 0.0623824 0.4281117 -0.8322147 0.5456166 0.09859675 -0.8677029 0.2753738 0.4138367 -0.8613954 0.2829921 0.4217978 -0.6394535 0.7362541 0.2214252 -0.6039216 0.7385752 0.2996422 -0.6287937 0.6955986 0.3475071 -0.570398 0.2364677 0.7865933 -0.9312481 0.07547372 0.3564838 -0.5214009 0.6186267 0.5877432 -0.4078096 0.5943231 0.6931604 -0.3831754 0.9096618 0.1602869 -0.4181039 0.748409 0.5148524 -0.9657128 0.2352945 0.1097055 -0.8452058 0.4413865 0.3013389 -0.7974371 0.4469447 0.405382 -0.6073711 0.3908507 0.6916185 -0.5461444 0.365698 0.753652 -0.2792122 0.0389136 0.9594406 0.01534271 0.5133647 0.8580334 0.05414217 0.3568316 0.9325985 -0.03373628 0.2504207 0.9675491 0.05915719 0.076613 0.9953044 0.03287357 0.6522929 0.7572538 0.01797908 0.510634 0.8596101 0.004672646 0.676677 0.7362653 0.008860349 0.4856709 0.8740969 0.005551457 0.4977796 0.8672857 0.00203967 0.2833719 0.959008 0.01408499 0.228733 0.9733873 0.001804113 0.02001684 0.9997981 0.003196656 0.9754024 0.2204084 0.005801379 0.9680048 0.2508651 0.005827367 0.9142267 0.4051611 0.003482699 0.9279401 0.3727132 0.003480851 0.8377321 0.5460703 0.003995537 0.834929 0.5503432 0.002559661 0.6691803 0.7430957 -7.95261e-5 0.6811417 0.7321515 -0.01158165 0.5325573 0.8463147 0.001755416 0.3561129 0.9344413 -0.01632887 0.2504914 0.9679812 0.007664918 0.07063913 0.9974724 4.2206e-6 0.6781972 0.7348801 -0.04492443 0.639716 0.7672973 0.01980936 0.4976132 0.8671728 -0.05337512 0.4050191 0.9127489 -0.009015679 0.2177343 0.9759663 -0.01773458 0.2288138 0.9733086 -0.05780982 0.1004156 0.9932647 -0.002180278 0.9693558 0.2456513 -0.002632021 0.9706849 0.2403414 -0.00797683 0.9264964 0.3762192 -0.002721369 0.8473665 0.5310016 -0.008778393 0.8696021 0.4936751 -0.002328455 0.7825143 0.6226283 -0.007213652 0.6457708 0.7634973 -0.004936873 0.6332332 0.7739453 -0.0060997 0.510775 0.8596929 -0.01228582 0.5240145 -0.8516207 -0.0462538 0.3890492 -0.9200551 0.01264691 0.2505517 -0.9680206 -0.02701193 0.2066286 -0.9780465 -0.05338096 0.08178418 -0.9952195 -0.03237938 0.5103799 -0.8593392 0.00331968 0.6479282 -0.7616942 -0.01176887 0.4977371 -0.8672481 0.002831697 0.4228388 -0.9062005 -0.009694755 0.2487371 -0.9685225 -0.01407539 0.2287515 -0.9733831 -0.001659452 0.01772898 -0.9998415 -0.003009676 0.969437 -0.2453221 5.10595e-4 0.9763248 -0.2163091 -0.006168723 0.9105032 -0.4134562 -0.001581013 0.8535514 -0.5210063 -5.81539e-4 0.8587523 -0.5123906 -0.006959974 0.7441116 -0.6680191 0.002067625 0.6524953 -0.75779 6.85817e-5 0.6186296 -0.7856828 0.009417712 0.5411445 -0.8408769 -0.004056453 0.3606991 -0.9326735 0.01462686 0.2504829 -0.9680106 -0.00876379 0.08358317 -0.9964622 -4.3234e-6 0.6865468 -0.7270856 0.04675292 0.6217632 -0.7818086 -0.01443594 0.4976314 -0.8672685 0.06790447 0.3804075 -0.9223226 -0.0317232 0.2287517 -0.9729677 0.05309957 0.09003192 -0.9945223 0.002933919 0.9704329 -0.2413531 0.002251088 0.9689772 -0.24714 0.004059016 0.8647972 -0.5021048 0.005835652 0.8737922 -0.4862644 0.005793333 0.767444 -0.6410897 0.002946972 0.7409156 -0.6715918 0.008058726 0.6316267 -0.7752307 -6.68984e-4 0.5107891 -0.8597058 -0.3263405 0.612311 0.720123 -0.4540241 0.5510039 0.7001834 -0.4343682 0.8280246 0.3545413 -0.426715 0.8303847 0.3582955 -0.55516 0.7177605 0.4202586 -0.4431779 0.7137137 0.5424078 -0.4428901 0.7138776 0.5424272 -0.5643664 0.5899608 0.57744 -0.7426963 0.4355598 0.5086156 -0.7557446 0.5921184 0.2797248 -0.8668251 0.3115808 0.3892707 -0.8477309 0.4039692 0.343746 -0.8954726 0.3534659 0.2705378 -0.8294494 0.5093248 0.2293514 -0.908506 0.2718262 0.3173755 -0.9180987 0.3545853 0.177099 -0.3822788 0.7763656 0.5011182 -0.3613174 0.5802714 0.7298867 -0.1783766 0.8998857 0.3979794 -0.2167788 0.9660282 0.1407006 -0.7957262 0.4789547 -0.3707051 -0.6196627 0.7174381 0.3182778 -0.6427875 0.7605572 0.09152597 -0.5040184 0.8631553 -0.03046917 -0.4797869 0.8596667 -0.1754354 -0.2683369 0.8932484 -0.3606972 -0.2880754 0.6607102 -0.6931629 -0.8687422 0.4918612 -0.05796247 -0.5546504 0.4905734 -0.6720868 -0.4295966 0.5377882 -0.7254177 -0.2546712 0.2934171 -0.9214385 -0.7215809 0.5321389 -0.4428874 -0.9092186 0.4163037 -0.00362122 -0.3665513 0.001718878 -0.9303963 -0.5045069 -0.002497494 -0.863404 -0.6522359 0.001726508 -0.7580142 -0.7817919 -0.002171695 -0.6235356 -0.9027383 0.004717707 -0.4301642 -0.9956471 1.41596e-4 -0.09320241 -0.2925986 -0.8321527 -0.471071 -0.4625648 -0.6705402 -0.5800085 -0.2235714 -0.6421536 -0.7332493 -0.2850098 -0.485058 -0.8267335 -0.2874241 -0.2494668 -0.9247452 -0.584616 -0.7424583 -0.3270777 -0.3315001 -0.4616555 -0.8227892 -0.3898136 -0.7647577 -0.5130216 -0.4322947 -0.3217374 -0.8423813 -0.5443626 -0.1577464 -0.8238843 -0.6035341 -0.5521426 -0.5752261 -0.6911175 -0.327399 -0.6443341 -0.7423784 -0.5896975 -0.3180114 -0.734919 -0.4406262 -0.5155023 -0.51614 -0.284509 -0.8078701 -0.7850773 -0.5382566 -0.3064857 -0.944929 -0.2329154 -0.2299122 -0.8199095 -0.3153859 -0.4777867 -0.9359393 -0.1422165 -0.3221682 -0.9467617 -0.2807726 -0.1575092 -0.9074376 -0.358592 -0.2190179 -0.4908003 -4.35575e-4 -0.8712719 -0.6290666 -0.01150834 -0.7772663 -0.8443005 -8.91628e-4 -0.5358694 -0.9658073 -0.008795082 -0.2591117 -0.9432224 -0.06563478 -0.3256126 -0.9456947 -0.1722984 -0.2756351 -0.9759222 -0.1362776 -0.1703066 -0.8982493 -0.377607 -0.2248578 -0.9213555 -0.3585555 -0.1501401 -0.8571833 -0.2738224 -0.4361858 -0.8312045 -0.5450467 -0.1096501 -0.7780601 -0.5174484 -0.3561877 -0.6295416 -0.1852697 -0.7545546 -0.6466096 -0.1637368 -0.7450411 -0.6436295 -0.2380234 -0.727383 -0.6381197 -0.5206975 -0.567166 -0.6385117 -0.5272478 -0.5606358 -0.4876978 -0.5293584 -0.6942121 -0.523725 -0.7583984 -0.3879999 -0.4885836 -0.7972756 -0.3544539 -0.5424622 -0.8047847 -0.2409487 -0.4479885 -0.4001184 -0.7995071 -0.4032967 -0.7332042 -0.5475065 -0.4142732 -0.8943889 -0.1686607 -0.4236576 -0.9058198 -0.002182185 -0.5968859 -0.8023215 0.002731204 -0.8603528 -0.5096988 -3.13303e-4 -0.8448147 -0.5350583 7.78165e-4 -0.9977288 -0.06734752 -0.00121808 -0.9780834 -0.1712651 0.1184107 -0.9201306 -0.2779532 0.2758654 -0.8729739 -0.4636361 0.1515196 -0.8286324 -0.2718066 0.4893767 -0.8522621 -0.1945575 0.4855892 -0.6642758 -0.6847662 0.2997217 -0.6855683 -0.5725406 0.4496591 -0.6240248 -0.1398934 0.7687801 -0.4809225 -0.8512498 0.2099698 -0.5586015 -0.7723898 0.3022884 -0.5249798 -0.622528 0.5803923 -0.5367354 -0.4680702 0.7020152 -0.3407784 -0.8485934 0.4046721 -0.4093821 -0.4572286 0.7895241 -0.4250323 -0.2474594 0.870696 -0.2988478 -0.7327193 0.611402 -0.3920006 0.002747833 0.9199608 -0.6476683 -0.01307797 0.7618101 -0.8361242 0.002005696 0.5485367 -0.9811263 -0.008107423 0.1931985 -0.2071638 -0.1557397 -0.9658303 -0.1733484 -0.8636698 0.4733127 -0.348182 -0.8021597 0.4850867 -0.7183589 -0.5860564 0.3748313 -0.9173507 -0.3445453 0.1993897 -0.9604525 -0.2346035 0.1499735 -0.6505492 -0.6565784 0.3816946 -0.3547466 -0.6475443 0.6744191 -0.392255 -0.5421041 0.7431415 -0.2356619 -0.6265716 0.7428806 -0.6731377 -0.4475055 0.5887481 -0.6766125 -0.4444228 0.587098 -0.9661062 -0.1489216 0.2108584 -0.3710644 -0.3143897 0.8737679 -0.7154209 -0.3527719 0.6030961 -0.7573639 -0.2507925 0.6029121 -0.5194864 -0.170438 0.8373079 -0.8558183 -0.18027 0.4848482 -0.4498551 -0.2256322 0.8641299 -0.9367323 4.20773e-4 0.3500461 -0.8893606 0.003668487 0.4571918 -0.7710472 -0.004960536 0.6367587 -0.3944216 0.004295408 0.9189195 -0.4740408 -9.68953e-4 0.8805024 -0.2960917 0.002515375 0.9551562 -0.05607897 0.5056849 0.8608936 -0.108397 0.5317389 0.8399429 -0.1263142 0.5316418 0.8374974 -0.3177496 0.751966 0.5775659 -0.4139426 0.7402672 0.5297698 -0.2307204 0.9610162 -0.1523675 -0.3216463 0.9419969 0.09584003 -0.4226516 0.8934383 0.1520974 -0.6371549 0.4920353 0.593241 -0.5464479 0.4208034 0.7240988 -0.09590327 0.9738845 -0.2057951 -0.5899272 0.5105141 0.6255887 -0.7164285 0.667384 -0.2032948 -0.4935251 0.7553315 -0.4311699 -0.9115062 0.3798523 0.1576979 -0.8818672 0.1458062 0.448387 -0.8208163 0.5533863 0.1415068 -0.7291576 0.6843437 -0.001705825 -0.5186019 0.7338225 -0.4388127 -0.05759662 0.6242526 -0.7790966 -0.3736175 0.5655248 -0.7352495 -0.4964906 0.5559428 -0.6666517 -0.7214623 0.4225917 -0.5485512 -0.8509615 0.3415417 -0.3990162 -0.9171693 0.2568442 -0.3046829 -0.9858764 0.1172326 -0.1196004 -0.3989465 0.683746 -0.6110098 -0.7658233 0.429193 -0.4788613 -0.4092785 0.6969076 -0.5889065 -0.6525175 0.6166931 -0.4403527 -0.7849712 0.486322 -0.3838114 -0.9843047 0.1433082 -0.1029897 -0.4269846 0.783907 -0.4507481 -0.4181618 0.785438 -0.4563199 -0.8469089 0.4599684 -0.2667847 -0.3015739 0.8800265 -0.3668876 -0.3835921 0.859502 -0.3378069 -0.5801454 0.743906 -0.3317156 -0.8606166 0.4721718 -0.1907687 -0.8083332 0.5321833 -0.2517505 -0.8634404 0.456761 -0.2141028 0.2969642 0.6101527 -0.7345243 0.05392581 0.6238099 -0.7797136 0.3944153 0.8471844 -0.3559708 0.4898123 0.7407875 -0.4596931 0.3422738 0.8591721 -0.380358 0.4437702 0.5495162 -0.7078841 0.5659049 0.5905446 -0.5753336 0.4486827 0.7102805 -0.5423886 0.3759129 0.7492426 -0.5452752 0.6504984 0.4897647 -0.5805019 0.7398674 0.6185461 -0.2645696 0.8355131 0.342332 -0.4297986 0.8650572 0.3858617 -0.3206037 0.6791961 0.6437093 -0.3526061 0.7781251 0.4328249 -0.4551746 0.8356794 0.4897901 -0.2484865 0.9002715 0.2849903 -0.3290772 0.6868927 0.4941421 -0.5329184 0.7135848 0.6128652 -0.339401 0.9922245 0.08927488 -0.08672106 0.6206678 0.07337725 0.7806327 0.8794671 0.4027712 0.2536 0.8468925 0.3780889 0.3739275 0.709264 0.3862933 0.5896797 0.1113353 0.9132477 -0.391897 0.7798117 0.5683459 -0.2624434 0.7885341 0.4225145 0.446873 0.3319097 0.4002783 0.8541741 0.4017412 0.5242818 0.7508213 0.7433269 0.6649742 -0.07262599 0.6420077 0.5880077 -0.4920093 0.2201364 0.3541874 0.9088957 0.3114438 0.695889 0.6471023 0.3829127 0.8326056 0.4001821 0.4461014 0.8924985 -0.06663322 0.2991778 0.872721 -0.3858117 0.3853481 0.7753659 -0.5003145 0.5404071 0.8409515 0.02758091 0.4884164 0.8168315 0.3069781 0.9245395 -1.30316e-4 0.3810862 0.9204903 -5.68463e-4 0.3907648 0.6886961 -0.001115143 0.7250493 0.6191461 0.002713859 0.7852712 0.3300971 -0.002790927 0.9439429 0.2243945 2.88835e-4 0.9744983 0.1218563 -0.21786 0.9683429 0.3186773 -0.8256202 0.4656135 0.4232755 -0.3270757 0.844902 0.495292 -0.6545729 0.5711569 0.383476 -0.5541934 0.7387936 0.4725518 -0.562227 0.6786721 0.2900953 -0.4243924 0.8577504 0.6079115 -0.7254958 0.3226445 0.393943 -0.7527325 0.5274495 0.1413077 -0.2128812 0.9668059 0.7398219 -0.3657516 0.5647029 0.5808231 -0.2920064 0.7598533 0.6935943 -0.1892351 0.6950661 0.6953926 -0.4825919 0.5324795 0.868446 -0.4234673 0.257831 0.8646904 -0.4300992 0.2594708 0.7749067 -0.4031863 0.486786 0.9312428 -0.1497626 0.3322017 0.9191948 -0.1557612 0.3616896 0.8698235 -0.4214996 0.2564082 0.9761824 -0.1595366 0.1470243 0.8904743 -0.006065547 0.4549931 0.9069337 -0.008735895 0.4211828 0.5800406 -5.7306e-5 0.8145877 0.4225099 -0.01049512 0.9062976 0.1658465 -0.002222895 0.9861491 0.9540157 -0.2669939 0.136265 0.9283541 -0.1807972 0.3247632 0.9204265 -0.3717482 0.1209062 0.8335342 -0.1537476 0.5306435 0.8442766 -0.3553661 0.4011383 0.8721688 -0.380995 0.3068624 0.792554 -0.1749874 0.5841554 0.7719334 -0.6099523 0.1791006 0.6260007 -0.504106 0.5949792 0.474233 -0.4411528 0.7618972 0.463795 -0.4583143 0.7581835 0.4896847 -0.6664469 0.5621898 0.5476359 -0.7218618 0.4230962 0.5399634 -0.7314563 0.4164267 0.5810877 -0.7537809 0.3068414 0.4329372 -0.1957305 0.8799176 0.4024441 -0.2147508 0.8898993 0.3355098 -0.917766 0.2124586 0.9428517 -0.3332087 0.00166136 0.8653811 -0.5011127 -0.001315891 0.741564 -0.6708801 0.00170809 0.5300331 -0.8479769 -3.0537e-4 0.4427847 -0.896626 0.001868486 0.9593506 -0.2004933 -0.1986172 0.862714 -0.1269767 -0.489491 0.8637988 -0.4873819 -0.127713 0.8569288 -0.4969635 -0.1367491 0.8497439 -0.4500338 -0.2746001 0.873806 -0.2566561 -0.4130265 0.7781013 -0.5244316 -0.3457309 0.5619379 -0.8056626 -0.1874399 0.5733633 -0.1980847 -0.7949949 0.5155112 -0.8290624 -0.2165729 0.5282744 -0.6029138 -0.5978469 0.565621 -0.4643148 -0.6815313 0.4979453 -0.4483824 -0.7422962 0.5509015 -0.2143775 -0.8065667 0.407105 -0.8225398 -0.3971067 0.4577992 -0.7767227 -0.432576 0.3576545 -0.7151809 -0.6004993 0.9443928 -0.009975373 -0.3286682 0.8449534 0.001693308 -0.5348373 0.5638775 -0.005874574 -0.8258376 0.502533 -9.26809e-4 -0.8645576 0.4157035 -0.7896341 -0.4512966 0.7267879 -0.5968119 -0.3399924 0.4943175 -0.7262634 -0.4776941 0.7737239 -0.557047 -0.3017449 0.897709 -0.3667105 -0.2442166 0.3067573 -0.6503018 -0.6949874 0.612515 -0.5681805 -0.549542 0.8777679 -0.289667 -0.3815975 0.9206814 -0.2543755 -0.2960387 0.4825085 -0.5179347 -0.7063492 0.6811583 -0.3071409 -0.664596 0.2126831 -0.3712407 -0.9038508 0.5524641 -0.3915978 -0.7358224 0.9421603 -0.1905338 -0.2757372 0.8707993 -0.103652 -0.480588 0.4460455 -0.2004548 -0.8722736 0.4989066 -0.1595608 -0.8518407 0.8560447 -0.1201412 -0.5027462 0.268482 9.8692e-4 -0.9632842 0.3389902 -0.001056849 -0.9407894 0.9393109 0.001370847 -0.3430644 0.9134411 -0.0019719 -0.4069662 0.6394919 -0.001163721 -0.7687969 0.5957407 0.001285254 -0.8031758 0.04648882 0.9067711 0.4190523 0.627912 0.7254616 0.281837 0.8300112 0.5463531 0.1121595 0.9145768 0.2094484 -0.3459485 0.103461 0.87138 -0.4795756 0.4933106 0.7518991 -0.43737 0.8696132 0.3238946 -0.3726463 0.7933673 0.5646712 -0.2274091 0.4947565 0.8245397 0.2745 0.06180965 0.6647654 -0.7444908 0.03431046 0.7776061 -0.6278148 0.5693162 0.752467 -0.3311684 0.6126725 0.3244339 -0.7206769 0.2214457 0.3301521 -0.9175845 0.4609631 0.4969886 -0.7351976 0.4533677 0.4969708 -0.7399174 0.4213107 0.8341628 0.355907 0.4261561 0.9045894 0.01044166 0.07638406 0.631776 0.7713784 0.632439 0.4932635 0.5972538 0.4752149 0.5454756 0.6903821 0.4347711 0.566797 0.6997964 0.8175362 0.3578882 0.4511659 0.9262551 0.2550616 0.2774795 0.5752748 0.6074048 0.5478306 0.4134954 0.7042051 0.5771628 0.4827507 0.6918768 0.5368969 0.7622762 0.5039913 0.406113 0.9150096 0.3331799 0.227483 0.4114837 0.7864207 0.4606774 0.4179545 0.7853443 0.4566709 0.8530789 0.4510121 0.2623825 0.2640735 0.8837934 0.3862311 0.4147531 0.8486278 0.3283454 0.8431624 0.4743605 0.2530995 0.9479497 0.2878035 0.1362379 -0.3788344 0.7934456 0.4763701 0.4619245 0.8298051 -0.3131279 0.04251831 0.9261006 0.3748731 0.2641746 0.9614145 0.0767728 0.6550724 0.7305305 -0.1928876 0.2440298 0.9480646 0.2040169 0.05982315 0.8016161 0.5948385 0.1857603 0.9341352 0.3047697 -0.7569355 -0.3727686 0.536742 0.4736644 0.8631857 0.1747928 0.2745722 0.906751 0.3200199 0.3801015 0.7886834 0.4832196 0.05511456 0.8113014 0.5820245 0.1587793 0.7481095 0.6442991 0.1619352 0.8110486 0.5621184 0.4480037 0.6887025 0.5700715 0.4763587 0.7348224 0.4828234 0.7621718 0.6271318 0.1606234 0.5662726 0.5200408 0.6394474 0.8197224 0.5501397 0.159379 0.7637526 0.6051642 0.2246292 0.6714872 0.454609 0.5851799 0.4559195 0.4707981 0.7553056 0.8497896 0.4055355 0.3367472 0.6008365 0.3582496 0.7145997 0.9677358 0.1736178 0.1826039 0.2866543 0.1735308 0.942187 0.4481953 0.1821729 0.8751766 0.7278525 0.1277154 0.6737354 0.7520448 0.1300714 0.6461502 0.9698987 0.04227375 0.2398117 0.1649866 0.002453923 0.9862928 0.2782893 0.003420352 0.9604911 0.4238753 0.001608848 0.9057192 0.5881153 0.00221771 0.8087741 0.76139 -4.09721e-4 0.648294 0.931705 0.002297103 0.3632087 0.5372847 0.008210122 0.843361 0.2680116 0.9622943 0.04646891 -0.7895254 0.3923059 0.4719595 -0.7683035 0.4870702 0.4152979 -0.7366157 0.4988703 0.4566464 -0.7240411 0.5842904 0.3665642 0.374412 0.8145282 0.4431249 0.4201831 0.7932742 0.4406382 -0.8556852 0.1419993 0.4976336 -0.8175188 0.2821351 0.5020586 -0.7523224 0.338307 0.5652958 -0.613532 0.6044485 0.508154 -0.06505262 0.8315156 0.5516792 -0.01910424 0.8367598 0.5472368 0.1264278 0.8501476 0.5111411 0.1761286 0.8142092 0.5532108 0.4282379 0.7355682 0.5249302 0.4836645 0.7003532 0.5249515 0.5876135 0.5939836 0.5494487 0.6944599 0.5733686 0.4347111 0.7134883 0.4690906 0.5204694 0.6876831 0.4300584 0.5849289 0.7357224 0.3931691 0.5514804 0.8323996 0.2379931 0.5004701 0.8534018 0.154308 0.4978898 0.8225057 0.1285604 0.5540367 0.822657 0.08392524 0.5623095 -0.7603072 0.1650664 0.6282405 -0.3468413 0.6889132 0.6364744 -0.2998809 0.7367176 0.6060682 -0.226467 0.705231 0.671835 -0.210739 0.7162311 0.6652834 0.02457803 0.7748938 0.6316135 0.4721146 0.5756019 0.6676751 0.5163315 0.5572609 0.6502783 -0.4668663 0.5081277 0.7237694 -0.4478889 0.6168624 0.6472067 -0.344516 0.6150593 0.7092326 -0.1280071 0.6710702 0.7302595 0.1927541 0.6195043 0.7609602 0.1723285 0.6122382 0.7716652 0.6835504 0.2505124 0.6855672 -0.5104549 0.09702616 0.854413 -0.5039426 0.2308658 0.8323117 -0.3315677 0.2682089 0.9045037 -0.4232914 0.4474068 0.7878144 0.3361316 0.2717716 0.9017516 0.4357691 0.2984973 0.84912 0.4582285 0.1443037 0.8770421 0.4932308 0.1215666 0.8613622 -0.3402552 0.088903 0.9361211 -0.2958649 0.2289578 0.9273846 -0.1569803 0.2663054 0.9510198 0.02249568 0.4269804 0.903981 0.08723008 0.3801116 0.9208182 0.2434509 0.4520515 0.8581265 0.2108418 0.3327065 0.9191583 -0.1158438 0.2090371 0.971022 -0.01468729 0.2833297 0.9589101 0.2814117 0.1087932 0.9534 0.05257743 0.06138086 0.9967287 -0.4174603 2.95697e-4 0.9086951 -0.5696988 0.003269731 0.8218471 -0.8599206 0.001537442 0.5104254 -0.8458158 0.002213835 0.5334704 -0.8394174 0.1000232 0.5342038 -0.8433572 0.0967487 0.5285722 -0.4375912 0.1694165 0.8830697 -0.4082078 0.1647369 0.8979021 -0.02029848 0.9442222 0.3286829 -0.2413954 0.9652344 0.1002532 -0.01061856 0.8371148 0.5469243 -0.2349261 0.9299091 0.2829817 -0.2452738 0.9661625 -0.0798186 -0.1587879 0.8712702 0.4644078 -0.04255151 0.6390042 0.7680253 -0.4884691 0.869305 -0.07554292 -0.4242721 0.9048125 0.03616148 -0.3056029 0.8246634 0.4759593 -0.3292987 0.8308857 0.4485436 -0.2234104 0.6985938 0.6797459 -0.6558172 0.7452718 -0.120307 -0.61977 0.7255798 0.2990303 -0.4101154 0.6994308 0.585322 -0.379814 0.6557956 0.6524366 -0.4190835 0.01543533 -0.9078165 -0.8519596 0.4807831 -0.2073945 -0.7874047 0.5418148 0.293991 -0.5062043 0.4603837 0.729249 -0.8100939 0.5207431 0.2693966 -0.5274645 0.4980786 0.6882578 -0.5695222 0.4693849 0.6747757 -0.5228072 0.4552809 0.7206885 -0.8294446 0.327883 0.4522327 -0.8371789 0.3372043 0.4306098 -0.3914987 0.2558397 0.8838974 0.3967204 0.1182122 -0.9102959 0.9609872 0.1735597 -0.2153617 -0.9154245 0.1571822 -0.3705291 -0.2309727 0.1342295 -0.9636566 -0.2837176 0.1424584 -0.9482668 -0.6841009 0.2935457 -0.6677101 -0.7138436 0.2668033 -0.6474901 -0.8497495 0.2653056 -0.4555643 -0.3256314 0.3423293 -0.8813483 -0.4609539 0.3800088 -0.8019445 -0.5283302 0.4253728 -0.7347961 0.8148357 0.2425191 -0.5265239 0.8197554 0.214105 -0.5311875 0.5995693 0.5873069 -0.5436794 0.3050511 0.3150368 -0.8987189 0.2858876 0.7325066 -0.6178207 0.1845087 0.8086726 -0.5585743 0.069678 0.5037557 -0.8610315 -0.2342374 0.8686125 -0.4366293 -0.3121421 0.8453652 -0.4335032 -0.03777366 0.3817915 -0.9234762 -0.06905895 0.5025148 -0.861806 -0.1139398 0.5213389 -0.8457089 -0.5496187 0.7027048 -0.4518023 -0.6244258 0.6843142 -0.376572 -0.4324315 0.6226079 -0.652198 0.7715458 0.6359634 -0.01636075 0.708858 0.4476539 -0.5450928 0.7461209 0.371093 -0.5528053 0.7228603 0.331531 -0.6062675 0.7470127 0.26476 -0.6098148 0.6854032 0.4507387 -0.5718889 0.6799886 0.5636521 -0.4689477 0.3541712 0.1552897 -0.9221973 0.3409686 0.9208801 -0.1889978 0.4267492 0.7790207 -0.4593605 0.4575085 0.7018603 -0.5459655 0.2368988 0.1354978 -0.9620392 0.3416184 0.243228 -0.9078199 0.4554911 0.5116565 -0.728516 0.4289586 0.6050078 -0.6707907 0.3215915 0.7719776 -0.5482969 0.1509475 0.8791322 -0.4520416 0.2248199 0.8089376 -0.543209 0.101596 0.1366962 -0.9853895 0.1890351 0.3571186 -0.9147305 0.1796679 0.396895 -0.9001076 0.06674748 0.7715628 -0.6326419 0.01922166 0.8049824 -0.5929871 -0.1571391 0.8944731 -0.4185991 -0.2288385 0.8799288 -0.416363 -0.05917537 0.7161813 -0.695401 -0.479545 0.8773099 -0.01907849 -0.3844686 0.9229928 -0.0163778 0.04953569 0.2173633 -0.974833 0.0520718 0.3890159 -0.9197582 -0.3330754 0.7376291 -0.5873366 -0.3917831 0.740172 -0.5464901 -0.6380209 0.5739855 -0.5132933 -0.1471417 0.4074403 -0.9013 -0.7361128 0.3698117 -0.5669015 -0.7252765 0.4156543 -0.5488218 -0.3346393 0.4486266 -0.8287042 -0.1015096 0.2149586 -0.9713334 -0.03190952 0.7874023 -0.6156129 0.3981857 0.7968554 -0.4543893 -0.2407497 0.809435 -0.535588 0.1547291 0.8996397 -0.4082982 -0.02296096 0.7118488 -0.7019574 0.1721326 0.9823025 -0.07383936 0.2936509 0.9222732 -0.2513589 0.07115077 0.8050568 -0.5889152 0.3076672 0.9265978 0.2162342 0.2015571 0.7755045 -0.5983039 0.5250301 0.8479755 0.07267034 0.2084096 0.9214643 -0.3278247 0.4655839 0.8849753 0.007102012 0.3513667 0.7713339 -0.5306462 0.3791552 0.7649588 -0.5206528 0.6994442 0.7017039 0.1356077 0.6969958 0.6999468 -0.1557924 0.54179 0.7524865 -0.3744698 0.3125857 0.5766408 -0.7548348 0.8933929 0.4461328 -0.05305427 0.6609175 0.5214408 -0.5397107 0.7630157 0.5867392 -0.2711902 0.5578953 0.5460453 -0.6249698 0.4266876 0.4844847 -0.7636834 0.8453904 0.3349696 -0.4160655 0.3966731 0.3281925 -0.8572865 0.8492951 0.3398265 -0.4039995 0.852522 0.09390604 -0.5141869 0.835329 0.1072428 -0.5391887 0.542846 0.1635083 -0.8237617 0.4709039 0.1534675 -0.8687331 0.04802638 0.001685321 -0.9988447 0.4778912 0.00236684 -0.8784158 0.5218319 0.001565873 -0.853047 0.8198468 0.002448678 -0.5725778 0.8193893 0.002468526 -0.5732321 -0.09764778 0.994381 -0.04088222 -0.01874929 0.9988719 -0.04362761 0.6046143 0.7958956 -0.03149229 0.6662025 0.7451787 -0.029715 0.2083538 0.9559776 -0.2066288 0.147918 0.9699319 -0.1932675 -0.4613468 0.7834386 -0.4163929 -0.5240432 0.7441344 -0.4142977 -0.8196719 0.3658928 -0.44075 -0.8446981 0.3062191 -0.438993 0.8514831 0.03810721 -0.5229955 0.8174964 0.2860831 -0.4998561 0.7780175 0.3226701 -0.5390481 0.6437404 0.5790827 -0.5002616 0.6095553 0.6163627 -0.4985371 -0.519068 0.6519804 -0.5527116 -0.5612472 0.5997895 -0.5703106 -0.5600089 0.5902086 -0.5814153 -0.6200202 0.5628677 -0.5465849 -0.7354421 0.4229048 -0.5294113 -0.7598606 0.3776939 -0.5291117 -0.8747609 0.1439355 -0.4626834 0.7766689 0.1477195 -0.6123434 0.7483898 0.1543292 -0.6450543 0.4987502 0.573123 -0.6502141 0.4851005 0.6725385 -0.5589001 0.371971 0.6754887 -0.6366731 0.3602683 0.6665516 -0.6526222 0.3020603 0.7797349 -0.5484278 0.2203651 0.7646247 -0.6056306 0.170543 0.6881857 -0.7052061 0.1026346 0.7641367 -0.636837 -0.2144685 0.7526599 -0.6225001 -0.3099501 0.7876889 -0.532426 -0.3532298 0.7055331 -0.6143711 -0.7189168 0.173478 -0.6731002 -0.7252051 0.1569258 -0.6704117 0.5796992 0.3036493 -0.7561389 0.588665 0.3748264 -0.7162254 0.5447996 0.3960706 -0.7391357 0.006328105 0.6880215 -0.7256627 -0.006181836 0.652504 -0.7577601 -0.09435135 0.6350103 -0.7667201 -0.0540744 0.7000283 -0.7120649 -0.1747152 0.6909577 -0.7014642 -0.5941727 0.4078764 -0.6932501 -0.6028784 0.08180135 -0.7936285 0.4174488 0.1925693 -0.8880617 0.369264 0.3192119 -0.8727816 0.3904485 0.4293161 -0.814394 0.2325181 0.430467 -0.872143 -0.1401456 0.4540668 -0.8798764 -0.240424 0.4275723 -0.8714231 -0.2427163 0.4422554 -0.8634228 -0.2871769 0.2965218 -0.910826 0.4420949 0.08942788 -0.8924992 0.4082068 0.08791393 -0.9086465 0.1733065 0.2694652 -0.9472874 0.1251518 0.4661776 -0.8757942 -0.3409577 0.2162141 -0.9148767 -0.4221187 0.1885053 -0.8867251 -0.4120615 0.1715834 -0.8948546 0.03619951 0.2299643 -0.9725255 -0.05912464 0.2590957 -0.9640403 -0.1300696 0.1860983 -0.9738836 -0.2692641 0.1835244 -0.9454182 0.02227562 0.02247917 -0.9994991 -0.537518 0.001564323 -0.8432508 -0.6086677 0.003288269 -0.7934184 -0.8620882 9.44909e-4 -0.5067573 -0.9223909 0.00290817 -0.3862466 -0.3311699 0.1560073 -0.9305849 -0.5481669 0.1720099 -0.8184899 -0.7398962 0.1245021 -0.6610997 -0.8603697 0.1132895 -0.4969201 -0.9363155 0.05938667 -0.3461017 -0.09588271 0.9462715 -0.3088313 -0.3523948 0.9031726 0.2451473 -0.6214821 0.6884031 0.37398 -0.4922852 0.8633982 -0.1104485 -0.1567509 0.9230329 -0.3513392 -0.1191973 0.9540953 -0.2747619 -0.4099083 0.9120253 0.01360082 -0.4634172 0.8748494 -0.1410073 0.09570735 0.6761547 -0.7305169 -0.1746626 0.887685 -0.4260381 -0.4337457 0.8141291 -0.386081 -0.1726787 0.862984 -0.4748061 -0.1827711 0.7595286 -0.6242685 -0.09389901 0.9151616 -0.3919978 -0.3519692 0.6466851 -0.6766948 -0.3648204 0.6488568 -0.6677507 -0.5194528 0.755409 -0.3994072 -0.7239385 0.6699248 -0.1646627 -0.7119899 0.7003857 -0.05030071 -0.5786019 0.5719207 -0.5814865 -0.8234524 0.5662003 -0.03665399 -0.2378265 0.4373752 -0.8672609 -0.6616004 0.4634553 -0.5894864 -0.8121081 0.387946 -0.4358651 -0.8625873 0.4166005 -0.2870317 -0.9043182 0.3438421 -0.2529448 -0.4678982 0.3746007 -0.8004659 -0.8862343 0.304274 -0.3492939 0.9999104 0.002788305 0.01309913 0.334286 0.9417101 0.0378797 0.9645501 0.1692645 0.2024667 -0.4033753 0.1323203 0.9054169 -0.9567573 0.1727992 0.2339999 0.07089495 0.05628645 0.9958944 0.3799074 0.1946182 0.9043197 0.4620896 0.1691483 0.8705527 0.1955986 0.2001392 0.9600445 0.2391706 0.3234989 0.9155031 0.4570659 0.4024323 0.7931828 0.7949808 0.2829415 0.5366094 0.8482757 0.261835 0.4602944 0.8554611 0.2216994 0.4680128 -0.8249815 0.2501531 0.5067828 -0.6158063 0.6074362 0.5018008 -0.6293307 0.5747078 0.5231193 -0.3120881 0.3629262 0.8780009 -0.1208741 0.4668734 0.8760244 0.09163773 -0.1488211 0.984609 0.1746107 0.8313019 0.527682 0.0998221 0.4153873 0.9041509 0.1972085 0.6421315 0.7407943 0.307775 0.7012566 0.6430504 0.3557943 0.6537016 0.6678957 0.6641647 0.6762735 0.3186525 0.7075875 0.6312937 0.3174718 0.354523 0.6804758 0.6413004 0.4475597 0.6266831 0.637933 0.518018 0.6580638 0.5464516 0.5433585 0.647754 0.534019 -0.7925661 0.2459757 0.5579739 -0.7412286 0.3488717 0.5734708 -0.7268974 0.2672924 0.6325939 -0.6534904 0.3921834 0.6474121 -0.3341706 0.7778653 0.5322178 -0.5345528 0.404891 0.7418333 -0.5563147 0.3728325 0.7426372 -0.3720555 0.8535347 0.3647645 -0.4195086 0.7033415 0.5738669 -0.4592862 0.6976277 0.5498836 -0.2744779 0.141712 0.9510939 -0.3449733 0.3180562 0.8830819 -0.4549809 0.5677664 0.6860275 -0.3278669 0.8346803 0.4425066 -0.237553 0.8665123 0.4390047 0.1038312 0.9602827 0.2589909 0.03717303 0.9474059 0.3178681 -0.1208599 0.8544918 0.5052095 -0.1813935 0.8218334 0.5400798 0.2826973 0.9586245 0.03348714 0.2791334 0.9595581 0.03650712 -0.1235989 0.2005092 0.9718639 -0.1873968 0.3932688 0.9001234 -0.1829183 0.4638888 0.8668034 -0.09185832 0.8326815 0.5460804 -0.009080469 0.8349124 0.5503081 0.1717092 0.809173 0.5619207 0.05866998 0.6183884 0.7836794 -0.003392994 0.6437964 0.7651894 -0.04451471 0.322667 0.9454652 0.7620152 0.4482094 0.467377 0.8229756 0.4024236 0.400957 0.6250209 0.422793 0.6561975 0.6111451 0.4407407 0.6574567 0.1723864 0.2964144 0.9393729 0.04225885 0.1154235 0.9924171 0.006462275 -0.7221413 -0.6917155 -0.07971775 -0.8959636 -0.4369146 -0.1135059 -0.860466 -0.4967039 -0.07316672 -0.683297 -0.7264654 -0.03117072 -0.3468175 -0.9374145 -0.001049995 -0.1793912 -0.9837772 -0.03944921 -0.896434 -0.4414181 -0.02187442 -0.880978 -0.4726514 -0.05370277 -0.8223415 -0.5664544 -0.0380271 -0.7539832 -0.655792 -0.04453158 -0.6325289 -0.7732555 -0.02587461 -0.4994433 -0.8659601 -0.01629364 -0.5200073 -0.8540064 -0.03627043 -0.3313212 -0.9428206 0.04872846 -0.9211745 -0.386087 0.107576 -0.8741324 -0.4736243 0.03663408 -0.8866565 -0.4609753 0.04744452 -0.8970383 -0.4393988 0.03540068 -0.8068398 -0.5897088 0.02598619 -0.8145281 -0.579542 0.0533055 -0.7461471 -0.6636437 0.02121925 -0.6078547 -0.7937647 0.01343631 -0.3872687 -0.921869 0.05385369 -0.5272461 -0.8480044 0.03555023 -0.218837 -0.9751136 0.0183745 -0.2562975 -0.9664233 -0.008078932 -0.8731637 0.4873602 -0.05435472 -0.7445681 0.6653301 -0.0518279 -0.8187115 0.5718612 -0.09518224 -0.8683303 0.4867678 -0.05096447 -0.51603 0.855053 -0.006286025 -0.1598274 0.9871249 -0.03248041 -0.241922 0.969752 -0.01358556 -0.3875066 0.9217668 -0.02501195 -0.5819277 0.8128558 -0.04361087 -0.7289771 0.6831474 0.09824824 -0.9400614 0.3265453 0.06416797 -0.8889582 0.453471 0.04744619 -0.8785271 0.4753304 0.02691143 -0.8911114 0.452986 0.04909539 -0.8978359 0.4375847 0.03275269 -0.7475209 0.6634305 0.1294003 -0.6416233 0.7560259 0.04644703 -0.7704965 0.6357498 0.0306071 -0.58678 0.8091678 0.02564394 -0.5988108 0.8004799 0.01819652 -0.3766737 0.9261673 0.03258788 -0.4081591 0.912329 0.02409237 -0.1852689 0.9823925 0.01119869 -0.2220129 0.9749794 -0.02894556 -0.2311004 -0.9724993 0.005172014 -0.3526453 -0.9357428 -0.01481562 -0.4035467 -0.9148391 -7.58417e-4 -0.6387959 -0.7693759 -0.00905174 -0.6512411 -0.758817 -0.02617359 -0.7754129 -0.6309119 0.02652817 -0.8657783 -0.4997241 -0.02732074 -0.9184036 -0.3947004 -0.03653609 -0.974119 -0.2230638 -0.04869139 -0.2262391 0.9728541 0.02342516 -0.5248344 0.850882 -0.002300739 -0.4961683 0.8682232 -0.01427036 -0.7531088 0.6577413 -3.29521e-4 -0.7694109 0.6387541 -0.006472766 -0.9182332 0.3959873 0.00876826 -0.9333782 0.3587872 -0.02688962 -0.9764631 0.2140015 0.0356419 -0.9736285 -0.2253377 0.01488858 -0.914355 -0.4046398 -0.02732706 -0.8799633 -0.4742548 0.02874714 -0.7519636 -0.6585775 -0.01210606 -0.659932 -0.7512279 0.03063797 -0.5169454 -0.8554698 -0.01818645 -0.3776428 -0.9257727 0.03427779 -0.2388834 -0.9704431 0.04376423 -0.9683621 0.2456819 -0.007308065 -0.8693766 0.4940961 -0.02889776 -0.8508602 0.524597 0.0289067 -0.7442791 0.667243 0.008440315 -0.5424396 0.8400524 -0.03252983 -0.4871227 0.8727276 0.04593575 -0.2596731 0.9646035 -0.2518491 0.963868 -0.0867775 -0.9827935 0.176458 -0.05458456 -0.9321289 0.3615186 0.02097553 -0.707805 0.6398556 -0.2993274 -0.1190059 0.8442215 0.5226162 -0.09412395 0.9936146 0.06221562 -0.03567785 0.9659272 -0.2563427 -0.9686189 0.1904938 -0.1596541 -0.8390843 0.4361597 -0.3251187 -0.8567866 0.4335972 -0.2791238 -0.6389629 0.6233444 -0.4507417 -0.5962154 0.7180108 -0.3591486 -0.4425332 0.7113916 -0.5459729 -0.1911192 0.7816552 -0.5937075 -0.940837 0.2095136 -0.2663267 -0.2893235 0.6612933 -0.6920862 -0.06490141 0.7418918 -0.6673713 0.04710209 0.6753764 -0.7359675 -0.8609915 0.2522016 -0.4416875 -0.6599882 0.3844578 -0.6454516 -0.6836044 0.3920894 -0.6155899 -0.4678493 0.5513501 -0.6907461 -0.9571974 0.1503124 -0.2473447 -0.8118467 0.2227645 -0.5397045 -0.08183199 0.2888204 -0.9538797 -0.7020117 0.3020739 -0.6449271 -0.5458198 0.173654 -0.8197103 -0.391424 0.3453242 -0.8529586 -0.225489 0.2409611 -0.9439769 -0.0544483 0.352461 -0.9342412 -0.3970067 -0.002778112 -0.9178115 -0.3617604 6.01305e-4 -0.932271 -0.07094293 6.23609e-5 -0.9974805 -0.09479677 -0.002346813 -0.9954939 -0.6489541 0.008183062 -0.7607836 -0.7177764 -0.008622109 -0.6962203 -0.5407481 0.001345336 -0.8411835 -0.8726117 5.43077e-5 -0.4884145 -0.8484051 -0.002883493 -0.5293397 0.02447277 0.7848507 0.6192015 0.6478908 0.6603584 -0.3796895 0.8588423 0.4366188 -0.2678691 -0.02697169 0.9896791 -0.1407407 0.2628468 0.9575856 -0.1180743 0.2687535 0.9567089 -0.1117131 0.9795386 0.06963908 -0.1888237 0.898293 0.2355047 -0.3709544 0.6645296 0.3378267 -0.6665386 0.4945194 0.3400743 -0.7998751 0.3370139 0.4794258 -0.8102917 0.1076062 0.3564193 -0.9281089 0.8471367 0.254832 -0.4662834 0.7552409 0.3704071 -0.5407494 0.5989896 0.4100839 -0.6877809 0.2482106 0.4131699 -0.8761748 0.02883774 0.5864378 -0.8094807 0.2397254 0.7416405 -0.6264991 0.1995922 0.8016765 -0.5634518 0.4812369 0.713576 -0.5091369 0.464283 0.7312029 -0.4997836 0.6955341 0.5798377 -0.4242883 0.8355898 0.4870051 -0.2541965 0.9243613 0.3294504 -0.1924024 0.9703639 0.1880132 -0.1518052 0.07530647 -2.0923e-4 -0.9971604 0.03923511 -0.003919482 -0.9992223 0.2222878 0.003440499 -0.9749751 0.8804424 0.002832233 -0.4741447 0.7722815 -0.001253783 -0.6352793 0.7441228 0.002445161 -0.6680384 0.6037693 -9.57724e-4 -0.7971585 0.4055938 -0.002248764 -0.9140506 0.3912274 -6.86182e-4 -0.9202938 0.5620209 0.002330541 -0.8271197 0.9990887 0.02258002 -0.03621941 0.970809 0.2082911 0.1189317 0.884214 0.4502534 0.1242482 0.04581111 0.9786406 -0.2004094 0.09489619 0.9945573 0.04301762 0.3344546 0.9099659 0.2451571 0.09502089 0.9525482 0.2891763 0.06684249 0.9389308 0.3375517 0.9356496 0.2147391 0.2800838 0.7428795 0.5964157 0.3040041 0.4635475 0.6646915 0.5859258 0.3348606 0.7413892 0.5815587 0.04772758 0.7841334 0.6187543 0.8614284 0.3897579 0.325622 0.6253263 0.5163863 0.5850746 0.3551773 0.7521067 0.5551439 0.9371068 0.2140595 0.2756981 0.3763219 0.4080093 0.8318114 0.08670037 0.7080926 0.7007766 0.1032517 0.3797091 0.9193259 0.6809448 0.221877 0.6979144 0.5169221 0.3827064 0.7657201 0.3327007 0.3393911 0.8798431 0.06342756 0.4717888 0.8794272 0.9505745 0.1584821 0.2670047 0.8275945 0.1347116 0.5449221 0.7218783 0.2506002 0.6450514 0.7546176 -0.003563404 0.6561552 0.3563483 0.004664242 0.9343416 0.4733121 -0.01120597 0.8808236 0.2683565 9.28791e-4 0.9633193 0.07875233 -0.001706957 0.9968928 0.6419575 0.001330673 0.7667391 0.5418356 -0.004079699 0.8404746 0.7620043 -0.002472698 0.6475672 0.8749439 -1.40251e-4 0.4842244 -0.01998281 0.7195746 -0.6941276 -0.01739585 0.9179074 -0.396413 -0.05733495 0.8416114 -0.5370316 -0.5496 0.7647994 0.3361871 -0.5675705 0.6837576 0.4586278 -0.9807964 0.1574862 0.1150504 0.03005743 0.9992309 0.02517896 -0.07669395 0.9725737 0.2195867 -0.1010074 0.8520587 0.5136083 -0.02625674 0.6821917 0.7307018 -0.2934869 0.8548546 0.4278889 -0.06337678 0.4485552 0.8915053 -0.9300634 0.2182933 0.2955164 -0.9404252 0.1416694 0.3090796 -0.793933 0.2365893 0.5600857 -0.7455149 0.30652 0.5918219 -0.5045388 0.3419504 0.7927866 -0.398837 0.247644 0.8829504 -0.939575 0.2600567 0.2226417 -0.8078747 0.4416158 0.390274 -0.6592165 0.6342337 0.403957 -0.3795499 0.7105387 0.5925173 -0.6985244 0.4468614 0.5589085 -0.459059 0.4856788 0.7438958 -0.3008958 0.5679196 0.7661129 -0.9062625 0.3693509 0.2055928 -0.09263813 -0.004759311 0.9956885 -0.8805971 0.004019498 0.4738489 -0.7475413 -0.002468943 0.6642109 -0.7366616 -5.83876e-4 0.6762614 -0.3331534 0.00243324 0.9428695 -0.3492085 7.51546e-4 0.9370447 -0.6160228 0.002357423 0.7877249 -0.5812141 -2.20852e-4 0.8137506 -0.03738731 0.6359493 0.7708247 -0.01311862 0.8832321 0.4687524 -0.08070611 0.9386712 -0.3352354 0.08088874 0.9247499 0.37188 0.0268253 0.9980213 -0.05686807 0.07338368 0.9402776 -0.3324043 -0.001477599 0.9234331 0.3837564 0.01242154 0.9722885 0.2334541 0.005449414 0.9449579 0.3271467 -8.14905e-5 0.9242463 0.3817968 -0.02966552 0.9382549 0.3446704 0.0061329 0.9937896 0.1111062 -0.03418296 0.9873237 0.154995 0.00226587 0.5224512 0.8526662 0.001770257 0.6162372 0.7875586 -9.02963e-4 0.5751997 0.8180125 7.64013e-4 0.4682967 0.883571 3.77817e-6 0.4544044 0.8907955 7.54222e-4 0.3224967 0.9465703 9.489e-5 0.3324916 0.9431062 3.17954e-4 0.1830416 0.9831051 -1.78243e-4 0.1883778 0.9820966 -4.16168e-4 0.9251089 0.3797015 2.78064e-4 0.8728179 0.488046 -3.50538e-4 0.8656237 0.5006951 -3.57171e-4 0.7955549 0.6058813 3.12458e-4 0.8048236 0.5935141 1.00467e-4 0.7117748 0.7024077 -1.28673e-5 0.7100487 0.7041525 -3.55858e-4 0.6157941 0.7879071 -3.83606e-4 0.6151269 0.7884281 -1.79184e-4 0.4312919 -0.9022123 -0.001351356 0.5913119 -0.806442 4.34563e-4 0.5431897 -0.8396099 -1.37188e-4 0.4356364 -0.9001227 -0.001152515 0.3567684 -0.9341922 0.001428663 0.4578806 -0.8890126 9.48887e-4 0.3113263 -0.9503026 -5.40643e-5 0.1880137 -0.9821664 -9.08917e-4 0.1979762 -0.9802063 -0.001374661 0.9202653 -0.3912924 -7.31229e-5 0.9242051 -0.3818964 -0.003814995 0.9686056 -0.248573 0.02396982 0.9954618 -0.0920937 -0.007485866 0.9770952 -0.2126711 0.05550515 0.9917811 -0.1152799 -4.94109e-4 0.9686687 -0.248356 1.05147e-4 0.5699641 -0.8216696 5.65168e-5 0.6107581 -0.7918172 1.10191e-4 0.6098285 -0.7925334 2.68497e-4 0.6913519 -0.7225182 -0.001027226 0.711818 -0.7023634 -0.001106441 0.8166117 -0.5771864 2.71142e-4 0.79764 -0.6031339 2.15848e-4 0.8724124 -0.4887705 8.81636e-4 0.8660234 -0.5000027 -1.50618e-4 0.9254287 -0.3789218 0.001285672 0.9215071 -0.3883593 -0.2850399 0.9563314 -0.0646727 -0.5042511 0.8584821 0.09348469 -0.6359233 0.7709919 -0.03424996 -0.9196628 0.3926649 0.00589013 -0.9350345 0.3495914 0.05913007 -0.9948278 -0.07973337 -0.06293082 -0.9448004 -0.3146427 0.09139037 -0.8738964 -0.4828444 -0.05627024 -0.5899962 -0.8054416 0.05628806 -0.4576639 -0.8864233 -0.069265 -0.2055405 -0.9770725 0.05551844 0.03751814 -0.997752 -0.05552971 0.3012628 -0.9510276 0.06918942 0.4452992 -0.8936092 -0.05631297 0.7797036 -0.6236139 0.05628567 0.8780328 -0.4697918 -0.09140068 0.9670503 -0.2466861 0.06292694 0.9858794 0.1593369 -0.05151283 0.9639799 0.2609346 0.05153483 0.7442901 0.6633542 -0.07741767 0.6311357 0.771803 0.07738071 0.2187868 0.9743967 -0.05180138 0.1225693 0.9914472 0.04482531 -8.2311e-6 1.46126e-5 1 -9.66526e-6 -2.72237e-6 1 -8.50459e-6 -6.64888e-6 1 -1.01077e-6 -6.43978e-6 1 -2.36751e-6 -1.50838e-5 1 -6.54432e-6 -4.04514e-6 1 -2.08879e-5 -9.28213e-6 1 -6.92893e-6 2.48148e-6 1 -6.42936e-6 -1.06311e-6 1 -3.52157e-5 2.25911e-5 1 -2.00576e-5 3.65018e-5 1 -1.38134e-5 6.27941e-6 1 2.76119e-6 1.31036e-5 1 5.95925e-6 -1.62904e-6 1 -1.53491e-6 -3.19719e-6 1 4.74653e-5 3.53411e-6 1 4.30279e-6 8.96262e-6 1 1.88501e-5 6.71365e-5 1 -2.21339e-5 -5.90723e-5 1 -2.26392e-5 -5.89525e-5 1 1.2096e-5 7.04676e-6 1 -0.2187553 0.9740265 0.05846756 -0.3105089 0.9498541 -0.03689664 -0.7547171 0.6559987 0.008248567 -0.7661026 0.6418945 0.03253394 -0.9972455 0.06664854 -0.03254812 -0.9987841 0.0485996 -0.00827825 -0.8824974 -0.4688807 0.03673279 -0.8475394 -0.5296661 -0.03362715 -0.551356 -0.8342078 0.01020097 -0.5418926 -0.8401781 0.02128887 -0.1061494 -0.9941241 -0.02120858 -0.06345653 -0.9977579 0.02127122 0.3682332 -0.9295406 -0.01893889 0.4024476 -0.9153696 0.01159304 0.6993865 -0.7146528 -0.01140272 0.7453934 -0.6651508 0.04430508 0.9393571 -0.3371195 -0.06291782 0.9850556 -0.164182 0.0520544 0.995431 0.08004993 -0.05204904 0.9548512 0.2854183 0.08243542 0.7620943 0.638559 -0.1070262 0.6564202 0.7529602 0.04651296 0.2856502 0.9582757 0.01057034 0.2187374 0.9740315 -0.0584504 -3.51317e-5 -4.49651e-5 1 1.60326e-5 -1.46367e-5 1 2.00525e-5 -1.3336e-6 1 -1.31186e-5 -2.03397e-5 1 5.30124e-6 -6.56321e-7 1 1.21011e-5 1.61096e-5 1 -2.82269e-5 2.94088e-5 1 -1.7512e-5 -1.28591e-5 1 4.47452e-6 -5.28872e-6 1 -5.83273e-6 6.89407e-6 1 -2.15384e-5 5.35078e-6 1 -4.00086e-5 -3.4559e-5 1 3.0837e-5 -1.46714e-5 1 3.17734e-5 1.81775e-5 1 2.56064e-6 2.18547e-5 1 -1.39321e-6 -1.18908e-5 1 1.20113e-5 1.24872e-5 1 -1.05571e-5 1.80124e-5 1 -1.46469e-5 6.61509e-6 1 4.10844e-6 -1.85552e-6 1 1.23768e-5 9.23221e-6 1 1.19213e-5 -8.66234e-6 1 -0.05345952 0.9982972 0.02334117 -0.1765758 0.9813705 -0.07571667 -0.4773974 0.8758786 0.07020252 -0.6958746 0.7163259 -0.0513392 -0.7990072 0.5991364 0.05121445 -0.9294136 0.3622928 -0.07024484 -0.9949864 0.08001339 0.05999881 -0.9885147 -0.13279 -0.07214999 -0.9393429 -0.3371546 0.06294178 -0.7276821 -0.6839821 -0.05145156 -0.6994386 -0.7146196 -0.01021629 -0.3681346 -0.9292669 0.03066003 -0.2973082 -0.9542917 -0.03058296 0.09514236 -0.9954102 0.01032447 0.07448065 -0.9971699 -0.01023471 0.4544875 -0.8902292 0.03054875 0.5199462 -0.8536511 -0.03059071 0.8258196 -0.5637801 0.01319319 0.8334565 -0.5517827 0.02976876 0.9995108 -0.009600758 -0.02976578 0.9990604 0.03625929 0.023736 0.8480337 0.5294113 -0.02371555 0.822742 0.5676354 0.02976191 0.3795025 0.9247058 -0.02995145 0.3630494 0.9317271 -0.00893253 -6.51317e-6 1.13955e-5 1 1.00545e-4 8.38611e-5 1 6.6727e-5 1.39838e-4 1 4.79096e-5 8.26913e-5 1 -4.33329e-6 9.95694e-6 1 1.95807e-6 1.96804e-5 1 5.97629e-5 1.68596e-6 1 -6.75825e-6 1.23541e-5 1 -7.32383e-6 -5.40973e-6 1 6.07357e-6 -9.28141e-7 1 7.93641e-6 -2.39896e-5 1 -3.73006e-5 -1.69321e-5 1 -3.64438e-7 5.25512e-5 1 4.56436e-5 2.92923e-5 1 9.24354e-6 1.24739e-5 1 2.26694e-5 1.45541e-5 1 2.19988e-5 1.66403e-5 1 -1.08152e-5 -8.18083e-6 1 -6.59931e-6 -1.32464e-5 1 6.01196e-6 1.90991e-6 1 1.26371e-5 1.3492e-5 1 6.38672e-6 -1.23247e-6 1 -2.56616e-5 4.95203e-6 1 -2.7993e-5 -1.52835e-5 1 4.97208e-6 2.71464e-6 1 -0.1179689 0.991563 -0.05372273 -0.2444466 0.9676474 0.06248337 -0.7021347 0.7102871 -0.04999017 -0.7651414 0.6411399 0.05914658 -0.9645553 0.2562645 -0.06294083 -0.9954319 0.0800355 0.05205303 -0.9897119 -0.1372271 -0.04048401 -0.9397513 -0.3373206 0.05552029 -0.8147317 -0.5759361 -0.06715506 -0.6985797 -0.7139741 0.04719442 -0.4543931 -0.8902612 -0.03101277 -0.3681403 -0.9292482 0.03115373 -0.04705601 -0.9974266 -0.05409121 0.1058961 -0.9919105 0.06999737 0.5154457 -0.8553707 -0.05154323 0.5512089 -0.8343015 -0.01046603 0.8309686 -0.5554869 0.03042227 0.893247 -0.4434396 -0.07396668 0.9924115 -0.07488614 0.09752684 0.9824861 0.158772 -0.09753262 0.8692056 0.4908037 0.0599457 0.7635369 0.6433948 -0.0552662 0.5896922 0.8057155 0.05554968 0.3646401 0.9291316 -0.06125438 0.1804186 0.9825392 0.04545205 0 -6.2912e-6 1 1.28341e-5 -1.55861e-5 1 4.13126e-6 -4.14019e-5 1 3.72106e-5 -3.69381e-5 1 7.65772e-6 1.4397e-5 1 -1.5299e-6 -2.87632e-6 1 7.54775e-6 -8.3055e-6 1 2.34932e-6 -1.76271e-5 1 -4.35356e-5 -4.53789e-7 1 -4.72307e-5 -2.26695e-5 1 8.33094e-6 -3.34602e-5 1 1.81353e-6 1.40187e-5 1 7.37899e-6 1.4012e-5 1 3.55722e-6 1.89423e-6 1 0 0 1 -8.94975e-5 5.10334e-5 1 -3.38445e-5 8.95595e-5 1 1.57676e-5 -6.25412e-6 1 -9.75353e-7 -1.25069e-5 1 -2.57656e-5 7.64766e-6 1 -2.76457e-5 4.99071e-6 1 -2.59623e-7 -1.80168e-5 1 2.28745e-5 -6.4358e-6 1 1.19782e-5 5.47566e-6 1 -0.00176531 0.001144289 -0.9999979 2.43709e-4 4.4201e-5 -1 1.13004e-4 1.23791e-4 -1 -1.76175e-5 -3.25091e-5 -1 -0.01062828 -0.002216219 -0.9999411 -4.38121e-6 -4.38404e-6 -1 -2.66613e-6 1.91596e-6 -1 -4.39388e-7 -2.13849e-6 -1 8.43138e-5 -5.90337e-5 -1 -0.01022881 0.01318913 -0.9998607 -0.008919715 0.002555012 -0.9999569 -4.7051e-6 -5.05329e-6 -1 2.64083e-6 -4.95173e-6 -1 -5.25293e-7 -1.377e-6 -1 3.00535e-6 3.79642e-6 -1 1.65675e-6 -2.80063e-6 -1 0 1.52733e-5 -1 -0.0470609 -0.05155378 -0.9975607 -0.1765563 -0.2159588 -0.960307 -5.78588e-6 -5.78961e-6 -1 8.96926e-6 6.84616e-6 -1 7.16461e-6 5.94552e-6 -1 2.60495e-6 2.79772e-6 -1 1.06078e-5 4.06976e-5 -1 -8.5859e-6 -1.58433e-5 -1 -7.17326e-6 5.02248e-6 -1 1.46866e-5 1.95415e-4 -1 -2.8395e-6 2.10095e-4 -1 -5.93407e-5 1.32765e-4 -1 -9.09195e-4 0.001334249 -0.9999988 -0.02126634 -0.007749736 -0.9997438 -2.53264e-6 -8.35536e-7 -1 -2.17318e-5 0.002260923 -0.9999975 -9.17017e-5 1.4334e-4 -1 0.001791954 7.77191e-4 -0.9999981 0.004188895 -4.3029e-4 -0.9999911 -1.38302e-6 3.11014e-6 -1 -1.1769e-6 -1.21295e-6 -1 -4.00775e-6 2.3662e-6 -1 -3.12984e-6 1.26985e-6 -1 -6.54978e-6 3.793e-6 -1 -1.5509e-4 1.02601e-4 -1 1.67993e-5 1.48457e-4 -1 2.03681e-5 -1.71779e-5 -1 -1.80815e-4 1.14056e-4 -1 0.002170026 3.92853e-4 -0.9999975 0.002926886 0.006476759 -0.9999747 0.001071631 0.00142014 -0.9999984 6.32888e-4 -2.16337e-4 -0.9999998 2.66698e-4 0.005466282 -0.999985 0.001006007 0.00154531 -0.9999983 2.58239e-5 6.05992e-5 -1 -5.21664e-4 0.003243744 -0.9999946 0.02383321 0.02050668 -0.9995056 -2.80482e-4 0.003445148 -0.999994 0.003319263 7.70919e-4 -0.9999942 0.004475831 2.23134e-4 -0.99999 0.005163967 0.01360672 -0.999894 -0.001005411 8.35688e-4 -0.9999992 -0.001884698 0.004430472 -0.9999885 -0.002397716 8.51983e-4 -0.9999968 -0.002394556 7.44931e-4 -0.9999969 -0.00137794 0.00170958 -0.9999976 0.9973452 0.06754529 -0.02720814 0.9849257 0.1729329 0.003957688 0.9809362 0.193897 -0.0129643 0.9503844 0.3108302 -0.01241648 0.9552713 0.2957309 1.9449e-4 0.905124 0.4251472 -6.2926e-4 0.8943622 0.4468272 -0.02149051 0.8370527 0.5467168 -0.02105855 0.844308 0.5357423 -0.011155 0.7855518 0.6186599 -0.01297223 0.7787224 0.6273528 -0.004463315 0.6874548 0.7262123 -0.004660308 0.5673811 0.8234416 0.004762172 0.4848845 0.8745745 0.00254625 0.4817147 0.8763279 -4.17702e-4 0.3828081 0.9238276 -7.92618e-4 0.1299477 0.991375 0.01700431 0.09562492 0.9950827 -0.0258128 0.005743384 0.9996567 -0.02556264 -0.1358643 0.9906513 -0.0122869 -0.234204 0.972052 -0.01622509 -0.2473168 0.9689193 -0.005469858 -0.3630247 0.9317616 -0.005777537 -0.3756099 0.9266106 -0.01760816 -0.4671231 0.8840162 -0.01764261 -0.4701297 0.882378 -0.01967316 -0.5886697 0.8083077 0.01033294 -0.5955449 0.8030907 0.01927345 -0.667674 0.7442045 0.01926571 -0.6864227 0.7272011 -0.001618266 -0.7789292 0.6271101 0.001482367 -0.7856048 0.6186972 -0.006222486 -0.840304 0.5421082 -0.002837836 -0.8316652 0.5552119 0.008524 -0.9018785 0.4318693 0.01020783 -0.9030573 0.4294425 0.00815463 -0.9477401 0.3188373 0.01146227 -0.9559441 0.2933589 -0.01054805 -0.9828113 0.1844891 -0.006753504 -0.9807173 0.1953729 0.004806399 0.9999316 -7.86258e-4 0.0116682 0.995351 0.007638633 -0.09601002 -0.9995462 0.002502381 0.03001683 -0.9995689 0.01433283 -0.02562624 -0.9983978 0.00507903 -0.05635797 -0.9999164 0.001817286 -0.01279592 -0.02277588 3.48054e-4 0.9997406 8.67176e-7 8.42625e-7 -1 1.93e-7 0 -1 2.00365e-7 2.236e-6 -1 -1.83294e-6 3.20173e-6 -1 -2.7465e-6 1.04909e-6 -1 -1.02787e-6 8.33878e-7 -1 1.75029e-7 1.19771e-7 -1 -9.7114e-7 9.30065e-7 -1 -9.58206e-7 5.71575e-7 -1 -6.00866e-7 0 -1 1.91288e-6 1.69438e-6 -1 1.79448e-6 2.24769e-6 -1 7.25747e-7 5.19605e-7 -1 8.7103e-7 -1.98855e-7 -1 -5.20063e-7 2.66445e-7 -1 -8.7146e-7 0 -1 -1.85401e-6 1.35472e-6 -1 -1.87081e-6 2.3423e-6 -1 -2.51364e-6 -3.67315e-6 -1 8.14362e-7 -3.18588e-6 -1 -2.55932e-7 -4.44283e-7 -1 0 -2.42312e-7 -1 2.22204e-7 2.1894e-6 -1 0.1619992 0.9843301 -0.0696454 0.4153513 0.9039709 0.1015868 0.6619305 0.7450308 -0.08232259 0.8792474 0.4704144 0.07506215 0.9250203 0.3789478 -0.0271306 0.9867555 -0.1594613 0.02976304 0.9847309 -0.1735876 0.01312941 0.825302 -0.5638637 -0.03056645 0.744521 -0.663496 0.07390302 0.4956032 -0.8657054 -0.07022529 0.2196394 -0.9735488 0.06293809 0.0913282 -0.9948363 -0.04427117 -0.3120664 -0.9474783 0.06999522 -0.4536759 -0.8895246 -0.05407679 -0.7181572 -0.6951846 0.03112018 -0.798986 -0.5991587 -0.05128496 -0.9381256 -0.3363819 0.08226501 -0.9926011 -0.01804161 -0.1200731 -0.9560263 0.2675722 0.1200787 -0.7836256 0.6095243 -0.120046 -0.5994729 0.7944294 0.09754091 -0.2878782 0.955786 -0.05999344 -0.1059748 0.992834 0.05522716 5.51816e-7 -2.03614e-7 -1 0 -6.01439e-7 -1 -4.31892e-7 1.59363e-7 -1 -5.11872e-7 -2.43381e-7 -1 -1.20704e-7 0 -1 2.47562e-7 -6.63679e-7 -1 -5.44967e-7 3.20987e-7 -1 1.60265e-6 -1.38336e-6 -1 2.30615e-6 -3.87181e-7 -1 0 -2.53494e-7 -1 -3.68761e-7 4.5764e-7 -1 3.17236e-7 -1.4976e-6 -1 0 -1.40701e-6 -1 -4.63735e-7 -1.59731e-6 -1 -9.36489e-7 8.29523e-7 -1 2.56053e-7 6.67877e-7 -1 -1.86441e-7 0 -1 0 -2.65988e-7 -1 5.87813e-7 -1.29051e-7 -1 7.1721e-7 -8.30825e-7 -1 2.4892e-7 -6.60067e-7 -1 -0.06050032 0.9964141 -0.05914843 0.3912854 0.9176053 0.06997323 0.5767992 0.8102794 -0.1036822 0.7882285 0.6095854 0.08427113 0.9593144 0.2684988 -0.08731877 0.9906152 0.1206051 0.0643109 0.9161795 -0.3942537 -0.07196593 0.8769972 -0.478906 0.03904873 0.4822371 -0.876001 -0.008349835 0.493056 -0.8699582 0.008268117 -0.05202442 -0.9978827 -0.03903162 -0.09144872 -0.9957779 0.007959663 -0.5197976 -0.8530282 0.0464046 -0.621472 -0.7796046 -0.07739078 -0.8950259 -0.4437993 0.0443955 -0.9441893 -0.3233556 -0.06283062 -0.9966005 -0.004642128 0.08225625 -0.9530041 0.2854071 -0.1016169 -0.8459722 0.5286636 0.06961202 -0.6518813 0.7551482 -0.069296 -0.550955 0.8338329 0.03422397 -0.1061607 0.9943313 -0.00593543 8.78531e-7 1.18388e-6 -1 1.0566e-6 2.59475e-7 -1 4.97496e-7 -1.42994e-7 -1 -9.11569e-7 1.78614e-6 -1 -7.47948e-7 1.81085e-6 -1 0 -3.60905e-7 -1 4.88596e-7 -1.29805e-7 -1 -1.15366e-6 8.75801e-7 -1 5.74073e-7 4.65875e-7 -1 -1.39876e-7 -6.5587e-7 -1 1.16633e-6 -1.28099e-6 -1 1.81869e-6 4.18005e-6 -1 2.80235e-6 3.45558e-6 -1 3.3315e-7 -2.21104e-7 -1 1.97707e-7 0 -1 4.63727e-7 1.79472e-7 -1 0 -2.05835e-6 -1 1.79526e-6 -2.30725e-6 -1 2.16514e-6 -1.60135e-7 -1 3.23914e-7 1.08378e-6 -1 8.4848e-7 0 -1 2.63629e-7 -3.23294e-7 -1 -1.76895e-7 2.1693e-7 -1 3.11253e-7 9.00083e-7 -1 0.04697656 0.9978178 -0.04639917 0.4544909 0.8906863 -0.01077067 0.5376246 0.8386459 0.0873664 0.8137003 0.5751575 -0.08417743 0.9436646 0.3142362 0.1036959 0.9895484 0.1372163 -0.04433697 0.9664191 -0.2567481 -0.01071077 0.9443327 -0.3235173 0.05976748 0.7353443 -0.6757233 -0.05164051 0.621684 -0.7797694 0.07394939 0.3421126 -0.9370288 -0.07025718 0.05192023 -0.9966725 0.06283438 -0.04733294 -0.9986998 -0.01892709 -0.4687363 -0.8830828 0.02123898 -0.5061711 -0.8621705 -0.02127975 -0.8256093 -0.5639244 0.01893162 -0.8619669 -0.5055579 -0.03774017 -0.9833716 -0.1733566 0.05410885 -0.9954866 0.009535372 -0.09442168 -0.922219 0.3777736 0.08245646 -0.8247628 0.5630747 -0.05208909 -0.6632061 0.7466279 0.05200463 -0.491871 0.8667564 -0.08244001 -0.1083571 0.9883363 0.1070044 3.1627e-7 -7.64065e-7 -1 -1.04445e-6 -2.27987e-7 -1 -5.40115e-7 4.38657e-7 -1 2.77456e-6 -1.35381e-6 -1 2.859e-6 -2.41981e-6 -1 -3.45912e-7 8.95489e-7 -1 -5.44906e-7 4.9204e-7 -1 2.34563e-7 3.42315e-7 -1 2.09206e-7 -3.16305e-6 -1 5.98043e-7 2.26668e-6 -1 0 -6.51466e-7 -1 6.86733e-7 0 -1 1.87389e-7 2.03644e-7 -1 -3.41657e-7 -3.71293e-7 -1 -4.81767e-7 -2.39359e-7 -1 0 1.54853e-7 -1 -3.45834e-6 1.17039e-6 -1 -4.79145e-6 -5.96774e-6 -1 -1.57121e-6 2.87814e-7 -1 2.94646e-6 1.92935e-6 -1 5.50859e-7 3.78399e-6 -1 1.15259e-6 3.5826e-7 -1 1.34385e-7 2.29764e-7 -1 0 -5.3925e-7 -1 0.09505885 0.9943544 0.04714864 0.2719776 0.9599611 -0.06710326 0.5193216 0.8527714 0.05555254 0.6838829 0.7284679 -0.04048198 0.8247469 0.5631042 0.05202364 0.9114236 0.406625 -0.06295359 0.9986271 0.009575366 0.05149894 0.9977346 -0.06382924 -0.02125322 0.8752492 -0.4833025 0.01890963 0.839497 -0.5420497 -0.0377745 0.6194289 -0.7836353 0.04715311 0.4677938 -0.8812823 -0.0671612 0.1623625 -0.983525 0.07947874 -0.0518285 -0.9941834 -0.09440958 -0.4396362 -0.8932003 0.09440934 -0.6434304 -0.7584447 -0.1037248 -0.8503475 -0.516318 0.1016106 -0.9711823 -0.2155901 -0.1016162 -0.9934524 0.07495141 0.08622312 -0.9475215 0.3125581 -0.06715959 -0.7977581 0.5977178 0.07946991 -0.6746633 0.7348034 -0.06995224 -0.3265139 0.9441538 0.04429668 -0.2309873 0.9722231 -0.03777772 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 6.20659e-5 -5.65634e-4 -0.9999998 0 0 -1 -0.001275718 2.06198e-4 -0.9999992 -0.003984689 -3.15155e-4 -0.999992 -5.65209e-5 -5.92699e-4 -0.9999999 1.34741e-4 -5.53783e-4 -0.9999998 4.68096e-4 -5.26941e-4 -0.9999997 0.001187205 -4.86326e-4 -0.9999992 -2.98068e-4 -4.89192e-4 -0.9999998 -6.77379e-7 0 -1 0 0 -1 -3.36484e-4 4.22142e-4 -0.9999999 0 0 -1 -0.00161767 0.006462633 -0.9999778 -0.001935362 0.001056909 -0.9999976 -0.002592027 -4.73342e-4 -0.9999966 -0.002362966 0.005302906 -0.9999832 -2.64971e-4 -3.21998e-5 -1 0 0 -1 0.004141151 -0.002834737 -0.9999874 0 0 -1 2.5747e-4 -7.44506e-4 -0.9999997 0.002821683 -0.002114176 -0.9999938 0.008332073 -2.28907e-4 -0.9999653 0.004378676 7.71913e-4 -0.9999901 0.002449154 0.001672923 -0.9999956 -2.39633e-5 4.62643e-4 -1 9.86608e-4 8.22639e-4 -0.9999992 5.0839e-4 9.58132e-4 -0.9999995 0.00310117 9.48669e-4 -0.9999947 0 0 -1 -7.78325e-4 -4.16438e-4 -0.9999995 1.85341e-7 0 -1 -0.003731131 0.005506277 -0.999978 -0.003324627 0.006039202 -0.9999763 -4.08118e-4 -4.40099e-4 -0.9999998 -5.69046e-4 -3.88493e-4 -0.9999997 -1.16704e-6 5.73853e-7 -1 0 -1.6793e-7 -1 -3.5723e-4 5.11837e-4 -0.9999999 0 0 -1 -2.10297e-4 9.3285e-4 -0.9999995 -5.49292e-4 4.89355e-4 -0.9999997 0 0 -1 0.00185579 8.62112e-6 -0.9999984 0.001050829 5.21007e-4 -0.9999994 -2.58632e-4 0.002535521 -0.9999967 0.002970874 0.0048756 -0.9999837 3.5694e-4 0.003885447 -0.9999923 4.33282e-7 -8.28605e-7 -1 0 -1.30755e-7 -1 0 0 -1 0 0 -1 -6.03532e-4 4.32242e-4 -0.9999998 0.004323184 -0.001050412 -0.9999901 0 0 -1 0 0 -1 0.9999795 0.001906275 0.006108105 0.9999045 0.002466976 0.0135948 -0.9840623 0.1777492 0.005156159 -0.9831985 0.1825394 -2.67332e-5 -0.9480401 0.3181293 0.003724217 -0.9513508 0.3080735 -0.004740417 -0.9084972 0.4178875 -0.001702904 -0.9056833 0.4238975 -0.006972134 -0.8331861 0.5529618 -0.005859792 -0.8441121 0.5357154 -0.02200156 -0.7847577 0.6193829 -0.02280867 -0.7668458 0.6418285 0.001935005 -0.686739 0.7269036 8.35332e-4 -0.6670535 0.7446374 0.02355712 -0.5967522 0.8020682 0.0239439 -0.5727862 0.8197032 0.001628816 -0.5060876 0.8624718 0.004207193 -0.3548572 0.934849 0.01156914 -0.2462139 0.9691724 0.009142458 -0.2308995 0.972736 0.02168577 -0.1043689 0.9943146 0.02111315 -0.1518605 0.9883414 -0.01094192 -0.009321689 0.9998573 -0.01409298 0.007521688 0.9999717 4.93363e-7 0.1357778 0.9907392 4.46933e-4 0.1220537 0.9923896 -0.01630479 0.3535153 0.9354118 0.005609929 0.3434394 0.939173 -0.001869678 0.4834645 0.8753551 -0.003960013 0.4854634 0.8742547 -0.002020955 0.5962761 0.8027705 -0.003773033 0.5982738 0.8012893 -0.001987874 0.6707814 0.741636 -0.005317151 0.6751751 0.7376571 -7.10738e-4 0.7587234 0.6514129 -2.13665e-4 0.8432283 0.5374803 -0.008995234 0.8493979 0.5277501 0.001741528 0.9091566 0.4164383 0.003671705 0.9090122 0.4167512 0.003917992 0.9447496 0.3276492 0.009711146 0.9499226 0.3124738 -0.002652227 0.9827786 0.1847087 -0.005386054 0.9840499 0.1778777 0.002306103 -0.9999665 0.002808928 0.007694125 -0.9999362 0.001657605 0.01117008 -0.9965797 0.007002294 0.08234083 -0.9989809 0.01195096 0.0435242 -2.23661e-7 -2.82946e-7 1 -3.24723e-4 3.5743e-4 0.9999999 0 0 1 1.61298e-6 -1.65872e-7 1 7.07286e-7 -6.83549e-7 1 8.70355e-7 -7.93921e-7 1 -1.84744e-7 -2.5346e-7 1 6.92109e-7 3.63315e-7 1 -3.15448e-6 2.58022e-6 1 -2.9997e-6 2.94981e-6 1 -0.00172615 0.008409142 0.9999631 -0.004144966 0.004633069 0.9999807 -1.7748e-7 0 1 8.40263e-4 0.002395451 0.9999968 0.00570333 5.4467e-4 0.9999836 0.003869235 0.01082777 0.9999339 -1.59367e-7 3.15581e-7 1 -2.08966e-7 7.1805e-7 1 3.19695e-7 3.69709e-7 1 -3.89723e-4 3.19602e-4 1 -3.89307e-6 6.69949e-6 1 3.27534e-6 -1.85986e-6 1 2.99951e-6 -1.45724e-6 1 -7.81296e-4 0.001832246 0.999998 1.29292e-4 0.002915561 0.9999957 4.03324e-4 0.002934515 0.9999956 -3.23243e-4 0.002741396 0.9999963 1.45057e-5 -1.58983e-5 1 -8.87109e-6 8.60709e-6 1 -0.004940569 0.005665838 0.9999718 0.001153945 0.002219915 0.9999969 0.00453782 0.00270766 0.999986 0 0 1 0 0 1 6.35439e-5 3.86253e-4 0.9999999 0 0 1 3.0658e-4 3.43696e-4 1 -0.008029103 0.001371562 0.9999668 0.005324542 0.001836955 0.9999842 0.0019207 0.003779113 0.9999911 0.001692235 0.001692473 0.9999971 6.45311e-7 7.88715e-7 1 0 -5.00369e-7 1 -0.01066499 -0.002368688 0.9999403 -0.009286344 0.002733111 0.9999531 -0.008930265 -0.001752436 0.9999586 -0.001566946 0.001283943 0.9999979 0 0 1 -1.69286e-4 4.72336e-4 0.9999999 -9.5241e-6 5.9569e-4 1 2.95643e-5 5.63844e-4 0.9999999 1.88892e-7 2.54208e-7 1 3.8454e-7 4.50817e-7 1 -5.05455e-7 -7.83309e-7 1 2.2685e-4 4.16178e-4 0.9999998 4.00544e-4 2.99778e-4 0.9999999 1.85297e-7 -1.8938e-7 1 -6.33813e-7 7.02732e-7 1 0 2.80204e-7 1 3.99133e-7 -1.43574e-7 1 3.83168e-4 3.09976e-4 1 -0.006685018 0.004549801 0.9999673 -0.008415699 0.00413233 0.999956 -7.73626e-7 8.35189e-7 1 -0.003805816 -0.9996344 -0.02676904 0.999982 8.01933e-4 -0.005948543 0.9997661 0.02159661 0.001142144 0.99995 -0.00946021 -0.003265023 0.9999652 0.007196247 0.004226267 0.9999656 0.008216619 0.001180887 0.9999746 0.007094085 7.51223e-4 -0.9999807 0.006208717 2.72931e-4 -0.9999846 0.005509674 5.84109e-4 -0.9998921 0.01221585 -0.008159637 -0.9996926 0.01681131 0.01822328 -0.9998926 0.01257413 0.007529258 -0.01550638 -0.9998795 6.90223e-4 0.02835673 -0.9994537 -0.01697707 0.001998186 -0.9999585 0.008897006 -0.01892453 -0.999821 0 0 -1 0 0 -1 0 0 -1 0 0.051521 -0.9981322 0.03282636 -0.0514844 -0.9893217 0.1363522 0.07001256 -0.838267 0.5407466 -0.1036905 -0.7011458 0.705438 0.08422088 -0.467558 0.8799411 -0.06000703 -0.1641303 0.9846118 0.07216179 0.04850167 0.9962129 -0.06291532 0.2562459 0.9645619 0.04431498 0.5994143 0.7992113 -0.01148813 0.6527596 0.7574779 0.01334595 0.890731 0.454335 0.003700315 0.8951445 0.4457607 -0.03422254 0.9993599 0.0104174 0.04823547 0.9946494 -0.09135627 -0.04824048 0.9129037 -0.4053144 0.03423786 0.8673706 -0.4964838 -0.008302927 0.5189986 -0.8547347 0.008295118 0.5295379 -0.8482456 -0.03672641 0.02097696 -0.9991051 0.05972194 -0.07509595 -0.9953864 -0.05974984 -0.4951724 -0.8667377 0.01076686 -0.5558902 -0.8311859 0.04648137 -0.8481458 -0.5277199 -0.07743585 -0.9059315 -0.4162833 -1 1.69926e-6 1.88282e-6 -1 0 0 -1 0 0 -1 0 1.99597e-7 -1 0 2.06233e-7 -1 0 -1.65506e-7 -1 0 -1.93203e-7 -1 0 1.72559e-7 -1 -2.2523e-7 0 -1 -3.01464e-7 2.07109e-7 -1 -4.8419e-7 0 -1 0 -3.08803e-7 -1 0 0 -1 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.23834e-7 -2.17027e-6 -1 4.44264e-6 -6.12302e-7 -0.08422613 -0.9908161 0.1057801 0.1036913 -0.9159982 0.3875505 -0.04436033 -0.8334731 0.5507764 -0.01074892 -0.5558712 0.831199 0.08730578 -0.4699545 0.8783624 -0.070243 -0.1370081 0.9880763 0.06287592 0.1592266 0.9852377 -0.01892715 0.2567208 0.9663003 0.02367049 0.665137 0.7463461 0.04302686 0.6522156 0.7568115 -0.06777316 0.8930801 0.4447638 0.08621901 0.9718585 0.2192198 -0.08624154 0.9949249 -0.05183476 0.06774252 0.9554072 -0.287416 -0.04300409 0.770757 -0.6356762 -0.02371054 0.7816897 -0.6232168 0.02371603 0.3670205 -0.9299105 0.04304665 0.3821628 -0.9230918 -0.06774359 -0.004943609 -0.9976905 0.08624422 -0.2417807 -0.9664905 -0.08623933 -0.4942033 -0.8650583 0.08421123 -0.7044485 -0.7047417 -0.07396376 -0.9061683 -0.4163993 0.07396239 -0.9666173 -0.2453176 -1 0 0 -1 -1.82426e-7 0 -1 0 -2.3124e-7 -1 0 -1.91348e-7 -1 0 -2.43594e-7 -1 0 0 -1 0 -1.34305e-7 -1 -1.66079e-7 0 -1 1.51873e-7 0 -1 2.08357e-7 -1.66116e-7 -1 0 -1.44315e-7 -1 0 -2.29486e-7 -1 2.16045e-7 -2.59174e-7 -1 0 4.33392e-7 -1 0 4.19857e-7 -1 0 -2.46229e-7 -1 0 -2.09954e-7 -1 3.23949e-7 2.16439e-7 -1 1.72592e-7 0 -1 0 0 -1 -1.30196e-7 0 -1 -1.2904e-7 0 -1 3.69099e-7 1.45489e-7 0.9655939 -0.2589313 -0.02414357 0.9996839 0.02503591 0.002334415 1 0 0 1 0 0 0.9999937 7.00413e-4 -0.003494858 0.9999897 -0.003249943 -0.003166437 0.9999919 -1.20024e-5 -0.004025042 0.9999975 -0.002028703 -9.12043e-4 0.9999946 -0.002563595 -0.002107799 0.9994936 0.02503114 0.01964509 1 0 -1.50505e-7 1 0 0 1 -3.78597e-7 0 -1 0 1.99099e-7 -1 0 2.04284e-7 -1 0 2.13399e-7 -1 0 1.99923e-7 -1 0 1.57322e-7 -1 0 1.63425e-7 -1 0 0 -1 -2.26947e-7 0 -1 -2.29859e-7 0 -1 2.40453e-7 0 -1 2.05169e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.46516e-7 -1.87843e-7 -1 0 -2.21545e-7 -1 0 1.60655e-7 -1 1.2256e-7 1.32073e-7 -1 0 0 -1 -2.23037e-7 0 -1 -2.18393e-7 0 -1 -2.1472e-7 0 -1 -1.64645e-7 -1.77424e-7 -0.06000113 -0.9748032 0.2148451 0.0721516 -0.9062939 0.4164438 -0.06294792 -0.7994595 0.597413 0.04428178 -0.5180816 0.8541842 -0.01156723 -0.4594166 0.8881456 0.011541 -0.1166759 0.9931031 -0.04428553 -0.04908496 0.9978123 0.06999444 0.3519981 0.9333799 -0.05408525 0.4910353 0.8694592 0.03774237 0.763836 0.6443058 -0.01894885 0.8067572 0.5905791 0.0236923 0.9863666 0.1628484 0.04305082 0.9828864 0.1791112 -0.06774848 0.9742559 -0.2150246 0.06963872 0.9062482 -0.416971 -0.0552085 0.7632106 -0.6437867 0.0431376 0.6522042 -0.7568149 -0.05972689 0.3234804 -0.9443479 0.06430566 0.2042052 -0.9768137 -0.05629968 -0.2561061 -0.9650078 0.04821866 -0.3786484 -0.9242838 -0.03918927 -0.6315502 -0.774344 0.05999404 -0.7462198 -0.6629908 -0.0975359 -0.9269719 -0.3622291 0.09753328 -0.9859101 -0.135899 0.9999949 0 -0.003175854 1 0 0 1 -1.22337e-7 0 0.9999883 -0.003926157 0.002817809 1 1.84819e-5 3.46159e-5 1 0 -1.43473e-7 1 0 0 0.9999578 -0.008820593 0.002586185 0.9999892 -0.001029312 0.004520475 1 0 0 0.9991946 0.04012674 0 0.9963847 0.04001361 0.0749439 0.9999943 -0.003215789 0.001030623 -0.001100361 0.01667368 0.9998604 -3.03894e-5 0.007609188 0.999971 5.9219e-5 -8.21388e-4 0.9999997 -1.20891e-4 -7.34526e-4 0.9999997 0 -8.0122e-7 1 1.11048e-5 -1.32658e-7 1 7.8225e-6 -1.32033e-5 1 -3.51448e-6 -5.76166e-6 1 -1.07817e-6 5.65652e-7 1 0 0 1 6.15184e-4 -6.42117e-4 0.9999997 3.20567e-7 -1.56407e-6 1 2.92253e-7 -1.42593e-6 1 2.12049e-4 -7.54705e-4 0.9999997 -5.99354e-4 -5.95711e-4 0.9999997 -0.003150284 -3.25173e-4 0.9999949 -9.44507e-4 -4.81754e-4 0.9999995 0.002031147 -4.62184e-4 0.9999978 0.002407371 -4.3578e-4 0.9999971 1 0 2.11934e-6 1 0 1.03243e-6 1 0 -1.72625e-6 1 0 -1.6884e-6 -0.002180278 -6.04502e-5 -0.9999976 1.75044e-4 0.0308156 -0.9995251 -4.95881e-4 -7.24029e-4 -0.9999997 0.001183867 -4.68624e-4 -0.9999992 -1.84078e-4 -8.3074e-4 -0.9999997 -2.435e-5 -7.41029e-4 -0.9999998 3.82661e-4 -5.97066e-4 -0.9999998 0.002160608 -4.04655e-4 -0.9999976 -1.06718e-6 9.24253e-7 -1 -1.09191e-6 9.45669e-7 -1 0 -3.48039e-6 -1 8.05157e-6 1.06988e-5 -1 -8.55362e-6 1.57887e-5 -1 1.88513e-6 -5.74984e-5 -1 1.87389e-6 -5.75084e-5 -1 3.59022e-5 1.30619e-5 -1 -0.00166881 -5.49208e-4 -0.9999985 -0.001648783 -5.50572e-4 -0.9999985 -0.03282594 -0.9989716 0.03127586 0.09091377 -0.9952893 -0.0336737 0.5545222 -0.8314873 0.03367483 0.6531183 -0.7566097 -0.03127914 0.9263738 -0.3749302 0.03548121 0.9411619 -0.3377884 0.01064008 0.9955528 0.0800721 -0.04962873 0.9269046 0.3676401 0.07542216 0.7455701 0.6621467 -0.07541143 0.4649979 0.8820895 0.0754649 0.0544067 0.9959478 -0.07160919 -0.1627748 0.9858283 0.04058051 -0.5653322 0.8245383 -0.02315467 -0.6446223 0.7642451 0.01978451 -0.8703932 0.4915435 -0.02829682 -0.944863 0.3236978 0.04953479 -0.9978587 -0.04908961 -0.04322475 -0.9476825 -0.315595 0.04793369 -0.8748847 -0.4834342 -0.02946507 -0.5647462 -0.8245772 0.03367662 -0.4585506 -0.8881184 -0.0312612 0.9923331 0.1234644 -0.00562489 0.9733529 0.2292934 0.002955853 0.7153176 0.6987978 0.001512527 0.6616141 0.7498217 -0.005848467 0.1450345 0.9894114 0.005475401 0.0242986 0.9996897 -0.005476653 -0.4822568 0.8760163 0.004891395 -0.6091328 0.7930403 -0.006652712 -0.8625466 0.505937 0.006415486 -0.9580883 0.2864241 -0.005298733 -0.9985969 0.05286514 0.003076434 -0.9905181 -0.1373478 -0.003075838 -0.9303511 -0.3666316 0.005299925 -0.8002843 -0.5995706 -0.007750988 -0.5908304 -0.8067715 0.006268382 -0.3268442 -0.9450703 -0.003891289 -0.1756275 -0.9844489 0.003898978 0.09515154 -0.9954485 -0.005344867 0.3772597 -0.9260963 0.00456506 0.5421184 -0.8402917 -0.004194617 0.725376 -0.68834 0.004217028 0.8884682 -0.4589051 -0.00550723 0.9632092 -0.268694 0.005616962 0.2620077 -0.9648027 0.0225318 0.2459635 -0.9691999 0.01239186 0.6963214 -0.7176226 -0.01242756 0.7072571 -0.7069495 -0.00310719 0.9620471 -0.2722058 0.01921796 0.9834687 -0.1783557 -0.03128087 0.9794462 0.2004386 0.02256911 0.9442885 0.3284782 -0.02052575 0.8077034 0.5890501 0.02520644 0.7436411 0.6683385 -0.01793396 0.3000833 0.9538967 0.005586922 0.3388352 0.9404585 -0.02698969 -0.2197722 0.9742078 0.05118012 -0.4134611 0.9086671 -0.05808579 -0.7656984 0.6415702 0.04575836 -0.8542641 0.5187471 -0.03367996 -0.9982506 0.04859483 0.03367841 -0.9936496 -0.102787 -0.04577386 -0.8671656 -0.495385 0.05116254 -0.7078441 -0.7035421 -0.06312894 -0.388887 -0.9191217 0.06310552 -0.1622692 -0.9859406 -0.03987163 0.002564847 -0.9766119 -0.2149948 -0.04679185 -0.9510271 -0.3055455 0.0511586 -0.7433297 -0.666966 -0.05117774 -0.5671741 -0.8220064 0.04576712 -0.186677 -0.9813547 -0.03367906 -0.03624951 -0.9987751 0.02946835 0.4159534 -0.9089083 -0.05996882 0.5971714 -0.7998688 0.03140795 0.7535813 -0.6566041 0.00550723 0.9729002 -0.2311597 -0.07046151 0.9914146 -0.1101465 0.06615281 0.9512231 0.3013277 -0.05333113 0.7916499 0.6086429 0.0479331 0.5742844 0.8172515 -0.01792025 0.4407881 0.8974323 0.004340648 -0.04862564 0.9988077 0.01702558 -0.06668245 0.9976289 -0.01556956 -0.620646 0.7839363 0.03096324 -0.6783764 0.7340619 -0.04111212 -0.9453769 0.3233762 0.02088993 -0.9780532 0.2073056 -0.02089101 -0.9780551 -0.207296 0.05696403 -0.9341497 -0.3523061 -0.04954862 -0.6979336 -0.7144463 0.04162454 -0.5290628 -0.8475612 -0.04164719 -0.2044469 -0.9779913 0.04952919 0.009584844 -0.9987267 -0.04953157 0.4026445 -0.9140153 0.05443614 0.6130705 -0.7881506 -0.04415512 0.815519 -0.5770434 0.03874707 0.9654312 -0.2577621 -0.03875273 0.9961546 -0.0785771 0.05117559 0.9520584 0.3016052 -0.05116617 0.8553801 0.5154676 0.03873199 0.5991801 0.7996769 -0.03877133 0.4443641 0.8950069 0.05116593 0.07513886 0.9958595 -0.06311714 -0.1865109 0.9804233 0.06311398 -0.5437417 0.8368761 -0.05116051 -0.7432984 0.6670008 0.04680269 -0.9510323 0.3055276 -0.002567291 -0.9766209 0.2149535 -0.9999991 -2.09347e-4 -0.001295328 -0.9999998 -6.57045e-4 -3.35139e-4 -0.9999762 -0.006886124 4.56185e-4 -0.9999803 -0.00624603 5.73689e-4 -0.9999989 -9.34581e-4 -0.001048684 -1 0 0 -0.9999791 -0.005865931 0.002698957 -0.9999981 -0.001913547 -4.3164e-4 -0.9999991 -9.35596e-4 -0.001046717 -0.9999983 -0.001197457 0.001389503 -0.9999758 -0.006935119 3.76696e-4 -0.9999958 -0.002506315 0.001434624 -1 0 0 -0.9999787 -0.006467819 9.27457e-4 -0.9999983 -3.82063e-4 0.001827538 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999995 9.54112e-4 -6.15476e-4 -1 0 0 -0.9999236 -0.01219755 -0.002013802 -0.9999359 -0.01123088 -0.001519203 -0.9999958 0.001361966 -0.002545535 -0.9999024 0.008352994 0.01119816 -0.9999991 0.001266241 3.21366e-4 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999964 0.002542018 8.34568e-4 -0.9999967 0.002529799 3.48713e-4 -0.9999998 2.48066e-4 6.05531e-4 -0.9999955 0.001266121 -0.002757787 -0.9999991 0.001387655 6.6869e-5 -0.9999989 0.00149846 -4.92815e-5 -0.9999939 0.002096831 0.002788722 -0.9999989 0.001341938 -6.16642e-4 -0.9999991 0.001317679 2.15372e-4 -1 0 0 -0.9999451 0.003655135 -0.009820103 -0.9999997 1.54062e-4 7.73493e-4 -0.9999999 3.51124e-4 3.11962e-4 -0.9999949 -7.3067e-4 0.003072261 -0.9997324 -0.003355383 -0.02289128 -0.9999004 0.005335569 0.01306545 -0.9999764 -0.001818597 -0.006639659 -0.9999993 0.00104016 -4.40098e-4 -0.999997 0.001939535 -0.001543998 -0.9890073 -0.06112444 0.1346415 -0.9999874 -0.001046001 0.004906117 -0.9999932 -0.001163065 -0.003486096 -0.9999866 0.003066956 0.004174053 -0.9999312 0.007163524 0.009289681 -1 0 0 -0.9999993 0.00109291 -2.54535e-4 -0.9999986 0.001197159 0.001197636 -0.9997802 0.01095211 -0.01788318 -0.9999844 0.002235531 0.005125463 -0.02124685 -0.01182162 -0.9997044 -0.00749427 -0.007566034 -0.9999433 -0.0142495 -0.9997849 -0.01507359 -0.02834564 -0.999454 0.01697587 0 -1 0 0 -1 0 0 -1 0 0.02172797 -0.9997639 0 0.01643353 -0.9998644 -0.001060724 0.0367341 -0.9936794 -0.1060749 -0.03362214 -0.9839029 -0.1755124 0.01029276 -0.8226505 -0.5684543 0.05156958 -0.797204 -0.6015034 -0.06995081 -0.4680529 -0.8809276 0.07945823 -0.2977804 -0.9513218 -0.05550503 -0.004954397 -0.9984462 0.06924742 0.2606276 -0.9629529 -0.03423964 0.3822897 -0.923408 0.003696739 0.7473847 -0.6643813 0.04486584 0.7733524 -0.6323869 -0.04712831 0.9452503 -0.3229254 0.04712605 0.9827072 -0.1790691 -0.04484915 0.9835619 0.1749131 0.0271483 0.969037 0.2454186 -0.02975052 0.6985399 0.7149525 0.05916839 0.6411337 0.7651448 -0.06292885 0.2562524 0.9645593 0.07216036 0.04848718 0.9962137 -0.06000155 -0.1641256 0.9846129 0.09753215 -0.4936687 0.8641636 -0.07606703 -0.6637508 0.7440758 0.05056822 -0.9249473 0.3767165 -0.008284568 -0.9086374 0.4175038 1 3.14372e-6 2.06859e-6 1 3.24679e-6 1.2951e-6 1 -2.68869e-6 1.6212e-6 1 -1.88749e-6 3.30403e-6 1 1.36915e-6 8.40573e-7 1 0 0 1 -1.10793e-6 3.19968e-6 1 2.49286e-6 2.97504e-6 1 0 -3.57205e-6 1 0 2.49876e-6 1 3.91971e-6 9.92707e-7 1 1.25606e-6 -2.21924e-6 1 -1.14841e-6 2.02905e-6 1 -3.13702e-7 2.46784e-6 1 2.32047e-7 -1.82547e-6 1 6.6092e-6 -3.48964e-6 1 5.27662e-7 -7.35085e-6 1 1.5573e-6 -9.51847e-7 1 -2.18885e-6 1.33786e-6 1 2.95862e-6 5.21316e-6 1 2.93446e-6 5.33555e-6 1 2.90829e-6 5.33739e-6 1 -3.39547e-6 -6.23146e-6 1 -5.36687e-6 -3.53144e-6 0.06430113 -0.9948391 -0.07848924 -0.03359991 -0.9839071 -0.1754934 0.01028567 -0.8226237 -0.5684931 0.05149221 -0.7972203 -0.6014885 -0.07745212 -0.4433381 -0.893002 0.07743161 -0.2978271 -0.9514744 -0.051512 0.1593189 -0.9858824 0.05151093 0.2609015 -0.9639901 -0.07743394 0.6633002 -0.7443365 0.1070079 0.7885002 -0.605654 -0.09442704 0.9711297 -0.219068 0.07947719 0.9968177 -0.006144046 -0.07946574 0.9378222 0.3378975 0.04437685 0.8771492 0.4781631 0.01076161 0.6243891 0.7810393 -0.05976599 0.5668947 0.8216195 0.05974394 0.1592527 0.9854284 -0.06431466 0.03618133 0.9972735 0.06431216 -0.44374 0.8938449 -0.05974525 -0.5510106 0.8323567 0.0597462 -0.8549913 0.5151896 -0.06431031 -0.9118649 0.4054215 1 1.92222e-6 2.60664e-6 1 -5.02954e-6 -6.82034e-6 1 -5.27915e-6 -1.03481e-6 1 0 0 1 1.54599e-6 -6.16068e-6 1 3.38052e-6 -4.93244e-6 1 -6.54847e-7 -1.5286e-6 1 -1.54399e-6 -3.60411e-6 1 4.3067e-6 -4.0597e-6 1 0 0 1 -2.87876e-6 1.45112e-6 1 0 0 1 2.11076e-6 1.50835e-6 1 3.17593e-6 1.24661e-6 1 0 0 1 -3.13382e-6 -2.36441e-6 1 -2.76022e-6 -2.27675e-6 1 2.55634e-7 -3.74995e-6 1 0 0 1 -1.24881e-6 -1.88002e-7 1 -9.2225e-7 3.29528e-6 1 -4.78012e-6 1.45497e-6 -0.9999949 0 0.003175377 -1 0 0 -1 0 0 -1 0 1.23696e-6 -0.999985 -0.00442332 -0.003214061 -1 5.77134e-5 -9.99303e-5 -1 0 0 -0.9999583 0.00390762 -0.008261084 -0.9991948 0.04012137 0 -0.9967924 0.04002487 -0.06930273 -0.999994 -0.003215312 -0.001372337 -1 1.9216e-6 0 1 3.86522e-6 -1.63333e-6 1 3.6658e-6 -1.10284e-6 1 2.85758e-6 -1.36634e-6 1 3.01329e-6 -2.6272e-6 1 3.72741e-6 -2.73275e-6 1 2.91726e-6 -5.97687e-6 1 -1.66886e-6 -1.4707e-6 1 -2.31447e-6 -2.03965e-6 1 -1.76428e-6 -2.73287e-6 1 1.00441e-6 -1.64035e-6 1 0 0 1 0 0 1 -1.95398e-7 -2.32569e-6 1 -3.93901e-6 2.50324e-7 1 -2.83221e-6 1.21286e-6 1 -5.07342e-6 5.12464e-6 1 -4.19074e-6 5.79185e-6 1 1.20576e-6 3.01084e-6 1 0 0 1 0 0 1 -2.56594e-6 -2.08114e-6 1 -2.08988e-6 -3.34977e-6 1 4.26401e-6 6.83457e-6 1 7.28859e-6 1.17207e-6 0.0377922 -0.9972739 0.06337678 -0.05407083 -0.9561067 -0.2879869 0.06999003 -0.8999672 -0.4303029 -0.05911052 -0.6129098 -0.7879388 -0.04311275 -0.6024876 -0.796963 0.06773054 -0.2465968 -0.9667484 -0.1037042 0.01807916 -0.9944439 0.09441685 0.2600749 -0.9609612 -0.09441667 0.6179518 -0.7805261 0.05410188 0.7526401 -0.6562055 -0.03110414 0.9255872 -0.3772544 0.03111839 0.9571393 -0.2879514 -0.05408 0.9978227 0.03775388 0.04437124 0.9863433 0.158613 0.01068407 0.8488459 0.5285325 -0.05973458 0.8082098 0.5858573 0.05976098 0.4784395 0.8760846 -0.06430131 0.3663449 0.9282547 0.06431037 -0.1206439 0.9906105 -0.08729839 -0.2685001 0.9593157 0.07023078 -0.5847538 0.8081649 -0.06288063 -0.7966822 0.6011186 0.01893001 -0.8539705 0.519977 -0.01891922 -0.991083 0.131896 -0.9655928 -0.2589354 0.02414393 -0.999684 0.02503085 -0.002333939 -1 0 0 -0.9998833 -0.009071052 0.01229214 -0.9999977 -0.002028346 7.39927e-4 -0.9999901 2.30311e-4 0.004447102 -1 0 0 -0.9999565 -0.004261732 0.008294045 -0.99944 0.02502471 -0.02221721 -0.9996932 0.01853525 -0.01643121 -1 0 -1.02711e-6 -1 4.53147e-7 -8.11857e-7 0.004441022 -0.02283561 0.9997293 -2.01522e-4 0.03306597 0.9994531 0.001137375 -6.09355e-4 0.9999992 0 2.19381e-6 1 -2.04724e-4 -6.44721e-4 0.9999998 3.27187e-4 -7.67906e-4 0.9999997 1.83153e-4 -8.31546e-4 0.9999997 -0.002123117 -4.05215e-4 0.9999977 -6.2054e-6 -1.8219e-6 1 -1.64415e-7 -6.28924e-6 1 4.00198e-6 2.04857e-6 1 -4.06698e-6 3.4939e-6 1 -4.78421e-7 4.11007e-7 1 9.78649e-7 1.34001e-6 1 1.83854e-6 -1.51909e-6 1 0.001941919 -5.49309e-4 0.999998 -9.17747e-4 -5.00396e-4 0.9999995 -1 -5.39024e-7 -7.94983e-6 -1 0 4.23879e-6 -1 -5.08815e-7 -3.43708e-6 -1 -4.86381e-7 -3.74447e-6 0.001654863 0.01393181 -0.9999015 -6.02392e-5 -9.52694e-4 -0.9999995 -3.20384e-4 -7.09391e-4 -0.9999997 8.03685e-4 -5.61331e-4 -0.9999995 0.001757323 -4.81235e-4 -0.9999984 -7.2849e-6 3.77783e-6 -1 -5.8881e-5 -8.24896e-4 -0.9999997 1.96655e-4 -7.01772e-4 -0.9999998 2.4968e-5 -1.2948e-5 -1 1.34494e-5 1.71061e-5 -1 -8.21526e-6 4.02643e-5 -1 -1.31051e-5 -9.63311e-6 -1 6.99819e-6 -2.31814e-6 -1 1.27252e-6 5.62402e-6 -1 -5.61028e-7 -2.47952e-6 -1 2.22809e-6 8.02446e-7 -1 0 0 -1 -0.002350211 -4.61525e-4 -0.9999971 -0.001352965 -5.33779e-4 -0.9999989 0.0328232 -0.9982334 -0.04952496 0.2749956 -0.9599032 0.05443578 0.5642663 -0.8238688 -0.05332803 0.8165507 -0.573812 0.06312435 0.9468831 -0.3153232 -0.06311714 0.999059 0.004649579 0.04312115 0.945516 0.323907 -0.03291845 0.9091439 0.4163646 0.009891688 0.6447404 0.764321 -0.01110064 0.6363121 0.7714128 -0.005391538 0.2584069 0.9658759 0.01759892 0.2154679 0.9764949 -0.00560671 -0.2060721 0.9782348 -0.02431118 -0.3553811 0.9330312 0.05618762 -0.7332606 0.6776224 -0.05618554 -0.8308503 0.5559656 0.02429211 -0.9864244 0.1641203 0.005604982 -0.9950509 0.09431463 -0.03127837 -0.9282238 -0.3703269 0.03547656 -0.9023586 -0.4309509 -0.005511462 -0.554494 -0.8314962 -0.03391963 -0.4151699 -0.9075583 0.06302392 -0.9838931 -0.1787076 0.004234373 -0.9552841 -0.295648 -0.004953444 -0.6964283 -0.7176097 0.004891276 -0.6230003 -0.7822174 -0.002556324 -0.2419394 -0.970291 7.77222e-4 -0.2311411 -0.9729189 0.001613438 0.2579659 -0.9661524 -0.001800656 0.3308154 -0.9436825 0.004948914 0.7719461 -0.635649 -0.007039487 0.8908548 -0.4541931 0.009299814 0.9926362 -0.1208851 -0.007752835 0.9721083 0.2343527 0.009179294 0.8776296 0.4792816 -0.007438182 0.6330069 0.7741258 0.005629479 0.5285527 0.8488973 -0.002315938 0.1586084 0.9873412 7.94314e-4 0.147848 0.9890088 0.001613616 -0.3128651 0.9497961 -0.001613259 -0.3532906 0.9355123 0.00161314 -0.7363488 0.6766003 -0.00161302 -0.7437641 0.6684418 -7.83459e-4 -0.9449306 0.3272625 0.002329528 -0.9733499 0.2292901 -0.004003345 0.2418618 -0.9701454 0.01791095 0.3892043 -0.9199044 -0.04791456 0.6223946 -0.7815091 0.04322856 0.8803374 -0.4710086 -0.05618554 0.9535499 -0.2984898 0.04057765 0.9759957 0.214945 -0.03508716 0.972554 0.2315183 -0.02319699 0.7143489 0.6979154 0.05118352 0.5331641 0.8428773 -0.07275903 0.1748652 0.9831463 0.05334329 -0.1448284 0.9879583 -0.05443561 -0.3231712 0.9460567 0.02317488 -0.6643862 0.7473685 0.005599796 -0.733651 0.6779828 -0.04577612 -0.9233276 0.382247 0.03678733 -0.9949981 0.09431338 -0.03292113 -0.9990928 -0.03573459 0.02316474 -0.8758028 -0.4806032 -0.04461121 -0.7882367 -0.6131333 0.0524441 -0.3041823 -0.951846 -0.03824073 -0.2579456 -0.9661497 -0.00433743 0.0384944 -0.9513654 0.3056504 -0.01487815 -0.9191543 0.3936166 0.01702094 -0.5447571 0.8384211 -0.03822773 -0.4767344 0.8782158 0.0446214 0.04907673 0.9977978 -0.05994552 0.2880146 0.955748 0.02945542 0.4833618 0.8749249 -0.03370261 0.8245395 0.5647998 0.0175687 0.8761199 0.4817731 -0.00541234 0.9972147 0.07438844 -0.01111388 0.9979255 0.06341195 0.01111042 0.9197852 -0.3922649 -0.01112073 0.9021193 -0.4313434 0.01240885 0.5896049 -0.8075966 -0.0155676 0.551926 -0.8337478 0.01418673 0.03576141 -0.9992596 -0.0234754 -0.03624558 -0.9990671 0.02465671 -0.3824235 -0.9236582 -0.03513598 -0.5420384 -0.8396189 0.0291239 -0.7471666 -0.6639984 -0.02570587 -0.8768748 -0.4800311 0.03168284 -0.9556677 -0.2927376 -0.03198945 -0.9973781 -0.06491398 0.03039562 -0.9991148 -0.02908504 -0.03788149 -0.981292 0.1887621 0.03030544 -0.8969792 0.4410328 -0.0288943 -0.7640618 0.6444959 0.03140968 -0.6314988 0.7747403 -0.05116683 -0.323655 0.9447907 0.05116969 -0.09425044 0.9942327 -0.04577541 0.3156199 0.9477809 0.01923269 0.4309012 0.9021942 -0.00191158 0.8009807 0.5986871 -0.05511462 0.8565185 0.5131652 0.04294431 0.969421 0.2416169 -0.02699404 0.9658042 -0.2578638 0.03062736 0.9818573 -0.1871317 -0.03982919 0.7815753 -0.6225382 0.0631197 0.6127702 -0.7877364 -0.06311488 0.2689766 -0.9610766 0.06311786 -0.01813018 -0.9978414 -0.05333429 -0.3665982 -0.9288494 0.03647869 -0.59961 -0.7994605 -0.02118718 -0.7712593 -0.6361684 0.02117574 -0.8778138 -0.4785336 -0.0306192 -0.9579207 -0.2853951 0.9999698 -0.007323384 -0.002638578 1 -1.59622e-6 0 0.9998645 -0.003789067 -0.01602166 0.9999938 0.003508269 -5.01845e-4 0.9999779 0.002230763 0.006256282 0.9999947 -0.001855015 -0.002688586 0.9999238 -0.01043796 0.006590068 0.9998801 -0.01510488 0.003407359 0.9999703 -0.007668137 -6.9892e-4 1 2.39129e-4 -3.61228e-4 0.9999853 -1.99847e-4 -0.005438566 0.9999876 -0.001249074 -0.004824459 1 1.83301e-6 1.28616e-7 1 -1.79302e-6 3.23134e-6 1 -2.02985e-6 3.08646e-6 0.9999965 0.002622544 4.66305e-4 0.9999953 0.002289652 -0.002036809 0.9999991 0.001162767 8.03571e-4 0.9999991 0.001392304 -3.05164e-4 1 -8.57932e-6 1.88035e-6 1 1.46637e-6 5.2436e-7 1 -1.78488e-6 0 0.9999981 -0.001761019 -8.5933e-4 1 1.71882e-6 6.14635e-7 0.9999941 0.00339055 -6.90039e-4 0.9999969 0.00177282 -0.00178039 0.9999919 9.17087e-5 -0.004017531 0.9999839 0.003536105 0.004447221 0.9999992 0.001182854 -5.23137e-4 0.9882668 0.05490058 0.1425296 0.9983471 -0.02332395 -0.0525251 0.9999704 -0.001953184 -0.007443785 0.9999938 0.003507435 -4.65025e-4 0.9999897 0.004188776 0.00176084 0.9999997 6.96217e-4 -5.25315e-4 0.9999123 -0.001747906 0.01312625 0.9999929 -6.4246e-4 0.003730297 0.9999976 0.001333773 0.001716494 0.9999057 0.005921363 -0.01238787 0.9999977 0.002041041 6.13217e-4 0.9999638 0.002142012 -0.008234679 0.9999985 0.0017066 3.04434e-4 0.9999963 -0.001681983 0.002122461 0.9999829 -1.04016e-4 0.005842745 0.9999853 -5.99207e-4 0.005369603 0.9999191 0.003045558 -0.01235616 0.999969 0.003047168 -0.007264137 0.9999967 0.001445353 0.002128958 0.9999967 0.002464771 6.85236e-4 0.9999992 -0.001156449 3.95088e-4 0.9999989 0.00148046 1.86346e-4 0.9999933 0.003028452 0.002092659 0.9999783 0.001618206 0.006384015 1 0 0 1 -1.40151e-6 9.13592e-7 0.9999951 -0.003107488 -5.50388e-5 0.9968534 -0.07804358 -0.01388025 0.9999966 -0.001138448 0.002357244 0.9999997 -6.04339e-4 5.37222e-4 0.9999943 -0.003370583 -1.27532e-4 0.9999976 -0.002044379 8.3328e-4 1 -2.31577e-6 9.13509e-7 1 1.75642e-6 3.58765e-6 1 1.45862e-6 3.69589e-6 1 3.79924e-6 1.2045e-6 0.9999516 -0.009375154 -0.002972245 -1.8029e-4 -7.89663e-4 -0.9999997 0 0 -1 3.85341e-4 -3.30229e-4 -0.9999999 4.39008e-4 -2.89421e-4 -0.9999999 -1.26175e-4 0.001289308 -0.9999992 6.68592e-4 -0.002867758 -0.9999957 6.20668e-4 0.002710402 -0.9999961 -0.004502892 0.999987 0.002422213 -0.002758443 0.9999955 -0.001195192 2.55053e-4 -0.003926694 0.9999923 9.61908e-4 -6.40125e-4 0.9999994 -0.003399908 -4.24912e-4 0.9999942 0.001246929 1.52243e-4 0.9999992 -6.9285e-4 -6.03949e-4 0.9999995 0 -7.19961e-5 1 1.90143e-4 0 1 0.004192113 0.9999902 -0.001421749 0.002735435 0.999995 0.001564383 0.003291606 -0.00807023 -0.999962 0.00426197 -0.007748484 -0.9999609 0.05337369 0.9982685 -0.02472096 -0.1887868 0.9815759 0.02946722 -0.3372951 0.9411075 -0.02342396 -0.6675259 0.7439298 0.03126448 -0.7723237 0.6333631 -0.04865372 -0.9849966 0.1565999 0.07251352 -0.9947276 -0.07252335 -0.07250636 -0.8409512 -0.5395177 0.04149478 -0.7281055 -0.6845039 -0.03628832 -0.4930443 -0.8692384 0.03649562 -0.2455401 -0.967921 -0.05328202 0.07852029 -0.9954848 0.05333566 0.3392748 -0.9399785 -0.03651082 0.5511886 -0.834113 0.02113538 0.6992015 -0.7146095 -0.02122229 0.8309421 -0.5555997 0.02905654 0.9408326 -0.3376245 -0.0290479 0.9903014 -0.1373115 0.02118444 0.9964104 0.08015155 -0.02724099 0.9572116 0.286144 0.04321593 0.7993054 0.5993688 -0.04321885 0.6569009 0.7534833 0.02727895 0.4784918 0.8778378 -0.02112692 0.285548 0.9578743 0.03064417 0.002548217 0.999752 -0.02212136 -0.2188743 0.9746006 0.04740887 -0.4638373 0.8847584 -0.0453602 -0.7657009 0.6415668 0.04576176 -0.8399372 0.5423436 -0.01921337 -0.9979549 0.06384664 0.003101766 -0.9987399 0.04863154 0.01239401 -0.8765953 -0.4810324 -0.0137304 -0.8827985 -0.4691817 -0.02313762 -0.5154785 -0.8553714 0.05120307 -0.3302445 -0.9421066 -0.05808377 0.04720753 -0.9983901 0.03144633 0.2057476 -0.9783917 -0.02043491 0.454482 -0.8905194 0.02052479 0.5906453 -0.8063188 -0.03143692 0.8327646 -0.5512583 0.05116087 0.93842 -0.3416868 -0.05116617 0.9967273 0.06662291 0.04578191 0.981661 0.1896635 -0.0192191 0.7647092 0.6443682 0.003080487 0.754665 0.6559923 0.01245069 0.3787966 0.9254285 -0.009760618 0.3106992 0.9502691 0.02132719 -0.3525918 0.9349743 0.03875523 -0.4401539 0.8976866 -0.02057474 -0.8256606 0.5641642 0.001842081 -0.8480435 0.5294074 0.02345681 -0.9794042 0.200398 -0.02465718 -0.9991605 0.0210157 0.03516656 -0.9442601 -0.3256328 -0.04833239 -0.8825566 -0.4690691 0.03268128 -0.5684919 -0.8226559 0.007355213 -0.4602299 -0.8859102 -0.05789309 -0.1753978 -0.9835487 0.04321575 0.2009511 -0.9783493 -0.04951179 0.4332434 -0.8996291 0.05447381 0.6566382 -0.7533693 -0.03550881 0.8973565 -0.4407307 0.02253252 0.8900641 -0.4556665 0.01240044 0.9999389 -0.004930257 -0.009897768 0.9949968 0.09432888 0.03291726 0.9233302 0.3822391 -0.03680622 0.7541199 0.6555926 0.03875064 0.6445123 0.7641174 -0.02699297 0.2786794 0.9598503 0.03201937 0.1622822 0.9862677 -0.03066849 -0.2216461 0.9724577 0.07210499 -0.4396307 0.8967068 -0.05139726 -0.8544501 0.5188319 0.02699136 -0.8490239 0.5280298 0.0185166 -0.9945461 -0.1029 -0.01702493 -0.9926564 -0.1208904 -0.004343569 -0.7521007 -0.6586926 0.02164953 -0.7090592 -0.7047498 -0.0237199 -0.1364954 -0.9906394 0.001674115 -0.1507201 -0.9885404 -0.008444905 0.3267188 -0.9449582 0.01757335 0.3921613 -0.9196956 -0.01922762 0.7748764 -0.6321099 0.001932382 0.8000931 -0.5994146 0.02351844 0.9588884 -0.2827115 -0.0246452 0.9902215 -0.1373072 0.0246613 0.9759634 0.216667 -0.02347075 0.9664768 0.2567467 -0.001938521 0.7572581 0.6528704 0.01790249 0.667491 0.7437398 -0.03615117 0.4161292 0.9085528 0.03698962 0.1621057 0.9853629 -0.05274277 0.01329743 -0.01498585 0.9997993 -0.01096367 -0.00685352 0.9999164 -0.01018488 -0.006471574 0.9999272 0.003901302 -0.01022213 0.9999402 0.06173062 -2.71035e-4 0.9980928 0.09666705 -0.9945186 -0.0398522 0.5201917 -0.8536119 0.02733498 0.5078336 -0.8612856 0.01709705 0.9293881 -0.368637 -0.01856422 0.9252456 -0.3784079 -0.02698558 0.9826587 0.1782228 0.05117034 0.9253992 0.3745162 -0.05808645 0.6734889 0.7377785 0.04577791 0.5545027 0.8315004 -0.03367578 0.06057465 0.997451 0.0377112 -0.006719529 0.9999687 -0.004183292 -0.4212297 0.906658 -0.02316939 -0.5543064 0.831269 0.04167115 -0.8069846 0.5891017 -0.04165464 -0.8879687 0.4593188 0.0231927 -0.9967889 0.07987809 0.005610525 -0.9987869 -0.01815754 -0.0457707 -0.9187529 -0.3923535 0.0441786 -0.799461 -0.5996116 -0.03644496 -0.6111575 -0.7909807 0.02891296 -0.4523369 -0.8912712 -0.03204625 -0.1195033 -0.9914623 0.05216616 0.2356582 -0.9709188 -0.04221379 0.4750573 -0.8787307 0.04639869 0.7810865 -0.6243321 -0.01065093 0.8049494 -0.5922816 -0.03548038 0.9814884 -0.1896042 0.0270316 0.9958396 -0.08971089 -0.01598352 0.9530484 0.3027699 0.005401968 0.949596 0.3132784 0.0111345 0.6874168 0.7261577 -0.01237767 0.6533995 0.7568532 0.01557481 0.1364883 0.9905195 -0.01555919 0.09093451 0.9957795 0.01241421 -0.3682801 0.9296622 -0.009892225 -0.4313808 0.9019526 0.01979935 -0.718339 0.6951163 -0.02832698 -0.8159846 0.5769094 0.0366699 -0.9880504 0.1509901 -0.03095704 -0.9943905 0.1057264 -0.003096044 -0.919537 -0.3925337 0.01921546 -0.8897558 -0.4560967 -0.01761865 -0.6201328 -0.7844789 0.005313634 -0.588984 -0.8077439 0.025451 -0.2156097 -0.9759829 -0.03114002 -0.02055823 -0.9991003 0.03709226 0.150637 -0.9885765 0.004995942 0.1626508 -0.9866057 0.01241707 0.6329564 -0.7740885 -0.01237922 0.644674 -0.7644512 -0.003126204 0.9355239 -0.3527421 0.01918065 0.9711307 -0.2341158 -0.0457732 0.9826648 0.1781924 0.05116134 0.9017949 0.427529 -0.06312656 0.6953688 0.716672 0.05332642 0.4816088 0.8756271 -0.03647226 0.2011294 0.9788932 0.03626185 0.01855415 0.9989666 -0.0414924 -0.40561 0.9121357 0.05906808 -0.6291909 0.7752948 -0.05510747 -0.7974737 0.6028497 0.02465748 -0.9654346 0.2592087 -0.02732789 -0.968791 0.2471039 -0.01958531 -0.9717312 -0.2313292 0.0471726 -0.8768826 -0.4760025 -0.06707119 -0.7574452 -0.6524896 0.02311575 -0.417456 -0.9086877 0.00413829 -0.3801862 -0.9246689 -0.02111756 0.4905018 -0.8707809 -0.03389418 0.5545476 -0.8319133 0.01993173 0.9643899 -0.2636289 -0.02126157 0.960983 -0.2749087 -0.0306096 0.978165 0.2039721 0.03985518 0.9246523 0.378722 -0.03984701 0.6638781 0.7473708 0.02651238 0.6740942 0.7384495 0.01701205 0.1089903 0.9938967 -0.01704257 0.1223439 0.9921345 -0.02647638 -0.3265869 0.9443272 0.03983974 -0.5386097 0.840187 -0.0631296 -0.7802281 0.6240085 0.04309952 -0.9391208 0.3420054 -0.03293234 -0.9758607 0.2171621 0.02316522 -0.9811899 -0.1895321 -0.03665858 -0.9171966 -0.3946977 0.05444353 -0.7455062 -0.6643623 -0.05332165 -0.4950571 -0.8672801 0.05238109 -0.1929433 -0.9797667 -0.0531978 0.006261765 -0.9994294 0.03319215 1.62951e-4 -1.09639e-4 1 1.58978e-4 -1.09802e-4 1 1.93662e-5 -6.91627e-5 1 0.006790995 6.18232e-5 0.999977 -1.84725e-5 -1.09313e-5 1 -3.66164e-6 -8.50566e-6 1 9.62898e-6 1.508e-5 1 1.8775e-6 2.08635e-6 1 8.66076e-4 0.002873361 0.9999955 0.001779079 0.00164473 0.999997 4.78328e-7 -3.54888e-6 1 9.27039e-5 -1.15014e-4 1 2.52417e-4 -6.70626e-5 1 0.004346311 5.91524e-4 0.9999905 1.09449e-4 -1.14011e-4 1 -4.68628e-4 -4.041e-4 0.9999998 1.54463e-5 7.04445e-5 1 2.7699e-6 1.6944e-5 1 8.24175e-4 0.007718622 0.9999699 1.5901e-5 2.56965e-6 1 8.54068e-6 8.99969e-7 1 -6.94526e-6 -7.46129e-6 1 -1.86128e-4 -5.00271e-4 0.9999999 -4.67802e-4 -3.86501e-4 0.9999998 4.42755e-6 -5.02565e-6 1 -2.42739e-6 -2.6974e-6 1 -2.05987e-5 -1.59489e-5 1 -1.0687e-5 1.40561e-5 1 -6.79159e-6 8.93262e-6 1 1.22116e-5 6.14592e-6 1 1.22185e-5 6.15605e-6 1 -9.54491e-5 -4.36572e-4 1 0.005370497 0.008119165 0.9999526 8.68747e-4 0.006178259 0.9999806 -4.48801e-4 -3.40341e-4 0.9999998 7.13176e-5 -6.21337e-4 0.9999998 -4.89509e-4 -3.79011e-4 0.9999998 -0.001986861 -3.33821e-4 0.999998 -0.007334947 -1.44785e-4 0.9999731 7.0897e-6 -6.40863e-6 1 0.001498997 9.40206e-4 0.9999985 0.001399755 0.00114876 0.9999983 0.001253306 7.95195e-4 0.9999989 -6.3068e-4 0.006635963 0.9999778 -9.52497e-6 -8.67155e-6 1 -5.82159e-5 -4.82834e-5 1 4.36027e-6 -4.42221e-6 1 1.40236e-5 -1.38684e-5 1 -0.003890573 0.001425802 0.9999914 -0.002203047 0.002251148 0.999995 7.81448e-4 0.005886435 0.9999823 -0.004442334 0.01117622 0.9999276 -2.89476e-6 6.21174e-6 1 -2.53805e-6 6.02261e-6 1 -0.002449691 0.001303195 0.9999961 0.001725673 0.005688428 0.9999824 -0.002551853 0.005161225 0.9999835 -0.01139563 0.001124083 0.9999344 -9.37887e-5 0.002309143 0.9999973 -0.001974225 0.001681983 0.9999967 -0.002302169 0.001784086 0.9999957 3.05663e-7 -3.28899e-6 1 -5.55378e-7 -2.47308e-6 1 0 0 -1 0 -1 0 0.01609718 -0.9937551 -0.1104158 0.01714968 -0.9997657 0.01320803 0.01534456 -0.9997441 0.01662325 0 -1 0 0 -1 0 0 -1 0 0 -4.72831e-5 -1 -1.25432e-4 0 -1 7.80683e-4 -0.005780994 -0.999983 -3.27161e-6 5.28675e-7 -1 -1.23746e-4 1.55484e-6 -1 -1.3193e-4 4.41327e-6 -1 -2.64956e-5 -1.01916e-5 -1 1.4066e-5 -1.7391e-7 -1 1.56967e-5 -1.23647e-5 -1 -1.27316e-5 -1.73529e-6 -1 2.16609e-6 1.49035e-5 -1 0 0 -1 -6.79326e-7 5.84927e-7 -1 0 1.18776e-6 -1 0 -5.33748e-6 -1 -1.0991e-5 -5.87261e-6 -1 -3.63516e-7 7.35174e-6 -1 1.30391e-5 -6.6405e-6 -1 -5.98138e-6 -1.11125e-5 -1 -2.13758e-6 6.944e-6 -1 2.76215e-5 -7.71925e-6 -1 -5.31455e-6 -1.26911e-5 -1 -3.13238e-7 2.33146e-6 -1 -3.88958e-7 2.42273e-6 -1 -1.8671e-5 -1.27012e-5 -1 -9.6883e-6 -2.40346e-5 -1 -8.37717e-6 -2.04834e-5 -1 -3.38109e-5 0 -1 -3.14217e-5 2.1589e-6 -1 -1.95607e-5 1.28772e-5 -1 -1.97628e-5 1.24127e-5 -1 -1.14134e-5 4.00582e-6 -1 -1.28383e-5 3.55248e-6 -1 -1.37572e-5 1.24316e-5 -1 2.27641e-6 8.74721e-7 -1 -2.80125e-6 -5.62551e-6 -1 -2.13181e-6 -6.84362e-6 -1 4.97578e-6 -2.00947e-6 -1 2.32206e-6 4.95046e-7 -1 5.15085e-6 5.70589e-6 -1 6.44016e-6 4.88663e-6 -1 -3.00265e-6 -2.27833e-6 -1 -1.64799e-6 -4.21464e-6 -1 2.71115e-6 -4.10715e-6 -1 1.88452e-6 1.78934e-6 -1 3.92641e-6 7.65694e-7 -1 2.51701e-6 -1.86896e-6 -1 1.08192e-6 6.21401e-7 -1 -5.6767e-6 -3.26041e-6 -1 -5.25171e-6 -6.10735e-6 -1 3.89672e-6 -6.18721e-6 -1 3.4835e-6 3.04291e-6 -1 0 0 1 -5.73296e-5 -4.91304e-5 1 -1.39741e-4 -0.002637505 0.9999965 0.002298116 -0.00112158 0.9999967 -5.8843e-4 -3.94426e-4 0.9999998 -0.002948403 -4.8025e-4 0.9999955 7.11527e-4 -5.48874e-4 0.9999997 -1.10063e-5 2.07123e-5 1 -1.12108e-5 1.80225e-5 1 -5.54122e-6 1.715e-5 1 -1.47598e-5 -3.34823e-6 1 -5.25477e-6 -9.14256e-6 1 -7.38098e-6 -2.01488e-5 1 9.16991e-5 7.52138e-5 1 1.01619e-4 3.7521e-5 1 -6.70802e-6 4.49071e-6 1 -4.57248e-6 -2.45905e-6 1 0 3.14897e-6 1 -1.09536e-5 1.12176e-5 1 -1.11821e-5 1.63266e-5 1 5.86298e-6 1.96375e-5 1 2.4706e-5 -1.26758e-5 1 9.25303e-6 -1.90066e-5 1 0 0 1 -2.50029e-5 -2.39786e-5 1 -2.49093e-5 -2.4516e-5 1 -3.77152e-5 -2.72591e-5 1 -3.83313e-5 -2.57505e-5 1 9.69061e-6 2.76869e-6 1 3.50174e-6 9.06256e-6 1 5.34799e-6 1.15957e-5 1 -1.32507e-5 1.3949e-5 1 -8.96908e-6 6.83998e-5 1 -1.63376e-4 5.06791e-5 1 1.23168e-6 5.89489e-6 1 1.94452e-6 9.30658e-6 1 -4.32736e-5 -1.24827e-5 1 -4.06325e-5 -1.59192e-5 1 4.12099e-6 5.96329e-5 1 4.00053e-5 2.23475e-5 1 1.71179e-5 5.26189e-6 1 1.40052e-7 1.62149e-5 1 8.19532e-6 -4.48233e-6 1 1.87122e-5 3.53697e-7 1 -7.83042e-6 1.51063e-5 1 -1.34076e-5 -1.87386e-5 1 1.30083e-5 -1.10066e-5 1 -1.37054e-5 6.54585e-6 1 -1.96963e-5 -9.36943e-6 1 1.02847e-5 -5.94431e-6 1 9.26121e-6 -1.95562e-5 1 -1.93833e-5 -1.92609e-5 1 -3.4206e-6 6.02712e-6 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.01658087 -0.9996609 0.02008193 -0.01539623 -0.9997425 0.01667928 0.1014096 -0.9887602 -0.1098604 -0.01619571 -0.9998353 -0.008181929 0 -1 0 -0.03708952 -0.999294 0.005989015 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -0.1165056 -0.9928346 0.026569 0.07133233 -0.9971798 -0.02333056 0.0424776 -0.9988005 -0.02435517 0.9531017 -0.3025127 -0.009117722 0.1027032 -0.9947116 -9.82501e-4 0.01850396 -0.9995887 0.02190923 0.1165114 -0.9926606 -0.03240382 -0.08245843 -0.9963306 0.02293312 0.3364801 -0.941011 0.03577136 1 -3.4359e-7 -1.44907e-7 1 0 0 1 0 2.67373e-7 1 -2.53678e-7 3.20419e-7 1 0 5.98907e-7 1 4.2145e-7 -3.55943e-7 1 -2.32498e-7 -4.72344e-7 1 -1.66284e-7 3.08617e-7 1 0 1.75581e-7 1 0 1.97887e-7 1 0 -1.83541e-7 1 3.96355e-7 0 1 5.19247e-7 -2.68641e-7 1 2.32356e-7 -3.48417e-7 1 -1.58377e-7 0 1 0 0 1 0 0 1 0 0 1 0 -4.68144e-7 1 -4.84247e-7 -2.5732e-7 1 -3.78443e-7 -1.21586e-7 1.16814e-5 -2.86754e-5 -1 -1.18146e-5 -6.62247e-5 -1 -2.29995e-5 -5.58077e-5 -1 2.2315e-5 -2.42322e-5 -1 2.24977e-5 -4.36681e-6 -1 -2.24815e-6 7.8662e-6 -1 -1.26176e-6 -2.81377e-6 -1 6.16599e-5 -1.62288e-5 -1 7.29761e-5 -1.50072e-5 -1 -9.83676e-7 4.97432e-6 -1 -2.75169e-6 6.27806e-7 -1 1.09403e-6 2.72295e-6 -1 1.74821e-6 1.72197e-7 -1 9.23257e-7 -2.71549e-6 -1 7.848e-6 3.0134e-6 -1 -1.13651e-4 -3.53667e-5 -1 -9.33864e-5 -3.77904e-5 -1 -3.7904e-5 -5.17574e-5 -1 -4.2649e-5 -1.40889e-5 1 9.72082e-6 6.59439e-6 1 -4.79947e-5 6.6663e-6 1 -1.47545e-5 2.84474e-5 1 -9.77771e-6 1.02846e-5 1 6.72766e-7 -3.1026e-5 1 3.4023e-5 -6.54595e-5 1 -8.30095e-6 -2.40022e-5 1 4.51077e-6 1.18893e-5 1 -5.60462e-7 -1.47724e-6 1 1.78253e-7 -3.73078e-6 1 -2.01603e-5 -1.91389e-5 1 -7.59357e-5 -1.05294e-5 1 1.01798e-4 -4.47341e-5 1 3.66953e-5 -6.3796e-5 1 -1.111e-5 1.49748e-6 1 1.78724e-4 -3.53542e-5 1 1 0 4.92852e-7 1 0 -2.11938e-6 1 -6.35924e-7 1.67614e-6 1 -2.04609e-7 7.599e-6 1 0 0 1 -1.22355e-7 -2.55419e-7 1 -5.40844e-7 2.2122e-7 1 0 3.0557e-7 1 0 0 1 3.95906e-7 -1.99137e-7 1 0 -1.16414e-6 1 -6.50454e-7 -4.02507e-7 1 0 0 1 0 0 1 -3.56507e-7 0 1 -3.93235e-7 0 1 -3.60054e-7 0 1 0 0 1 0 0 1 2.54466e-7 0 1 1.20861e-7 -5.48435e-7 1 -4.4367e-7 -1.49841e-7 1 2.39552e-7 5.66182e-7 1 3.06967e-7 0 1 0 0 1 0 0 0.007126569 -0.9999124 -0.01115566 -1 -4.00861e-6 -3.21283e-7 -1 -2.92458e-6 -3.56935e-6 -1 3.07089e-6 -3.47802e-6 -1 -1.24356e-6 1.40843e-6 -1 -2.39507e-6 -3.59118e-6 -1 0 -3.53872e-6 -1 -1.07251e-6 -9.06611e-7 -1 0 0 -1 3.38646e-6 -1.96473e-6 -1 2.1256e-6 -3.86055e-6 -1 -3.44015e-6 9.18499e-7 -1 -4.14278e-6 -8.00354e-7 -1 -3.67567e-6 -9.16119e-7 -1 -3.00351e-6 -2.24495e-6 -1 -5.7859e-7 2.94438e-6 -1 1.41604e-6 2.96481e-6 -1 9.68213e-7 4.92549e-6 -1 -2.98247e-7 3.14616e-6 -1 -4.34745e-7 3.23795e-6 -1 4.84959e-7 -3.61195e-6 -1 3.60759e-6 -1.77381e-6 -1 3.8731e-6 -1.79562e-6 -1 3.19269e-6 3.99048e-6 -1.16055e-5 -6.27066e-7 -1 1.04635e-5 -2.35171e-5 -1 2.98675e-5 -1.66337e-5 -1 4.76929e-5 -1.46758e-5 -1 1.77286e-6 -5.45536e-7 -1 -5.18079e-6 -5.60995e-6 -1 1.88008e-5 1.02397e-5 -1 -4.79397e-6 1.23228e-5 -1 3.59407e-7 1.70228e-6 -1 0 0 -1 -1.05179e-6 -5.89147e-7 -1 -5.56379e-5 -5.6171e-5 -1 0 0 -1 -1.7824e-5 -7.50246e-5 -1 -3.40237e-5 -6.0933e-5 -1 -1.51138e-4 -3.58629e-5 -1 -1.80557e-4 -3.27952e-5 -1 4.6605e-5 -5.08087e-5 1 -2.10858e-5 -2.35208e-5 1 -1.99737e-5 -4.9613e-6 1 -1.60378e-7 -7.40705e-6 1 1.0766e-5 -5.29802e-6 1 9.13801e-6 9.43004e-6 1 7.27626e-5 -3.58069e-5 1 2.43713e-4 -1.8295e-5 1 1.55579e-5 -6.4527e-5 1 2.43084e-5 -5.69146e-5 1 -5.57338e-6 -3.17857e-5 1 -5.56404e-5 -1.55325e-5 1 -6.5219e-5 -1.44985e-5 1 -3.45327e-5 8.08596e-5 1 -9.69379e-6 2.60154e-5 1 3.04352e-5 1.95269e-5 1 -8.84254e-6 -5.67326e-6 1 -8.9497e-6 -4.88751e-6 1 -1 0 -4.23878e-6 -1 -2.28312e-7 8.82331e-7 -1 0 3.46789e-6 -1 -2.25079e-7 3.78829e-7 -1 -1.47466e-6 1.54963e-6 -1 -1.75122e-6 1.1606e-6 -1 0 0 -1 -6.47884e-7 -3.02536e-6 -1 1.29487e-6 -2.83984e-6 -1 0 0 -1 -1.77367e-6 -1.88504e-6 -1 -1.26809e-6 -2.29912e-6 -1 0 0 -1 0 0 -1 4.73192e-7 1.83701e-6 -1 -3.75922e-6 1.34919e-6 -1 -4.16262e-6 -2.04897e-6 -1 -3.08878e-6 -2.5192e-6 -1 -3.85755e-6 0 -1 -5.11259e-6 -1.66911e-6 -1 0 -3.86149e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 5.34039e-7 -1.64872e-6 -1 1.34443e-6 -1.41278e-6 -0.9999973 -5.33311e-4 -0.002268552 -0.9999629 -4.14812e-6 0.008610427 -0.9999752 -4.65145e-6 -0.007044196 -0.9999995 -5.14637e-4 -9.40292e-4 -0.999985 -3.00644e-6 -0.00547409 -0.9999991 -3.3381e-4 0.001292109 -0.99999 -3.56615e-7 0.004478693 -0.9999998 -3.28461e-4 5.54614e-4 0.9999525 -0.002231538 0.009486019 0.9993498 -1.73512e-5 -0.03605556 0.9995647 -5.75037e-6 0.02950495 0.9999904 -0.002151787 0.003799319 0.9999735 -4.00238e-6 0.007286131 0.9999983 -4.44996e-4 -0.001719295 0.9999823 4.99537e-7 -0.005961239 0.9999996 -4.37824e-4 -7.30735e-4 -1 -2.27921e-7 -2.66203e-6 -1 0 0 -1 -2.04008e-7 3.86968e-7 -1 3.02144e-7 -1.47049e-6 -1 0 -8.5593e-7 -1 -3.49859e-7 3.51027e-7 -1 -1.74052e-6 2.70111e-6 -1 -1.77692e-7 -3.22732e-7 -1 1.25665e-7 -1.36827e-6 0.01627874 -0.9357222 0.3523621 -0.01847082 -0.8555064 0.5174627 0.0127604 -0.6643393 0.7473222 -0.009306073 -0.4967265 0.8678573 0.01196372 -0.2972426 0.954727 -0.01898646 -0.09144037 0.9956296 0.0247001 0.3100588 0.9503965 -0.01783132 0.4822362 0.8758598 0.01017302 0.8079279 0.5891935 -0.01445794 0.8775625 0.4792443 0.01615732 0.9795818 0.2003954 -0.02011609 0.9883258 -0.1510214 0.008439838 0.9621863 -0.2722615 -0.001908123 0.6874479 -0.7262312 0.001905143 0.6963906 -0.7176604 -0.008977413 0.2012591 -0.9794969 0.01656013 0.1089483 -0.9939094 -0.01655721 -0.4338511 -0.9008325 0.02439773 -0.5635184 -0.8257432 -0.02284115 -0.8750556 -0.4834831 0.02007967 -0.9777321 -0.2088938 -0.009304523 -0.9984747 -0.05442357 1 -1.16373e-6 1.33625e-6 1 -3.12043e-7 -1.05498e-6 1 2.53311e-7 -1.62008e-6 1 1.11656e-6 -3.41335e-6 1 8.48161e-7 -2.99289e-6 1 -1.33751e-6 4.0888e-6 1 5.16364e-7 -1.49079e-6 1 9.69232e-6 -3.2635e-6 1 -2.21147e-5 -5.29802e-6 -0.01474726 -0.9981453 -0.0590614 0.01281505 -0.9498765 -0.3123628 -0.01381069 -0.8751662 -0.4836251 0.01938253 -0.6761518 -0.7365073 -0.01602655 -0.4818456 -0.8761096 0.01269006 -0.2311367 -0.9728385 -0.009911239 -0.07441425 -0.9971781 0.01187145 0.2726352 -0.9620443 -0.007021486 0.368277 -0.9296897 0.002374947 0.6994251 -0.714702 0.01184129 0.7285079 -0.6849351 -0.01447147 0.9411164 -0.3377729 0.0254746 0.9970291 -0.07269036 -0.003210961 0.9985983 0.05283045 -0.01378732 0.875388 0.4832243 0.0206871 0.7730894 0.6339597 -0.009902179 0.6199501 0.7845788 0.01373356 0.2836078 0.9588419 -0.01479285 0.1629008 0.9865316 0.01479011 -0.3272564 0.9448198 -0.01373773 -0.4415594 0.8971269 0.01186621 -0.7646136 0.6443797 -0.01760601 -0.8562349 0.5162865 0.02062928 -0.9817955 0.1888177 -1 1.21819e-7 -5.44433e-7 -1 -4.37196e-7 6.26005e-7 -1 0 -2.59619e-7 -1 -3.33856e-7 2.0248e-7 -1 2.09258e-7 -3.46296e-7 -1 4.2316e-7 -4.96854e-7 -1 -1.73285e-7 -1.64524e-7 -1 -3.18805e-7 8.22046e-7 -1 0 0 0.08932554 -0.119028 -0.9888647 -0.06341552 0.3608521 -0.9304645 0.02001136 0.4586634 -0.8883847 -0.01823782 0.8548934 -0.5184832 0.03015726 0.8897183 -0.4555126 -0.03169393 0.9926767 -0.1165693 0.05808871 0.9938563 0.09420877 -0.04561501 0.9435139 0.3281778 0.03401768 0.7247825 0.6881373 0.02189022 0.7342373 0.67854 -0.02186602 0.1928149 0.9809915 -0.03405952 0.2060168 0.9779556 0.04559892 -0.2152901 0.975485 -0.05809926 -0.4408634 0.8956918 0.04519319 -0.644122 0.7635865 -0.04519081 -0.8392267 0.5419006 0.0452013 -0.9347034 0.3525425 -0.04520165 -0.99694 0.06377744 0.04517912 -0.9879428 -0.1480813 -0.05354654 -0.8888461 -0.4550663 0.07991069 -0.7498723 -0.6567388 -0.1090646 -0.4053783 -0.9076196 -1 3.90802e-7 -1.47399e-7 -1 2.73282e-7 0 -1 0 0 -1 0 -3.31908e-7 -1 0 -4.07518e-7 -1 -3.97419e-7 -7.30808e-7 -1 2.34971e-7 4.32085e-7 -1 0 4.75909e-7 -1 0 0 -1 8.45562e-7 0 -1 8.71269e-7 0 -1 5.89735e-7 1.99957e-7 -1 4.14095e-7 -2.12006e-7 -1 0 2.35929e-7 -1 0 -2.85463e-7 -1 0 -2.7269e-7 -1 0 0 -1 -1.62146e-7 1.3126e-7 -1 4.64367e-7 9.36269e-7 -1 6.44785e-7 5.64703e-7 -1 3.78672e-7 4.85439e-7 -1 5.0401e-7 -1.6147e-7 -1 4.0524e-7 -1.29827e-7 0.1262717 -0.03258025 -0.9914606 -0.1233428 0.2294053 -0.9654842 0.1084087 0.5515593 -0.8270611 -0.04491871 0.6562822 -0.7531772 0.01519089 0.8974575 -0.4408391 -0.01521009 0.8880699 -0.4594567 0.04938632 0.9975736 -0.04907125 -0.05397051 0.9983224 0.02096813 0.005400836 0.875431 0.4833129 0.06594711 0.8528949 0.5179008 -0.06919342 0.6185678 0.7826788 0.1262665 0.4380871 0.8900204 -0.148561 0.1611011 0.9756926 0.1751148 -0.1898963 0.9660612 -0.142632 -0.4371036 0.8880295 0.1278221 -0.7601997 0.6369914 -0.09435409 -0.8509407 0.5167176 0.09435909 -0.9943612 0.04839551 -0.08767956 -0.9933239 -0.07496595 0.07579797 -0.8805271 -0.4678959 -0.1084572 -0.7955778 -0.5960645 0.1233057 -0.5379408 -0.8339158 -0.1262991 -0.2995592 -0.9456811 -1 0 0 -1 -1.33547e-7 0 -1 -2.03646e-7 -1.03589e-6 -1 0 0 -1 0 1.48727e-7 -1 2.09639e-7 2.63216e-7 -1 9.8708e-7 3.4364e-7 -1 0 4.05291e-7 -1 0 2.0145e-7 0.05351376 -0.09083306 -0.9944272 -0.03734487 0.2056792 -0.9779067 0.03713607 0.4310535 -0.9015619 -0.04039043 0.5903996 -0.8061 0.04726862 0.7968773 -0.6022892 -0.05057847 0.9475538 -0.3155691 0.01824033 0.9759594 -0.2171883 -0.02189671 0.9364437 0.3501341 -0.00553435 0.9301407 0.3671615 0.02632343 0.5867563 0.8093356 -0.04845404 0.5081802 0.8598867 0.04328256 0.006181299 0.9990438 -0.0588116 -0.1447587 0.9877176 0.04728811 -0.478039 0.8770648 -0.05054599 -0.7334725 0.6778372 -0.002469837 -0.7811138 0.6243839 0.0247029 -0.9815463 0.1896227 -0.02260762 -0.9924744 0.1203474 0.008858442 -0.9443682 -0.3287709 -0.003992378 -0.9496579 -0.3132633 0.02630114 -0.6532096 -0.7567203 -0.005336999 -0.6229937 -0.7822087 -0.02980715 -0.2417454 -0.9698818 -1 1.94998e-7 5.31881e-7 -1 1.02264e-6 7.18586e-7 -1 6.0728e-7 0 -1 5.98984e-7 0 -1 0 -2.27182e-7 -1 0 0 -1 0 0 -1 6.02498e-7 0 -1 4.56169e-7 -5.83829e-7 -1 -2.04166e-7 -3.821e-7 -1 2.43532e-7 4.55775e-7 -1 0 4.76657e-7 -1 0 0 -1 0 0 -1 1.93335e-7 2.93284e-7 -1 6.08285e-7 0 -1 0 -2.42047e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 4.2548e-7 -1 0 4.12235e-7 -1 1.73535e-7 6.05774e-7 0.08263427 0.2144734 -0.973228 -0.1015416 0.3620474 -0.9266127 0.08147692 0.5966007 -0.7983916 -0.1164488 0.802151 -0.5856565 0.1381572 0.9063671 -0.3992633 -0.1381512 0.9903655 -0.009513139 0.1515392 0.9609225 0.2316544 -0.123349 0.856011 0.5020263 0.1278624 0.6041361 0.7865563 -0.05393815 0.5055513 0.8611088 0.00543487 0.04738032 0.9988621 0.06589239 0.006174385 0.9978076 -0.06922441 -0.3421348 0.9370975 0.1262568 -0.5281978 0.8396823 -0.1485571 -0.7463575 0.6487537 0.1485494 -0.9152985 0.3743818 -0.1515661 -0.9862471 0.06591176 0.06514298 -0.9910576 -0.1164519 0.01172667 -0.8549763 -0.5185346 -0.1055379 -0.8136329 -0.5717197 0.1055278 -0.3874834 -0.9158169 -0.1055132 -0.2738546 -0.9559658 1 4.45391e-7 -1.93713e-6 1 4.82342e-7 0 1 4.19139e-7 2.54189e-7 1 0 3.24832e-6 1 0 2.20684e-6 1 5.86376e-7 0 1 -8.60991e-7 -1.25573e-6 1 -4.82508e-7 2.09857e-6 1 1.33858e-6 -1.50308e-5 -0.02536219 0.3353639 -0.9417473 0.04508674 0.4073868 -0.9121422 -0.04711341 0.7901968 -0.6110395 0.03639096 0.8747043 -0.483289 -0.03018444 0.992217 -0.1208069 0.01823461 0.9986283 -0.04908061 -0.01823353 0.8897505 0.4560829 0.008962273 0.8706892 0.4917522 -0.007762551 0.6200423 0.78453 0.02978038 0.5652408 0.8243883 -0.05212229 0.1626533 0.9853056 0.03124338 0.03778886 0.9987972 0.007209002 -0.377419 0.9260146 -0.07799702 -0.4901249 0.8681555 0.09738558 -0.7987002 0.5937963 -0.1127403 -0.9584578 0.2620084 0.06380289 -0.9961088 -0.06079965 -0.05056381 -0.9024515 -0.4278137 0.01823347 -0.854906 -0.5184625 -0.02381742 -0.4076899 -0.9128097 0.02733141 -0.3614379 -0.9319956 1 -8.79224e-7 1.103e-6 1 -2.62551e-6 3.29374e-6 1 -2.09602e-6 5.8859e-6 1 -9.07957e-7 5.66293e-6 1 1.04838e-6 1.55982e-6 1 -1.01043e-6 -1.50336e-6 1 4.22532e-6 -4.37143e-7 1 2.50064e-6 3.34952e-6 1 -2.25989e-6 -3.02705e-6 1 -2.33853e-6 -2.95891e-6 1 -1.87116e-6 4.45745e-7 1 0 0 1 0 0 1 1.17062e-6 4.74427e-7 1 8.17263e-6 -5.95542e-6 1 -4.29028e-6 -5.65292e-6 1 -7.04152e-6 4.5128e-6 1 -1.96227e-6 5.50177e-6 1 1.42501e-6 -3.99541e-6 1 4.90008e-6 -4.51228e-7 1 2.20052e-6 3.6519e-6 -0.0478245 0.06052303 -0.9970205 0.04781574 0.1088424 -0.9929084 -0.04374122 0.6528253 -0.7562446 0.08679497 0.706588 -0.702282 -0.1026006 0.9446665 -0.3115742 0.1515462 0.9832023 -0.10172 -0.1233632 0.9743453 0.1882362 0.08800172 0.8673912 0.4897838 -0.1059038 0.7423698 0.6615673 0.09231346 0.5880583 0.8035333 -0.08679884 0.1921526 0.977519 0.04375451 0.1173758 0.9921232 -0.04783165 -0.4658254 0.883583 -0.07426184 -0.4531341 0.8883438 0.09939354 -0.7772228 0.6213256 -0.1262868 -0.8999778 0.4172427 0.1262832 -0.9792861 0.1582757 -0.09937226 -0.9918696 -0.07949674 0.06328368 -0.8863904 -0.4585928 0.0348457 -0.8951515 -0.4443981 -0.03489041 -0.5545138 -0.8314428 0.04374992 -0.5156189 -0.8557004 1 -1.69796e-7 1.59066e-6 1 3.66744e-7 3.3891e-7 1 0 6.17006e-7 1 7.82183e-6 1.17275e-6 1 -4.57103e-6 3.36243e-6 1 -2.37579e-6 2.53097e-6 1 -8.36677e-7 -7.75842e-6 1 0 0 1 -2.0288e-6 7.99342e-6 -0.04711133 0.06333041 -0.9968801 0.05353355 0.245656 -0.9678778 -0.06210118 0.5873913 -0.8069169 0.0207647 0.6842533 -0.7289488 0.04617774 0.9122886 -0.4069365 -0.08612501 0.9798408 -0.1802622 0.06362819 0.9935209 0.09416854 -0.06362032 0.8758782 0.4783199 0.06993949 0.7326284 0.6770259 -0.080648 0.4554378 0.8866072 0.08067941 0.1745183 0.981343 -0.06340223 -0.2806217 0.9577221 0.0437982 -0.4092401 0.9113749 -0.06738239 -0.8366355 0.5435998 0.05731838 -0.9128121 0.4043371 -0.03464525 -0.9965688 -0.07516908 0.01432818 -0.9888446 -0.1482607 -0.01427435 -0.8164504 -0.577239 0.01426321 -0.79099 -0.6116628 -0.01431781 -0.4313501 -0.9020711 0.03465211 -0.3637298 -0.9308598 1 -8.1319e-6 1.27338e-6 1 4.1398e-6 -2.89608e-6 1 3.59234e-6 2.43377e-7 1 2.53504e-6 -1.34741e-6 1 -3.31494e-6 1.76193e-6 1 -3.18697e-6 -8.15637e-6 1 4.08609e-6 -5.1611e-6 1 -5.88326e-6 7.43109e-6 1 -6.33542e-6 6.30169e-6 1 -5.63863e-6 6.00711e-6 1 -8.16475e-6 3.64194e-6 1 -5.9975e-6 1.10336e-6 1 -4.05113e-6 2.1868e-6 1 0 0 1 1.24357e-6 2.68163e-6 1 1.40126e-6 2.72785e-6 1 1.28391e-7 8.63814e-6 1 -1.68699e-6 5.75746e-6 1 2.14706e-6 2.50222e-6 1 0 0 1 -3.60358e-6 5.69682e-6 0.06321519 0.2614912 -0.9631335 0.03488516 0.2458285 -0.9686854 -0.03125202 0.6759722 -0.7362642 -0.01517546 0.6843127 -0.7290309 0.044896 0.9123435 -0.4069566 -0.04489457 0.9402678 -0.3374626 0.01520323 0.9984869 0.05284506 0.07564151 0.9926861 0.09408879 -0.1134526 0.8427962 0.5261396 0.1563419 0.7253901 0.6703481 -0.1381679 0.3780773 0.9154055 0.1515438 0.1433259 0.9780042 -0.1485465 -0.1731477 0.9736293 0.1204918 -0.4510393 0.8843332 -0.1100932 -0.729939 0.6745877 0.03989613 -0.7993652 0.5995195 -0.04374492 -0.9945862 0.09425902 0.08679842 -0.9960616 0.01809042 -0.0922876 -0.9093951 -0.4055656 0.1059543 -0.8031079 -0.5863372 -0.08798009 -0.6615069 -0.7447604 0.1426418 -0.3602169 -0.9218986 -0.11149 -0.1613715 -0.980576 -3.50527e-5 3.79297e-5 1 5.72218e-6 3.84237e-7 1 3.8335e-6 5.8027e-7 1 0 0 1 -5.15484e-6 5.57793e-6 1 0 0 1 0 0 1 -8.06862e-6 -9.62953e-6 1 -2.84548e-6 2.44359e-6 1 0.9891734 0.1388739 0.04743421 0.9650471 0.2620084 -0.005983352 0.7173829 0.6961256 -0.02776688 0.621892 0.7822511 0.03651732 0.1784106 0.9837088 -0.02206045 0.1057221 0.9943541 0.009093046 -0.3528556 0.9356337 -0.009092271 -0.3926411 0.9196467 0.009094238 -0.74739 0.6643363 -0.008098602 -0.771432 0.6362928 0.004930377 -0.9547773 0.2972673 -0.005690097 -0.9659635 0.258418 0.0116102 -0.9659654 -0.2584106 -0.01160985 -0.9447448 -0.3272432 0.01921373 -0.7712742 -0.6361837 -0.02015733 -0.6442148 -0.7643029 0.02878409 -0.366874 -0.9296461 -0.03408199 -0.1594068 -0.9863802 0.04054319 0.2425037 -0.9693028 -0.04054731 0.4444226 -0.8951688 0.03407824 0.7258006 -0.6870602 -0.03408288 0.855817 -0.5156877 0.04054093 0.9861064 -0.1623052 -0.03537118 3.81728e-5 -1.16809e-5 1 2.1133e-5 -1.26072e-5 1 4.87446e-7 7.37926e-6 1 -8.73027e-6 -9.46607e-6 1 3.56704e-5 2.10453e-5 1 2.62525e-5 3.22233e-5 1 5.51499e-6 -1.65516e-5 1 -1.06909e-6 -1.48579e-5 1 -5.41786e-6 4.59002e-6 1 -1.24899e-5 5.57232e-6 1 -4.80826e-6 3.93213e-5 1 -4.24787e-5 3.81027e-5 1 -4.2009e-5 3.4375e-5 1 -8.03603e-5 1.74831e-5 1 -7.7682e-5 1.4205e-5 1 -7.08921e-5 2.44713e-5 1 3.10854e-5 -1.07304e-5 1 3.42513e-5 1.22061e-5 1 -3.59971e-5 2.85771e-6 1 -9.1227e-6 -2.75146e-5 1 -7.52918e-6 2.06245e-6 1 3.79955e-6 -1.0408e-6 1 -1.34814e-5 -4.49702e-5 1 3.98109e-5 -6.56356e-5 1 -0.9923902 -0.0338363 -0.1183934 -0.9908004 -0.1312032 0.03317147 -0.8318574 -0.5541835 0.02989965 -0.8171521 -0.5762651 -0.01345402 -0.5143241 -0.8551185 -0.06513744 -0.3760274 -0.9192655 0.1164231 -0.0360127 -0.9925455 -0.1164324 0.1164273 -0.9910613 0.06513231 0.5185687 -0.8549557 0.0117129 0.5510897 -0.8324674 -0.0574305 0.8906765 -0.4546054 0.005417287 0.9153661 -0.3872766 0.1100987 0.9919236 -0.07402038 -0.1029974 0.9635601 0.2445384 0.1084104 0.9287942 0.3678663 -0.04489547 0.7146162 0.6993513 0.0152136 0.6830256 0.7264681 0.07563209 0.2850409 0.9517748 -0.1134738 0.1640242 0.9840938 0.06823086 -0.2567257 0.9663558 0.01576048 -0.3228304 0.9423862 -0.08768641 -0.6515032 0.7559949 0.06336593 -0.7857918 0.606824 -0.1195654 -0.9011796 0.4139786 0.1284409 -9.57912e-6 4.19977e-5 -1 2.40979e-7 3.64456e-6 -1 1.28216e-6 -2.05641e-5 -1 8.01805e-6 1.8025e-5 -1 -1.67889e-5 -4.27133e-5 -1 4.78346e-5 8.76934e-5 -1 -3.98149e-6 -7.29912e-6 -1 -5.46769e-6 -8.21672e-6 -1 6.44645e-7 -1.88181e-6 -1 1.16239e-4 1.18853e-4 -1</float_array> + <technique_common> + <accessor source="#Link4-mesh-normals-array" count="7396" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Link4-mesh-vertices"> + <input semantic="POSITION" source="#Link4-mesh-positions"/> + </vertices> + <polylist material="Material_002_001-material" count="7396"> + <input semantic="VERTEX" source="#Link4-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Link4-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>0 0 1 0 2 0 2 1 1 1 3 1 4 2 5 2 6 2 6 3 5 3 7 3 8 4 9 4 10 4 10 5 9 5 11 5 14 6 15 6 13 6 13 7 15 7 16 7 13 8 16 8 12 8 14 9 13 9 17 9 17 10 13 10 18 10 18 11 19 11 1 11 1 12 0 12 18 12 20 13 17 13 18 13 20 14 18 14 0 14 21 15 20 15 0 15 21 16 0 16 2 16 22 17 23 17 24 17 24 18 23 18 25 18 7 19 5 19 27 19 27 20 5 20 26 20 22 21 24 21 27 21 22 22 27 22 26 22 23 23 28 23 29 23 23 24 29 24 25 24 25 25 29 25 30 25 31 26 32 26 33 26 33 27 32 27 871 27 36 28 37 28 35 28 35 29 37 29 38 29 35 30 38 30 34 30 36 31 35 31 42 31 42 32 35 32 43 32 40 33 41 33 43 33 40 34 43 34 39 34 44 35 42 35 43 35 44 36 43 36 41 36 11 37 9 37 45 37 11 38 45 38 46 38 47 39 48 39 49 39 49 40 48 40 50 40 51 41 47 41 8 41 9 42 8 42 45 42 45 43 8 43 47 43 47 44 49 44 45 44 48 45 52 45 53 45 48 46 53 46 50 46 50 47 53 47 54 47 55 48 56 48 24 48 24 49 56 49 27 49 59 50 60 50 61 50 61 51 60 51 62 51 61 52 62 52 63 52 63 53 62 53 57 53 63 54 57 54 58 54 42 55 44 55 64 55 64 56 44 56 1047 56 65 57 66 57 67 57 68 58 69 58 70 58 70 59 69 59 71 59 70 60 71 60 65 60 65 61 71 61 66 61 72 62 73 62 1268 62 74 63 75 63 76 63 77 64 78 64 73 64 73 65 78 65 79 65 73 66 79 66 80 66 81 67 82 67 1177 67 83 68 84 68 85 68 86 69 87 69 942 69 942 70 87 70 88 70 942 71 88 71 89 71 89 72 90 72 91 72 92 73 93 73 84 73 72 74 84 74 94 74 72 75 94 75 73 75 73 76 94 76 74 76 73 77 74 77 77 77 77 78 74 78 76 78 83 79 85 79 91 79 91 80 85 80 81 80 91 81 81 81 89 81 89 82 81 82 1177 82 89 83 1177 83 942 83 82 84 95 84 1177 84 1177 85 95 85 96 85 1177 86 96 86 1268 86 1268 87 96 87 97 87 1268 88 97 88 72 88 84 89 93 89 98 89 100 90 85 90 103 90 100 91 102 91 85 91 85 92 102 92 95 92 95 93 102 93 99 93 84 94 98 94 101 94 84 95 101 95 85 95 101 96 103 96 85 96 95 97 99 97 104 97 107 98 106 98 96 98 96 99 106 99 105 99 95 100 104 100 107 100 95 101 107 101 96 101 96 102 105 102 84 102 84 103 105 103 92 103 59 104 108 104 109 104 110 105 111 105 112 105 113 106 69 106 1266 106 1266 107 69 107 68 107 1266 108 68 108 114 108 117 109 118 109 119 109 119 110 118 110 110 110 120 111 1183 111 121 111 121 112 1183 112 122 112 123 113 124 113 114 113 114 114 124 114 125 114 114 115 125 115 1266 115 1266 116 125 116 118 116 110 117 112 117 119 117 119 118 112 118 126 118 119 119 126 119 127 119 120 120 119 120 1183 120 1183 121 119 121 127 121 1183 122 127 122 109 122 109 123 127 123 60 123 109 124 60 124 59 124 128 125 129 125 122 125 122 126 129 126 116 126 122 127 116 127 121 127 121 128 116 128 115 128 121 129 115 129 130 129 121 130 130 130 131 130 117 131 132 131 133 131 121 132 131 132 134 132 117 133 133 133 135 133 122 134 1266 134 128 134 128 135 1266 135 118 135 128 136 118 136 136 136 136 137 118 137 117 137 136 138 117 138 135 138 136 139 135 139 137 139 116 140 138 140 115 140 141 141 138 141 116 141 134 142 139 142 121 142 121 143 139 143 117 143 117 144 139 144 132 144 136 145 137 145 140 145 136 146 141 146 116 146 136 147 140 147 141 147 142 148 939 148 930 148 144 149 147 149 143 149 145 150 146 150 167 150 145 151 148 151 146 151 146 152 148 152 931 152 930 153 149 153 142 153 142 154 151 154 939 154 939 155 151 155 147 155 939 156 147 156 150 156 150 157 147 157 144 157 148 158 933 158 931 158 149 159 930 159 148 159 148 160 930 160 933 160 153 161 1267 161 154 161 939 162 150 162 152 162 155 163 939 163 152 163 155 164 154 164 1267 164 156 165 157 165 158 165 151 166 142 166 169 166 151 167 169 167 162 167 163 168 164 168 165 168 166 169 167 169 168 169 168 170 167 170 146 170 169 171 170 171 162 171 172 172 171 172 143 172 143 173 171 173 144 173 173 174 975 174 174 174 170 175 169 175 176 175 170 176 176 176 177 176 178 177 179 177 168 177 153 178 180 178 1267 178 1267 179 180 179 165 179 163 180 165 180 181 180 157 181 156 181 182 181 159 182 183 182 160 182 160 183 183 183 175 183 157 184 184 184 158 184 158 185 184 185 161 185 158 186 161 186 185 186 185 187 161 187 186 187 188 188 976 188 189 188 189 189 976 189 165 189 189 190 165 190 164 190 182 191 190 191 157 191 157 192 190 192 160 192 160 193 190 193 159 193 185 194 186 194 187 194 975 195 188 195 174 195 171 196 172 196 191 196 185 197 187 197 192 197 185 198 192 198 193 198 180 199 194 199 165 199 165 200 194 200 181 200 181 201 194 201 160 201 181 202 160 202 175 202 168 203 179 203 193 203 188 204 975 204 976 204 157 205 195 205 184 205 184 206 195 206 196 206 186 207 197 207 187 207 187 208 197 208 198 208 199 209 200 209 202 209 202 210 200 210 201 210 1010 211 202 211 201 211 193 212 192 212 168 212 168 213 192 213 166 213 177 214 176 214 197 214 197 215 176 215 198 215 178 216 168 216 1010 216 178 217 1010 217 201 217 191 218 172 218 195 218 195 219 172 219 196 219 203 220 205 220 204 220 206 221 207 221 205 221 205 222 207 222 204 222 207 223 206 223 208 223 207 224 208 224 209 224 207 225 209 225 212 225 210 226 213 226 204 226 204 227 213 227 211 227 211 228 203 228 204 228 215 229 214 229 216 229 217 230 218 230 219 230 215 231 220 231 214 231 222 232 221 232 223 232 220 233 215 233 222 233 220 234 222 234 223 234 216 235 214 235 224 235 224 236 225 236 216 236 225 237 217 237 216 237 216 238 217 238 219 238 222 239 226 239 221 239 227 240 228 240 229 240 227 241 230 241 228 241 233 242 232 242 227 242 233 243 231 243 234 243 233 244 234 244 232 244 233 245 227 245 239 245 230 246 235 246 228 246 228 247 235 247 236 247 229 248 239 248 227 248 236 249 237 249 228 249 237 250 238 250 228 250 240 251 243 251 242 251 244 252 245 252 241 252 241 253 245 253 240 253 240 254 242 254 246 254 240 255 246 255 247 255 240 256 247 256 241 256 248 257 249 257 250 257 242 258 243 258 250 258 242 259 250 259 249 259 204 260 251 260 252 260 204 261 252 261 210 261 210 262 252 262 253 262 210 263 253 263 213 263 213 264 253 264 254 264 213 265 254 265 255 265 213 266 255 266 211 266 211 267 255 267 256 267 211 268 256 268 203 268 203 269 256 269 257 269 203 270 257 270 205 270 205 271 257 271 258 271 205 272 258 272 206 272 206 273 258 273 208 273 208 274 258 274 259 274 208 275 259 275 260 275 208 276 260 276 209 276 209 277 260 277 212 277 212 278 260 278 261 278 212 279 261 279 207 279 207 280 261 280 262 280 207 281 262 281 204 281 204 282 262 282 251 282 217 283 263 283 218 283 218 284 263 284 264 284 218 285 264 285 219 285 219 286 264 286 265 286 219 287 265 287 216 287 216 288 265 288 266 288 216 289 266 289 215 289 215 290 266 290 267 290 215 291 267 291 222 291 222 292 267 292 226 292 226 293 267 293 268 293 226 294 268 294 269 294 226 295 269 295 221 295 221 296 269 296 270 296 221 297 270 297 223 297 223 298 270 298 220 298 220 299 270 299 271 299 220 300 271 300 214 300 214 301 271 301 272 301 214 302 272 302 224 302 224 303 272 303 273 303 224 304 273 304 225 304 225 305 273 305 274 305 225 306 274 306 217 306 217 307 274 307 263 307 239 308 285 308 275 308 239 309 275 309 233 309 233 310 275 310 231 310 231 311 275 311 276 311 231 312 276 312 277 312 231 313 277 313 234 313 234 314 277 314 278 314 234 315 278 315 232 315 232 316 278 316 227 316 227 317 278 317 279 317 227 318 279 318 280 318 227 319 280 319 230 319 230 320 280 320 235 320 235 321 280 321 281 321 235 322 281 322 236 322 236 323 281 323 282 323 236 324 282 324 237 324 237 325 282 325 283 325 237 326 283 326 238 326 238 327 283 327 284 327 238 328 284 328 228 328 228 329 284 329 229 329 229 330 284 330 285 330 229 331 285 331 239 331 244 332 286 332 287 332 244 333 287 333 245 333 245 334 287 334 288 334 245 335 288 335 240 335 240 336 288 336 289 336 240 337 289 337 243 337 243 338 289 338 290 338 243 339 290 339 250 339 250 340 290 340 291 340 250 341 291 341 248 341 248 342 291 342 292 342 248 343 292 343 249 343 249 344 292 344 293 344 249 345 293 345 242 345 242 346 293 346 294 346 242 347 294 347 246 347 246 348 294 348 295 348 246 349 295 349 247 349 247 350 295 350 296 350 247 351 296 351 241 351 241 352 296 352 286 352 241 353 286 353 244 353 298 354 297 354 301 354 298 355 301 355 299 355 301 356 302 356 299 356 297 357 298 357 300 357 299 358 302 358 303 358 299 359 303 359 304 359 297 360 300 360 305 360 305 361 306 361 297 361 311 362 308 362 307 362 307 363 309 363 313 363 309 364 310 364 313 364 307 365 313 365 311 365 310 366 312 366 313 366 308 367 315 367 307 367 316 368 317 368 307 368 310 369 314 369 312 369 307 370 315 370 316 370 258 371 318 371 319 371 258 372 319 372 259 372 259 373 319 373 260 373 260 374 319 374 320 374 260 375 320 375 321 375 260 376 321 376 261 376 261 377 321 377 322 377 261 378 322 378 262 378 262 379 322 379 323 379 262 380 323 380 251 380 251 381 323 381 252 381 252 382 323 382 324 382 252 383 324 383 253 383 253 384 324 384 325 384 253 385 325 385 254 385 254 386 325 386 255 386 255 387 325 387 326 387 255 388 326 388 256 388 256 389 326 389 327 389 256 390 327 390 257 390 257 391 327 391 328 391 257 392 328 392 258 392 258 393 328 393 318 393 273 394 329 394 274 394 274 395 329 395 330 395 274 396 330 396 263 396 263 397 330 397 331 397 263 398 331 398 264 398 264 399 331 399 332 399 264 400 332 400 333 400 264 401 333 401 265 401 265 402 333 402 334 402 265 403 334 403 266 403 266 404 334 404 335 404 266 405 335 405 267 405 267 406 335 406 336 406 267 407 336 407 268 407 268 408 336 408 337 408 268 409 337 409 269 409 269 410 337 410 338 410 269 411 338 411 270 411 270 412 338 412 339 412 270 413 339 413 271 413 271 414 339 414 340 414 271 415 340 415 272 415 272 416 340 416 329 416 272 417 329 417 273 417 280 418 341 418 281 418 281 419 341 419 342 419 281 420 342 420 282 420 282 421 342 421 343 421 282 422 343 422 283 422 283 423 343 423 344 423 283 424 344 424 284 424 284 425 344 425 345 425 284 426 345 426 285 426 285 427 345 427 346 427 285 428 346 428 275 428 275 429 346 429 347 429 275 430 347 430 348 430 275 431 348 431 276 431 276 432 348 432 277 432 277 433 348 433 349 433 277 434 349 434 278 434 278 435 349 435 350 435 278 436 350 436 351 436 278 437 351 437 279 437 279 438 351 438 352 438 279 439 352 439 280 439 280 440 352 440 341 440 295 441 363 441 353 441 295 442 353 442 296 442 296 443 353 443 286 443 286 444 353 444 354 444 286 445 354 445 287 445 287 446 354 446 355 446 287 447 355 447 288 447 288 448 355 448 356 448 288 449 356 449 289 449 289 450 356 450 357 450 289 451 357 451 290 451 290 452 357 452 358 452 290 453 358 453 359 453 290 454 359 454 291 454 291 455 359 455 360 455 291 456 360 456 292 456 292 457 360 457 361 457 292 458 361 458 293 458 293 459 361 459 294 459 294 460 361 460 362 460 294 461 362 461 363 461 294 462 363 462 295 462 368 463 365 463 366 463 366 464 367 464 368 464 366 465 369 465 367 465 373 466 370 466 371 466 372 467 373 467 371 467 375 468 376 468 374 468 374 469 376 469 372 469 374 470 377 470 375 470 374 471 364 471 377 471 379 472 378 472 380 472 382 473 381 473 378 473 366 474 365 474 383 474 379 475 380 475 364 475 379 476 364 476 384 476 384 477 364 477 374 477 384 478 374 478 371 478 371 479 374 479 372 479 382 480 378 480 379 480 382 481 379 481 384 481 382 482 384 482 371 482 383 483 381 483 382 483 383 484 382 484 366 484 366 485 382 485 371 485 366 486 371 486 369 486 369 487 371 487 370 487 386 488 388 488 385 488 386 489 391 489 387 489 386 490 387 490 388 490 386 491 385 491 389 491 386 492 390 492 391 492 389 493 392 493 386 493 394 494 393 494 395 494 394 495 395 495 396 495 393 496 394 496 397 496 397 497 398 497 393 497 394 498 396 498 399 498 407 499 402 499 401 499 403 500 401 500 404 500 401 501 403 501 405 501 401 502 402 502 400 502 401 503 400 503 406 503 405 504 407 504 401 504 415 505 409 505 408 505 408 506 411 506 410 506 410 507 411 507 412 507 410 508 414 508 408 508 408 509 414 509 415 509 412 510 413 510 410 510 418 511 416 511 419 511 416 512 418 512 420 512 418 513 419 513 421 513 416 514 420 514 422 514 418 515 421 515 423 515 416 516 422 516 417 516 417 517 424 517 416 517 417 518 426 518 424 518 423 519 425 519 427 519 418 520 423 520 427 520 430 521 431 521 438 521 431 522 432 522 438 522 432 523 433 523 438 523 438 524 433 524 434 524 428 525 429 525 435 525 435 526 429 526 436 526 428 527 437 527 429 527 429 528 437 528 438 528 434 529 429 529 438 529 299 530 439 530 440 530 299 531 440 531 298 531 298 532 440 532 441 532 298 533 441 533 300 533 300 534 441 534 442 534 300 535 442 535 305 535 305 536 442 536 443 536 305 537 443 537 306 537 306 538 443 538 444 538 306 539 444 539 297 539 297 540 444 540 301 540 301 541 444 541 445 541 301 542 445 542 302 542 302 543 445 543 446 543 302 544 446 544 303 544 303 545 446 545 447 545 303 546 447 546 304 546 304 547 447 547 439 547 304 548 439 548 299 548 311 549 459 549 448 549 311 550 448 550 308 550 308 551 448 551 449 551 308 552 449 552 315 552 315 553 449 553 450 553 315 554 450 554 316 554 316 555 450 555 451 555 316 556 451 556 317 556 317 557 451 557 452 557 317 558 452 558 307 558 307 559 452 559 453 559 307 560 453 560 454 560 307 561 454 561 309 561 309 562 454 562 310 562 310 563 454 563 455 563 310 564 455 564 314 564 314 565 455 565 456 565 314 566 456 566 457 566 314 567 457 567 312 567 312 568 457 568 458 568 312 569 458 569 313 569 313 570 458 570 459 570 313 571 459 571 311 571 325 572 460 572 326 572 326 573 460 573 461 573 326 574 461 574 327 574 327 575 461 575 462 575 327 576 462 576 463 576 327 577 463 577 328 577 328 578 463 578 464 578 328 579 464 579 318 579 318 580 464 580 465 580 318 581 465 581 319 581 319 582 465 582 466 582 319 583 466 583 320 583 320 584 466 584 467 584 320 585 467 585 321 585 321 586 467 586 468 586 321 587 468 587 322 587 322 588 468 588 469 588 322 589 469 589 323 589 323 590 469 590 470 590 323 591 470 591 471 591 323 592 471 592 324 592 324 593 471 593 472 593 324 594 472 594 325 594 325 595 472 595 460 595 331 596 473 596 332 596 332 597 473 597 474 597 332 598 474 598 333 598 333 599 474 599 334 599 334 600 474 600 475 600 334 601 475 601 335 601 335 602 475 602 476 602 335 603 476 603 477 603 335 604 477 604 336 604 336 605 477 605 337 605 477 606 478 606 337 606 337 607 478 607 338 607 338 608 478 608 479 608 338 609 479 609 480 609 338 610 480 610 339 610 339 611 480 611 481 611 339 612 481 612 340 612 340 613 481 613 482 613 340 614 482 614 329 614 329 615 482 615 483 615 329 616 483 616 330 616 330 617 483 617 484 617 330 618 484 618 485 618 330 619 485 619 331 619 331 620 485 620 473 620 350 621 486 621 351 621 351 622 486 622 487 622 351 623 487 623 352 623 352 624 487 624 488 624 352 625 488 625 341 625 341 626 488 626 489 626 341 627 489 627 342 627 342 628 489 628 490 628 342 629 490 629 343 629 343 630 490 630 491 630 343 631 491 631 344 631 344 632 491 632 492 632 344 633 492 633 345 633 345 634 492 634 493 634 345 635 493 635 346 635 346 636 493 636 494 636 346 637 494 637 347 637 347 638 494 638 495 638 347 639 495 639 348 639 348 640 495 640 496 640 348 641 496 641 349 641 349 642 496 642 497 642 349 643 497 643 350 643 350 644 497 644 486 644 361 645 498 645 499 645 361 646 499 646 362 646 362 647 499 647 500 647 362 648 500 648 363 648 363 649 500 649 501 649 363 650 501 650 353 650 353 651 501 651 502 651 353 652 502 652 354 652 354 653 502 653 503 653 354 654 503 654 355 654 355 655 503 655 504 655 355 656 504 656 356 656 356 657 504 657 505 657 356 658 505 658 357 658 357 659 505 659 506 659 357 660 506 660 358 660 358 661 506 661 507 661 358 662 507 662 359 662 359 663 507 663 508 663 359 664 508 664 360 664 360 665 508 665 498 665 360 666 498 666 361 666 365 667 511 667 383 667 383 668 511 668 512 668 383 669 512 669 381 669 381 670 512 670 513 670 381 671 513 671 514 671 381 672 514 672 378 672 378 673 514 673 380 673 380 674 514 674 510 674 380 675 510 675 364 675 364 676 510 676 515 676 364 677 515 677 377 677 377 678 515 678 516 678 377 679 516 679 375 679 375 680 516 680 509 680 375 681 509 681 376 681 376 682 509 682 372 682 372 683 509 683 517 683 372 684 517 684 373 684 373 685 517 685 518 685 373 686 518 686 370 686 370 687 518 687 519 687 519 688 369 688 370 688 365 689 368 689 511 689 511 690 368 690 520 690 520 691 368 691 367 691 520 692 367 692 369 692 520 693 369 693 519 693 391 694 528 694 521 694 391 695 521 695 387 695 387 696 521 696 388 696 388 697 521 697 522 697 388 698 522 698 385 698 385 699 522 699 523 699 385 700 523 700 389 700 389 701 523 701 524 701 389 702 524 702 525 702 389 703 525 703 392 703 392 704 525 704 526 704 392 705 526 705 386 705 386 706 526 706 527 706 386 707 527 707 390 707 390 708 527 708 528 708 390 709 528 709 391 709 398 710 534 710 393 710 393 711 534 711 529 711 393 712 529 712 395 712 395 713 529 713 530 713 395 714 530 714 396 714 396 715 530 715 531 715 396 716 531 716 399 716 399 717 531 717 532 717 399 718 532 718 394 718 394 719 532 719 533 719 394 720 533 720 397 720 397 721 533 721 534 721 397 722 534 722 398 722 404 723 540 723 535 723 404 724 535 724 403 724 403 725 535 725 536 725 403 726 536 726 405 726 405 727 536 727 537 727 405 728 537 728 407 728 407 729 537 729 402 729 402 730 537 730 538 730 402 731 538 731 400 731 400 732 538 732 539 732 400 733 539 733 406 733 406 734 539 734 401 734 401 735 539 735 540 735 401 736 540 736 404 736 408 737 541 737 411 737 411 738 541 738 542 738 411 739 542 739 412 739 412 740 542 740 543 740 412 741 543 741 413 741 543 742 544 742 413 742 413 743 544 743 410 743 410 744 544 744 545 744 410 745 545 745 414 745 414 746 545 746 546 746 414 747 546 747 415 747 415 748 546 748 547 748 415 749 547 749 409 749 409 750 547 750 548 750 409 751 548 751 408 751 408 752 548 752 541 752 559 753 418 753 549 753 549 754 418 754 550 754 550 755 418 755 427 755 550 756 427 756 425 756 550 757 425 757 551 757 551 758 425 758 423 758 551 759 423 759 552 759 552 760 423 760 421 760 552 761 421 761 553 761 553 762 421 762 419 762 553 763 419 763 554 763 554 764 419 764 555 764 555 765 419 765 416 765 555 766 416 766 424 766 555 767 424 767 556 767 556 768 424 768 426 768 556 769 426 769 417 769 556 770 417 770 557 770 557 771 417 771 558 771 558 772 417 772 422 772 558 773 422 773 559 773 559 774 422 774 420 774 559 775 420 775 418 775 560 776 437 776 428 776 560 777 428 777 561 777 561 778 428 778 562 778 562 779 428 779 435 779 562 780 435 780 563 780 563 781 435 781 436 781 563 782 436 782 564 782 564 783 436 783 429 783 564 784 429 784 565 784 565 785 429 785 434 785 565 786 434 786 566 786 566 787 434 787 433 787 566 788 433 788 567 788 567 789 433 789 432 789 567 790 432 790 568 790 568 791 432 791 431 791 568 792 431 792 569 792 569 793 431 793 430 793 569 794 430 794 570 794 570 795 430 795 438 795 570 796 438 796 560 796 560 797 438 797 437 797 441 798 581 798 571 798 441 799 571 799 442 799 442 800 571 800 572 800 442 801 572 801 443 801 443 802 572 802 573 802 443 803 573 803 444 803 444 804 573 804 574 804 444 805 574 805 575 805 444 806 575 806 445 806 445 807 575 807 576 807 445 808 576 808 446 808 446 809 576 809 577 809 446 810 577 810 578 810 446 811 578 811 447 811 447 812 578 812 579 812 447 813 579 813 439 813 439 814 579 814 580 814 439 815 580 815 440 815 440 816 580 816 581 816 440 817 581 817 441 817 449 818 582 818 450 818 450 819 582 819 583 819 450 820 583 820 451 820 451 821 583 821 584 821 451 822 584 822 452 822 452 823 584 823 585 823 452 824 585 824 453 824 453 825 585 825 586 825 453 826 586 826 454 826 454 827 586 827 587 827 454 828 587 828 455 828 455 829 587 829 456 829 456 830 587 830 588 830 456 831 588 831 457 831 457 832 588 832 589 832 457 833 589 833 458 833 458 834 589 834 590 834 458 835 590 835 459 835 459 836 590 836 591 836 459 837 591 837 448 837 448 838 591 838 592 838 448 839 592 839 449 839 449 840 592 840 582 840 596 841 597 841 541 841 491 842 490 842 595 842 595 843 490 843 601 843 601 844 490 844 489 844 489 845 488 845 601 845 601 846 488 846 600 846 600 847 488 847 487 847 604 848 530 848 529 848 603 849 529 849 534 849 532 850 531 850 600 850 530 851 602 851 531 851 531 852 602 852 600 852 602 853 530 853 604 853 533 854 532 854 600 854 604 855 529 855 603 855 476 856 603 856 477 856 475 857 474 857 605 857 605 858 474 858 599 858 603 859 476 859 605 859 605 860 476 860 475 860 473 861 599 861 474 861 599 862 606 862 607 862 524 863 523 863 599 863 599 864 523 864 522 864 599 865 522 865 606 865 606 866 522 866 521 866 606 867 521 867 598 867 526 868 525 868 608 868 521 869 528 869 598 869 598 870 528 870 527 870 525 871 524 871 608 871 608 872 524 872 599 872 598 873 460 873 472 873 598 874 472 874 610 874 469 875 609 875 470 875 470 876 609 876 610 876 472 877 471 877 610 877 610 878 471 878 470 878 609 879 469 879 468 879 609 880 468 880 467 880 609 881 467 881 612 881 539 882 538 882 611 882 593 883 536 883 535 883 540 884 539 884 612 884 612 885 539 885 611 885 611 886 538 886 613 886 613 887 538 887 537 887 537 888 536 888 613 888 613 889 536 889 593 889 501 890 500 890 614 890 614 891 500 891 615 891 615 892 500 892 597 892 597 893 500 893 499 893 613 894 502 894 501 894 613 895 501 895 614 895 595 896 544 896 543 896 546 897 545 897 595 897 616 898 596 898 548 898 616 899 548 899 547 899 595 900 545 900 544 900 541 901 548 901 596 901 616 902 547 902 546 902 616 903 546 903 595 903 593 904 466 904 465 904 593 905 465 905 464 905 608 906 463 906 462 906 612 907 467 907 466 907 593 908 464 908 463 908 593 909 463 909 608 909 608 910 462 910 461 910 608 911 461 911 460 911 534 912 478 912 477 912 534 913 477 913 603 913 481 914 480 914 533 914 478 915 534 915 533 915 478 916 533 916 479 916 533 917 480 917 479 917 473 918 485 918 599 918 599 919 485 919 608 919 608 920 485 920 484 920 608 921 482 921 533 921 533 922 482 922 481 922 484 923 483 923 608 923 483 924 482 924 608 924 487 925 486 925 600 925 600 926 486 926 497 926 495 927 533 927 496 927 600 928 497 928 533 928 533 929 497 929 496 929 533 930 495 930 494 930 493 931 492 931 594 931 533 932 494 932 594 932 594 933 494 933 493 933 492 934 491 934 594 934 499 935 498 935 597 935 597 936 498 936 541 936 541 937 498 937 508 937 541 938 508 938 594 938 504 939 593 939 505 939 508 940 507 940 594 940 594 941 507 941 506 941 594 942 506 942 593 942 593 943 506 943 505 943 504 944 503 944 593 944 593 945 503 945 613 945 613 946 503 946 502 946 608 947 511 947 520 947 608 948 520 948 593 948 512 949 511 949 608 949 608 950 513 950 512 950 533 951 514 951 608 951 608 952 514 952 513 952 515 953 510 953 533 953 594 954 509 954 516 954 594 955 516 955 533 955 533 956 516 956 515 956 594 957 517 957 509 957 517 958 594 958 518 958 518 959 594 959 593 959 593 960 520 960 519 960 593 961 519 961 518 961 466 962 593 962 612 962 612 963 593 963 540 963 593 964 535 964 540 964 543 965 542 965 594 965 594 966 542 966 541 966 491 967 595 967 594 967 594 968 595 968 543 968 460 969 598 969 608 969 608 970 598 970 527 970 608 971 527 971 526 971 514 972 533 972 510 972 617 973 641 973 618 973 617 974 618 974 619 974 619 975 618 975 620 975 620 976 618 976 621 976 620 977 621 977 622 977 620 978 622 978 623 978 623 979 622 979 624 979 623 980 624 980 625 980 625 981 624 981 626 981 625 982 626 982 627 982 625 983 627 983 628 983 628 984 627 984 629 984 628 985 629 985 630 985 630 986 629 986 631 986 630 987 631 987 632 987 632 988 631 988 633 988 632 989 633 989 634 989 634 990 633 990 635 990 634 991 635 991 636 991 636 992 635 992 637 992 636 993 637 993 638 993 638 994 637 994 639 994 638 995 639 995 640 995 640 996 639 996 641 996 640 997 641 997 617 997 642 998 643 998 644 998 644 999 643 999 645 999 644 1000 645 1000 646 1000 644 1001 646 1001 647 1001 647 1002 646 1002 648 1002 647 1003 648 1003 649 1003 649 1004 648 1004 650 1004 649 1005 650 1005 651 1005 651 1006 650 1006 652 1006 651 1007 652 1007 653 1007 653 1008 652 1008 654 1008 653 1009 654 1009 655 1009 655 1010 654 1010 656 1010 655 1011 656 1011 657 1011 657 1012 656 1012 658 1012 657 1013 658 1013 659 1013 659 1014 658 1014 660 1014 659 1015 660 1015 661 1015 659 1016 661 1016 662 1016 662 1017 661 1017 663 1017 662 1018 663 1018 643 1018 662 1019 643 1019 642 1019 664 1020 665 1020 666 1020 666 1021 665 1021 667 1021 666 1022 667 1022 668 1022 666 1023 668 1023 669 1023 669 1024 668 1024 670 1024 669 1025 670 1025 671 1025 671 1026 670 1026 672 1026 671 1027 672 1027 673 1027 673 1028 672 1028 674 1028 674 1029 672 1029 675 1029 674 1030 675 1030 676 1030 676 1031 675 1031 677 1031 676 1032 677 1032 678 1032 678 1033 677 1033 679 1033 678 1034 679 1034 680 1034 680 1035 679 1035 681 1035 680 1036 681 1036 682 1036 682 1037 681 1037 683 1037 682 1038 683 1038 684 1038 684 1039 683 1039 685 1039 684 1040 685 1040 664 1040 664 1041 685 1041 665 1041 686 1042 644 1042 647 1042 686 1043 647 1043 687 1043 687 1044 647 1044 688 1044 688 1045 647 1045 649 1045 688 1046 649 1046 689 1046 689 1047 649 1047 651 1047 689 1048 651 1048 653 1048 689 1049 653 1049 690 1049 690 1050 653 1050 655 1050 690 1051 655 1051 691 1051 691 1052 655 1052 692 1052 692 1053 655 1053 657 1053 692 1054 657 1054 693 1054 693 1055 657 1055 659 1055 693 1056 659 1056 694 1056 694 1057 659 1057 662 1057 694 1058 662 1058 695 1058 695 1059 662 1059 642 1059 695 1060 642 1060 696 1060 696 1061 642 1061 644 1061 696 1062 644 1062 686 1062 697 1063 640 1063 617 1063 697 1064 617 1064 698 1064 698 1065 617 1065 699 1065 699 1066 617 1066 619 1066 699 1067 619 1067 620 1067 699 1068 620 1068 700 1068 700 1069 620 1069 701 1069 701 1070 620 1070 623 1070 701 1071 623 1071 702 1071 702 1072 623 1072 625 1072 702 1073 625 1073 703 1073 703 1074 625 1074 628 1074 703 1075 628 1075 704 1075 704 1076 628 1076 630 1076 704 1077 630 1077 705 1077 705 1078 630 1078 632 1078 705 1079 632 1079 706 1079 706 1080 632 1080 634 1080 706 1081 634 1081 707 1081 707 1082 634 1082 636 1082 707 1083 636 1083 708 1083 708 1084 636 1084 638 1084 708 1085 638 1085 697 1085 697 1086 638 1086 640 1086 720 1087 680 1087 682 1087 720 1088 682 1088 709 1088 709 1089 682 1089 684 1089 709 1090 684 1090 710 1090 710 1091 684 1091 711 1091 711 1092 684 1092 664 1092 711 1093 664 1093 712 1093 712 1094 664 1094 666 1094 712 1095 666 1095 713 1095 713 1096 666 1096 714 1096 714 1097 666 1097 669 1097 714 1098 669 1098 715 1098 715 1099 669 1099 671 1099 715 1100 671 1100 716 1100 716 1101 671 1101 673 1101 716 1102 673 1102 717 1102 717 1103 673 1103 674 1103 717 1104 674 1104 718 1104 718 1105 674 1105 676 1105 718 1106 676 1106 719 1106 719 1107 676 1107 678 1107 719 1108 678 1108 720 1108 720 1109 678 1109 680 1109 721 1110 724 1110 722 1110 723 1111 725 1111 724 1111 725 1112 726 1112 724 1112 726 1113 727 1113 724 1113 724 1114 727 1114 722 1114 721 1115 722 1115 728 1115 729 1116 730 1116 724 1116 724 1117 730 1117 731 1117 724 1118 731 1118 723 1118 728 1119 732 1119 721 1119 732 1120 733 1120 721 1120 550 1121 745 1121 734 1121 550 1122 734 1122 735 1122 550 1123 735 1123 549 1123 549 1124 735 1124 559 1124 559 1125 735 1125 736 1125 559 1126 736 1126 737 1126 559 1127 737 1127 558 1127 558 1128 737 1128 738 1128 558 1129 738 1129 557 1129 557 1130 738 1130 556 1130 556 1131 738 1131 739 1131 556 1132 739 1132 740 1132 556 1133 740 1133 555 1133 555 1134 740 1134 741 1134 555 1135 741 1135 554 1135 554 1136 741 1136 553 1136 553 1137 741 1137 742 1137 553 1138 742 1138 743 1138 553 1139 743 1139 552 1139 552 1140 743 1140 744 1140 552 1141 744 1141 551 1141 551 1142 744 1142 745 1142 551 1143 745 1143 550 1143 568 1144 746 1144 747 1144 568 1145 747 1145 567 1145 567 1146 747 1146 748 1146 567 1147 748 1147 566 1147 566 1148 748 1148 749 1148 566 1149 749 1149 565 1149 565 1150 749 1150 750 1150 565 1151 750 1151 751 1151 565 1152 751 1152 564 1152 564 1153 751 1153 752 1153 564 1154 752 1154 563 1154 563 1155 752 1155 753 1155 563 1156 753 1156 754 1156 563 1157 754 1157 562 1157 562 1158 754 1158 755 1158 562 1159 755 1159 561 1159 561 1160 755 1160 756 1160 561 1161 756 1161 560 1161 560 1162 756 1162 757 1162 560 1163 757 1163 570 1163 570 1164 757 1164 758 1164 570 1165 758 1165 569 1165 569 1166 758 1166 759 1166 569 1167 759 1167 568 1167 568 1168 759 1168 746 1168 760 1169 762 1169 761 1169 761 1170 762 1170 763 1170 761 1171 763 1171 764 1171 761 1172 764 1172 765 1172 761 1173 766 1173 760 1173 761 1174 765 1174 769 1174 761 1175 769 1175 770 1175 760 1176 766 1176 768 1176 768 1177 766 1177 767 1177 768 1178 767 1178 771 1178 580 1179 783 1179 772 1179 580 1180 772 1180 581 1180 581 1181 772 1181 773 1181 581 1182 773 1182 774 1182 581 1183 774 1183 571 1183 571 1184 774 1184 775 1184 571 1185 775 1185 572 1185 572 1186 775 1186 776 1186 572 1187 776 1187 573 1187 573 1188 776 1188 777 1188 573 1189 777 1189 574 1189 574 1190 777 1190 778 1190 574 1191 778 1191 575 1191 575 1192 778 1192 779 1192 575 1193 779 1193 576 1193 576 1194 779 1194 780 1194 576 1195 780 1195 577 1195 577 1196 780 1196 781 1196 577 1197 781 1197 578 1197 578 1198 781 1198 782 1198 578 1199 782 1199 579 1199 579 1200 782 1200 783 1200 579 1201 783 1201 580 1201 591 1202 784 1202 592 1202 592 1203 784 1203 785 1203 592 1204 785 1204 582 1204 582 1205 785 1205 786 1205 582 1206 786 1206 787 1206 582 1207 787 1207 583 1207 583 1208 787 1208 788 1208 583 1209 788 1209 584 1209 584 1210 788 1210 789 1210 584 1211 789 1211 585 1211 585 1212 789 1212 790 1212 585 1213 790 1213 586 1213 586 1214 790 1214 791 1214 586 1215 791 1215 587 1215 587 1216 791 1216 792 1216 587 1217 792 1217 588 1217 588 1218 792 1218 793 1218 588 1219 793 1219 589 1219 589 1220 793 1220 590 1220 590 1221 793 1221 794 1221 590 1222 794 1222 591 1222 591 1223 794 1223 784 1223 601 1224 796 1224 595 1224 595 1225 796 1225 795 1225 595 1226 795 1226 797 1226 595 1227 797 1227 616 1227 616 1228 797 1228 799 1228 616 1229 799 1229 800 1229 616 1230 800 1230 596 1230 596 1231 800 1231 798 1231 596 1232 798 1232 597 1232 597 1233 798 1233 801 1233 597 1234 801 1234 615 1234 615 1235 801 1235 614 1235 614 1236 801 1236 802 1236 614 1237 802 1237 613 1237 802 1238 803 1238 613 1238 613 1239 803 1239 611 1239 611 1240 803 1240 804 1240 611 1241 804 1241 612 1241 612 1242 804 1242 805 1242 612 1243 805 1243 609 1243 805 1244 806 1244 609 1244 609 1245 806 1245 610 1245 610 1246 806 1246 807 1246 610 1247 807 1247 808 1247 610 1248 808 1248 598 1248 808 1249 809 1249 598 1249 598 1250 809 1250 810 1250 598 1251 810 1251 606 1251 606 1252 810 1252 607 1252 607 1253 810 1253 811 1253 607 1254 811 1254 599 1254 599 1255 811 1255 812 1255 599 1256 812 1256 605 1256 605 1257 812 1257 813 1257 605 1258 813 1258 814 1258 605 1259 814 1259 603 1259 603 1260 814 1260 815 1260 603 1261 815 1261 604 1261 604 1262 815 1262 816 1262 816 1263 817 1263 604 1263 604 1264 817 1264 602 1264 602 1265 817 1265 818 1265 602 1266 818 1266 600 1266 600 1267 818 1267 819 1267 600 1268 819 1268 601 1268 601 1269 819 1269 796 1269 639 1270 830 1270 820 1270 639 1271 820 1271 641 1271 641 1272 820 1272 821 1272 641 1273 821 1273 618 1273 618 1274 821 1274 822 1274 618 1275 822 1275 621 1275 621 1276 822 1276 823 1276 621 1277 823 1277 622 1277 622 1278 823 1278 824 1278 622 1279 824 1279 624 1279 624 1280 824 1280 626 1280 626 1281 824 1281 825 1281 626 1282 825 1282 627 1282 627 1283 825 1283 826 1283 627 1284 826 1284 629 1284 629 1285 826 1285 631 1285 631 1286 826 1286 827 1286 631 1287 827 1287 633 1287 633 1288 827 1288 828 1288 633 1289 828 1289 635 1289 635 1290 828 1290 829 1290 635 1291 829 1291 637 1291 637 1292 829 1292 830 1292 637 1293 830 1293 639 1293 645 1294 842 1294 831 1294 645 1295 831 1295 646 1295 646 1296 831 1296 648 1296 648 1297 831 1297 832 1297 648 1298 832 1298 833 1298 648 1299 833 1299 650 1299 650 1300 833 1300 834 1300 650 1301 834 1301 652 1301 652 1302 834 1302 835 1302 652 1303 835 1303 654 1303 654 1304 835 1304 836 1304 654 1305 836 1305 656 1305 656 1306 836 1306 837 1306 656 1307 837 1307 658 1307 658 1308 837 1308 838 1308 658 1309 838 1309 660 1309 660 1310 838 1310 839 1310 660 1311 839 1311 661 1311 661 1312 839 1312 840 1312 661 1313 840 1313 841 1313 661 1314 841 1314 663 1314 663 1315 841 1315 643 1315 643 1316 841 1316 842 1316 643 1317 842 1317 645 1317 681 1318 843 1318 683 1318 683 1319 843 1319 844 1319 683 1320 844 1320 845 1320 683 1321 845 1321 685 1321 685 1322 845 1322 846 1322 685 1323 846 1323 847 1323 685 1324 847 1324 665 1324 665 1325 847 1325 848 1325 665 1326 848 1326 667 1326 667 1327 848 1327 668 1327 668 1328 848 1328 849 1328 668 1329 849 1329 670 1329 670 1330 849 1330 850 1330 670 1331 850 1331 672 1331 672 1332 850 1332 851 1332 672 1333 851 1333 675 1333 675 1334 851 1334 852 1334 675 1335 852 1335 677 1335 677 1336 852 1336 853 1336 677 1337 853 1337 854 1337 677 1338 854 1338 679 1338 679 1339 854 1339 681 1339 681 1340 854 1340 843 1340 692 1341 866 1341 691 1341 691 1342 866 1342 855 1342 691 1343 855 1343 690 1343 690 1344 855 1344 856 1344 690 1345 856 1345 857 1345 690 1346 857 1346 689 1346 689 1347 857 1347 858 1347 689 1348 858 1348 688 1348 688 1349 858 1349 859 1349 688 1350 859 1350 687 1350 687 1351 859 1351 860 1351 687 1352 860 1352 686 1352 686 1353 860 1353 861 1353 686 1354 861 1354 696 1354 696 1355 861 1355 862 1355 696 1356 862 1356 695 1356 695 1357 862 1357 863 1357 695 1358 863 1358 694 1358 694 1359 863 1359 864 1359 694 1360 864 1360 693 1360 693 1361 864 1361 865 1361 693 1362 865 1362 692 1362 692 1363 865 1363 866 1363 867 1364 871 1364 872 1364 868 1365 867 1365 872 1365 868 1366 872 1366 870 1366 869 1367 868 1367 870 1367 871 1368 32 1368 873 1368 852 1369 872 1369 873 1369 873 1370 872 1370 871 1370 874 1371 877 1371 876 1371 875 1372 874 1372 876 1372 875 1373 876 1373 873 1373 32 1374 875 1374 873 1374 700 1375 878 1375 699 1375 699 1376 878 1376 879 1376 699 1377 879 1377 698 1377 698 1378 879 1378 880 1378 698 1379 880 1379 697 1379 697 1380 880 1380 881 1380 697 1381 881 1381 708 1381 708 1382 881 1382 882 1382 708 1383 882 1383 707 1383 707 1384 882 1384 883 1384 707 1385 883 1385 706 1385 706 1386 883 1386 884 1386 706 1387 884 1387 705 1387 705 1388 884 1388 885 1388 705 1389 885 1389 886 1389 705 1390 886 1390 704 1390 704 1391 886 1391 703 1391 703 1392 886 1392 887 1392 703 1393 887 1393 702 1393 702 1394 887 1394 888 1394 702 1395 888 1395 701 1395 701 1396 888 1396 889 1396 701 1397 889 1397 700 1397 700 1398 889 1398 878 1398 711 1399 890 1399 891 1399 711 1400 891 1400 710 1400 710 1401 891 1401 892 1401 710 1402 892 1402 709 1402 709 1403 892 1403 893 1403 709 1404 893 1404 720 1404 720 1405 893 1405 894 1405 720 1406 894 1406 895 1406 720 1407 895 1407 719 1407 719 1408 895 1408 896 1408 719 1409 896 1409 718 1409 718 1410 896 1410 717 1410 717 1411 896 1411 897 1411 717 1412 897 1412 716 1412 716 1413 897 1413 898 1413 716 1414 898 1414 899 1414 716 1415 899 1415 715 1415 715 1416 899 1416 900 1416 715 1417 900 1417 714 1417 714 1418 900 1418 901 1418 714 1419 901 1419 713 1419 713 1420 901 1420 902 1420 713 1421 902 1421 712 1421 712 1422 902 1422 711 1422 711 1423 902 1423 890 1423 903 1424 41 1424 904 1424 904 1425 41 1425 40 1425 905 1426 735 1426 906 1426 906 1427 735 1427 734 1427 906 1428 734 1428 907 1428 907 1429 734 1429 745 1429 907 1430 745 1430 908 1430 908 1431 745 1431 744 1431 908 1432 744 1432 909 1432 909 1433 744 1433 743 1433 909 1434 743 1434 910 1434 910 1435 743 1435 742 1435 910 1436 742 1436 911 1436 911 1437 742 1437 741 1437 911 1438 741 1438 912 1438 912 1439 741 1439 740 1439 912 1440 740 1440 913 1440 913 1441 740 1441 739 1441 913 1442 739 1442 914 1442 914 1443 739 1443 738 1443 914 1444 738 1444 915 1444 915 1445 738 1445 737 1445 915 1446 737 1446 916 1446 916 1447 737 1447 736 1447 916 1448 736 1448 905 1448 905 1449 736 1449 735 1449 917 1450 756 1450 918 1450 918 1451 756 1451 755 1451 918 1452 755 1452 919 1452 919 1453 755 1453 754 1453 919 1454 754 1454 920 1454 920 1455 754 1455 753 1455 920 1456 753 1456 752 1456 920 1457 752 1457 921 1457 921 1458 752 1458 751 1458 921 1459 751 1459 922 1459 922 1460 751 1460 750 1460 922 1461 750 1461 923 1461 923 1462 750 1462 749 1462 923 1463 749 1463 748 1463 923 1464 748 1464 924 1464 924 1465 748 1465 747 1465 924 1466 747 1466 746 1466 924 1467 746 1467 925 1467 925 1468 746 1468 759 1468 925 1469 759 1469 926 1469 926 1470 759 1470 758 1470 926 1471 758 1471 927 1471 927 1472 758 1472 917 1472 917 1473 758 1473 757 1473 917 1474 757 1474 756 1474 932 1475 930 1475 929 1475 933 1476 930 1476 932 1476 933 1477 932 1477 934 1477 931 1478 933 1478 934 1478 931 1479 934 1479 928 1479 155 1480 937 1480 939 1480 937 1481 936 1481 935 1481 939 1482 937 1482 940 1482 940 1483 937 1483 935 1483 939 1484 940 1484 938 1484 27 1485 56 1485 6 1485 27 1486 6 1486 7 1486 941 1487 876 1487 877 1487 941 1488 877 1488 942 1488 943 1489 944 1489 945 1489 945 1490 944 1490 946 1490 947 1491 782 1491 781 1491 947 1492 781 1492 948 1492 948 1493 781 1493 780 1493 947 1494 783 1494 782 1494 946 1495 774 1495 773 1495 774 1496 946 1496 944 1496 774 1497 944 1497 775 1497 778 1498 948 1498 779 1498 946 1499 773 1499 772 1499 946 1500 772 1500 783 1500 946 1501 783 1501 947 1501 948 1502 780 1502 779 1502 777 1503 776 1503 944 1503 948 1504 778 1504 777 1504 948 1505 777 1505 944 1505 776 1506 775 1506 944 1506 949 1507 950 1507 951 1507 951 1508 950 1508 952 1508 953 1509 793 1509 954 1509 954 1510 793 1510 792 1510 784 1511 794 1511 953 1511 790 1512 789 1512 950 1512 953 1513 794 1513 793 1513 952 1514 786 1514 785 1514 785 1515 784 1515 952 1515 952 1516 784 1516 953 1516 954 1517 792 1517 791 1517 950 1518 789 1518 788 1518 786 1519 952 1519 787 1519 787 1520 952 1520 950 1520 791 1521 790 1521 954 1521 954 1522 790 1522 950 1522 950 1523 788 1523 787 1523 963 1524 955 1524 956 1524 956 1525 955 1525 957 1525 959 1526 955 1526 960 1526 958 1527 957 1527 955 1527 955 1528 959 1528 958 1528 961 1529 956 1529 962 1529 961 1530 963 1530 956 1530 961 1531 962 1531 965 1531 961 1532 965 1532 966 1532 960 1533 964 1533 959 1533 967 1534 968 1534 969 1534 969 1535 968 1535 970 1535 969 1536 970 1536 971 1536 972 1537 977 1537 976 1537 972 1538 976 1538 975 1538 973 1539 972 1539 978 1539 978 1540 972 1540 975 1540 978 1541 974 1541 973 1541 980 1542 979 1542 984 1542 982 1543 981 1543 980 1543 982 1544 980 1544 984 1544 983 1545 982 1545 984 1545 813 1546 985 1546 814 1546 813 1547 986 1547 985 1547 812 1548 986 1548 813 1548 986 1549 812 1549 987 1549 812 1550 811 1550 987 1550 987 1551 811 1551 988 1551 988 1552 811 1552 810 1552 988 1553 810 1553 989 1553 989 1554 810 1554 809 1554 989 1555 809 1555 990 1555 809 1556 808 1556 990 1556 808 1557 807 1557 990 1557 990 1558 807 1558 991 1558 991 1559 807 1559 806 1559 991 1560 806 1560 992 1560 806 1561 805 1561 992 1561 992 1562 805 1562 993 1562 993 1563 805 1563 804 1563 993 1564 804 1564 994 1564 994 1565 804 1565 803 1565 994 1566 803 1566 995 1566 803 1567 802 1567 995 1567 995 1568 802 1568 996 1568 996 1569 802 1569 801 1569 996 1570 801 1570 997 1570 997 1571 801 1571 798 1571 997 1572 798 1572 998 1572 798 1573 800 1573 998 1573 998 1574 800 1574 999 1574 999 1575 800 1575 799 1575 999 1576 799 1576 797 1576 999 1577 797 1577 1000 1577 797 1578 795 1578 1000 1578 1000 1579 795 1579 1001 1579 1001 1580 795 1580 796 1580 1001 1581 796 1581 1002 1581 796 1582 819 1582 1002 1582 1002 1583 819 1583 818 1583 1002 1584 818 1584 1003 1584 818 1585 817 1585 1003 1585 1003 1586 817 1586 1004 1586 817 1587 816 1587 1004 1587 1004 1588 816 1588 1005 1588 814 1589 985 1589 815 1589 815 1590 985 1590 1005 1590 815 1591 1005 1591 816 1591 1006 1592 1009 1592 1010 1592 1010 1593 1009 1593 202 1593 1007 1594 1006 1594 1010 1594 1007 1595 1010 1595 1008 1595 1012 1596 1011 1596 1015 1596 1013 1597 1012 1597 1016 1597 1016 1598 1012 1598 1015 1598 1013 1599 1016 1599 1014 1599 1002 1600 1017 1600 1001 1600 847 1601 993 1601 994 1601 825 1602 824 1602 1018 1602 1018 1603 824 1603 1017 1603 997 1604 998 1604 833 1604 833 1605 998 1605 834 1605 834 1606 998 1606 999 1606 834 1607 999 1607 1000 1607 847 1608 992 1608 993 1608 840 1609 851 1609 841 1609 870 1610 826 1610 1018 1610 1018 1611 826 1611 825 1611 824 1612 823 1612 1017 1612 1017 1613 823 1613 1001 1613 1001 1614 823 1614 1000 1614 1002 1615 1003 1615 1017 1615 1017 1616 1003 1616 1013 1616 1013 1617 1003 1617 1004 1617 1000 1618 823 1618 822 1618 994 1619 995 1619 847 1619 847 1620 995 1620 996 1620 847 1621 996 1621 848 1621 848 1622 996 1622 997 1622 844 1623 843 1623 941 1623 872 1624 839 1624 838 1624 1004 1625 1005 1625 1012 1625 1012 1626 1005 1626 985 1626 834 1627 1000 1627 835 1627 835 1628 1000 1628 822 1628 835 1629 822 1629 821 1629 997 1630 833 1630 832 1630 838 1631 828 1631 827 1631 838 1632 827 1632 872 1632 826 1633 870 1633 872 1633 848 1634 997 1634 832 1634 848 1635 832 1635 849 1635 1176 1636 845 1636 941 1636 941 1637 845 1637 844 1637 852 1638 873 1638 853 1638 853 1639 873 1639 876 1639 872 1640 852 1640 839 1640 839 1641 852 1641 851 1641 839 1642 851 1642 840 1642 851 1643 850 1643 841 1643 821 1644 820 1644 836 1644 826 1645 872 1645 827 1645 981 1646 982 1646 988 1646 941 1647 843 1647 854 1647 941 1648 854 1648 876 1648 849 1649 832 1649 831 1649 849 1650 831 1650 842 1650 849 1651 842 1651 850 1651 850 1652 842 1652 841 1652 835 1653 821 1653 836 1653 838 1654 837 1654 828 1654 828 1655 837 1655 829 1655 829 1656 837 1656 836 1656 986 1657 987 1657 982 1657 982 1658 987 1658 988 1658 853 1659 876 1659 854 1659 836 1660 820 1660 830 1660 836 1661 830 1661 829 1661 1012 1662 1013 1662 1004 1662 989 1663 981 1663 988 1663 981 1664 989 1664 1176 1664 1176 1665 989 1665 990 1665 1176 1666 990 1666 991 1666 1176 1667 991 1667 992 1667 992 1668 847 1668 846 1668 992 1669 846 1669 1176 1669 1176 1670 846 1670 845 1670 109 1671 869 1671 870 1671 109 1672 870 1672 1018 1672 728 1673 861 1673 732 1673 732 1674 861 1674 860 1674 732 1675 860 1675 733 1675 733 1676 860 1676 859 1676 733 1677 859 1677 721 1677 721 1678 859 1678 858 1678 721 1679 858 1679 724 1679 724 1680 858 1680 857 1680 724 1681 857 1681 729 1681 729 1682 857 1682 730 1682 730 1683 857 1683 856 1683 730 1684 856 1684 855 1684 730 1685 855 1685 731 1685 731 1686 855 1686 866 1686 731 1687 866 1687 723 1687 723 1688 866 1688 865 1688 723 1689 865 1689 725 1689 725 1690 865 1690 864 1690 725 1691 864 1691 726 1691 726 1692 864 1692 727 1692 727 1693 864 1693 863 1693 727 1694 863 1694 722 1694 722 1695 863 1695 862 1695 722 1696 862 1696 728 1696 728 1697 862 1697 861 1697 8 1698 57 1698 51 1698 51 1699 57 1699 62 1699 51 1700 62 1700 47 1700 47 1701 62 1701 48 1701 48 1702 62 1702 60 1702 48 1703 60 1703 52 1703 33 1704 871 1704 867 1704 867 1705 868 1705 33 1705 33 1706 868 1706 1019 1706 869 1707 1019 1707 868 1707 877 1708 874 1708 1020 1708 874 1709 875 1709 1020 1709 1020 1710 875 1710 31 1710 31 1711 875 1711 32 1711 1021 1712 18 1712 88 1712 88 1713 18 1713 13 1713 88 1714 13 1714 12 1714 18 1715 1021 1715 1022 1715 18 1716 1022 1716 19 1716 19 1717 1022 1717 1023 1717 19 1718 1023 1718 1 1718 887 1719 1024 1719 1025 1719 887 1720 1025 1720 1026 1720 887 1721 1026 1721 888 1721 888 1722 1026 1722 1027 1722 888 1723 1027 1723 889 1723 889 1724 1027 1724 1028 1724 889 1725 1028 1725 878 1725 878 1726 1028 1726 1029 1726 878 1727 1029 1727 879 1727 879 1728 1029 1728 880 1728 880 1729 1029 1729 1030 1729 880 1730 1030 1730 881 1730 881 1731 1030 1731 1031 1731 881 1732 1031 1732 882 1732 882 1733 1031 1733 1032 1733 882 1734 1032 1734 883 1734 883 1735 1032 1735 1033 1735 883 1736 1033 1736 884 1736 884 1737 1033 1737 1034 1737 884 1738 1034 1738 885 1738 885 1739 1034 1739 1035 1739 885 1740 1035 1740 886 1740 886 1741 1035 1741 1024 1741 886 1742 1024 1742 887 1742 900 1743 1036 1743 1037 1743 900 1744 1037 1744 901 1744 901 1745 1037 1745 1038 1745 901 1746 1038 1746 902 1746 902 1747 1038 1747 1039 1747 902 1748 1039 1748 890 1748 890 1749 1039 1749 1040 1749 890 1750 1040 1750 891 1750 891 1751 1040 1751 1041 1751 891 1752 1041 1752 892 1752 892 1753 1041 1753 1042 1753 892 1754 1042 1754 893 1754 893 1755 1042 1755 894 1755 894 1756 1042 1756 1043 1756 894 1757 1043 1757 895 1757 895 1758 1043 1758 1044 1758 895 1759 1044 1759 896 1759 896 1760 1044 1760 1045 1760 896 1761 1045 1761 897 1761 897 1762 1045 1762 898 1762 898 1763 1045 1763 1046 1763 898 1764 1046 1764 899 1764 899 1765 1046 1765 1036 1765 899 1766 1036 1766 900 1766 41 1767 903 1767 44 1767 44 1768 903 1768 1047 1768 1048 1769 771 1769 1049 1769 1049 1770 771 1770 767 1770 1049 1771 767 1771 1050 1771 1050 1772 767 1772 766 1772 1050 1773 766 1773 761 1773 1050 1774 761 1774 1051 1774 1051 1775 761 1775 1052 1775 1052 1776 761 1776 770 1776 1052 1777 770 1777 1053 1777 1053 1778 770 1778 769 1778 1053 1779 769 1779 1054 1779 1054 1780 769 1780 765 1780 1054 1781 765 1781 1055 1781 1055 1782 765 1782 764 1782 1055 1783 764 1783 763 1783 1055 1784 763 1784 1056 1784 1056 1785 763 1785 762 1785 1056 1786 762 1786 1057 1786 1057 1787 762 1787 760 1787 1057 1788 760 1788 1058 1788 1058 1789 760 1789 1059 1789 1059 1790 760 1790 768 1790 1059 1791 768 1791 1048 1791 1048 1792 768 1792 771 1792 67 1793 40 1793 39 1793 67 1794 39 1794 65 1794 65 1795 39 1795 43 1795 65 1796 43 1796 70 1796 70 1797 43 1797 68 1797 68 1798 43 1798 35 1798 68 1799 35 1799 34 1799 22 1800 1060 1800 23 1800 23 1801 1060 1801 78 1801 23 1802 78 1802 28 1802 1060 1803 22 1803 26 1803 1060 1804 26 1804 1061 1804 1061 1805 26 1805 5 1805 1062 1806 1063 1806 1064 1806 1064 1807 1063 1807 1065 1807 1064 1808 1065 1808 1066 1808 1066 1809 1065 1809 1067 1809 1066 1810 1067 1810 1068 1810 1068 1811 1067 1811 1069 1811 1069 1812 1067 1812 1070 1812 1069 1813 1070 1813 1071 1813 1069 1814 1071 1814 1072 1814 1072 1815 1071 1815 1073 1815 1073 1816 1071 1816 1074 1816 1073 1817 1074 1817 1075 1817 1075 1818 1074 1818 1076 1818 1075 1819 1076 1819 1077 1819 1077 1820 1076 1820 1078 1820 1077 1821 1078 1821 1079 1821 1079 1822 1078 1822 1080 1822 1079 1823 1080 1823 1081 1823 1081 1824 1080 1824 1082 1824 1081 1825 1082 1825 1083 1825 1081 1826 1083 1826 1062 1826 1062 1827 1083 1827 1063 1827 1084 1828 1085 1828 1086 1828 1084 1829 1086 1829 1087 1829 1087 1830 1086 1830 1088 1830 1087 1831 1088 1831 1089 1831 1089 1832 1088 1832 1090 1832 1089 1833 1090 1833 1091 1833 1091 1834 1090 1834 1092 1834 1091 1835 1092 1835 1093 1835 1091 1836 1093 1836 1094 1836 1094 1837 1093 1837 1095 1837 1094 1838 1095 1838 1096 1838 1096 1839 1095 1839 1097 1839 1096 1840 1097 1840 1098 1840 1098 1841 1097 1841 1099 1841 1098 1842 1099 1842 1100 1842 1098 1843 1100 1843 1101 1843 1101 1844 1100 1844 1102 1844 1102 1845 1100 1845 1103 1845 1102 1846 1103 1846 1104 1846 1104 1847 1103 1847 1105 1847 1104 1848 1105 1848 1106 1848 1106 1849 1105 1849 1107 1849 1106 1850 1107 1850 1108 1850 1108 1851 1107 1851 1085 1851 1108 1852 1085 1852 1084 1852 1109 1853 1110 1853 1111 1853 1111 1854 1110 1854 1112 1854 1110 1855 908 1855 1112 1855 1112 1856 908 1856 909 1856 913 1857 1113 1857 912 1857 1114 1858 916 1858 905 1858 1114 1859 915 1859 916 1859 1110 1860 907 1860 908 1860 1112 1861 909 1861 910 1861 1112 1862 910 1862 911 1862 1114 1863 905 1863 1110 1863 1110 1864 905 1864 906 1864 1110 1865 906 1865 907 1865 913 1866 914 1866 1113 1866 1113 1867 914 1867 1114 1867 1114 1868 914 1868 915 1868 1112 1869 911 1869 912 1869 1112 1870 912 1870 1113 1870 1115 1871 1116 1871 1117 1871 1117 1872 1116 1872 1118 1872 1119 1873 917 1873 1116 1873 1116 1874 917 1874 918 1874 918 1875 919 1875 1116 1875 924 1876 1120 1876 923 1876 1120 1877 924 1877 925 1877 920 1878 921 1878 1118 1878 919 1879 920 1879 1116 1879 1116 1880 920 1880 1118 1880 1118 1881 921 1881 922 1881 922 1882 923 1882 1118 1882 1118 1883 923 1883 1120 1883 1120 1884 925 1884 1119 1884 1119 1885 925 1885 926 1885 1119 1886 926 1886 927 1886 1119 1887 927 1887 917 1887 1121 1888 1122 1888 1123 1888 1123 1889 1124 1889 1121 1889 1121 1890 1125 1890 1126 1890 1123 1891 1122 1891 1127 1891 1129 1892 1128 1892 1130 1892 1123 1893 1127 1893 1129 1893 1124 1894 1125 1894 1121 1894 1126 1895 1131 1895 1121 1895 1129 1896 1127 1896 1128 1896 1132 1897 1133 1897 1134 1897 1134 1898 1133 1898 1135 1898 1134 1899 1135 1899 1136 1899 1137 1900 1064 1900 1066 1900 1137 1901 1066 1901 1138 1901 1138 1902 1066 1902 1068 1902 1138 1903 1068 1903 1139 1903 1139 1904 1068 1904 1069 1904 1139 1905 1069 1905 1072 1905 1139 1906 1072 1906 1140 1906 1140 1907 1072 1907 1073 1907 1140 1908 1073 1908 1141 1908 1141 1909 1073 1909 1142 1909 1142 1910 1073 1910 1075 1910 1142 1911 1075 1911 1143 1911 1143 1912 1075 1912 1077 1912 1143 1913 1077 1913 1144 1913 1144 1914 1077 1914 1079 1914 1144 1915 1079 1915 1145 1915 1145 1916 1079 1916 1081 1916 1145 1917 1081 1917 1146 1917 1146 1918 1081 1918 1062 1918 1146 1919 1062 1919 1147 1919 1147 1920 1062 1920 1064 1920 1147 1921 1064 1921 1137 1921 1159 1922 1059 1922 1148 1922 1148 1923 1059 1923 1048 1923 1148 1924 1048 1924 1149 1924 1149 1925 1048 1925 1049 1925 1149 1926 1049 1926 1150 1926 1150 1927 1049 1927 1050 1927 1150 1928 1050 1928 1151 1928 1151 1929 1050 1929 1051 1929 1151 1930 1051 1930 1152 1930 1152 1931 1051 1931 1052 1931 1152 1932 1052 1932 1153 1932 1153 1933 1052 1933 1053 1933 1153 1934 1053 1934 1154 1934 1154 1935 1053 1935 1155 1935 1155 1936 1053 1936 1054 1936 1155 1937 1054 1937 1156 1937 1156 1938 1054 1938 1055 1938 1156 1939 1055 1939 1157 1939 1157 1940 1055 1940 1056 1940 1157 1941 1056 1941 1158 1941 1158 1942 1056 1942 1057 1942 1158 1943 1057 1943 1058 1943 1158 1944 1058 1944 1159 1944 1159 1945 1058 1945 1059 1945 1160 1946 1091 1946 1161 1946 1161 1947 1091 1947 1094 1947 1161 1948 1094 1948 1162 1948 1162 1949 1094 1949 1096 1949 1162 1950 1096 1950 1163 1950 1163 1951 1096 1951 1164 1951 1164 1952 1096 1952 1098 1952 1164 1953 1098 1953 1165 1953 1165 1954 1098 1954 1101 1954 1165 1955 1101 1955 1102 1955 1165 1956 1102 1956 1166 1956 1166 1957 1102 1957 1104 1957 1166 1958 1104 1958 1167 1958 1167 1959 1104 1959 1106 1959 1167 1960 1106 1960 1168 1960 1168 1961 1106 1961 1108 1961 1168 1962 1108 1962 1169 1962 1169 1963 1108 1963 1084 1963 1169 1964 1084 1964 1170 1964 1170 1965 1084 1965 1087 1965 1170 1966 1087 1966 1171 1966 1171 1967 1087 1967 1089 1967 1171 1968 1089 1968 1160 1968 1160 1969 1089 1969 1091 1969 929 1970 1172 1970 932 1970 932 1971 1172 1971 1173 1971 932 1972 1173 1972 934 1972 934 1973 1173 1973 928 1973 936 1974 1174 1974 935 1974 935 1975 1174 1975 940 1975 940 1976 1174 1976 1175 1976 940 1977 1175 1977 938 1977 1176 1978 941 1978 1177 1978 941 1979 942 1979 1177 1979 28 1980 78 1980 77 1980 28 1981 77 1981 1178 1981 76 1982 1179 1982 77 1982 77 1983 1179 1983 1178 1983 20 1984 21 1984 17 1984 17 1985 21 1985 1180 1985 1181 1986 90 1986 1182 1986 1182 1987 90 1987 89 1987 1182 1988 89 1988 12 1988 12 1989 89 1989 88 1989 877 1990 1020 1990 942 1990 942 1991 1020 1991 86 1991 947 1992 72 1992 946 1992 946 1993 72 1993 97 1993 946 1994 97 1994 945 1994 943 1995 945 1995 96 1995 96 1996 945 1996 97 1996 943 1997 96 1997 944 1997 944 1998 96 1998 84 1998 944 1999 84 1999 948 1999 948 2000 84 2000 947 2000 947 2001 84 2001 72 2001 953 2002 85 2002 952 2002 952 2003 85 2003 95 2003 952 2004 95 2004 951 2004 949 2005 951 2005 82 2005 82 2006 951 2006 95 2006 949 2007 82 2007 950 2007 950 2008 82 2008 81 2008 950 2009 81 2009 954 2009 85 2010 953 2010 81 2010 81 2011 953 2011 954 2011 961 2012 92 2012 963 2012 963 2013 92 2013 105 2013 963 2014 105 2014 955 2014 955 2015 105 2015 106 2015 955 2016 106 2016 960 2016 960 2017 106 2017 107 2017 960 2018 107 2018 964 2018 964 2019 107 2019 104 2019 964 2020 104 2020 959 2020 959 2021 104 2021 99 2021 959 2022 99 2022 958 2022 958 2023 99 2023 102 2023 958 2024 102 2024 957 2024 957 2025 102 2025 100 2025 957 2026 100 2026 956 2026 956 2027 100 2027 103 2027 956 2028 103 2028 962 2028 962 2029 103 2029 101 2029 962 2030 101 2030 965 2030 965 2031 101 2031 98 2031 965 2032 98 2032 966 2032 966 2033 98 2033 93 2033 966 2034 93 2034 961 2034 961 2035 93 2035 92 2035 971 2036 84 2036 969 2036 969 2037 84 2037 83 2037 74 2038 968 2038 75 2038 75 2039 968 2039 967 2039 94 2040 970 2040 74 2040 74 2041 970 2041 968 2041 84 2042 971 2042 94 2042 94 2043 971 2043 970 2043 1177 2044 979 2044 980 2044 1177 2045 980 2045 1176 2045 1176 2046 980 2046 981 2046 979 2047 977 2047 972 2047 979 2048 972 2048 984 2048 984 2049 972 2049 973 2049 984 2050 973 2050 983 2050 983 2051 973 2051 974 2051 1011 2052 985 2052 986 2052 986 2053 982 2053 983 2053 983 2054 1011 2054 986 2054 985 2055 1011 2055 1012 2055 1011 2056 1009 2056 1015 2056 1015 2057 1009 2057 1006 2057 1015 2058 1006 2058 1016 2058 1016 2059 1006 2059 1007 2059 1016 2060 1007 2060 1014 2060 1014 2061 1007 2061 1008 2061 1017 2062 1013 2062 1183 2062 1183 2063 1013 2063 1014 2063 109 2064 1018 2064 1183 2064 1183 2065 1018 2065 1017 2065 109 2066 108 2066 869 2066 869 2067 108 2067 1019 2067 88 2068 87 2068 1021 2068 1021 2069 87 2069 1184 2069 1021 2070 1184 2070 1022 2070 1184 2071 1185 2071 1022 2071 1022 2072 1185 2072 1023 2072 52 2073 60 2073 127 2073 52 2074 127 2074 1186 2074 126 2075 1187 2075 127 2075 127 2076 1187 2076 1186 2076 46 2077 45 2077 1188 2077 1188 2078 45 2078 49 2078 1189 2079 123 2079 1190 2079 1190 2080 123 2080 114 2080 1190 2081 114 2081 34 2081 34 2082 114 2082 68 2082 79 2083 78 2083 1191 2083 1191 2084 78 2084 1060 2084 1191 2085 1060 2085 1061 2085 1191 2086 1061 2086 1192 2086 1113 2087 136 2087 1112 2087 1112 2088 136 2088 116 2088 1112 2089 116 2089 1111 2089 1109 2090 1111 2090 129 2090 129 2091 1111 2091 116 2091 1109 2092 129 2092 1110 2092 1110 2093 129 2093 128 2093 1110 2094 128 2094 1114 2094 136 2095 1113 2095 128 2095 128 2096 1113 2096 1114 2096 1120 2097 119 2097 1118 2097 1118 2098 119 2098 120 2098 1118 2099 120 2099 1117 2099 1115 2100 1117 2100 121 2100 121 2101 1117 2101 120 2101 1115 2102 121 2102 1116 2102 1116 2103 121 2103 117 2103 1116 2104 117 2104 1119 2104 1119 2105 117 2105 1120 2105 1120 2106 117 2106 119 2106 140 2107 1122 2107 141 2107 141 2108 1122 2108 1121 2108 141 2109 1121 2109 138 2109 138 2110 1121 2110 1131 2110 138 2111 1131 2111 115 2111 115 2112 1131 2112 1126 2112 115 2113 1126 2113 130 2113 130 2114 1126 2114 1125 2114 130 2115 1125 2115 131 2115 131 2116 1125 2116 134 2116 134 2117 1125 2117 1124 2117 134 2118 1124 2118 139 2118 139 2119 1124 2119 1123 2119 139 2120 1123 2120 132 2120 132 2121 1123 2121 1129 2121 132 2122 1129 2122 133 2122 133 2123 1129 2123 1130 2123 133 2124 1130 2124 135 2124 135 2125 1130 2125 1128 2125 135 2126 1128 2126 137 2126 137 2127 1128 2127 1127 2127 137 2128 1127 2128 140 2128 140 2129 1127 2129 1122 2129 111 2130 110 2130 1134 2130 1134 2131 110 2131 1132 2131 1132 2132 110 2132 1133 2132 1133 2133 110 2133 118 2133 125 2134 1135 2134 118 2134 118 2135 1135 2135 1133 2135 124 2136 1136 2136 125 2136 125 2137 1136 2137 1135 2137 1193 2138 1147 2138 1194 2138 1194 2139 1147 2139 1137 2139 1194 2140 1137 2140 1195 2140 1195 2141 1137 2141 1138 2141 1195 2142 1138 2142 1196 2142 1196 2143 1138 2143 1139 2143 1196 2144 1139 2144 1197 2144 1197 2145 1139 2145 1140 2145 1197 2146 1140 2146 1198 2146 1198 2147 1140 2147 1141 2147 1198 2148 1141 2148 1199 2148 1199 2149 1141 2149 1142 2149 1199 2150 1142 2150 1200 2150 1200 2151 1142 2151 1143 2151 1200 2152 1143 2152 1201 2152 1201 2153 1143 2153 1144 2153 1201 2154 1144 2154 1202 2154 1202 2155 1144 2155 1145 2155 1202 2156 1145 2156 1203 2156 1203 2157 1145 2157 1146 2157 1203 2158 1146 2158 1193 2158 1193 2159 1146 2159 1147 2159 1215 2160 1148 2160 1204 2160 1204 2161 1148 2161 1149 2161 1204 2162 1149 2162 1205 2162 1205 2163 1149 2163 1150 2163 1205 2164 1150 2164 1151 2164 1205 2165 1151 2165 1206 2165 1206 2166 1151 2166 1152 2166 1206 2167 1152 2167 1207 2167 1207 2168 1152 2168 1153 2168 1207 2169 1153 2169 1208 2169 1208 2170 1153 2170 1154 2170 1208 2171 1154 2171 1209 2171 1209 2172 1154 2172 1155 2172 1209 2173 1155 2173 1210 2173 1210 2174 1155 2174 1156 2174 1210 2175 1156 2175 1211 2175 1211 2176 1156 2176 1157 2176 1211 2177 1157 2177 1212 2177 1212 2178 1157 2178 1158 2178 1212 2179 1158 2179 1213 2179 1213 2180 1158 2180 1159 2180 1213 2181 1159 2181 1214 2181 1214 2182 1159 2182 1215 2182 1215 2183 1159 2183 1148 2183 1227 2184 1169 2184 1216 2184 1216 2185 1169 2185 1170 2185 1216 2186 1170 2186 1217 2186 1217 2187 1170 2187 1171 2187 1217 2188 1171 2188 1218 2188 1218 2189 1171 2189 1160 2189 1218 2190 1160 2190 1219 2190 1219 2191 1160 2191 1220 2191 1220 2192 1160 2192 1161 2192 1220 2193 1161 2193 1162 2193 1220 2194 1162 2194 1221 2194 1221 2195 1162 2195 1163 2195 1221 2196 1163 2196 1164 2196 1221 2197 1164 2197 1222 2197 1222 2198 1164 2198 1165 2198 1222 2199 1165 2199 1223 2199 1223 2200 1165 2200 1224 2200 1224 2201 1165 2201 1166 2201 1224 2202 1166 2202 1225 2202 1225 2203 1166 2203 1167 2203 1225 2204 1167 2204 1226 2204 1226 2205 1167 2205 1168 2205 1226 2206 1168 2206 1227 2206 1227 2207 1168 2207 1169 2207 928 2208 1173 2208 1266 2208 1266 2209 1173 2209 113 2209 929 2210 938 2210 1172 2210 1172 2211 938 2211 1175 2211 73 2212 80 2212 936 2212 936 2213 80 2213 1174 2213 1177 2214 1268 2214 979 2214 979 2215 1268 2215 977 2215 983 2216 974 2216 1011 2216 1011 2217 974 2217 1009 2217 1014 2218 1008 2218 1183 2218 1183 2219 1008 2219 122 2219 1193 2220 1194 2220 1228 2220 1229 2221 1199 2221 1200 2221 1229 2222 1200 2222 1230 2222 1230 2223 1200 2223 1231 2223 1195 2224 1196 2224 1232 2224 1231 2225 1200 2225 1201 2225 1231 2226 1201 2226 1233 2226 1233 2227 1201 2227 1202 2227 1233 2228 1202 2228 1203 2228 1233 2229 1203 2229 1234 2229 1234 2230 1203 2230 1235 2230 1235 2231 1203 2231 1193 2231 1235 2232 1193 2232 1228 2232 1228 2233 1194 2233 1236 2233 1236 2234 1194 2234 1195 2234 1236 2235 1195 2235 1232 2235 1198 2236 1237 2236 1238 2236 1198 2237 1238 2237 1197 2237 1197 2238 1238 2238 1239 2238 1199 2239 1229 2239 1237 2239 1199 2240 1237 2240 1198 2240 1232 2241 1196 2241 1239 2241 1239 2242 1196 2242 1197 2242 1205 2243 1206 2243 1241 2243 1240 2244 1204 2244 1242 2244 1242 2245 1204 2245 1205 2245 1242 2246 1205 2246 1241 2246 1241 2247 1206 2247 1243 2247 1206 2248 1207 2248 1243 2248 1243 2249 1207 2249 1244 2249 1244 2250 1207 2250 1208 2250 1244 2251 1208 2251 1245 2251 1246 2252 1210 2252 1211 2252 1246 2253 1211 2253 1247 2253 1247 2254 1211 2254 1212 2254 1247 2255 1212 2255 1248 2255 1248 2256 1212 2256 1213 2256 1248 2257 1213 2257 1249 2257 1249 2258 1213 2258 1214 2258 1249 2259 1214 2259 1250 2259 1250 2260 1214 2260 1215 2260 1250 2261 1215 2261 1251 2261 1251 2262 1215 2262 1204 2262 1251 2263 1204 2263 1240 2263 1208 2264 1209 2264 1245 2264 1245 2265 1209 2265 1252 2265 1252 2266 1209 2266 1210 2266 1252 2267 1210 2267 1246 2267 1253 2268 1216 2268 1217 2268 1253 2269 1217 2269 1255 2269 1216 2270 1253 2270 1227 2270 1227 2271 1253 2271 1256 2271 1227 2272 1256 2272 1257 2272 1227 2273 1257 2273 1226 2273 1226 2274 1257 2274 1258 2274 1226 2275 1258 2275 1225 2275 1225 2276 1258 2276 1259 2276 1225 2277 1259 2277 1224 2277 1224 2278 1259 2278 1260 2278 1224 2279 1260 2279 1223 2279 1223 2280 1260 2280 1254 2280 1223 2281 1254 2281 1222 2281 1255 2282 1217 2282 1261 2282 1261 2283 1217 2283 1218 2283 1222 2284 1254 2284 1262 2284 1222 2285 1262 2285 1221 2285 1221 2286 1262 2286 1263 2286 1221 2287 1263 2287 1264 2287 1221 2288 1264 2288 1220 2288 1220 2289 1264 2289 1265 2289 1220 2290 1265 2290 1219 2290 1218 2291 1219 2291 1261 2291 1261 2292 1219 2292 1265 2292 146 2293 931 2293 1266 2293 1266 2294 931 2294 928 2294 938 2295 929 2295 930 2295 938 2296 930 2296 939 2296 73 2297 936 2297 937 2297 73 2298 937 2298 1267 2298 155 2299 1267 2299 937 2299 1267 2300 165 2300 73 2300 73 2301 165 2301 1268 2301 165 2302 976 2302 1268 2302 1268 2303 976 2303 977 2303 1009 2304 974 2304 978 2304 975 2305 202 2305 978 2305 978 2306 202 2306 1009 2306 199 2307 202 2307 173 2307 173 2308 202 2308 975 2308 122 2309 1008 2309 168 2309 168 2310 1008 2310 1010 2310 1266 2311 122 2311 168 2311 1266 2312 168 2312 146 2312 1229 2313 145 2313 1237 2313 1237 2314 145 2314 167 2314 1237 2315 167 2315 1238 2315 1238 2316 167 2316 166 2316 1238 2317 166 2317 1239 2317 1239 2318 166 2318 192 2318 1239 2319 192 2319 1232 2319 1232 2320 192 2320 187 2320 1232 2321 187 2321 1236 2321 1236 2322 187 2322 198 2322 1236 2323 198 2323 1228 2323 1228 2324 198 2324 176 2324 1228 2325 176 2325 1235 2325 1235 2326 176 2326 169 2326 1235 2327 169 2327 1234 2327 1234 2328 169 2328 142 2328 1234 2329 142 2329 1233 2329 1233 2330 142 2330 149 2330 1233 2331 149 2331 1231 2331 1231 2332 149 2332 148 2332 1231 2333 148 2333 1230 2333 1230 2334 148 2334 145 2334 1230 2335 145 2335 1229 2335 1252 2336 177 2336 1245 2336 1245 2337 177 2337 197 2337 1245 2338 197 2338 1244 2338 1244 2339 197 2339 186 2339 1244 2340 186 2340 1243 2340 1243 2341 186 2341 161 2341 1243 2342 161 2342 1241 2342 1241 2343 161 2343 184 2343 1241 2344 184 2344 1242 2344 1242 2345 184 2345 196 2345 1242 2346 196 2346 1240 2346 1240 2347 196 2347 172 2347 1240 2348 172 2348 1251 2348 1251 2349 172 2349 143 2349 1251 2350 143 2350 1250 2350 1250 2351 143 2351 1249 2351 1249 2352 143 2352 147 2352 1249 2353 147 2353 151 2353 1249 2354 151 2354 1248 2354 1248 2355 151 2355 1247 2355 1247 2356 151 2356 162 2356 1247 2357 162 2357 170 2357 1247 2358 170 2358 1246 2358 1246 2359 170 2359 177 2359 1246 2360 177 2360 1252 2360 1262 2361 191 2361 195 2361 1262 2362 195 2362 1263 2362 1263 2363 195 2363 1264 2363 1264 2364 195 2364 157 2364 1264 2365 157 2365 1265 2365 1265 2366 157 2366 160 2366 1265 2367 160 2367 1261 2367 1261 2368 160 2368 194 2368 1261 2369 194 2369 180 2369 1261 2370 180 2370 1255 2370 1255 2371 180 2371 1253 2371 1253 2372 180 2372 153 2372 1253 2373 153 2373 154 2373 1253 2374 154 2374 1256 2374 1256 2375 154 2375 155 2375 1256 2376 155 2376 1257 2376 1257 2377 155 2377 152 2377 1257 2378 152 2378 1258 2378 1258 2379 152 2379 150 2379 1258 2380 150 2380 1259 2380 1259 2381 150 2381 144 2381 1259 2382 144 2382 1260 2382 1260 2383 144 2383 1254 2383 1254 2384 144 2384 171 2384 1254 2385 171 2385 1262 2385 1262 2386 171 2386 191 2386 1271 2387 1272 2387 1273 2387 1273 2388 1272 2388 1274 2388 1274 2389 1272 2389 1275 2389 1274 2390 1275 2390 1276 2390 1276 2391 1275 2391 1277 2391 1276 2392 1277 2392 1278 2392 1278 2393 1277 2393 1279 2393 1269 2394 1280 2394 1270 2394 1270 2395 1280 2395 1281 2395 1281 2396 1280 2396 1282 2396 1281 2397 1282 2397 1283 2397 1283 2398 1282 2398 1284 2398 1283 2399 1284 2399 1271 2399 1271 2400 1284 2400 1272 2400 1278 2401 1279 2401 1285 2401 1278 2402 1285 2402 1286 2402 1286 2403 1285 2403 1287 2403 1287 2404 1285 2404 1288 2404 1287 2405 1288 2405 1289 2405 1289 2406 1288 2406 1269 2406 1289 2407 1269 2407 1270 2407 1271 2408 1300 2408 1290 2408 1271 2409 1290 2409 1283 2409 1283 2410 1290 2410 1291 2410 1283 2411 1291 2411 1281 2411 1281 2412 1291 2412 1292 2412 1281 2413 1292 2413 1270 2413 1270 2414 1292 2414 1293 2414 1270 2415 1293 2415 1289 2415 1289 2416 1293 2416 1294 2416 1289 2417 1294 2417 1287 2417 1287 2418 1294 2418 1295 2418 1287 2419 1295 2419 1296 2419 1287 2420 1296 2420 1286 2420 1286 2421 1296 2421 1297 2421 1286 2422 1297 2422 1278 2422 1278 2423 1297 2423 1298 2423 1278 2424 1298 2424 1276 2424 1276 2425 1298 2425 1299 2425 1276 2426 1299 2426 1274 2426 1274 2427 1299 2427 1300 2427 1274 2428 1300 2428 1273 2428 1273 2429 1300 2429 1271 2429 1301 2430 1302 2430 1303 2430 1303 2431 1302 2431 1304 2431 1320 2432 1305 2432 1306 2432 1306 2433 1305 2433 1307 2433 1306 2434 1307 2434 1308 2434 1308 2435 1307 2435 1309 2435 1309 2436 1307 2436 1310 2436 1309 2437 1310 2437 1311 2437 1311 2438 1310 2438 1312 2438 1311 2439 1312 2439 1313 2439 1301 2440 1303 2440 1314 2440 1301 2441 1314 2441 1315 2441 1301 2442 1315 2442 1316 2442 1316 2443 1315 2443 1313 2443 1316 2444 1313 2444 1312 2444 1318 2445 1317 2445 1319 2445 1318 2446 1319 2446 1320 2446 1302 2447 1321 2447 1304 2447 1304 2448 1321 2448 1322 2448 1322 2449 1321 2449 1317 2449 1322 2450 1317 2450 1318 2450 1320 2451 1319 2451 1305 2451 1306 2452 1323 2452 1320 2452 1320 2453 1323 2453 1324 2453 1320 2454 1324 2454 1318 2454 1318 2455 1324 2455 1325 2455 1318 2456 1325 2456 1322 2456 1322 2457 1325 2457 1326 2457 1322 2458 1326 2458 1304 2458 1304 2459 1326 2459 1327 2459 1304 2460 1327 2460 1328 2460 1304 2461 1328 2461 1303 2461 1303 2462 1328 2462 1329 2462 1303 2463 1329 2463 1314 2463 1314 2464 1329 2464 1330 2464 1314 2465 1330 2465 1315 2465 1315 2466 1330 2466 1331 2466 1315 2467 1331 2467 1313 2467 1313 2468 1331 2468 1332 2468 1313 2469 1332 2469 1311 2469 1311 2470 1332 2470 1333 2470 1311 2471 1333 2471 1309 2471 1309 2472 1333 2472 1334 2472 1309 2473 1334 2473 1308 2473 1308 2474 1334 2474 1306 2474 1306 2475 1334 2475 1323 2475 1336 2476 1335 2476 1337 2476 1336 2477 1337 2477 1338 2477 1338 2478 1337 2478 1339 2478 1338 2479 1339 2479 1340 2479 1340 2480 1339 2480 1341 2480 1340 2481 1341 2481 1342 2481 1342 2482 1341 2482 1343 2482 1343 2483 1341 2483 1344 2483 1343 2484 1344 2484 1345 2484 1343 2485 1345 2485 1346 2485 1346 2486 1345 2486 1347 2486 1346 2487 1347 2487 1348 2487 1348 2488 1347 2488 1349 2488 1348 2489 1349 2489 1350 2489 1350 2490 1349 2490 1351 2490 1351 2491 1349 2491 1352 2491 1351 2492 1352 2492 1353 2492 1353 2493 1352 2493 1354 2493 1353 2494 1354 2494 1355 2494 1355 2495 1354 2495 1356 2495 1355 2496 1356 2496 1357 2496 1357 2497 1356 2497 1358 2497 1358 2498 1356 2498 1335 2498 1358 2499 1335 2499 1336 2499 1336 2500 1359 2500 1360 2500 1336 2501 1360 2501 1358 2501 1358 2502 1360 2502 1361 2502 1358 2503 1361 2503 1357 2503 1357 2504 1361 2504 1362 2504 1357 2505 1362 2505 1355 2505 1355 2506 1362 2506 1353 2506 1353 2507 1362 2507 1363 2507 1353 2508 1363 2508 1351 2508 1351 2509 1363 2509 1364 2509 1351 2510 1364 2510 1350 2510 1350 2511 1364 2511 1365 2511 1350 2512 1365 2512 1348 2512 1348 2513 1365 2513 1366 2513 1348 2514 1366 2514 1346 2514 1346 2515 1366 2515 1367 2515 1346 2516 1367 2516 1343 2516 1343 2517 1367 2517 1368 2517 1343 2518 1368 2518 1342 2518 1342 2519 1368 2519 1369 2519 1342 2520 1369 2520 1340 2520 1340 2521 1369 2521 1370 2521 1340 2522 1370 2522 1338 2522 1338 2523 1370 2523 1359 2523 1338 2524 1359 2524 1336 2524 1372 2525 1371 2525 1373 2525 1391 2526 1374 2526 1375 2526 1375 2527 1374 2527 1371 2527 1375 2528 1371 2528 1372 2528 1371 2529 1376 2529 1373 2529 1373 2530 1376 2530 1377 2530 1373 2531 1377 2531 1378 2531 1380 2532 1379 2532 1381 2532 1381 2533 1379 2533 1378 2533 1381 2534 1378 2534 1377 2534 1379 2535 1380 2535 1382 2535 1379 2536 1382 2536 1383 2536 1383 2537 1382 2537 1384 2537 1383 2538 1384 2538 1385 2538 1385 2539 1384 2539 1386 2539 1385 2540 1386 2540 1387 2540 1387 2541 1386 2541 1388 2541 1387 2542 1388 2542 1389 2542 1389 2543 1388 2543 1390 2543 1390 2544 1388 2544 1391 2544 1390 2545 1391 2545 1392 2545 1392 2546 1391 2546 1375 2546 1378 2547 1404 2547 1373 2547 1373 2548 1404 2548 1393 2548 1373 2549 1393 2549 1372 2549 1372 2550 1393 2550 1394 2550 1372 2551 1394 2551 1395 2551 1372 2552 1395 2552 1375 2552 1375 2553 1395 2553 1396 2553 1375 2554 1396 2554 1392 2554 1392 2555 1396 2555 1397 2555 1392 2556 1397 2556 1390 2556 1390 2557 1397 2557 1398 2557 1390 2558 1398 2558 1389 2558 1389 2559 1398 2559 1399 2559 1389 2560 1399 2560 1387 2560 1387 2561 1399 2561 1400 2561 1387 2562 1400 2562 1385 2562 1385 2563 1400 2563 1401 2563 1385 2564 1401 2564 1383 2564 1383 2565 1401 2565 1402 2565 1383 2566 1402 2566 1379 2566 1379 2567 1402 2567 1403 2567 1379 2568 1403 2568 1404 2568 1379 2569 1404 2569 1378 2569 1405 2570 1406 2570 1407 2570 1407 2571 1406 2571 173 2571 1407 2572 173 2572 1408 2572 173 2573 174 2573 1408 2573 1408 2574 174 2574 1409 2574 1409 2575 174 2575 188 2575 1409 2576 188 2576 1410 2576 1410 2577 188 2577 189 2577 1410 2578 189 2578 164 2578 1410 2579 164 2579 1411 2579 1411 2580 164 2580 1412 2580 1412 2581 164 2581 163 2581 1412 2582 163 2582 181 2582 1412 2583 181 2583 1413 2583 1413 2584 181 2584 175 2584 1413 2585 175 2585 1414 2585 1414 2586 175 2586 183 2586 1414 2587 183 2587 1415 2587 1415 2588 183 2588 159 2588 1415 2589 159 2589 1416 2589 1416 2590 159 2590 190 2590 1416 2591 190 2591 1417 2591 1417 2592 190 2592 1418 2592 1418 2593 190 2593 182 2593 1418 2594 182 2594 1419 2594 1419 2595 182 2595 156 2595 1419 2596 156 2596 1420 2596 1420 2597 156 2597 158 2597 1420 2598 158 2598 185 2598 1420 2599 185 2599 1421 2599 1421 2600 185 2600 193 2600 1421 2601 193 2601 1422 2601 1422 2602 193 2602 179 2602 1422 2603 179 2603 1423 2603 1423 2604 179 2604 178 2604 1423 2605 178 2605 1424 2605 1424 2606 178 2606 1425 2606 1425 2607 178 2607 201 2607 1425 2608 201 2608 200 2608 1425 2609 200 2609 1426 2609 1426 2610 200 2610 199 2610 1426 2611 199 2611 1405 2611 1405 2612 199 2612 1406 2612 199 2613 173 2613 1406 2613 1299 2614 1408 2614 1300 2614 1300 2615 1408 2615 1409 2615 1408 2616 1299 2616 1407 2616 1407 2617 1299 2617 1298 2617 1423 2618 1366 2618 1422 2618 1359 2619 1370 2619 1411 2619 1412 2620 1334 2620 1411 2620 1411 2621 1334 2621 1333 2621 1365 2622 1422 2622 1366 2622 1418 2623 1395 2623 1417 2623 1394 2624 1416 2624 1417 2624 1394 2625 1417 2625 1395 2625 1418 2626 1419 2626 1397 2626 1416 2627 1394 2627 1393 2627 1416 2628 1393 2628 1415 2628 1397 2629 1396 2629 1418 2629 1418 2630 1396 2630 1395 2630 1359 2631 1332 2631 1331 2631 1414 2632 1325 2632 1324 2632 1414 2633 1324 2633 1413 2633 1413 2634 1324 2634 1323 2634 1413 2635 1323 2635 1412 2635 1412 2636 1323 2636 1334 2636 1332 2637 1359 2637 1411 2637 1332 2638 1411 2638 1333 2638 1407 2639 1298 2639 1405 2639 1419 2640 1398 2640 1397 2640 1415 2641 1393 2641 1404 2641 1415 2642 1404 2642 1414 2642 1359 2643 1331 2643 1330 2643 1327 2644 1360 2644 1328 2644 1298 2645 1297 2645 1405 2645 1405 2646 1297 2646 1426 2646 1295 2647 1424 2647 1425 2647 1295 2648 1425 2648 1296 2648 1296 2649 1425 2649 1426 2649 1296 2650 1426 2650 1297 2650 1414 2651 1404 2651 1403 2651 1402 2652 1401 2652 1360 2652 1360 2653 1327 2653 1414 2653 1414 2654 1327 2654 1326 2654 1414 2655 1326 2655 1325 2655 1423 2656 1367 2656 1366 2656 1293 2657 1292 2657 1370 2657 1370 2658 1292 2658 1411 2658 1411 2659 1292 2659 1291 2659 1411 2660 1291 2660 1290 2660 1411 2661 1290 2661 1410 2661 1410 2662 1290 2662 1300 2662 1410 2663 1300 2663 1409 2663 1365 2664 1364 2664 1422 2664 1422 2665 1364 2665 1421 2665 1403 2666 1402 2666 1414 2666 1414 2667 1402 2667 1360 2667 1361 2668 1360 2668 1400 2668 1360 2669 1401 2669 1400 2669 1424 2670 1368 2670 1423 2670 1423 2671 1368 2671 1367 2671 1364 2672 1363 2672 1421 2672 1421 2673 1363 2673 1420 2673 1420 2674 1363 2674 1362 2674 1420 2675 1362 2675 1419 2675 1419 2676 1362 2676 1398 2676 1398 2677 1362 2677 1399 2677 1399 2678 1362 2678 1361 2678 1361 2679 1400 2679 1399 2679 1359 2680 1330 2680 1329 2680 1359 2681 1329 2681 1360 2681 1360 2682 1329 2682 1328 2682 1295 2683 1294 2683 1369 2683 1369 2684 1294 2684 1370 2684 1370 2685 1294 2685 1293 2685 1295 2686 1369 2686 1424 2686 1424 2687 1369 2687 1368 2687 1377 2688 1427 2688 1381 2688 1381 2689 1427 2689 1428 2689 1381 2690 1428 2690 1380 2690 1380 2691 1428 2691 1429 2691 1380 2692 1429 2692 1382 2692 1382 2693 1429 2693 1430 2693 1382 2694 1430 2694 1384 2694 1384 2695 1430 2695 1431 2695 1384 2696 1431 2696 1432 2696 1384 2697 1432 2697 1386 2697 1386 2698 1432 2698 1388 2698 1388 2699 1432 2699 1433 2699 1388 2700 1433 2700 1434 2700 1388 2701 1434 2701 1391 2701 1391 2702 1434 2702 1435 2702 1391 2703 1435 2703 1374 2703 1374 2704 1435 2704 1436 2704 1374 2705 1436 2705 1371 2705 1371 2706 1436 2706 1437 2706 1371 2707 1437 2707 1438 2707 1371 2708 1438 2708 1376 2708 1376 2709 1438 2709 1427 2709 1376 2710 1427 2710 1377 2710 1439 2711 1440 2711 1335 2711 1335 2712 1440 2712 1337 2712 1337 2713 1440 2713 1441 2713 1337 2714 1441 2714 1339 2714 1339 2715 1441 2715 1442 2715 1339 2716 1442 2716 1341 2716 1341 2717 1442 2717 1443 2717 1341 2718 1443 2718 1344 2718 1344 2719 1443 2719 1345 2719 1345 2720 1443 2720 1444 2720 1345 2721 1444 2721 1347 2721 1347 2722 1444 2722 1445 2722 1347 2723 1445 2723 1349 2723 1349 2724 1445 2724 1446 2724 1349 2725 1446 2725 1352 2725 1352 2726 1446 2726 1354 2726 1354 2727 1446 2727 1447 2727 1354 2728 1447 2728 1356 2728 1356 2729 1447 2729 1448 2729 1356 2730 1448 2730 1439 2730 1356 2731 1439 2731 1335 2731 1305 2732 1449 2732 1307 2732 1307 2733 1449 2733 1450 2733 1307 2734 1450 2734 1451 2734 1307 2735 1451 2735 1310 2735 1310 2736 1451 2736 1452 2736 1310 2737 1452 2737 1312 2737 1312 2738 1452 2738 1453 2738 1312 2739 1453 2739 1316 2739 1316 2740 1453 2740 1454 2740 1316 2741 1454 2741 1301 2741 1301 2742 1454 2742 1455 2742 1301 2743 1455 2743 1456 2743 1301 2744 1456 2744 1302 2744 1302 2745 1456 2745 1457 2745 1302 2746 1457 2746 1321 2746 1321 2747 1457 2747 1458 2747 1321 2748 1458 2748 1317 2748 1317 2749 1458 2749 1459 2749 1317 2750 1459 2750 1319 2750 1319 2751 1459 2751 1460 2751 1319 2752 1460 2752 1305 2752 1305 2753 1460 2753 1449 2753 1284 2754 1461 2754 1462 2754 1284 2755 1462 2755 1272 2755 1272 2756 1462 2756 1275 2756 1275 2757 1462 2757 1463 2757 1275 2758 1463 2758 1277 2758 1277 2759 1463 2759 1464 2759 1277 2760 1464 2760 1279 2760 1279 2761 1464 2761 1465 2761 1279 2762 1465 2762 1466 2762 1279 2763 1466 2763 1285 2763 1285 2764 1466 2764 1467 2764 1285 2765 1467 2765 1468 2765 1285 2766 1468 2766 1288 2766 1288 2767 1468 2767 1469 2767 1288 2768 1469 2768 1269 2768 1269 2769 1469 2769 1470 2769 1269 2770 1470 2770 1280 2770 1280 2771 1470 2771 1282 2771 1282 2772 1470 2772 1471 2772 1282 2773 1471 2773 1284 2773 1284 2774 1471 2774 1461 2774 1455 2775 1472 2775 1456 2775 1456 2776 1472 2776 1473 2776 1456 2777 1473 2777 1457 2777 1457 2778 1473 2778 1474 2778 1457 2779 1474 2779 1458 2779 1458 2780 1474 2780 1475 2780 1458 2781 1475 2781 1459 2781 1459 2782 1475 2782 1476 2782 1459 2783 1476 2783 1460 2783 1460 2784 1476 2784 1449 2784 1449 2785 1476 2785 1477 2785 1449 2786 1477 2786 1450 2786 1450 2787 1477 2787 1478 2787 1450 2788 1478 2788 1451 2788 1451 2789 1478 2789 1479 2789 1451 2790 1479 2790 1452 2790 1452 2791 1479 2791 1480 2791 1452 2792 1480 2792 1481 2792 1452 2793 1481 2793 1453 2793 1453 2794 1481 2794 1482 2794 1453 2795 1482 2795 1454 2795 1454 2796 1482 2796 1455 2796 1455 2797 1482 2797 1472 2797 1446 2798 1483 2798 1484 2798 1446 2799 1484 2799 1447 2799 1447 2800 1484 2800 1485 2800 1447 2801 1485 2801 1448 2801 1448 2802 1485 2802 1486 2802 1448 2803 1486 2803 1439 2803 1439 2804 1486 2804 1487 2804 1439 2805 1487 2805 1440 2805 1440 2806 1487 2806 1488 2806 1440 2807 1488 2807 1441 2807 1441 2808 1488 2808 1489 2808 1441 2809 1489 2809 1442 2809 1442 2810 1489 2810 1490 2810 1442 2811 1490 2811 1491 2811 1442 2812 1491 2812 1443 2812 1443 2813 1491 2813 1444 2813 1444 2814 1491 2814 1492 2814 1444 2815 1492 2815 1493 2815 1444 2816 1493 2816 1445 2816 1445 2817 1493 2817 1494 2817 1445 2818 1494 2818 1446 2818 1446 2819 1494 2819 1483 2819 1433 2820 1430 2820 1429 2820 1433 2821 1429 2821 1428 2821 1427 2822 1438 2822 1433 2822 1430 2823 1433 2823 1431 2823 1431 2824 1433 2824 1432 2824 1433 2825 1428 2825 1427 2825 1438 2826 1437 2826 1433 2826 1437 2827 1436 2827 1433 2827 1436 2828 1435 2828 1433 2828 1435 2829 1434 2829 1433 2829 1467 2830 1464 2830 1463 2830 1467 2831 1461 2831 1471 2831 1467 2832 1470 2832 1469 2832 1469 2833 1468 2833 1467 2833 1464 2834 1467 2834 1465 2834 1465 2835 1467 2835 1466 2835 1463 2836 1462 2836 1467 2836 1467 2837 1462 2837 1461 2837 1471 2838 1470 2838 1467 2838 1495 2839 1496 2839 1499 2839 1496 2840 1497 2840 1498 2840 1498 2841 1499 2841 1496 2841 1500 2842 1501 2842 1495 2842 1496 2843 1502 2843 1497 2843 1501 2844 1500 2844 1504 2844 1501 2845 1496 2845 1495 2845 1497 2846 1502 2846 1503 2846 1496 2847 1505 2847 1502 2847 1502 2848 1505 2848 1506 2848 1502 2849 1506 2849 1507 2849 1502 2850 1507 2850 1503 2850 1503 2851 1507 2851 1508 2851 1503 2852 1508 2852 1497 2852 1497 2853 1508 2853 1509 2853 1497 2854 1509 2854 1498 2854 1498 2855 1509 2855 1510 2855 1498 2856 1510 2856 1499 2856 1499 2857 1510 2857 1511 2857 1499 2858 1511 2858 1495 2858 1495 2859 1511 2859 1512 2859 1495 2860 1512 2860 1500 2860 1500 2861 1512 2861 1513 2861 1500 2862 1513 2862 1504 2862 1504 2863 1513 2863 1514 2863 1504 2864 1514 2864 1501 2864 1501 2865 1514 2865 1515 2865 1501 2866 1515 2866 1516 2866 1501 2867 1516 2867 1496 2867 1496 2868 1516 2868 1505 2868 1511 2869 1517 2869 1512 2869 1512 2870 1517 2870 1518 2870 1512 2871 1518 2871 1513 2871 1513 2872 1518 2872 1519 2872 1513 2873 1519 2873 1514 2873 1514 2874 1519 2874 1515 2874 1515 2875 1519 2875 1520 2875 1515 2876 1520 2876 1516 2876 1516 2877 1520 2877 1521 2877 1516 2878 1521 2878 1505 2878 1505 2879 1521 2879 1522 2879 1505 2880 1522 2880 1506 2880 1506 2881 1522 2881 1523 2881 1506 2882 1523 2882 1507 2882 1507 2883 1523 2883 1524 2883 1507 2884 1524 2884 1508 2884 1508 2885 1524 2885 1525 2885 1508 2886 1525 2886 1509 2886 1509 2887 1525 2887 1526 2887 1509 2888 1526 2888 1510 2888 1510 2889 1526 2889 1527 2889 1510 2890 1527 2890 1511 2890 1511 2891 1527 2891 1517 2891 1527 2892 1477 2892 1517 2892 1517 2893 1477 2893 1476 2893 1517 2894 1476 2894 1518 2894 1518 2895 1476 2895 1475 2895 1518 2896 1475 2896 1519 2896 1519 2897 1475 2897 1474 2897 1519 2898 1474 2898 1520 2898 1520 2899 1474 2899 1473 2899 1520 2900 1473 2900 1521 2900 1521 2901 1473 2901 1472 2901 1521 2902 1472 2902 1522 2902 1522 2903 1472 2903 1482 2903 1522 2904 1482 2904 1523 2904 1523 2905 1482 2905 1481 2905 1523 2906 1481 2906 1524 2906 1524 2907 1481 2907 1480 2907 1524 2908 1480 2908 1525 2908 1525 2909 1480 2909 1479 2909 1525 2910 1479 2910 1526 2910 1526 2911 1479 2911 1478 2911 1526 2912 1478 2912 1527 2912 1527 2913 1478 2913 1477 2913 1528 2914 1529 2914 1535 2914 1528 2915 1532 2915 1529 2915 1529 2916 1532 2916 1530 2916 1531 2917 1530 2917 1533 2917 1531 2918 1533 2918 1534 2918 1531 2919 1529 2919 1530 2919 1535 2920 1536 2920 1537 2920 1535 2921 1537 2921 1538 2921 1528 2922 1535 2922 1538 2922 1535 2923 1539 2923 1536 2923 1529 2924 1540 2924 1535 2924 1535 2925 1540 2925 1541 2925 1535 2926 1541 2926 1539 2926 1539 2927 1541 2927 1542 2927 1539 2928 1542 2928 1536 2928 1536 2929 1542 2929 1543 2929 1536 2930 1543 2930 1544 2930 1536 2931 1544 2931 1537 2931 1537 2932 1544 2932 1545 2932 1537 2933 1545 2933 1538 2933 1538 2934 1545 2934 1546 2934 1538 2935 1546 2935 1528 2935 1528 2936 1546 2936 1547 2936 1528 2937 1547 2937 1532 2937 1532 2938 1547 2938 1548 2938 1532 2939 1548 2939 1530 2939 1530 2940 1548 2940 1549 2940 1530 2941 1549 2941 1533 2941 1533 2942 1549 2942 1534 2942 1534 2943 1549 2943 1550 2943 1534 2944 1550 2944 1531 2944 1531 2945 1550 2945 1551 2945 1531 2946 1551 2946 1529 2946 1529 2947 1551 2947 1540 2947 1548 2948 1552 2948 1553 2948 1548 2949 1553 2949 1549 2949 1549 2950 1553 2950 1554 2950 1549 2951 1554 2951 1550 2951 1550 2952 1554 2952 1555 2952 1550 2953 1555 2953 1551 2953 1551 2954 1555 2954 1556 2954 1551 2955 1556 2955 1557 2955 1551 2956 1557 2956 1540 2956 1540 2957 1557 2957 1541 2957 1541 2958 1557 2958 1558 2958 1541 2959 1558 2959 1542 2959 1542 2960 1558 2960 1559 2960 1542 2961 1559 2961 1543 2961 1543 2962 1559 2962 1560 2962 1543 2963 1560 2963 1544 2963 1544 2964 1560 2964 1561 2964 1544 2965 1561 2965 1545 2965 1545 2966 1561 2966 1562 2966 1545 2967 1562 2967 1546 2967 1546 2968 1562 2968 1563 2968 1546 2969 1563 2969 1547 2969 1547 2970 1563 2970 1548 2970 1548 2971 1563 2971 1552 2971 1487 2972 1486 2972 1563 2972 1563 2973 1486 2973 1552 2973 1552 2974 1486 2974 1485 2974 1552 2975 1485 2975 1553 2975 1553 2976 1485 2976 1484 2976 1553 2977 1484 2977 1554 2977 1554 2978 1484 2978 1483 2978 1554 2979 1483 2979 1555 2979 1555 2980 1483 2980 1494 2980 1555 2981 1494 2981 1556 2981 1556 2982 1494 2982 1493 2982 1556 2983 1493 2983 1557 2983 1557 2984 1493 2984 1492 2984 1557 2985 1492 2985 1558 2985 1558 2986 1492 2986 1491 2986 1558 2987 1491 2987 1559 2987 1559 2988 1491 2988 1490 2988 1559 2989 1490 2989 1560 2989 1560 2990 1490 2990 1489 2990 1560 2991 1489 2991 1561 2991 1561 2992 1489 2992 1488 2992 1561 2993 1488 2993 1562 2993 1562 2994 1488 2994 1487 2994 1562 2995 1487 2995 1563 2995 1564 2996 15 2996 14 2996 14 2997 17 2997 1565 2997 1577 2998 1184 2998 1565 2998 1565 2999 1184 2999 87 2999 1565 3000 87 3000 14 3000 14 3001 87 3001 1566 3001 14 3002 1566 3002 1564 3002 1567 3003 1 3003 1023 3003 1567 3004 1023 3004 1568 3004 1568 3005 1023 3005 1185 3005 61 3006 1569 3006 59 3006 59 3007 1569 3007 1570 3007 1570 3008 49 3008 59 3008 59 3009 49 3009 50 3009 59 3010 50 3010 1571 3010 1571 3011 50 3011 54 3011 1569 3012 61 3012 63 3012 1569 3013 63 3013 1572 3013 1572 3014 63 3014 58 3014 71 3015 1573 3015 1574 3015 71 3016 1574 3016 66 3016 1192 3017 1575 3017 1191 3017 1191 3018 1575 3018 1576 3018 1568 3019 1185 3019 1577 3019 1577 3020 1185 3020 1184 3020 1581 3021 1582 3021 1583 3021 1578 3022 1583 3022 1580 3022 1580 3023 1583 3023 1582 3023 1586 3024 1578 3024 1580 3024 1586 3025 1580 3025 1579 3025 1588 3026 1586 3026 1579 3026 1585 3027 1584 3027 1586 3027 1579 3028 1587 3028 1588 3028 1589 3029 1592 3029 1590 3029 1589 3030 1594 3030 1596 3030 1594 3031 1761 3031 1597 3031 1761 3032 1584 3032 1585 3032 1597 3033 1596 3033 1594 3033 1597 3034 1761 3034 1585 3034 1592 3035 1589 3035 1596 3035 1597 3036 1585 3036 1588 3036 1598 3037 1597 3037 1588 3037 1588 3038 1585 3038 1586 3038 1592 3039 1596 3039 1593 3039 1593 3040 1596 3040 1598 3040 1598 3041 1596 3041 1597 3041 1599 3042 1598 3042 1588 3042 1595 3043 1598 3043 1599 3043 1599 3044 1588 3044 1587 3044 1591 3045 1593 3045 1598 3045 1591 3046 1598 3046 1595 3046 1592 3047 1593 3047 1602 3047 1603 3048 1604 3048 1592 3048 1593 3049 1591 3049 1602 3049 1602 3050 1591 3050 1605 3050 1602 3051 1605 3051 1606 3051 1603 3052 1592 3052 1602 3052 1603 3053 1602 3053 1600 3053 1606 3054 1601 3054 1602 3054 1601 3055 1600 3055 1602 3055 1607 3056 1600 3056 1608 3056 1608 3057 1600 3057 1601 3057 1608 3058 1601 3058 1612 3058 1608 3059 1612 3059 1611 3059 1601 3060 1606 3060 1612 3060 1610 3061 1609 3061 1608 3061 1610 3062 1608 3062 1611 3062 1617 3063 1616 3063 1615 3063 1618 3064 1616 3064 1619 3064 1619 3065 1616 3065 1617 3065 1613 3066 1619 3066 1617 3066 1615 3067 1616 3067 1614 3067 1619 3068 1613 3068 1618 3068 1618 3069 1613 3069 1621 3069 1618 3070 1621 3070 1620 3070 1624 3071 1625 3071 1623 3071 1627 3072 1628 3072 1634 3072 1628 3073 1627 3073 1623 3073 1623 3074 1627 3074 1631 3074 1631 3075 1620 3075 1621 3075 1624 3076 1632 3076 1633 3076 1633 3077 1632 3077 1621 3077 1633 3078 1621 3078 1622 3078 1625 3079 1624 3079 1626 3079 1626 3080 1624 3080 1633 3080 1626 3081 1633 3081 1629 3081 1629 3082 1633 3082 1630 3082 1630 3083 1633 3083 1622 3083 1632 3084 1623 3084 1631 3084 1632 3085 1631 3085 1621 3085 1632 3086 1624 3086 1623 3086 1621 3087 1613 3087 1622 3087 1636 3088 1628 3088 1623 3088 1623 3089 1625 3089 1637 3089 1623 3090 1637 3090 1636 3090 1636 3091 1637 3091 1638 3091 1637 3092 1639 3092 1638 3092 1636 3093 1638 3093 1635 3093 1628 3094 1636 3094 1634 3094 1634 3095 1636 3095 1635 3095 1634 3096 1635 3096 1646 3096 1643 3097 1640 3097 1645 3097 1645 3098 1640 3098 1642 3098 1642 3099 1640 3099 1644 3099 1646 3100 1643 3100 1645 3100 1641 3101 1645 3101 1642 3101 1635 3102 1638 3102 1643 3102 1635 3103 1643 3103 1646 3103 1638 3104 1639 3104 1643 3104 1639 3105 1640 3105 1643 3105 1651 3106 1647 3106 1652 3106 1655 3107 2225 3107 1649 3107 1654 3108 2225 3108 1652 3108 1652 3109 2225 3109 1655 3109 1652 3110 1655 3110 1651 3110 1655 3111 1649 3111 1653 3111 1653 3112 1649 3112 1648 3112 1655 3113 1650 3113 1651 3113 1651 3114 1650 3114 1647 3114 1655 3115 1653 3115 1650 3115 1652 3116 1656 3116 1654 3116 1660 3117 1658 3117 1659 3117 1659 3118 1654 3118 1656 3118 1661 3119 1660 3119 1656 3119 1647 3120 1657 3120 1661 3120 1659 3121 1656 3121 1660 3121 1661 3122 1656 3122 1647 3122 1647 3123 1656 3123 1652 3123 1721 3124 1663 3124 1664 3124 1662 3125 1661 3125 1665 3125 1667 3126 1668 3126 1671 3126 1666 3127 1664 3127 1670 3127 1666 3128 1670 3128 1717 3128 1717 3129 1670 3129 1672 3129 1660 3130 1661 3130 1662 3130 1662 3131 1665 3131 1669 3131 1669 3132 1665 3132 1667 3132 1669 3133 1667 3133 1671 3133 1671 3134 1670 3134 1669 3134 1662 3135 1669 3135 1658 3135 1662 3136 1658 3136 1660 3136 1670 3137 1671 3137 1672 3137 1670 3138 1664 3138 1669 3138 1669 3139 1664 3139 1658 3139 1658 3140 1664 3140 1663 3140 1673 3141 1672 3141 1674 3141 1674 3142 1672 3142 1671 3142 1674 3143 1671 3143 1675 3143 1675 3144 1671 3144 1668 3144 1674 3145 1678 3145 1677 3145 1675 3146 1678 3146 1674 3146 1679 3147 1673 3147 1674 3147 1679 3148 1674 3148 1677 3148 1687 3149 1685 3149 1686 3149 1690 3150 1684 3150 1682 3150 1692 3151 1680 3151 1689 3151 1685 3152 1687 3152 1680 3152 1680 3153 1687 3153 1689 3153 1681 3154 1682 3154 1687 3154 1687 3155 1682 3155 1684 3155 1684 3156 1689 3156 1687 3156 1681 3157 1687 3157 1686 3157 1684 3158 1690 3158 1689 3158 1698 3159 1699 3159 1694 3159 1695 3160 1694 3160 1699 3160 1699 3161 1691 3161 1695 3161 1692 3162 1695 3162 1693 3162 1692 3163 1689 3163 1695 3163 1695 3164 1689 3164 1690 3164 1695 3165 1691 3165 1693 3165 1694 3166 1695 3166 1690 3166 1693 3167 1700 3167 1692 3167 1699 3168 1701 3168 1691 3168 1691 3169 1701 3169 1706 3169 1706 3170 1701 3170 1702 3170 1706 3171 1702 3171 1707 3171 1707 3172 1704 3172 1705 3172 1704 3173 1707 3173 1702 3173 1701 3174 1699 3174 1698 3174 1707 3175 1705 3175 1697 3175 1693 3176 1691 3176 1706 3176 1693 3177 1706 3177 1700 3177 1700 3178 1706 3178 1707 3178 1700 3179 1707 3179 1703 3179 1703 3180 1707 3180 1697 3180 1703 3181 1697 3181 1696 3181 1696 3182 1697 3182 1709 3182 1709 3183 1697 3183 1708 3183 1708 3184 1697 3184 1710 3184 1697 3185 1705 3185 1710 3185 1711 3186 1806 3186 1712 3186 1713 3187 1711 3187 1712 3187 1714 3188 1713 3188 1708 3188 1710 3189 1715 3189 1714 3189 1710 3190 1714 3190 1708 3190 1716 3191 1672 3191 1673 3191 1723 3192 1724 3192 1720 3192 1720 3193 1724 3193 1721 3193 1725 3194 1723 3194 1720 3194 1720 3195 1721 3195 1722 3195 1722 3196 1721 3196 1664 3196 1722 3197 1664 3197 1719 3197 1719 3198 1664 3198 1666 3198 1732 3199 1720 3199 1722 3199 1726 3200 1727 3200 1728 3200 1729 3201 1730 3201 1731 3201 1731 3202 1730 3202 1726 3202 1731 3203 1726 3203 1732 3203 1732 3204 1726 3204 1728 3204 1733 3205 1729 3205 1719 3205 1719 3206 1729 3206 1731 3206 1717 3207 1718 3207 1666 3207 1666 3208 1718 3208 1733 3208 1666 3209 1733 3209 1719 3209 1719 3210 1731 3210 1722 3210 1722 3211 1731 3211 1732 3211 1732 3212 1734 3212 1720 3212 1716 3213 1717 3213 1672 3213 1725 3214 1720 3214 1734 3214 1734 3215 1732 3215 1728 3215 1736 3216 1735 3216 1737 3216 1736 3217 1737 3217 1738 3217 1736 3218 1738 3218 1739 3218 1743 3219 1744 3219 1742 3219 1745 3220 1701 3220 1698 3220 1704 3221 1702 3221 1741 3221 1746 3222 1705 3222 1704 3222 1702 3223 1701 3223 1747 3223 1702 3224 1747 3224 1741 3224 1741 3225 1747 3225 1748 3225 1701 3226 1745 3226 1747 3226 1744 3227 1743 3227 1698 3227 1698 3228 1743 3228 1745 3228 1747 3229 1745 3229 1749 3229 1747 3230 1749 3230 1748 3230 1743 3231 1738 3231 1745 3231 1745 3232 1738 3232 1737 3232 1745 3233 1737 3233 1749 3233 1749 3234 1737 3234 1750 3234 1742 3235 1740 3235 1743 3235 1743 3236 1740 3236 1739 3236 1743 3237 1739 3237 1738 3237 1737 3238 1735 3238 1750 3238 1746 3239 1710 3239 1705 3239 1711 3240 1713 3240 1714 3240 1751 3241 1752 3241 1753 3241 1751 3242 1753 3242 1754 3242 1754 3243 1753 3243 1755 3243 1590 3244 1759 3244 1760 3244 1760 3245 1589 3245 1590 3245 1757 3246 1761 3246 1594 3246 1594 3247 1762 3247 1757 3247 1589 3248 1760 3248 1594 3248 1594 3249 1760 3249 1764 3249 1594 3250 1764 3250 1762 3250 1762 3251 1764 3251 1763 3251 1759 3252 1758 3252 1760 3252 1764 3253 1765 3253 1763 3253 1758 3254 1755 3254 1760 3254 1760 3255 1755 3255 1764 3255 1764 3256 1755 3256 1753 3256 1764 3257 1753 3257 1765 3257 1765 3258 1753 3258 1752 3258 2590 3259 1756 3259 1758 3259 1758 3260 1756 3260 1755 3260 1755 3261 1756 3261 1754 3261 1766 3262 1586 3262 1584 3262 1586 3263 1766 3263 1578 3263 1786 3264 1581 3264 1583 3264 1767 3265 1613 3265 1617 3265 1767 3266 1622 3266 1613 3266 1630 3267 1622 3267 1767 3267 1769 3268 1630 3268 1768 3268 1770 3269 1629 3269 1769 3269 1771 3270 1772 3270 1625 3270 1630 3271 1769 3271 1629 3271 1774 3272 1772 3272 1771 3272 1772 3273 1774 3273 1775 3273 1771 3274 1776 3274 1774 3274 1771 3275 1625 3275 1773 3275 1773 3276 1625 3276 1626 3276 1776 3277 1771 3277 1777 3277 1773 3278 1626 3278 1770 3278 1770 3279 1626 3279 1629 3279 1777 3280 1771 3280 1773 3280 1778 3281 1779 3281 1782 3281 1780 3282 1781 3282 1784 3282 1784 3283 1781 3283 1778 3283 1784 3284 1778 3284 1782 3284 1769 3285 1783 3285 1770 3285 1770 3286 1783 3286 1780 3286 1784 3287 1782 3287 1777 3287 1770 3288 1780 3288 1773 3288 1773 3289 1780 3289 1784 3289 1773 3290 1784 3290 1777 3290 1776 3291 1777 3291 1782 3291 1785 3292 1782 3292 1779 3292 1788 3293 1579 3293 1787 3293 1580 3294 1790 3294 1787 3294 1580 3295 1787 3295 1579 3295 1582 3296 1791 3296 1789 3296 1582 3297 1789 3297 1580 3297 1580 3298 1789 3298 1790 3298 1582 3299 1581 3299 1792 3299 1582 3300 1792 3300 1791 3300 1581 3301 1786 3301 1792 3301 1786 3302 1793 3302 1792 3302 1614 3303 1795 3303 1615 3303 1795 3304 2408 3304 1615 3304 1795 3305 1614 3305 1796 3305 1614 3306 1616 3306 1796 3306 1616 3307 1794 3307 1796 3307 1618 3308 1797 3308 1794 3308 1616 3309 1618 3309 1794 3309 1618 3310 1798 3310 1797 3310 1676 3311 1801 3311 1800 3311 1802 3312 1801 3312 1676 3312 1676 3313 1677 3313 1802 3313 1802 3314 1677 3314 1678 3314 1678 3315 1803 3315 1802 3315 1799 3316 1803 3316 1678 3316 1675 3317 1804 3317 1799 3317 1678 3318 1675 3318 1799 3318 1675 3319 1805 3319 1804 3319 1679 3320 1677 3320 1800 3320 1800 3321 1677 3321 1676 3321 1710 3322 1746 3322 1715 3322 2644 3323 1709 3323 1808 3323 1708 3324 1808 3324 1709 3324 1708 3325 1809 3325 1807 3325 1708 3326 1807 3326 1808 3326 1713 3327 1809 3327 1708 3327 1712 3328 1810 3328 1713 3328 1713 3329 1810 3329 1809 3329 1712 3330 1806 3330 1810 3330 1806 3331 1811 3331 1810 3331 1584 3332 1630 3332 1767 3332 1584 3333 1767 3333 1766 3333 1617 3334 1583 3334 1578 3334 1617 3335 1578 3335 1767 3335 1767 3336 1578 3336 1766 3336 1615 3337 1786 3337 1583 3337 1615 3338 1583 3338 1617 3338 33 3339 1779 3339 1778 3339 33 3340 1778 3340 31 3340 1630 3341 1584 3341 1768 3341 1768 3342 1584 3342 1761 3342 1768 3343 1761 3343 1769 3343 1769 3344 1761 3344 1757 3344 1769 3345 1757 3345 1783 3345 1783 3346 1757 3346 1762 3346 1783 3347 1762 3347 1780 3347 1780 3348 1762 3348 1763 3348 1780 3349 1763 3349 1765 3349 1780 3350 1765 3350 1781 3350 1781 3351 1765 3351 1778 3351 1778 3352 1765 3352 1752 3352 1778 3353 1752 3353 31 3353 1175 3354 1727 3354 1726 3354 1800 3355 1806 3355 1711 3355 1711 3356 1679 3356 1800 3356 1711 3357 1714 3357 1679 3357 1679 3358 1714 3358 1673 3358 1673 3359 1714 3359 1715 3359 1746 3360 1716 3360 1673 3360 1673 3361 1715 3361 1746 3361 1175 3362 1726 3362 1172 3362 1735 3363 1172 3363 1750 3363 1750 3364 1172 3364 1726 3364 1750 3365 1726 3365 1730 3365 1750 3366 1730 3366 1749 3366 1749 3367 1730 3367 1748 3367 1748 3368 1730 3368 1729 3368 1748 3369 1729 3369 1733 3369 1748 3370 1733 3370 1741 3370 1741 3371 1733 3371 1718 3371 1741 3372 1718 3372 1704 3372 1704 3373 1718 3373 1717 3373 1704 3374 1717 3374 1746 3374 1746 3375 1717 3375 1716 3375 1814 3376 1813 3376 1816 3376 2306 3377 1814 3377 1816 3377 1817 3378 1812 3378 1816 3378 1822 3379 1815 3379 1821 3379 1821 3380 1819 3380 1820 3380 1821 3381 1820 3381 1822 3381 1822 3382 1820 3382 1823 3382 1822 3383 1823 3383 1813 3383 1815 3384 1822 3384 1813 3384 1816 3385 1823 3385 1817 3385 1817 3386 1823 3386 1820 3386 1823 3387 1816 3387 1813 3387 1819 3388 1821 3388 1818 3388 1813 3389 1814 3389 1815 3389 1820 3390 1819 3390 1818 3390 1815 3391 1849 3391 1824 3391 1824 3392 1821 3392 1815 3392 1825 3393 1821 3393 1824 3393 1821 3394 1825 3394 1818 3394 1818 3395 1825 3395 1847 3395 1826 3396 1833 3396 1827 3396 1828 3397 1827 3397 1834 3397 1828 3398 1834 3398 1829 3398 1829 3399 1834 3399 1835 3399 1829 3400 1835 3400 1836 3400 1829 3401 1836 3401 1830 3401 1831 3402 1830 3402 1837 3402 1831 3403 1837 3403 1832 3403 1818 3404 1832 3404 1820 3404 1827 3405 1833 3405 1834 3405 1830 3406 1836 3406 1838 3406 1830 3407 1838 3407 1837 3407 1837 3408 1838 3408 1839 3408 1837 3409 1839 3409 1832 3409 1832 3410 1839 3410 1820 3410 1834 3411 1840 3411 1835 3411 1836 3412 1835 3412 1841 3412 1836 3413 1841 3413 1838 3413 1833 3414 1842 3414 1834 3414 1834 3415 1842 3415 1840 3415 1835 3416 1840 3416 1841 3416 1838 3417 1841 3417 1843 3417 1838 3418 1843 3418 1839 3418 1839 3419 1843 3419 1820 3419 1820 3420 1843 3420 1817 3420 1841 3421 1840 3421 1844 3421 1842 3422 1845 3422 1840 3422 1840 3423 1845 3423 1844 3423 1841 3424 1844 3424 1846 3424 1841 3425 1846 3425 1843 3425 1843 3426 1846 3426 1817 3426 1817 3427 1846 3427 1812 3427 1848 3428 1863 3428 1825 3428 1825 3429 1863 3429 1847 3429 1824 3430 1849 3430 1848 3430 1825 3431 1824 3431 1848 3431 1885 3432 1845 3432 1842 3432 1885 3433 1842 3433 1850 3433 1850 3434 1842 3434 1833 3434 1850 3435 1833 3435 1851 3435 1851 3436 1833 3436 1826 3436 1851 3437 1826 3437 1852 3437 1856 3438 1855 3438 1857 3438 1854 3439 1853 3439 1858 3439 1860 3440 1858 3440 1861 3440 1862 3441 1854 3441 1860 3441 1862 3442 1860 3442 1861 3442 1862 3443 1861 3443 1863 3443 1857 3444 1862 3444 1863 3444 1855 3445 1862 3445 1857 3445 1857 3446 1863 3446 1848 3446 1857 3447 1848 3447 1859 3447 1859 3448 1848 3448 1849 3448 1861 3449 1847 3449 1863 3449 1858 3450 1860 3450 1854 3450 1856 3451 1857 3451 1859 3451 1864 3452 1870 3452 1865 3452 1865 3453 1870 3453 1871 3453 1865 3454 1871 3454 1872 3454 1865 3455 1872 3455 1866 3455 1866 3456 1872 3456 1867 3456 1867 3457 1873 3457 1868 3457 1869 3458 1868 3458 1874 3458 1869 3459 1874 3459 1875 3459 1869 3460 1875 3460 1852 3460 1852 3461 1875 3461 1851 3461 1867 3462 1872 3462 1876 3462 1867 3463 1876 3463 1873 3463 1868 3464 1873 3464 1874 3464 1870 3465 1877 3465 1871 3465 1871 3466 1877 3466 1878 3466 1871 3467 1878 3467 1872 3467 1872 3468 1878 3468 1876 3468 1873 3469 1876 3469 1879 3469 1851 3470 1875 3470 1850 3470 1879 3471 1880 3471 1873 3471 1873 3472 1880 3472 1874 3472 1875 3473 1874 3473 1881 3473 1875 3474 1881 3474 1850 3474 1876 3475 1878 3475 1879 3475 1874 3476 1880 3476 1881 3476 1877 3477 1882 3477 1878 3477 1878 3478 1882 3478 1879 3478 1879 3479 1883 3479 1880 3479 1880 3480 1883 3480 1884 3480 1880 3481 1884 3481 1881 3481 1881 3482 1884 3482 1885 3482 1881 3483 1885 3483 1850 3483 1879 3484 1882 3484 1883 3484 1854 3485 1862 3485 1855 3485 1877 3486 1900 3486 1882 3486 1882 3487 1900 3487 1886 3487 1887 3488 1905 3488 1888 3488 1887 3489 1891 3489 1856 3489 1856 3490 1891 3490 1892 3490 1856 3491 1892 3491 1855 3491 1855 3492 1892 3492 1893 3492 1855 3493 1893 3493 1854 3493 1854 3494 1893 3494 1894 3494 1854 3495 1894 3495 1853 3495 1896 3496 1899 3496 1898 3496 1864 3497 1895 3497 1870 3497 1870 3498 1895 3498 1897 3498 1877 3499 1898 3499 1900 3499 1896 3500 1897 3500 1895 3500 1898 3501 1877 3501 1896 3501 1896 3502 1877 3502 1897 3502 1897 3503 1877 3503 1870 3503 1899 3504 1901 3504 1898 3504 1901 3505 1886 3505 1898 3505 1898 3506 1886 3506 1900 3506 1906 3507 1905 3507 1859 3507 1905 3508 1906 3508 1907 3508 1888 3509 1905 3509 1907 3509 1907 3510 1906 3510 1911 3510 1911 3511 1906 3511 1903 3511 1908 3512 1907 3512 1911 3512 1911 3513 1909 3513 1908 3513 1908 3514 1889 3514 1907 3514 1907 3515 1889 3515 1888 3515 1890 3516 1889 3516 1908 3516 1904 3517 1908 3517 1909 3517 1904 3518 1909 3518 1920 3518 1908 3519 1904 3519 1890 3519 1891 3520 1887 3520 1912 3520 1912 3521 1887 3521 1888 3521 1912 3522 1888 3522 1913 3522 1913 3523 1888 3523 1914 3523 1914 3524 1888 3524 1889 3524 1914 3525 1889 3525 1890 3525 1914 3526 1890 3526 1915 3526 1892 3527 1891 3527 1916 3527 1864 3528 1917 3528 1918 3528 1864 3529 1918 3529 1895 3529 1931 3530 1896 3530 1918 3530 1918 3531 1896 3531 1895 3531 1896 3532 1931 3532 1932 3532 1896 3533 1932 3533 1899 3533 1910 3534 1903 3534 1906 3534 1921 3535 1920 3535 1909 3535 1919 3536 1920 3536 1921 3536 1921 3537 1909 3537 1911 3537 1903 3538 1921 3538 1911 3538 1894 3539 1893 3539 1922 3539 1916 3540 1891 3540 1924 3540 1892 3541 1916 3541 1925 3541 1922 3542 1929 3542 1928 3542 1928 3543 1929 3543 1927 3543 1926 3544 1925 3544 1929 3544 1893 3545 1892 3545 1925 3545 1893 3546 1925 3546 1926 3546 1893 3547 1926 3547 1929 3547 1929 3548 1922 3548 1893 3548 1928 3549 1927 3549 1930 3549 1928 3550 1923 3550 1922 3550 1922 3551 1923 3551 1894 3551 1929 3552 1931 3552 1927 3552 1918 3553 1930 3553 1927 3553 1918 3554 1927 3554 1931 3554 1932 3555 1931 3555 1929 3555 1932 3556 1929 3556 1925 3556 1918 3557 1917 3557 1930 3557 1933 3558 1919 3558 1921 3558 1933 3559 1921 3559 1947 3559 1947 3560 1921 3560 1949 3560 1934 3561 1949 3561 1903 3561 1903 3562 1949 3562 1921 3562 1934 3563 1903 3563 1910 3563 1912 3564 1913 3564 1938 3564 1891 3565 1912 3565 1924 3565 1914 3566 1937 3566 1938 3566 1938 3567 1937 3567 1935 3567 1913 3568 1914 3568 1938 3568 1938 3569 1935 3569 1939 3569 1936 3570 2040 3570 1940 3570 1914 3571 1915 3571 1936 3571 1914 3572 1936 3572 1937 3572 1937 3573 1936 3573 1940 3573 1935 3574 1937 3574 1940 3574 1935 3575 1940 3575 1952 3575 1924 3576 1938 3576 1939 3576 1912 3577 1938 3577 1924 3577 1941 3578 1924 3578 1939 3578 1941 3579 1939 3579 1942 3579 1945 3580 1943 3580 1954 3580 1945 3581 1944 3581 1943 3581 1948 3582 1949 3582 1945 3582 1945 3583 1949 3583 1944 3583 1948 3584 1947 3584 1949 3584 1949 3585 1934 3585 1944 3585 1945 3586 1946 3586 1948 3586 1951 3587 1942 3587 1939 3587 1951 3588 1939 3588 1935 3588 1951 3589 1935 3589 1952 3589 1950 3590 1952 3590 1940 3590 1953 3591 1942 3591 1951 3591 1945 3592 1954 3592 1955 3592 1947 3593 1948 3593 1946 3593 1991 3594 1953 3594 1956 3594 1951 3595 1956 3595 1953 3595 1956 3596 1951 3596 1983 3596 1983 3597 1951 3597 1952 3597 1983 3598 1952 3598 1950 3598 1983 3599 1950 3599 1957 3599 1933 3600 1947 3600 1958 3600 1958 3601 1965 3601 1959 3601 1963 3602 1966 3602 1964 3602 1964 3603 1966 3603 1967 3603 1947 3604 1946 3604 1958 3604 1958 3605 1946 3605 1965 3605 1959 3606 1965 3606 1968 3606 1959 3607 1968 3607 1960 3607 1960 3608 1968 3608 1961 3608 1962 3609 1961 3609 1969 3609 1962 3610 1969 3610 1963 3610 1963 3611 1969 3611 1966 3611 1961 3612 1968 3612 1969 3612 1967 3613 1966 3613 1970 3613 1946 3614 1945 3614 1965 3614 1965 3615 1945 3615 1955 3615 1965 3616 1955 3616 1971 3616 1965 3617 1971 3617 1968 3617 1968 3618 1971 3618 1972 3618 1968 3619 1972 3619 1969 3619 1969 3620 1973 3620 1966 3620 1969 3621 1972 3621 1973 3621 1966 3622 1973 3622 1974 3622 1966 3623 1974 3623 1970 3623 1971 3624 1955 3624 1975 3624 1971 3625 1975 3625 1972 3625 1955 3626 1954 3626 1975 3626 1972 3627 1975 3627 1973 3627 1973 3628 1975 3628 1974 3628 1974 3629 1975 3629 1976 3629 1974 3630 1976 3630 1970 3630 1956 3631 1983 3631 1984 3631 1984 3632 1978 3632 1977 3632 1983 3633 1981 3633 1984 3633 1984 3634 1981 3634 1980 3634 1984 3635 1980 3635 1978 3635 1977 3636 1991 3636 1984 3636 1984 3637 1991 3637 1956 3637 1957 3638 1982 3638 1983 3638 1983 3639 1982 3639 1981 3639 1979 3640 1978 3640 1980 3640 1985 3641 1964 3641 1967 3641 1985 3642 1967 3642 1986 3642 1986 3643 1967 3643 1970 3643 1986 3644 1970 3644 1987 3644 1987 3645 1970 3645 1988 3645 1988 3646 1970 3646 1976 3646 1988 3647 1976 3647 1989 3647 1981 3648 1982 3648 1990 3648 1990 3649 1980 3649 1981 3649 1985 3650 1986 3650 1992 3650 1994 3651 1997 3651 1995 3651 1992 3652 1986 3652 1998 3652 1992 3653 1998 3653 1993 3653 1993 3654 1998 3654 1999 3654 1993 3655 1999 3655 2000 3655 1993 3656 2000 3656 1994 3656 1994 3657 2000 3657 1997 3657 1957 3658 1996 3658 1982 3658 1995 3659 1997 3659 2001 3659 1995 3660 2001 3660 1996 3660 1986 3661 1987 3661 1998 3661 1998 3662 1987 3662 2002 3662 1998 3663 2002 3663 1999 3663 2000 3664 2003 3664 1997 3664 1997 3665 2003 3665 2001 3665 1996 3666 2001 3666 1990 3666 1996 3667 1990 3667 1982 3667 2000 3668 1999 3668 2003 3668 2001 3669 2004 3669 1990 3669 1987 3670 1988 3670 2002 3670 2002 3671 1988 3671 2005 3671 2002 3672 2005 3672 1999 3672 1999 3673 2005 3673 2003 3673 2001 3674 2003 3674 2004 3674 1990 3675 2004 3675 2006 3675 1990 3676 2006 3676 1980 3676 2003 3677 2005 3677 2007 3677 2003 3678 2007 3678 2004 3678 1980 3679 2006 3679 1979 3679 1988 3680 1989 3680 2005 3680 2005 3681 1989 3681 2007 3681 2004 3682 2007 3682 2006 3682 1923 3683 1928 3683 2014 3683 1928 3684 1930 3684 2014 3684 2014 3685 1930 3685 2013 3685 2013 3686 1930 3686 1917 3686 2014 3687 2015 3687 1923 3687 1923 3688 2015 3688 2016 3688 1923 3689 2016 3689 1894 3689 2013 3690 2012 3690 2014 3690 2014 3691 2012 3691 2015 3691 2012 3692 2017 3692 2015 3692 2015 3693 2017 3693 2016 3693 2012 3694 2011 3694 2017 3694 2017 3695 2011 3695 2018 3695 2017 3696 2018 3696 2016 3696 2016 3697 2018 3697 2019 3697 2011 3698 2010 3698 2018 3698 2010 3699 2009 3699 2020 3699 2010 3700 2020 3700 2018 3700 2018 3701 2020 3701 2021 3701 2018 3702 2021 3702 2019 3702 2009 3703 2008 3703 2022 3703 2009 3704 2022 3704 2020 3704 2020 3705 2022 3705 2021 3705 2023 3706 2021 3706 2022 3706 2023 3707 2022 3707 2024 3707 2024 3708 2022 3708 2008 3708 2024 3709 2008 3709 2025 3709 1847 3710 1861 3710 2027 3710 2026 3711 2027 3711 2029 3711 2031 3712 2034 3712 2032 3712 2026 3713 1847 3713 2027 3713 2031 3714 2030 3714 2035 3714 2031 3715 2035 3715 2034 3715 2032 3716 2034 3716 2036 3716 2032 3717 2036 3717 2033 3717 2025 3718 2033 3718 2024 3718 2029 3719 2027 3719 2037 3719 2029 3720 2037 3720 2030 3720 2030 3721 2037 3721 2035 3721 2033 3722 2036 3722 2024 3722 2027 3723 1861 3723 2028 3723 2027 3724 2028 3724 2037 3724 2034 3725 2035 3725 2036 3725 1861 3726 1858 3726 2028 3726 2036 3727 2035 3727 2038 3727 2024 3728 2036 3728 2023 3728 2028 3729 1858 3729 1853 3729 2037 3730 2028 3730 2039 3730 2037 3731 2039 3731 2035 3731 2036 3732 2038 3732 2023 3732 2028 3733 1853 3733 2039 3733 2035 3734 2039 3734 2038 3734 1950 3735 1940 3735 2040 3735 2040 3736 1936 3736 2041 3736 1915 3737 2043 3737 2044 3737 1915 3738 2044 3738 2041 3738 1915 3739 2041 3739 1936 3739 2042 3740 2045 3740 2043 3740 2043 3741 2046 3741 2044 3741 2042 3742 2047 3742 2045 3742 2045 3743 2047 3743 2048 3743 2043 3744 2045 3744 2049 3744 2043 3745 2049 3745 2046 3745 2044 3746 2046 3746 2041 3746 2045 3747 2048 3747 2050 3747 2045 3748 2050 3748 2049 3748 2046 3749 2051 3749 2041 3749 2047 3750 2052 3750 2048 3750 2049 3751 2050 3751 2053 3751 2041 3752 2051 3752 2054 3752 2041 3753 2054 3753 2040 3753 2048 3754 2052 3754 2055 3754 2048 3755 2055 3755 2050 3755 2049 3756 2053 3756 2056 3756 2049 3757 2056 3757 2046 3757 2046 3758 2056 3758 2051 3758 2042 3759 2057 3759 2058 3759 2042 3760 2058 3760 2047 3760 2047 3761 2058 3761 2052 3761 2052 3762 2058 3762 2059 3762 2064 3763 1904 3763 2061 3763 2061 3764 1904 3764 1920 3764 2064 3765 1890 3765 1904 3765 2058 3766 2057 3766 2063 3766 2064 3767 2069 3767 2060 3767 2064 3768 2060 3768 2062 3768 2067 3769 2058 3769 2063 3769 2067 3770 2063 3770 2068 3770 2068 3771 2063 3771 2065 3771 2061 3772 2066 3772 2064 3772 2064 3773 2062 3773 1890 3773 2071 3774 2065 3774 2069 3774 2071 3775 2069 3775 2070 3775 2059 3776 2058 3776 2067 3776 2071 3777 2068 3777 2065 3777 2063 3778 2057 3778 2060 3778 2063 3779 2060 3779 2065 3779 2065 3780 2060 3780 2069 3780 2069 3781 2064 3781 2070 3781 2070 3782 2064 3782 2066 3782 2061 3783 1920 3783 1919 3783 2030 3784 2072 3784 2029 3784 2029 3785 2072 3785 2026 3785 2026 3786 2072 3786 2073 3786 2026 3787 2073 3787 1847 3787 2031 3788 2075 3788 2030 3788 2030 3789 2075 3789 2072 3789 1829 3790 1830 3790 2074 3790 2074 3791 1830 3791 1831 3791 2074 3792 1831 3792 2076 3792 2076 3793 1831 3793 1832 3793 2076 3794 1832 3794 2077 3794 2077 3795 1832 3795 1818 3795 2025 3796 1826 3796 1827 3796 2025 3797 1827 3797 2033 3797 2033 3798 1827 3798 1828 3798 2033 3799 1828 3799 2032 3799 2032 3800 1828 3800 1829 3800 2032 3801 1829 3801 2031 3801 2031 3802 1829 3802 2074 3802 2031 3803 2074 3803 2075 3803 1960 3804 2078 3804 1959 3804 1959 3805 2078 3805 1958 3805 1958 3806 2078 3806 2079 3806 1958 3807 2079 3807 1933 3807 2071 3808 2080 3808 2081 3808 2071 3809 2070 3809 2080 3809 2080 3810 2070 3810 2082 3810 2082 3811 2070 3811 2066 3811 2082 3812 2066 3812 2061 3812 2082 3813 2061 3813 2083 3813 2083 3814 2061 3814 1919 3814 1964 3815 2059 3815 2067 3815 1964 3816 2067 3816 1963 3816 1963 3817 2067 3817 2068 3817 1963 3818 2068 3818 2071 3818 1963 3819 2071 3819 1962 3819 1962 3820 2071 3820 1961 3820 1961 3821 2071 3821 2081 3821 1961 3822 2081 3822 1960 3822 1960 3823 2081 3823 2078 3823 2056 3824 2084 3824 2051 3824 2051 3825 2084 3825 2054 3825 2054 3826 2084 3826 2085 3826 2054 3827 2085 3827 2040 3827 2040 3828 2085 3828 1950 3828 2056 3829 2087 3829 2084 3829 1993 3830 1994 3830 2086 3830 2086 3831 1994 3831 2088 3831 2088 3832 1994 3832 1995 3832 2088 3833 1995 3833 1996 3833 2088 3834 1996 3834 2089 3834 2089 3835 1996 3835 1957 3835 2052 3836 1985 3836 1992 3836 2052 3837 1992 3837 2055 3837 2055 3838 1992 3838 2050 3838 2050 3839 1992 3839 1993 3839 2050 3840 1993 3840 2053 3840 2053 3841 1993 3841 2056 3841 2056 3842 1993 3842 2086 3842 2056 3843 2086 3843 2087 3843 1867 3844 2090 3844 1866 3844 1866 3845 2090 3845 1865 3845 1865 3846 2090 3846 2091 3846 1865 3847 2091 3847 1864 3847 2011 3848 2092 3848 2093 3848 2011 3849 2012 3849 2092 3849 2092 3850 2012 3850 2094 3850 2094 3851 2012 3851 2013 3851 2094 3852 2013 3852 2095 3852 2095 3853 2013 3853 1917 3853 1852 3854 2008 3854 2009 3854 1852 3855 2009 3855 1869 3855 1869 3856 2009 3856 2010 3856 1869 3857 2010 3857 1868 3857 1868 3858 2010 3858 2011 3858 1868 3859 2011 3859 1867 3859 1867 3860 2011 3860 2093 3860 1867 3861 2093 3861 2090 3861 2102 3862 2395 3862 2103 3862 2102 3863 2103 3863 2098 3863 1934 3864 2100 3864 1944 3864 1944 3865 2100 3865 2104 3865 2100 3866 2099 3866 2104 3866 2099 3867 2101 3867 2098 3867 2099 3868 2098 3868 2104 3868 2101 3869 2102 3869 2098 3869 2103 3870 2109 3870 2098 3870 1944 3871 2104 3871 1943 3871 2098 3872 2109 3872 2096 3872 2098 3873 2096 3873 2105 3873 2098 3874 2105 3874 2104 3874 2104 3875 2105 3875 1943 3875 2109 3876 2097 3876 2096 3876 1943 3877 2105 3877 1954 3877 2103 3878 2106 3878 2107 3878 2103 3879 2395 3879 2106 3879 2107 3880 2106 3880 2108 3880 2107 3881 2108 3881 2110 3881 2112 3882 2114 3882 2111 3882 2109 3883 2103 3883 2107 3883 2109 3884 2107 3884 2112 3884 2112 3885 2107 3885 2110 3885 2112 3886 2110 3886 2115 3886 2115 3887 2110 3887 2113 3887 2113 3888 2116 3888 2115 3888 2109 3889 2112 3889 2111 3889 2114 3890 2115 3890 2117 3890 2117 3891 2115 3891 2116 3891 2118 3892 2117 3892 2116 3892 2114 3893 2112 3893 2115 3893 2097 3894 2109 3894 2111 3894 2118 3895 1646 3895 2117 3895 2117 3896 1646 3896 1645 3896 2117 3897 1645 3897 2114 3897 2114 3898 1645 3898 1641 3898 2114 3899 1641 3899 2111 3899 2111 3900 1641 3900 2097 3900 1640 3901 1639 3901 2119 3901 2119 3902 2120 3902 2125 3902 2125 3903 2120 3903 2126 3903 2120 3904 2122 3904 2127 3904 2127 3905 2122 3905 2123 3905 1640 3906 2119 3906 1644 3906 2126 3907 2120 3907 2127 3907 2125 3908 1644 3908 2119 3908 2127 3909 2123 3909 2128 3909 2128 3910 2123 3910 2124 3910 2125 3911 2126 3911 2129 3911 2129 3912 2126 3912 2127 3912 1644 3913 2125 3913 2130 3913 2130 3914 2125 3914 2129 3914 2129 3915 2127 3915 2128 3915 1642 3916 1644 3916 2130 3916 2130 3917 2129 3917 2131 3917 2131 3918 2129 3918 2132 3918 2132 3919 2129 3919 2128 3919 1641 3920 1642 3920 2130 3920 1641 3921 2130 3921 2131 3921 2124 3922 2133 3922 2128 3922 2128 3923 2133 3923 2134 3923 2128 3924 2134 3924 2132 3924 2132 3925 2134 3925 2135 3925 2135 3926 2134 3926 2138 3926 2135 3927 2138 3927 2139 3927 2135 3928 2139 3928 2136 3928 2136 3929 2139 3929 2140 3929 2136 3930 2140 3930 2137 3930 2138 3931 2141 3931 2139 3931 2137 3932 2140 3932 2142 3932 2139 3933 2143 3933 2140 3933 2134 3934 2133 3934 2138 3934 2138 3935 2133 3935 2144 3935 2138 3936 2144 3936 2141 3936 2139 3937 2141 3937 2145 3937 2139 3938 2145 3938 2143 3938 2141 3939 2146 3939 2145 3939 2140 3940 2143 3940 2147 3940 2140 3941 2147 3941 2148 3941 2140 3942 2148 3942 2142 3942 2141 3943 2144 3943 2146 3943 2143 3944 2145 3944 2147 3944 2142 3945 2148 3945 2149 3945 2149 3946 2150 3946 2142 3946 2142 3947 2150 3947 2151 3947 2142 3948 2151 3948 2152 3948 2142 3949 2152 3949 2137 3949 2137 3950 2152 3950 2136 3950 2152 3951 2154 3951 2153 3951 2153 3952 2154 3952 2156 3952 2152 3953 2151 3953 2154 3953 2153 3954 2156 3954 2157 3954 2153 3955 2157 3955 2155 3955 2154 3956 2151 3956 2158 3956 2154 3957 2158 3957 2156 3957 2155 3958 2157 3958 2159 3958 2151 3959 2150 3959 2160 3959 2151 3960 2160 3960 2158 3960 2156 3961 2158 3961 2161 3961 2156 3962 2161 3962 2157 3962 2158 3963 2160 3963 2162 3963 2157 3964 2161 3964 2163 3964 2157 3965 2163 3965 2159 3965 2158 3966 2162 3966 2161 3966 2159 3967 2594 3967 2173 3967 2159 3968 2173 3968 2155 3968 2155 3969 2173 3969 2174 3969 2155 3970 2174 3970 2153 3970 1682 3971 1681 3971 1686 3971 2167 3972 1690 3972 2168 3972 2168 3973 1690 3973 1682 3973 2170 3974 1682 3974 1686 3974 2170 3975 1686 3975 2169 3975 2169 3976 1686 3976 1688 3976 2168 3977 1682 3977 2170 3977 2166 3978 2167 3978 2168 3978 2165 3979 2166 3979 2171 3979 2171 3980 2166 3980 2168 3980 2171 3981 2168 3981 2172 3981 2172 3982 2168 3982 2170 3982 2172 3983 2170 3983 2169 3983 2164 3984 2165 3984 2171 3984 2164 3985 2171 3985 2172 3985 2174 3986 2172 3986 2169 3986 2173 3987 2164 3987 2172 3987 2173 3988 2172 3988 2174 3988 2594 3989 2164 3989 2173 3989 2175 3990 1688 3990 1686 3990 2175 3991 1686 3991 2176 3991 2176 3992 1686 3992 1685 3992 2176 3993 1685 3993 1680 3993 2176 3994 1680 3994 2177 3994 2177 3995 1680 3995 1683 3995 2182 3996 2177 3996 2180 3996 2645 3997 2180 3997 1683 3997 1683 3998 2180 3998 2177 3998 2182 3999 2180 3999 2181 3999 2184 4000 2182 4000 2181 4000 2188 4001 2183 4001 2186 4001 2183 4002 2188 4002 2181 4002 2181 4003 2188 4003 2184 4003 2182 4004 2184 4004 2176 4004 2182 4005 2176 4005 2177 4005 2186 4006 2183 4006 2529 4006 2184 4007 2185 4007 2176 4007 2188 4008 2179 4008 2178 4008 2187 4009 2179 4009 2188 4009 2185 4010 2178 4010 2175 4010 2185 4011 2175 4011 2176 4011 2178 4012 2185 4012 2184 4012 2178 4013 2184 4013 2188 4013 2188 4014 2186 4014 2187 4014 2192 4015 2190 4015 2187 4015 2194 4016 2187 4016 2190 4016 2194 4017 2179 4017 2187 4017 2195 4018 2179 4018 2194 4018 2178 4019 2179 4019 2195 4019 2178 4020 2195 4020 2196 4020 2178 4021 2196 4021 2175 4021 2190 4022 2191 4022 2194 4022 2194 4023 2191 4023 2195 4023 2191 4024 2193 4024 2197 4024 2191 4025 2197 4025 2195 4025 2195 4026 2197 4026 2198 4026 2195 4027 2198 4027 2196 4027 2193 4028 2189 4028 2199 4028 2193 4029 2199 4029 2197 4029 2197 4030 2199 4030 2198 4030 2189 4031 1991 4031 1977 4031 2189 4032 1977 4032 2199 4032 2199 4033 1977 4033 1978 4033 2199 4034 1978 4034 1979 4034 2199 4035 1979 4035 2198 4035 2198 4036 1979 4036 2196 4036 2221 4037 2204 4037 2205 4037 2451 4038 2221 4038 2205 4038 1899 4039 2206 4039 1901 4039 2206 4040 2207 4040 2209 4040 2206 4041 2209 4041 1901 4041 2205 4042 2204 4042 2203 4042 2205 4043 2203 4043 2208 4043 2208 4044 2203 4044 2207 4044 2207 4045 2203 4045 2209 4045 2202 4046 2203 4046 2204 4046 2209 4047 1902 4047 1901 4047 2203 4048 2202 4048 2201 4048 2209 4049 2203 4049 2210 4049 2209 4050 2210 4050 1902 4050 2203 4051 2201 4051 2210 4051 1901 4052 1902 4052 1886 4052 2202 4053 2200 4053 2201 4053 2201 4054 2200 4054 2210 4054 1902 4055 2210 4055 1886 4055 2210 4056 2200 4056 2215 4056 2213 4057 2218 4057 2212 4057 2200 4058 2219 4058 2215 4058 2215 4059 2219 4059 2213 4059 2213 4060 2220 4060 2218 4060 2221 4061 2222 4061 2217 4061 2202 4062 2223 4062 2200 4062 2219 4063 2220 4063 2213 4063 2212 4064 2218 4064 2224 4064 2224 4065 2218 4065 2220 4065 2219 4066 2200 4066 2223 4066 2204 4067 2223 4067 2202 4067 2211 4068 2212 4068 2224 4068 2224 4069 2220 4069 2214 4069 2214 4070 2220 4070 2216 4070 2217 4071 2216 4071 2223 4071 2217 4072 2223 4072 2221 4072 2221 4073 2223 4073 2204 4073 2223 4074 2216 4074 2219 4074 2219 4075 2216 4075 2220 4075 1648 4076 2215 4076 2213 4076 1648 4077 2213 4077 1653 4077 1653 4078 2213 4078 1650 4078 1650 4079 2213 4079 2212 4079 1650 4080 2212 4080 1647 4080 1647 4081 2212 4081 2211 4081 2230 4082 2229 4082 2231 4082 2225 4083 1654 4083 2226 4083 2232 4084 2228 4084 2229 4084 2233 4085 2226 4085 2227 4085 2233 4086 2227 4086 2228 4086 2233 4087 2228 4087 2234 4087 2234 4088 2228 4088 2232 4088 1649 4089 2225 4089 2226 4089 1649 4090 2226 4090 2233 4090 2232 4091 2229 4091 2230 4091 2235 4092 2234 4092 2232 4092 2235 4093 2232 4093 2236 4093 2236 4094 2232 4094 2230 4094 2233 4095 2234 4095 2235 4095 1648 4096 1649 4096 2237 4096 2237 4097 1649 4097 2233 4097 2237 4098 2233 4098 2235 4098 2239 4099 2235 4099 2236 4099 2239 4100 2236 4100 2238 4100 2239 4101 1648 4101 2237 4101 2239 4102 2237 4102 2235 4102 2242 4103 2238 4103 2240 4103 2240 4104 2238 4104 2236 4104 2240 4105 2236 4105 2230 4105 2240 4106 2230 4106 2241 4106 2241 4107 2230 4107 2231 4107 2243 4108 2245 4108 2244 4108 2242 4109 2247 4109 2243 4109 2244 4110 2245 4110 2246 4110 2242 4111 2240 4111 2247 4111 2243 4112 2247 4112 2248 4112 2243 4113 2248 4113 2245 4113 2247 4114 2240 4114 2249 4114 2245 4115 2250 4115 2246 4115 2248 4116 2247 4116 2251 4116 2249 4117 2252 4117 2247 4117 2247 4118 2252 4118 2251 4118 2248 4119 2251 4119 2253 4119 2248 4120 2253 4120 2245 4120 2245 4121 2253 4121 2254 4121 2245 4122 2254 4122 2250 4122 2240 4123 2241 4123 2249 4123 2249 4124 2241 4124 2252 4124 2250 4125 2254 4125 2255 4125 2256 4126 2244 4126 2246 4126 2256 4127 2246 4127 2257 4127 2257 4128 2246 4128 2250 4128 2257 4129 2250 4129 2258 4129 2258 4130 2250 4130 2255 4130 2260 4131 2259 4131 2261 4131 2260 4132 2262 4132 2263 4132 2256 4133 2257 4133 2259 4133 2259 4134 2257 4134 2264 4134 2259 4135 2264 4135 2261 4135 2260 4136 2261 4136 2262 4136 2261 4137 2264 4137 2265 4137 2257 4138 2258 4138 2264 4138 2263 4139 2262 4139 2266 4139 2264 4140 2258 4140 2267 4140 2261 4141 2265 4141 2268 4141 2261 4142 2268 4142 2262 4142 2262 4143 2268 4143 2269 4143 2262 4144 2269 4144 2266 4144 2264 4145 2267 4145 2270 4145 2264 4146 2270 4146 2265 4146 2265 4147 2270 4147 2268 4147 2271 4148 2260 4148 2263 4148 2271 4149 2263 4149 2272 4149 2272 4150 2263 4150 2266 4150 2272 4151 2266 4151 2273 4151 2275 4152 1607 4152 1608 4152 2275 4153 1608 4153 1609 4153 2276 4154 1607 4154 2275 4154 2275 4155 1609 4155 2277 4155 2277 4156 1609 4156 1610 4156 2278 4157 2276 4157 2275 4157 2279 4158 2278 4158 2275 4158 2279 4159 2275 4159 2277 4159 2279 4160 2277 4160 2282 4160 2274 4161 2276 4161 2278 4161 2280 4162 2278 4162 2279 4162 2281 4163 2274 4163 2278 4163 2281 4164 2278 4164 2280 4164 2280 4165 2279 4165 2282 4165 2271 4166 2280 4166 2282 4166 2273 4167 2281 4167 2272 4167 2272 4168 2281 4168 2280 4168 2272 4169 2280 4169 2271 4169 1606 4170 2297 4170 2298 4170 1606 4171 2298 4171 1612 4171 2283 4172 1610 4172 2295 4172 2295 4173 1610 4173 1611 4173 2295 4174 1611 4174 1612 4174 2295 4175 1612 4175 2298 4175 2288 4176 2289 4176 2287 4176 2290 4177 2286 4177 2285 4177 2290 4178 2285 4178 2284 4178 2284 4179 2283 4179 2295 4179 2292 4180 2293 4180 2291 4180 2294 4181 2292 4181 2291 4181 2295 4182 2294 4182 2284 4182 2284 4183 2294 4183 2290 4183 2290 4184 2288 4184 2286 4184 2296 4185 2626 4185 2292 4185 2292 4186 2626 4186 2293 4186 2291 4187 2290 4187 2294 4187 2294 4188 2295 4188 2298 4188 2297 4189 2296 4189 2298 4189 2296 4190 2292 4190 2298 4190 2292 4191 2294 4191 2298 4191 2287 4192 2286 4192 2288 4192 2288 4193 2290 4193 2291 4193 2301 4194 2287 4194 2310 4194 2285 4195 2286 4195 2303 4195 2303 4196 2286 4196 2301 4196 2301 4197 2286 4197 2287 4197 2304 4198 2285 4198 2303 4198 2285 4199 2304 4199 2284 4199 2301 4200 2300 4200 2303 4200 2300 4201 2302 4201 2305 4201 2300 4202 2305 4202 2303 4202 2303 4203 2305 4203 2306 4203 2303 4204 2306 4204 2304 4204 2302 4205 2299 4205 2307 4205 2302 4206 2307 4206 2305 4206 2305 4207 2307 4207 2306 4207 2299 4208 1815 4208 1814 4208 2299 4209 1814 4209 2307 4209 2307 4210 1814 4210 2306 4210 2306 4211 1816 4211 1812 4211 2306 4212 1812 4212 2304 4212 2312 4213 2313 4213 2314 4213 2311 4214 2289 4214 2312 4214 2316 4215 2312 4215 2314 4215 2316 4216 2314 4216 2315 4216 2311 4217 2312 4217 2316 4217 2318 4218 2310 4218 2311 4218 2319 4219 2311 4219 2316 4219 2319 4220 2316 4220 2318 4220 2316 4221 2315 4221 2317 4221 2320 4222 2318 4222 2316 4222 2320 4223 2316 4223 2317 4223 2311 4224 2319 4224 2318 4224 2320 4225 2317 4225 2321 4225 2318 4226 2320 4226 2321 4226 2322 4227 2321 4227 2317 4227 2322 4228 2317 4228 2323 4228 2323 4229 2317 4229 2315 4229 2325 4230 2322 4230 2323 4230 2325 4231 2323 4231 2324 4231 2324 4232 2323 4232 2315 4232 2326 4233 2322 4233 2325 4233 2308 4234 2322 4234 2326 4234 2309 4235 2325 4235 2324 4235 2327 4236 2326 4236 2325 4236 2327 4237 2325 4237 2309 4237 2328 4238 2308 4238 2326 4238 2328 4239 2326 4239 2329 4239 2329 4240 2326 4240 2327 4240 2329 4241 2327 4241 2330 4241 2330 4242 2327 4242 2309 4242 2331 4243 2328 4243 2379 4243 2379 4244 2328 4244 2369 4244 2369 4245 2328 4245 2329 4245 2369 4246 2329 4246 2332 4246 2332 4247 2329 4247 2330 4247 2332 4248 2330 4248 2333 4248 2333 4249 2330 4249 2309 4249 2342 4250 2343 4250 2344 4250 2354 4251 2355 4251 2358 4251 2354 4252 2358 4252 2353 4252 2353 4253 2358 4253 2359 4253 2353 4254 2359 4254 2352 4254 2341 4255 2342 4255 2360 4255 2341 4256 2360 4256 2340 4256 2357 4257 2361 4257 2356 4257 2355 4258 2356 4258 2362 4258 2355 4259 2362 4259 2358 4259 2352 4260 2359 4260 2351 4260 2346 4261 2347 4261 2363 4261 2346 4262 2363 4262 2345 4262 2344 4263 2345 4263 2364 4263 2344 4264 2364 4264 2342 4264 2340 4265 2360 4265 2365 4265 2340 4266 2365 4266 2339 4266 2338 4267 2339 4267 2366 4267 2338 4268 2366 4268 2337 4268 2337 4269 2366 4269 2336 4269 2336 4270 2366 4270 2367 4270 2336 4271 2367 4271 2335 4271 2334 4272 2335 4272 2368 4272 2334 4273 2368 4273 2333 4273 2333 4274 2368 4274 2369 4274 2333 4275 2369 4275 2332 4275 2356 4276 2361 4276 2362 4276 2349 4277 2350 4277 2370 4277 2349 4278 2370 4278 2348 4278 2348 4279 2370 4279 2371 4279 2348 4280 2371 4280 2347 4280 2345 4281 2363 4281 2364 4281 2339 4282 2365 4282 2372 4282 2339 4283 2372 4283 2366 4283 2351 4284 2359 4284 2374 4284 2351 4285 2374 4285 2350 4285 2350 4286 2374 4286 2370 4286 2347 4287 2371 4287 2363 4287 2342 4288 2364 4288 2375 4288 2342 4289 2375 4289 2360 4289 2335 4290 2367 4290 2368 4290 2361 4291 2373 4291 2362 4291 2362 4292 2376 4292 2358 4292 2359 4293 2358 4293 2377 4293 2359 4294 2377 4294 2374 4294 2366 4295 2372 4295 2378 4295 2366 4296 2378 4296 2367 4296 2368 4297 2367 4297 2379 4297 2368 4298 2379 4298 2369 4298 2362 4299 2373 4299 2376 4299 2358 4300 2376 4300 2377 4300 2374 4301 2377 4301 2370 4301 2364 4302 2363 4302 2380 4302 2364 4303 2380 4303 2375 4303 2360 4304 2375 4304 2365 4304 2365 4305 2375 4305 2372 4305 2370 4306 2377 4306 2371 4306 2363 4307 2371 4307 2380 4307 2367 4308 2378 4308 2379 4308 2372 4309 2375 4309 2378 4309 2381 4310 2373 4310 2382 4310 2382 4311 2373 4311 2361 4311 2382 4312 2361 4312 2357 4312 2382 4313 2357 4313 2383 4313 2383 4314 2385 4314 2386 4314 2383 4315 2386 4315 2382 4315 2382 4316 2386 4316 2381 4316 2381 4317 2386 4317 2384 4317 2392 4318 2108 4318 2394 4318 2396 4319 2392 4319 2394 4319 2396 4320 2394 4320 2393 4320 2396 4321 2393 4321 2397 4321 2396 4322 2391 4322 2392 4322 2397 4323 2393 4323 2398 4323 2398 4324 2393 4324 2395 4324 2390 4325 2391 4325 2396 4325 2390 4326 2396 4326 2399 4326 2399 4327 2396 4327 2397 4327 2399 4328 2397 4328 2400 4328 2400 4329 2397 4329 2398 4329 2401 4330 2388 4330 2390 4330 2401 4331 2390 4331 2399 4331 2401 4332 2399 4332 2389 4332 2389 4333 2399 4333 2400 4333 2389 4334 2400 4334 2398 4334 2402 4335 2387 4335 2388 4335 2402 4336 2388 4336 2401 4336 2403 4337 2401 4337 2389 4337 2404 4338 2402 4338 2401 4338 2404 4339 2401 4339 2403 4339 2404 4340 2403 4340 2384 4340 2384 4341 2403 4341 2389 4341 2385 4342 2402 4342 2386 4342 2386 4343 2402 4343 2404 4343 2386 4344 2404 4344 2384 4344 2409 4345 1792 4345 1793 4345 1791 4346 2410 4346 1789 4346 2405 4347 1796 4347 1794 4347 2411 4348 2408 4348 2412 4348 2412 4349 2408 4349 1795 4349 2412 4350 1795 4350 2414 4350 2414 4351 1795 4351 1796 4351 2414 4352 1796 4352 2405 4352 2413 4353 2411 4353 2440 4353 2440 4354 2411 4354 2412 4354 2440 4355 2412 4355 2443 4355 2415 4356 2410 4356 1792 4356 1792 4357 2410 4357 1791 4357 2407 4358 2420 4358 2421 4358 2421 4359 2423 4359 2424 4359 2425 4360 2430 4360 2426 4360 2426 4361 2430 4361 2343 4361 2431 4362 2430 4362 2434 4362 2436 4363 2437 4363 2406 4363 2406 4364 2437 4364 2432 4364 2434 4365 2433 4365 2435 4365 2434 4366 2435 4366 2436 4366 2436 4367 2435 4367 2437 4367 2439 4368 2440 4368 2441 4368 2441 4369 2440 4369 2442 4369 2439 4370 2438 4370 2440 4370 2420 4371 2337 4371 2416 4371 2416 4372 2417 4372 2422 4372 2422 4373 2417 4373 2415 4373 2422 4374 2415 4374 2409 4374 2409 4375 2415 4375 1792 4375 2422 4376 2421 4376 2416 4376 2416 4377 2421 4377 2420 4377 2422 4378 2409 4378 1793 4378 2426 4379 2343 4379 2418 4379 2418 4380 2419 4380 2425 4380 2425 4381 2419 4381 2407 4381 1793 4382 2423 4382 2422 4382 2422 4383 2423 4383 2421 4383 2421 4384 2424 4384 2407 4384 2407 4385 2424 4385 2425 4385 2418 4386 2425 4386 2426 4386 2427 4387 2343 4387 2431 4387 2431 4388 2343 4388 2430 4388 2423 4389 2429 4389 2424 4389 2424 4390 2429 4390 2425 4390 2425 4391 2429 4391 2430 4391 2431 4392 2434 4392 2427 4392 2427 4393 2434 4393 2428 4393 2428 4394 2436 4394 2445 4394 2445 4395 2436 4395 2406 4395 2436 4396 2428 4396 2434 4396 2432 4397 2439 4397 2349 4397 2432 4398 2349 4398 2406 4398 2429 4399 2433 4399 2430 4399 2430 4400 2433 4400 2434 4400 2437 4401 2438 4401 2432 4401 2432 4402 2438 4402 2439 4402 2443 4403 2442 4403 2440 4403 2438 4404 2437 4404 2435 4404 2414 4405 2444 4405 2412 4405 2412 4406 2444 4406 2443 4406 2413 4407 2440 4407 2438 4407 2413 4408 2438 4408 2435 4408 2222 4409 2221 4409 2451 4409 2222 4410 2451 4410 2452 4410 2453 4411 2222 4411 2452 4411 2454 4412 2453 4412 2452 4412 2454 4413 2452 4413 2451 4413 2456 4414 2453 4414 2454 4414 2456 4415 2454 4415 2457 4415 2455 4416 2454 4416 2451 4416 2459 4417 2456 4417 2457 4417 2458 4418 2454 4418 2455 4418 2450 4419 2459 4419 2457 4419 2457 4420 2454 4420 2458 4420 2460 4421 2450 4421 2457 4421 2460 4422 2457 4422 2458 4422 2449 4423 2460 4423 2458 4423 2448 4424 2450 4424 2461 4424 2461 4425 2450 4425 2460 4425 2461 4426 2460 4426 2462 4426 2462 4427 2460 4427 2449 4427 2447 4428 2448 4428 2461 4428 2463 4429 2461 4429 2462 4429 2463 4430 2447 4430 2461 4430 2463 4431 2462 4431 2464 4431 2464 4432 2462 4432 2449 4432 2465 4433 2447 4433 2463 4433 2465 4434 2463 4434 2464 4434 2446 4435 2447 4435 2465 4435 2466 4436 2446 4436 2465 4436 2466 4437 2465 4437 2468 4437 2468 4438 2465 4438 2467 4438 2467 4439 2465 4439 2464 4439 2467 4440 2516 4440 2469 4440 2467 4441 2469 4441 2470 4441 2467 4442 2470 4442 2468 4442 2468 4443 2470 4443 2471 4443 2468 4444 2471 4444 2466 4444 2483 4445 2482 4445 2484 4445 2483 4446 2484 4446 2485 4446 2489 4447 2491 4447 2490 4447 2490 4448 2491 4448 2492 4448 2486 4449 2487 4449 2498 4449 2486 4450 2498 4450 2485 4450 2479 4451 2480 4451 2499 4451 2479 4452 2499 4452 2478 4452 2473 4453 2475 4453 2500 4453 2473 4454 2500 4454 2474 4454 2471 4455 2470 4455 2497 4455 2495 4456 2496 4456 2502 4456 2495 4457 2502 4457 2494 4457 2492 4458 2493 4458 2503 4458 2492 4459 2503 4459 2490 4459 2478 4460 2499 4460 2504 4460 2478 4461 2504 4461 2477 4461 2477 4462 2504 4462 2505 4462 2477 4463 2505 4463 2476 4463 2475 4464 2476 4464 2506 4464 2475 4465 2506 4465 2500 4465 2472 4466 2474 4466 2501 4466 2497 4467 2470 4467 2496 4467 2496 4468 2470 4468 2502 4468 2490 4469 2503 4469 2507 4469 2490 4470 2507 4470 2489 4470 2489 4471 2507 4471 2488 4471 2488 4472 2507 4472 2508 4472 2488 4473 2508 4473 2487 4473 2487 4474 2508 4474 2498 4474 2498 4475 2508 4475 2509 4475 2498 4476 2509 4476 2485 4476 2481 4477 2482 4477 2510 4477 2481 4478 2510 4478 2480 4478 2480 4479 2510 4479 2499 4479 2474 4480 2500 4480 2511 4480 2474 4481 2511 4481 2501 4481 2494 4482 2502 4482 2512 4482 2494 4483 2512 4483 2493 4483 2493 4484 2512 4484 2503 4484 2485 4485 2509 4485 2483 4485 2483 4486 2509 4486 2513 4486 2483 4487 2513 4487 2482 4487 2482 4488 2513 4488 2514 4488 2482 4489 2514 4489 2510 4489 2476 4490 2505 4490 2506 4490 2501 4491 2511 4491 2515 4491 2502 4492 2516 4492 2512 4492 2503 4493 2512 4493 2517 4493 2503 4494 2517 4494 2507 4494 2508 4495 2507 4495 2518 4495 2510 4496 2514 4496 2519 4496 2510 4497 2519 4497 2499 4497 2499 4498 2519 4498 2504 4498 2505 4499 2504 4499 2520 4499 2470 4500 2469 4500 2502 4500 2502 4501 2469 4501 2516 4501 2507 4502 2517 4502 2518 4502 2508 4503 2518 4503 2509 4503 2506 4504 2505 4504 2521 4504 2506 4505 2521 4505 2500 4505 2500 4506 2521 4506 2511 4506 2509 4507 2518 4507 2513 4507 2514 4508 2513 4508 2519 4508 2504 4509 2519 4509 2520 4509 2505 4510 2520 4510 2521 4510 2517 4511 2512 4511 2518 4511 2515 4512 2522 4512 2523 4512 2515 4513 2523 4513 2501 4513 2501 4514 2523 4514 2524 4514 2501 4515 2524 4515 2472 4515 2522 4516 2525 4516 2544 4516 2522 4517 2544 4517 2523 4517 2523 4518 2544 4518 2545 4518 2523 4519 2545 4519 2524 4519 2524 4520 2545 4520 2526 4520 2528 4521 2529 4521 2530 4521 2530 4522 2529 4522 2531 4522 2530 4523 2532 4523 2533 4523 2530 4524 2533 4524 2535 4524 2527 4525 2528 4525 2534 4525 2534 4526 2528 4526 2530 4526 2534 4527 2530 4527 2535 4527 2536 4528 2535 4528 2533 4528 2192 4529 2527 4529 2534 4529 2534 4530 2535 4530 2537 4530 2537 4531 2535 4531 2536 4531 2192 4532 2534 4532 2537 4532 2537 4533 2536 4533 2538 4533 2529 4534 2528 4534 2527 4534 2539 4535 2538 4535 2540 4535 2540 4536 2538 4536 2536 4536 2540 4537 2536 4537 2541 4537 2541 4538 2536 4538 2533 4538 2541 4539 2533 4539 2542 4539 2543 4540 2540 4540 2541 4540 2543 4541 2541 4541 2542 4541 2544 4542 2539 4542 2540 4542 2544 4543 2540 4543 2545 4543 2545 4544 2540 4544 2543 4544 2546 4545 2543 4545 2542 4545 2545 4546 2543 4546 2546 4546 2525 4547 2539 4547 2544 4547 2545 4548 2546 4548 2526 4548 2632 4549 1799 4549 1804 4549 2575 4550 2487 4550 2574 4550 2547 4551 1803 4551 1799 4551 2551 4552 1810 4552 1811 4552 1809 4553 2552 4553 1807 4553 2554 4554 1801 4554 2553 4554 2553 4555 1801 4555 2550 4555 2550 4556 1801 4556 1802 4556 2554 4557 2553 4557 2581 4557 2580 4558 2554 4558 2581 4558 2577 4559 2581 4559 2553 4559 2555 4560 2550 4560 1802 4560 2555 4561 1802 4561 2547 4561 2547 4562 1802 4562 1803 4562 2556 4563 2552 4563 1809 4563 2549 4564 2583 4564 2562 4564 2562 4565 2583 4565 2557 4565 2567 4566 2561 4566 2562 4566 2564 4567 2568 4567 2586 4567 2569 4568 2586 4568 2570 4568 2585 4569 2570 4569 2574 4569 2572 4570 2571 4570 2573 4570 2572 4571 2573 4571 2574 4571 2574 4572 2573 4572 2575 4572 2575 4573 2573 4573 2576 4573 2491 4574 2577 4574 2578 4574 2578 4575 2577 4575 2579 4575 2573 4576 2580 4576 2576 4576 2576 4577 2580 4577 2581 4577 2576 4578 2581 4578 2491 4578 2491 4579 2581 4579 2577 4579 2556 4580 1809 4580 1810 4580 2558 4581 2556 4581 2551 4581 2551 4582 2556 4582 1810 4582 2558 4583 2551 4583 2557 4583 2584 4584 2559 4584 2548 4584 2562 4585 2557 4585 2560 4585 2560 4586 2557 4586 2551 4586 2584 4587 2548 4587 2563 4587 2563 4588 2548 4588 2561 4588 2561 4589 2548 4589 2549 4589 2551 4590 1811 4590 2560 4590 2560 4591 2567 4591 2562 4591 2549 4592 2562 4592 2561 4592 2563 4593 2564 4593 2584 4593 2584 4594 2564 4594 2565 4594 2585 4595 2566 4595 2570 4595 2570 4596 2566 4596 2484 4596 2484 4597 2565 4597 2586 4597 2586 4598 2565 4598 2564 4598 2585 4599 2574 4599 2486 4599 2486 4600 2574 4600 2487 4600 2567 4601 2568 4601 2561 4601 2561 4602 2568 4602 2563 4602 2563 4603 2568 4603 2564 4603 2586 4604 2569 4604 2484 4604 2484 4605 2569 4605 2570 4605 2574 4606 2570 4606 2572 4606 2572 4607 2570 4607 2571 4607 2571 4608 2570 4608 2586 4608 2571 4609 2586 4609 2568 4609 2579 4610 2550 4610 2582 4610 2582 4611 2550 4611 2555 4611 2550 4612 2579 4612 2553 4612 2553 4613 2579 4613 2577 4613 2580 4614 2573 4614 2554 4614 2554 4615 2573 4615 2571 4615 2120 4616 2119 4616 2121 4616 2589 4617 1637 4617 1625 4617 2589 4618 1625 4618 1772 4618 2121 4619 1772 4619 1775 4619 2123 4620 2588 4620 2587 4620 2123 4621 2587 4621 2124 4621 1639 4622 1637 4622 2589 4622 2119 4623 1639 4623 2589 4623 2119 4624 2589 4624 1772 4624 2119 4625 1772 4625 2121 4625 2120 4626 2121 4626 1775 4626 2120 4627 1775 4627 2122 4627 2122 4628 1775 4628 2588 4628 2122 4629 2588 4629 2123 4629 1604 4630 1590 4630 1592 4630 1604 4631 1759 4631 1590 4631 1603 4632 1600 4632 1604 4632 1604 4633 1600 4633 1607 4633 1604 4634 1607 4634 2276 4634 1759 4635 1604 4635 2276 4635 1759 4636 2276 4636 1758 4636 1758 4637 2276 4637 2274 4637 2590 4638 2274 4638 2281 4638 1758 4639 2274 4639 2590 4639 2281 4640 2273 4640 2590 4640 2590 4641 2273 4641 2591 4641 2167 4642 1694 4642 1690 4642 2167 4643 1742 4643 1744 4643 2167 4644 1744 4644 1694 4644 1694 4645 1744 4645 1698 4645 2165 4646 2592 4646 1742 4646 2594 4647 2593 4647 2164 4647 2164 4648 2593 4648 2592 4648 2164 4649 2592 4649 2165 4649 2165 4650 1742 4650 2166 4650 2166 4651 1742 4651 2167 4651 1659 4652 1658 4652 1663 4652 2597 4653 1659 4653 1663 4653 2226 4654 1654 4654 1659 4654 2226 4655 1659 4655 2597 4655 2597 4656 1663 4656 1721 4656 2227 4657 2226 4657 2597 4657 2227 4658 2597 4658 1721 4658 2227 4659 1721 4659 1724 4659 2228 4660 2227 4660 1724 4660 2228 4661 1724 4661 1723 4661 2229 4662 2228 4662 2596 4662 2596 4663 2228 4663 1723 4663 2231 4664 2229 4664 2596 4664 2231 4665 2596 4665 2595 4665 2133 4666 2598 4666 2144 4666 2144 4667 2598 4667 2599 4667 2144 4668 2599 4668 2146 4668 2146 4669 2599 4669 2600 4669 2146 4670 2600 4670 2145 4670 2145 4671 2600 4671 2147 4671 2147 4672 2600 4672 2601 4672 2147 4673 2601 4673 2148 4673 2148 4674 2601 4674 2149 4674 2602 4675 2159 4675 2163 4675 2602 4676 2163 4676 2161 4676 2602 4677 2161 4677 2603 4677 2603 4678 2161 4678 2162 4678 2603 4679 2162 4679 2604 4679 2604 4680 2162 4680 2160 4680 2604 4681 2160 4681 2605 4681 2605 4682 2160 4682 2150 4682 2258 4683 2606 4683 2267 4683 2267 4684 2606 4684 2270 4684 2270 4685 2606 4685 2607 4685 2270 4686 2607 4686 2268 4686 2268 4687 2607 4687 2608 4687 2268 4688 2608 4688 2269 4688 2269 4689 2608 4689 2609 4689 2269 4690 2609 4690 2266 4690 2610 4691 2255 4691 2254 4691 2610 4692 2254 4692 2253 4692 2610 4693 2253 4693 2611 4693 2611 4694 2253 4694 2251 4694 2611 4695 2251 4695 2252 4695 2611 4696 2252 4696 2612 4696 2612 4697 2252 4697 2241 4697 2392 4698 2391 4698 2613 4698 2614 4699 2402 4699 2385 4699 2402 4700 2614 4700 2387 4700 2390 4701 2388 4701 2615 4701 2394 4702 2108 4702 2393 4702 2108 4703 2392 4703 2110 4703 2613 4704 2110 4704 2392 4704 2614 4705 2618 4705 2387 4705 2387 4706 2618 4706 2619 4706 2387 4707 2619 4707 2388 4707 2388 4708 2619 4708 2615 4708 2615 4709 2620 4709 2390 4709 2390 4710 2620 4710 2391 4710 2391 4711 2620 4711 2613 4711 2614 4712 1797 4712 2618 4712 2620 4713 2621 4713 2613 4713 2613 4714 2621 4714 2116 4714 2613 4715 2116 4715 2113 4715 2618 4716 2616 4716 2619 4716 2619 4717 2616 4717 2622 4717 2619 4718 2622 4718 2615 4718 2615 4719 2622 4719 2620 4719 1797 4720 1798 4720 2618 4720 2618 4721 1798 4721 2616 4721 2623 4722 2118 4722 2116 4722 2622 4723 2616 4723 2617 4723 2622 4724 2617 4724 2620 4724 2620 4725 2617 4725 2623 4725 2620 4726 2623 4726 2621 4726 2621 4727 2623 4727 2116 4727 2617 4728 1627 4728 2623 4728 2623 4729 1627 4729 1634 4729 1646 4730 2118 4730 1634 4730 1634 4731 2118 4731 2623 4731 2616 4732 1620 4732 2617 4732 1620 4733 1631 4733 2617 4733 2617 4734 1631 4734 1627 4734 1798 4735 1618 4735 1620 4735 1798 4736 1620 4736 2616 4736 2311 4737 2310 4737 2287 4737 2624 4738 2315 4738 2314 4738 2324 4739 2315 4739 2625 4739 2289 4740 2291 4740 2293 4740 2293 4741 2313 4741 2312 4741 2293 4742 2312 4742 2289 4742 1790 4743 2625 4743 1787 4743 1787 4744 2625 4744 1788 4744 2629 4745 2631 4745 2628 4745 2628 4746 2631 4746 2630 4746 2628 4747 2630 4747 2627 4747 2627 4748 2296 4748 2297 4748 1788 4749 2625 4749 2624 4749 1788 4750 2624 4750 2629 4750 2629 4751 2624 4751 2631 4751 2627 4752 2630 4752 2626 4752 2627 4753 2626 4753 2296 4753 2293 4754 2626 4754 2630 4754 2293 4755 2630 4755 2313 4755 2313 4756 2630 4756 2631 4756 2313 4757 2631 4757 2314 4757 2314 4758 2631 4758 2624 4758 2315 4759 2624 4759 2625 4759 2324 4760 2625 4760 1790 4760 2324 4761 1790 4761 2309 4761 2297 4762 1606 4762 2627 4762 2627 4763 1606 4763 1605 4763 2627 4764 1605 4764 1591 4764 1579 4765 1788 4765 1587 4765 1587 4766 1788 4766 2629 4766 1587 4767 2629 4767 1599 4767 1599 4768 2629 4768 2628 4768 2627 4769 1591 4769 1595 4769 2627 4770 1595 4770 2628 4770 2628 4771 1595 4771 1599 4771 2632 4772 2446 4772 2466 4772 2446 4773 2632 4773 2447 4773 2447 4774 2632 4774 2448 4774 2217 4775 2453 4775 2456 4775 2216 4776 2217 4776 2456 4776 2456 4777 2459 4777 2636 4777 2456 4778 2636 4778 2214 4778 2456 4779 2214 4779 2216 4779 2632 4780 2638 4780 2448 4780 2450 4781 2448 4781 2639 4781 2450 4782 2639 4782 2459 4782 2636 4783 2459 4783 2637 4783 2636 4784 2637 4784 2214 4784 2638 4785 2640 4785 2448 4785 2448 4786 2640 4786 2639 4786 2459 4787 2639 4787 2637 4787 2632 4788 1804 4788 2638 4788 2639 4789 2635 4789 2637 4789 2637 4790 2224 4790 2214 4790 2635 4791 2211 4791 2224 4791 2640 4792 2633 4792 2639 4792 2639 4793 2633 4793 2634 4793 2639 4794 2634 4794 2635 4794 2637 4795 2635 4795 2224 4795 1804 4796 1805 4796 2638 4796 2638 4797 1805 4797 2640 4797 2640 4798 1805 4798 2633 4798 2633 4799 1805 4799 1667 4799 2634 4800 1665 4800 2635 4800 1665 4801 1661 4801 2635 4801 2635 4802 1661 4802 1657 4802 1657 4803 2211 4803 2635 4803 2633 4804 1667 4804 1665 4804 2633 4805 1665 4805 2634 4805 1805 4806 1668 4806 1667 4806 1805 4807 1675 4807 1668 4807 2192 4808 2187 4808 2527 4808 2186 4809 2529 4809 2527 4809 2186 4810 2527 4810 2187 4810 2530 4811 2642 4811 2532 4811 2643 4812 2533 4812 2532 4812 2546 4813 2641 4813 2526 4813 2529 4814 2183 4814 2531 4814 2183 4815 2181 4815 2531 4815 2531 4816 2181 4816 2180 4816 2180 4817 2645 4817 2531 4817 2642 4818 2530 4818 2531 4818 2646 4819 2645 4819 1683 4819 1808 4820 2641 4820 2649 4820 1808 4821 2649 4821 2644 4821 2644 4822 2649 4822 2643 4822 2644 4823 2643 4823 2647 4823 2647 4824 2643 4824 2648 4824 2648 4825 2645 4825 2646 4825 2641 4826 2542 4826 2649 4826 2649 4827 2542 4827 2533 4827 2649 4828 2533 4828 2643 4828 2642 4829 2531 4829 2645 4829 2643 4830 2532 4830 2648 4830 2648 4831 2532 4831 2642 4831 2648 4832 2642 4832 2645 4832 2542 4833 2641 4833 2546 4833 1683 4834 1692 4834 2646 4834 1709 4835 2644 4835 1696 4835 1696 4836 2644 4836 2647 4836 1696 4837 2647 4837 1703 4837 1692 4838 1700 4838 2646 4838 2646 4839 1700 4839 2648 4839 2648 4840 1700 4840 2647 4840 2647 4841 1700 4841 1703 4841 2106 4842 2395 4842 2393 4842 2106 4843 2393 4843 2108 4843 2110 4844 2613 4844 2113 4844 2311 4845 2287 4845 2289 4845 2289 4846 2288 4846 2291 4846 2217 4847 2222 4847 2453 4847 1910 4848 2100 4848 1934 4848 1859 4849 1849 4849 1910 4849 1910 4850 1849 4850 2100 4850 1815 4851 2299 4851 1849 4851 1859 4852 1910 4852 1906 4852 1887 4853 1856 4853 1905 4853 1905 4854 1856 4854 1859 4854 2395 4855 2318 4855 2321 4855 2301 4856 2310 4856 2318 4856 2395 4857 2321 4857 2398 4857 2322 4858 2389 4858 2321 4858 2321 4859 2389 4859 2398 4859 2389 4860 2322 4860 2308 4860 2389 4861 2308 4861 2384 4861 2328 4862 2381 4862 2384 4862 2328 4863 2384 4863 2308 4863 2100 4864 1849 4864 2299 4864 2100 4865 2299 4865 2099 4865 2099 4866 2299 4866 2302 4866 2099 4867 2302 4867 2101 4867 2101 4868 2302 4868 2300 4868 2101 4869 2300 4869 2102 4869 2102 4870 2300 4870 2301 4870 2102 4871 2301 4871 2395 4871 2395 4872 2301 4872 2318 4872 2538 4873 2458 4873 2537 4873 2192 4874 2537 4874 2458 4874 2192 4875 2458 4875 2455 4875 2458 4876 2538 4876 2539 4876 2539 4877 2464 4877 2449 4877 2458 4878 2539 4878 2449 4878 2464 4879 2539 4879 2525 4879 2522 4880 2467 4880 2525 4880 2525 4881 2467 4881 2464 4881 1932 4882 1953 4882 2189 4882 2189 4883 1953 4883 1991 4883 1932 4884 1925 4884 1953 4884 1953 4885 1925 4885 1942 4885 1916 4886 1941 4886 1925 4886 1916 4887 1924 4887 1941 4887 1925 4888 1941 4888 1942 4888 2192 4889 2455 4889 2451 4889 2192 4890 2451 4890 2190 4890 2190 4891 2451 4891 2205 4891 2190 4892 2205 4892 2191 4892 2191 4893 2205 4893 2208 4893 2191 4894 2208 4894 2193 4894 2193 4895 2208 4895 2207 4895 2193 4896 2207 4896 2189 4896 2189 4897 2207 4897 2206 4897 2189 4898 2206 4898 1932 4898 1932 4899 2206 4899 1899 4899 2650 4900 2651 4900 2652 4900 2650 4901 2652 4901 2653 4901 2653 4902 2652 4902 2654 4902 2653 4903 2654 4903 2655 4903 2653 4904 2655 4904 2656 4904 2656 4905 2655 4905 2657 4905 2656 4906 2657 4906 2658 4906 2658 4907 2657 4907 2659 4907 2658 4908 2659 4908 2660 4908 2660 4909 2659 4909 2661 4909 2660 4910 2661 4910 2662 4910 2662 4911 2661 4911 2663 4911 2662 4912 2663 4912 2664 4912 2664 4913 2663 4913 2665 4913 2664 4914 2665 4914 2666 4914 2666 4915 2665 4915 2667 4915 2666 4916 2667 4916 2668 4916 2668 4917 2667 4917 2669 4917 2668 4918 2669 4918 2670 4918 2670 4919 2669 4919 2671 4919 2670 4920 2671 4920 2672 4920 2672 4921 2671 4921 2651 4921 2672 4922 2651 4922 2650 4922 2664 4923 2673 4923 2674 4923 2664 4924 2674 4924 2662 4924 2662 4925 2675 4925 2660 4925 2660 4926 2675 4926 2658 4926 2658 4927 2675 4927 2676 4927 2662 4928 2674 4928 2675 4928 2658 4929 2676 4929 2656 4929 2656 4930 2676 4930 2678 4930 2656 4931 2678 4931 2679 4931 2656 4932 2679 4932 2653 4932 2653 4933 2679 4933 2677 4933 2653 4934 2677 4934 2650 4934 2673 4935 2664 4935 2666 4935 2673 4936 2666 4936 2680 4936 2680 4937 2666 4937 2668 4937 2681 4938 2680 4938 2670 4938 2670 4939 2680 4939 2668 4939 2681 4940 2670 4940 2682 4940 2682 4941 2670 4941 2672 4941 2682 4942 2672 4942 2650 4942 2682 4943 2650 4943 2677 4943 2683 4944 2684 4944 2685 4944 2685 4945 2684 4945 2686 4945 2685 4946 2686 4946 2687 4946 2685 4947 2687 4947 2688 4947 2688 4948 2687 4948 2689 4948 2688 4949 2689 4949 2690 4949 2690 4950 2689 4950 2691 4950 2691 4951 2689 4951 2692 4951 2691 4952 2692 4952 2693 4952 2691 4953 2693 4953 2694 4953 2694 4954 2693 4954 2695 4954 2694 4955 2695 4955 2696 4955 2696 4956 2695 4956 2697 4956 2696 4957 2697 4957 2698 4957 2698 4958 2697 4958 2699 4958 2698 4959 2699 4959 2700 4959 2700 4960 2699 4960 2701 4960 2700 4961 2701 4961 2702 4961 2702 4962 2701 4962 2703 4962 2702 4963 2703 4963 2704 4963 2704 4964 2703 4964 2705 4964 2704 4965 2705 4965 2706 4965 2706 4966 2705 4966 2683 4966 2683 4967 2705 4967 2684 4967 2706 4968 2683 4968 2707 4968 2707 4969 2683 4969 2708 4969 2694 4970 2709 4970 2712 4970 2694 4971 2712 4971 2691 4971 2708 4972 2683 4972 2685 4972 2708 4973 2685 4973 2710 4973 2710 4974 2685 4974 2688 4974 2710 4975 2688 4975 2711 4975 2711 4976 2688 4976 2690 4976 2711 4977 2690 4977 2691 4977 2711 4978 2691 4978 2712 4978 2706 4979 2707 4979 2713 4979 2706 4980 2713 4980 2704 4980 2704 4981 2713 4981 2714 4981 2704 4982 2714 4982 2702 4982 2702 4983 2714 4983 2700 4983 2700 4984 2715 4984 2698 4984 2698 4985 2715 4985 2716 4985 2698 4986 2716 4986 2696 4986 2696 4987 2716 4987 2709 4987 2696 4988 2709 4988 2694 4988 2715 4989 2700 4989 2714 4989 2717 4990 2741 4990 2718 4990 2717 4991 2718 4991 2719 4991 2717 4992 2719 4992 2720 4992 2720 4993 2719 4993 2721 4993 2720 4994 2721 4994 2722 4994 2722 4995 2721 4995 2723 4995 2722 4996 2723 4996 2724 4996 2724 4997 2723 4997 2725 4997 2724 4998 2725 4998 2726 4998 2726 4999 2725 4999 2727 4999 2726 5000 2727 5000 2728 5000 2728 5001 2727 5001 2729 5001 2729 5002 2727 5002 2730 5002 2729 5003 2730 5003 2731 5003 2729 5004 2731 5004 2732 5004 2732 5005 2731 5005 2733 5005 2733 5006 2731 5006 2734 5006 2733 5007 2734 5007 2735 5007 2733 5008 2735 5008 2736 5008 2736 5009 2735 5009 2737 5009 2736 5010 2737 5010 2738 5010 2738 5011 2737 5011 2739 5011 2738 5012 2739 5012 2740 5012 2740 5013 2739 5013 2718 5013 2740 5014 2718 5014 2741 5014 2742 5015 2743 5015 2729 5015 2729 5016 2743 5016 2728 5016 2728 5017 2743 5017 2726 5017 2726 5018 2743 5018 2744 5018 2742 5019 2729 5019 2732 5019 2742 5020 2732 5020 2745 5020 2744 5021 2746 5021 2726 5021 2726 5022 2746 5022 2724 5022 2724 5023 2746 5023 2722 5023 2722 5024 2746 5024 2747 5024 2722 5025 2747 5025 2720 5025 2720 5026 2747 5026 2748 5026 2720 5027 2748 5027 2717 5027 2717 5028 2748 5028 2749 5028 2750 5029 2738 5029 2740 5029 2750 5030 2740 5030 2751 5030 2751 5031 2740 5031 2741 5031 2751 5032 2741 5032 2749 5032 2749 5033 2741 5033 2717 5033 2738 5034 2750 5034 2752 5034 2745 5035 2732 5035 2733 5035 2745 5036 2733 5036 2753 5036 2753 5037 2733 5037 2736 5037 2753 5038 2736 5038 2752 5038 2752 5039 2736 5039 2738 5039 2755 5040 2756 5040 2754 5040 2754 5041 2756 5041 2757 5041 2757 5042 2756 5042 2758 5042 2757 5043 2758 5043 2759 5043 2759 5044 2758 5044 2760 5044 2759 5045 2760 5045 2761 5045 2761 5046 2760 5046 2762 5046 2761 5047 2762 5047 2763 5047 2763 5048 2762 5048 2764 5048 2763 5049 2764 5049 2765 5049 2765 5050 2764 5050 2766 5050 2765 5051 2766 5051 2767 5051 2767 5052 2766 5052 2768 5052 2767 5053 2768 5053 2769 5053 2769 5054 2768 5054 2770 5054 2769 5055 2770 5055 2771 5055 2771 5056 2770 5056 2772 5056 2772 5057 2770 5057 2773 5057 2772 5058 2773 5058 2774 5058 2774 5059 2773 5059 2775 5059 2774 5060 2775 5060 2776 5060 2776 5061 2775 5061 2777 5061 2776 5062 2777 5062 2778 5062 2778 5063 2777 5063 2755 5063 2778 5064 2755 5064 2754 5064 2789 5065 2754 5065 2779 5065 2779 5066 2754 5066 2757 5066 2779 5067 2757 5067 2780 5067 2780 5068 2757 5068 2759 5068 2780 5069 2759 5069 2781 5069 2781 5070 2759 5070 2761 5070 2781 5071 2761 5071 2782 5071 2782 5072 2761 5072 2763 5072 2782 5073 2763 5073 2783 5073 2783 5074 2763 5074 2765 5074 2783 5075 2765 5075 2784 5075 2784 5076 2765 5076 2767 5076 2784 5077 2767 5077 2769 5077 2784 5078 2769 5078 2785 5078 2785 5079 2769 5079 2786 5079 2786 5080 2769 5080 2771 5080 2786 5081 2771 5081 2772 5081 2786 5082 2772 5082 2787 5082 2787 5083 2772 5083 2774 5083 2787 5084 2774 5084 2788 5084 2788 5085 2774 5085 2776 5085 2788 5086 2776 5086 2778 5086 2788 5087 2778 5087 2789 5087 2789 5088 2778 5088 2754 5088 2515 5089 2806 5089 2522 5089 2522 5090 2806 5090 2791 5090 2522 5091 2791 5091 2790 5091 2815 5092 2792 5092 2800 5092 2794 5093 2795 5093 2515 5093 2796 5094 2797 5094 2806 5094 2808 5095 2799 5095 2800 5095 2800 5096 2799 5096 2826 5096 2803 5097 2804 5097 2805 5097 2511 5098 2820 5098 2515 5098 2515 5099 2820 5099 2794 5099 2813 5100 2806 5100 2798 5100 2802 5101 2801 5101 2807 5101 2802 5102 2807 5102 2808 5102 2809 5103 2810 5103 2811 5103 2800 5104 2816 5104 2808 5104 2808 5105 2816 5105 2802 5105 2515 5106 2795 5106 2796 5106 2515 5107 2796 5107 2806 5107 2806 5108 2797 5108 2798 5108 2808 5109 2807 5109 2813 5109 2808 5110 2813 5110 2814 5110 2814 5111 2813 5111 2798 5111 2812 5112 2815 5112 2800 5112 2800 5113 2792 5113 2816 5113 2803 5114 2805 5114 2817 5114 2522 5115 2790 5115 2793 5115 2522 5116 2793 5116 2467 5116 2467 5117 2818 5117 2819 5117 2521 5118 2822 5118 2820 5118 2521 5119 2820 5119 2511 5119 2802 5120 2821 5120 2801 5120 2809 5121 2822 5121 2521 5121 2793 5122 2804 5122 2467 5122 2823 5123 2516 5123 2824 5123 2824 5124 2516 5124 2829 5124 2812 5125 2800 5125 2825 5125 2811 5126 2826 5126 2799 5126 2803 5127 2817 5127 2827 5127 2803 5128 2827 5128 2821 5128 2821 5129 2827 5129 2801 5129 2804 5130 2803 5130 2467 5130 2467 5131 2803 5131 2818 5131 2809 5132 2811 5132 2799 5132 2467 5133 2819 5133 2829 5133 2467 5134 2829 5134 2516 5134 2828 5135 2513 5135 2830 5135 2516 5136 2823 5136 2812 5136 2831 5137 2834 5137 2516 5137 2513 5138 2828 5138 2519 5138 2831 5139 2516 5139 2812 5139 2831 5140 2812 5140 2825 5140 2519 5141 2828 5141 2832 5141 2830 5142 2513 5142 2833 5142 2833 5143 2513 5143 2518 5143 2833 5144 2518 5144 2834 5144 2834 5145 2518 5145 2512 5145 2834 5146 2512 5146 2516 5146 2810 5147 2809 5147 2521 5147 2810 5148 2521 5148 2520 5148 2810 5149 2520 5149 2835 5149 2835 5150 2520 5150 2519 5150 2835 5151 2519 5151 2832 5151 1799 5152 2471 5152 2497 5152 1799 5153 2497 5153 2547 5153 2547 5154 2497 5154 2496 5154 2547 5155 2496 5155 2555 5155 2555 5156 2496 5156 2495 5156 2555 5157 2495 5157 2582 5157 2582 5158 2495 5158 2494 5158 2582 5159 2494 5159 2579 5159 2579 5160 2494 5160 2493 5160 2579 5161 2493 5161 2492 5161 2579 5162 2492 5162 2578 5162 2578 5163 2492 5163 2491 5163 2491 5164 2489 5164 2576 5164 2576 5165 2489 5165 2575 5165 2575 5166 2489 5166 2488 5166 2575 5167 2488 5167 2487 5167 2585 5168 2486 5168 2566 5168 2566 5169 2486 5169 2485 5169 2566 5170 2485 5170 2484 5170 2565 5171 2484 5171 2482 5171 2565 5172 2482 5172 2481 5172 2565 5173 2481 5173 2584 5173 2584 5174 2481 5174 2559 5174 2559 5175 2481 5175 2480 5175 2559 5176 2480 5176 2548 5176 2548 5177 2480 5177 2479 5177 2548 5178 2479 5178 2478 5178 2548 5179 2478 5179 2549 5179 2549 5180 2478 5180 2583 5180 2583 5181 2478 5181 2477 5181 2583 5182 2477 5182 2557 5182 2557 5183 2477 5183 2476 5183 2557 5184 2476 5184 2558 5184 2558 5185 2476 5185 2475 5185 2558 5186 2475 5186 2556 5186 2556 5187 2475 5187 2473 5187 2556 5188 2473 5188 2552 5188 2552 5189 2473 5189 2474 5189 2552 5190 2474 5190 1807 5190 1807 5191 2474 5191 2472 5191 2471 5192 1799 5192 2466 5192 2466 5193 1799 5193 2632 5193 2641 5194 1808 5194 1807 5194 2524 5195 2526 5195 2641 5195 2524 5196 2641 5196 1807 5196 2524 5197 1807 5197 2472 5197 1692 5198 1683 5198 1680 5198 2837 5199 2836 5199 2838 5199 2837 5200 2838 5200 2839 5200 2840 5201 2841 5201 2842 5201 2842 5202 2841 5202 2843 5202 2843 5203 2841 5203 2844 5203 2843 5204 2844 5204 2845 5204 2839 5205 2838 5205 2844 5205 2844 5206 2838 5206 2845 5206 2840 5207 2842 5207 2846 5207 2840 5208 2846 5208 2847 5208 2847 5209 2846 5209 2848 5209 2847 5210 2848 5210 2849 5210 2847 5211 2849 5211 2850 5211 2850 5212 2849 5212 2851 5212 2851 5213 2849 5213 2852 5213 2851 5214 2852 5214 2853 5214 2853 5215 2852 5215 2854 5215 2836 5216 2837 5216 2855 5216 2836 5217 2855 5217 2856 5217 2856 5218 2855 5218 2857 5218 2856 5219 2857 5219 2858 5219 2858 5220 2857 5220 2854 5220 2854 5221 2857 5221 2853 5221 2858 5222 2859 5222 2856 5222 2856 5223 2859 5223 2860 5223 2856 5224 2860 5224 2836 5224 2836 5225 2860 5225 2861 5225 2836 5226 2861 5226 2838 5226 2838 5227 2861 5227 2862 5227 2838 5228 2862 5228 2845 5228 2845 5229 2862 5229 2843 5229 2843 5230 2862 5230 2863 5230 2843 5231 2863 5231 2842 5231 2842 5232 2863 5232 2864 5232 2842 5233 2864 5233 2846 5233 2846 5234 2864 5234 2865 5234 2846 5235 2865 5235 2848 5235 2848 5236 2865 5236 2866 5236 2848 5237 2866 5237 2849 5237 2849 5238 2866 5238 2867 5238 2849 5239 2867 5239 2852 5239 2852 5240 2867 5240 2868 5240 2852 5241 2868 5241 2854 5241 2854 5242 2868 5242 2869 5242 2854 5243 2869 5243 2858 5243 2858 5244 2869 5244 2859 5244 2871 5245 2870 5245 2872 5245 2871 5246 2872 5246 2873 5246 2871 5247 2874 5247 2870 5247 2870 5248 2874 5248 2875 5248 2875 5249 2874 5249 2876 5249 2875 5250 2876 5250 2890 5250 2878 5251 2877 5251 2879 5251 2878 5252 2879 5252 2880 5252 2880 5253 2879 5253 2873 5253 2873 5254 2872 5254 2880 5254 2877 5255 2878 5255 2881 5255 2877 5256 2881 5256 2882 5256 2882 5257 2881 5257 2883 5257 2883 5258 2881 5258 2884 5258 2883 5259 2884 5259 2885 5259 2885 5260 2884 5260 2886 5260 2885 5261 2886 5261 2887 5261 2887 5262 2886 5262 2888 5262 2887 5263 2888 5263 2889 5263 2889 5264 2888 5264 2890 5264 2889 5265 2890 5265 2876 5265 2890 5266 2891 5266 2875 5266 2875 5267 2891 5267 2892 5267 2875 5268 2892 5268 2870 5268 2870 5269 2892 5269 2893 5269 2870 5270 2893 5270 2872 5270 2872 5271 2893 5271 2894 5271 2872 5272 2894 5272 2880 5272 2880 5273 2894 5273 2895 5273 2880 5274 2895 5274 2896 5274 2880 5275 2896 5275 2878 5275 2878 5276 2896 5276 2881 5276 2881 5277 2896 5277 2897 5277 2881 5278 2897 5278 2898 5278 2881 5279 2898 5279 2884 5279 2884 5280 2898 5280 2899 5280 2884 5281 2899 5281 2886 5281 2886 5282 2899 5282 2900 5282 2886 5283 2900 5283 2888 5283 2888 5284 2900 5284 2901 5284 2888 5285 2901 5285 2890 5285 2890 5286 2901 5286 2902 5286 2890 5287 2902 5287 2891 5287 2903 5288 2904 5288 2905 5288 2905 5289 2904 5289 2906 5289 2905 5290 2906 5290 2907 5290 2909 5291 2908 5291 2910 5291 2909 5292 2910 5292 2911 5292 2911 5293 2910 5293 2907 5293 2911 5294 2907 5294 2906 5294 2909 5295 2912 5295 2908 5295 2908 5296 2912 5296 2913 5296 2913 5297 2912 5297 2914 5297 2913 5298 2914 5298 2915 5298 2913 5299 2915 5299 2916 5299 2916 5300 2915 5300 2917 5300 2916 5301 2917 5301 2918 5301 2918 5302 2917 5302 2919 5302 2918 5303 2919 5303 2920 5303 2920 5304 2919 5304 2921 5304 2920 5305 2921 5305 2922 5305 2922 5306 2921 5306 2923 5306 2903 5307 2905 5307 2924 5307 2903 5308 2924 5308 2925 5308 2925 5309 2924 5309 2926 5309 2925 5310 2926 5310 2923 5310 2923 5311 2926 5311 2922 5311 2923 5312 2927 5312 2925 5312 2925 5313 2927 5313 2903 5313 2903 5314 2927 5314 2928 5314 2903 5315 2928 5315 2904 5315 2904 5316 2928 5316 2929 5316 2904 5317 2929 5317 2906 5317 2906 5318 2929 5318 2911 5318 2911 5319 2929 5319 2930 5319 2911 5320 2930 5320 2909 5320 2909 5321 2930 5321 2931 5321 2909 5322 2931 5322 2912 5322 2912 5323 2931 5323 2932 5323 2912 5324 2932 5324 2914 5324 2914 5325 2932 5325 2933 5325 2914 5326 2933 5326 2915 5326 2915 5327 2933 5327 2934 5327 2915 5328 2934 5328 2917 5328 2917 5329 2934 5329 2935 5329 2917 5330 2935 5330 2919 5330 2919 5331 2935 5331 2936 5331 2919 5332 2936 5332 2921 5332 2921 5333 2936 5333 2937 5333 2921 5334 2937 5334 2923 5334 2923 5335 2937 5335 2927 5335 2950 5336 2938 5336 2939 5336 2941 5337 2940 5337 2939 5337 2941 5338 2939 5338 2938 5338 2943 5339 2942 5339 2944 5339 2946 5340 2945 5340 2947 5340 2946 5341 2947 5341 2948 5341 2948 5342 2947 5342 2949 5342 2948 5343 2949 5343 2943 5343 2943 5344 2949 5344 2942 5344 2942 5345 2950 5345 2944 5345 2944 5346 2950 5346 2939 5346 2951 5347 2952 5347 2953 5347 2951 5348 2953 5348 2954 5348 2954 5349 2953 5349 2955 5349 2955 5350 2953 5350 2956 5350 2955 5351 2956 5351 2957 5351 2957 5352 2956 5352 2945 5352 2957 5353 2945 5353 2946 5353 2940 5354 2941 5354 2958 5354 2958 5355 2941 5355 2959 5355 2958 5356 2959 5356 2960 5356 2958 5357 2960 5357 2961 5357 2961 5358 2960 5358 2951 5358 2951 5359 2960 5359 2952 5359 2961 5360 2962 5360 2963 5360 2961 5361 2963 5361 2958 5361 2958 5362 2963 5362 2964 5362 2958 5363 2964 5363 2940 5363 2940 5364 2964 5364 2965 5364 2940 5365 2965 5365 2939 5365 2939 5366 2965 5366 2966 5366 2939 5367 2966 5367 2944 5367 2944 5368 2966 5368 2967 5368 2944 5369 2967 5369 2943 5369 2943 5370 2967 5370 2968 5370 2943 5371 2968 5371 2948 5371 2948 5372 2968 5372 2969 5372 2948 5373 2969 5373 2946 5373 2946 5374 2969 5374 2970 5374 2946 5375 2970 5375 2957 5375 2957 5376 2970 5376 2971 5376 2957 5377 2971 5377 2955 5377 2955 5378 2971 5378 2972 5378 2955 5379 2972 5379 2954 5379 2954 5380 2972 5380 2973 5380 2954 5381 2973 5381 2951 5381 2951 5382 2973 5382 2962 5382 2951 5383 2962 5383 2961 5383 2965 5384 2860 5384 2859 5384 2965 5385 2859 5385 2966 5385 2968 5386 2967 5386 2859 5386 2968 5387 2859 5387 2869 5387 2859 5388 2967 5388 2966 5388 2927 5389 2937 5389 1786 5389 2869 5390 2969 5390 2968 5390 2862 5391 2861 5391 2408 5391 2408 5392 2861 5392 1615 5392 2962 5393 1615 5393 2963 5393 1615 5394 2927 5394 1786 5394 2937 5395 2936 5395 1786 5395 1786 5396 2936 5396 2935 5396 1615 5397 2964 5397 2963 5397 2929 5398 2972 5398 2971 5398 2929 5399 2971 5399 2970 5399 2931 5400 2930 5400 2429 5400 2929 5401 2928 5401 2972 5401 2435 5402 2895 5402 2413 5402 2413 5403 2895 5403 2894 5403 2413 5404 2894 5404 2411 5404 2411 5405 2894 5405 2408 5405 2408 5406 2894 5406 2893 5406 2902 5407 2969 5407 2891 5407 1615 5408 2972 5408 2927 5408 2927 5409 2972 5409 2928 5409 1615 5410 2962 5410 2973 5410 1615 5411 2973 5411 2972 5411 1786 5412 2935 5412 1793 5412 1793 5413 2935 5413 2934 5413 2934 5414 2933 5414 1793 5414 2931 5415 2429 5415 2932 5415 2932 5416 2429 5416 2423 5416 2932 5417 2423 5417 2933 5417 2933 5418 2423 5418 1793 5418 2969 5419 2869 5419 2868 5419 2861 5420 2860 5420 1615 5420 2969 5421 2902 5421 2901 5421 2433 5422 2896 5422 2435 5422 2435 5423 2896 5423 2895 5423 2860 5424 2965 5424 1615 5424 1615 5425 2965 5425 2964 5425 2867 5426 2866 5426 2892 5426 2864 5427 2893 5427 2865 5427 2893 5428 2864 5428 2408 5428 2969 5429 2868 5429 2867 5429 2864 5430 2863 5430 2408 5430 2408 5431 2863 5431 2862 5431 2969 5432 2901 5432 2900 5432 2900 5433 2899 5433 2429 5433 2429 5434 2899 5434 2898 5434 2429 5435 2898 5435 2433 5435 2433 5436 2898 5436 2897 5436 2433 5437 2897 5437 2896 5437 2892 5438 2866 5438 2865 5438 2892 5439 2865 5439 2893 5439 2929 5440 2970 5440 2969 5440 2929 5441 2969 5441 2930 5441 2930 5442 2969 5442 2429 5442 2429 5443 2969 5443 2900 5443 2891 5444 2969 5444 2867 5444 2891 5445 2867 5445 2892 5445 2309 5446 1790 5446 1789 5446 2309 5447 1789 5447 2333 5447 1794 5448 2357 5448 2356 5448 1794 5449 2356 5449 2405 5449 2405 5450 2356 5450 2414 5450 2414 5451 2356 5451 2355 5451 2414 5452 2355 5452 2354 5452 2414 5453 2354 5453 2444 5453 2444 5454 2354 5454 2443 5454 2443 5455 2354 5455 2353 5455 2443 5456 2353 5456 2442 5456 2442 5457 2353 5457 2352 5457 2442 5458 2352 5458 2441 5458 2441 5459 2352 5459 2351 5459 2441 5460 2351 5460 2350 5460 2441 5461 2350 5461 2439 5461 2439 5462 2350 5462 2349 5462 2406 5463 2349 5463 2348 5463 2406 5464 2348 5464 2445 5464 2445 5465 2348 5465 2347 5465 2445 5466 2347 5466 2428 5466 2428 5467 2347 5467 2346 5467 2428 5468 2346 5468 2427 5468 2427 5469 2346 5469 2345 5469 2427 5470 2345 5470 2343 5470 2343 5471 2345 5471 2344 5471 2418 5472 2343 5472 2342 5472 2418 5473 2342 5473 2341 5473 2418 5474 2341 5474 2419 5474 2419 5475 2341 5475 2340 5475 2419 5476 2340 5476 2407 5476 2407 5477 2340 5477 2339 5477 2407 5478 2339 5478 2420 5478 2420 5479 2339 5479 2338 5479 2420 5480 2338 5480 2337 5480 2416 5481 2337 5481 2417 5481 2417 5482 2337 5482 2336 5482 2417 5483 2336 5483 2335 5483 2417 5484 2335 5484 2415 5484 2415 5485 2335 5485 2334 5485 2415 5486 2334 5486 2410 5486 2410 5487 2334 5487 1789 5487 1789 5488 2334 5488 2333 5488 1794 5489 1797 5489 2614 5489 2357 5490 1794 5490 2383 5490 2383 5491 1794 5491 2614 5491 2383 5492 2614 5492 2385 5492 2974 5493 2975 5493 2976 5493 2331 5494 2977 5494 2328 5494 2974 5495 2978 5495 2979 5495 2982 5496 2983 5496 2990 5496 2993 5497 2984 5497 2985 5497 2985 5498 2984 5498 2996 5498 2974 5499 2976 5499 2978 5499 2987 5500 2986 5500 2977 5500 2987 5501 2977 5501 2988 5501 2990 5502 2989 5502 2982 5502 3003 5503 2991 5503 2371 5503 2371 5504 2991 5504 2380 5504 2992 5505 2979 5505 2993 5505 2378 5506 2975 5506 2994 5506 2378 5507 2994 5507 2379 5507 2379 5508 2994 5508 2331 5508 2331 5509 2994 5509 2980 5509 2331 5510 2980 5510 2995 5510 2979 5511 2992 5511 2974 5511 2977 5512 2997 5512 2328 5512 2331 5513 2995 5513 2998 5513 2986 5514 2987 5514 2982 5514 2982 5515 2987 5515 2983 5515 2376 5516 3000 5516 3001 5516 2376 5517 3001 5517 2377 5517 2377 5518 3001 5518 3010 5518 2377 5519 3010 5519 2371 5519 2331 5520 2998 5520 2977 5520 2998 5521 3002 5521 2977 5521 2999 5522 3003 5522 2371 5522 2380 5523 2991 5523 3004 5523 2380 5524 3004 5524 2375 5524 2992 5525 2993 5525 2990 5525 2990 5526 2993 5526 2985 5526 3006 5527 3007 5527 2381 5527 2989 5528 2990 5528 2985 5528 3007 5529 3008 5529 2381 5529 2381 5530 3008 5530 2373 5530 2375 5531 3004 5531 2976 5531 2375 5532 2976 5532 2378 5532 2378 5533 2976 5533 2975 5533 2989 5534 2985 5534 3011 5534 2989 5535 3011 5535 3012 5535 3008 5536 3013 5536 2373 5536 2373 5537 3013 5537 3014 5537 2373 5538 3014 5538 2376 5538 2376 5539 3014 5539 3000 5539 2977 5540 3002 5540 2988 5540 2997 5541 3015 5541 2328 5541 2328 5542 3015 5542 2381 5542 2381 5543 3015 5543 2981 5543 3006 5544 3005 5544 3016 5544 3016 5545 3017 5545 3006 5545 3006 5546 3017 5546 3011 5546 2981 5547 3018 5547 2381 5547 2381 5548 3018 5548 3005 5548 3011 5549 3017 5549 3012 5549 2996 5550 2984 5550 3019 5550 2996 5551 3019 5551 3010 5551 3010 5552 3019 5552 3009 5552 3005 5553 3006 5553 2381 5553 2371 5554 3010 5554 3020 5554 2371 5555 3020 5555 2999 5555 3009 5556 3020 5556 3010 5556 1752 5557 1751 5557 31 5557 2023 5558 2038 5558 1853 5558 1853 5559 1894 5559 2016 5559 1853 5560 2016 5560 2019 5560 1853 5561 2038 5561 2039 5561 1853 5562 2019 5562 2021 5562 1853 5563 2021 5563 2023 5563 1915 5564 1890 5564 2057 5564 2057 5565 2042 5565 1915 5565 1915 5566 2042 5566 2043 5566 2062 5567 2060 5567 1890 5567 2060 5568 2057 5568 1890 5568 2150 5569 2149 5569 3021 5569 3021 5570 2149 5570 2601 5570 2605 5571 2150 5571 3022 5571 3022 5572 2150 5572 3021 5572 3022 5573 3021 5573 1134 5573 1134 5574 3021 5574 112 5574 1134 5575 112 5575 111 5575 3023 5576 3046 5576 3024 5576 3023 5577 3024 5577 3025 5577 3025 5578 3024 5578 3026 5578 3025 5579 3026 5579 3027 5579 3027 5580 3026 5580 3028 5580 3027 5581 3028 5581 3029 5581 3029 5582 3028 5582 3030 5582 3029 5583 3030 5583 3031 5583 3031 5584 3030 5584 3032 5584 3031 5585 3032 5585 3033 5585 3033 5586 3032 5586 3034 5586 3033 5587 3034 5587 3035 5587 3035 5588 3034 5588 3036 5588 3036 5589 3034 5589 3037 5589 3036 5590 3037 5590 3038 5590 3038 5591 3037 5591 3039 5591 3038 5592 3039 5592 3040 5592 3038 5593 3040 5593 3041 5593 3041 5594 3040 5594 3042 5594 3042 5595 3040 5595 3043 5595 3042 5596 3043 5596 3044 5596 3044 5597 3043 5597 3045 5597 3044 5598 3045 5598 3046 5598 3044 5599 3046 5599 3023 5599 3023 5600 3047 5600 3048 5600 3023 5601 3048 5601 3044 5601 3044 5602 3048 5602 3049 5602 3044 5603 3049 5603 3042 5603 3042 5604 3049 5604 3041 5604 3041 5605 3049 5605 3050 5605 3041 5606 3050 5606 3038 5606 3038 5607 3050 5607 3051 5607 3038 5608 3051 5608 3036 5608 3036 5609 3051 5609 3052 5609 3036 5610 3052 5610 3035 5610 3035 5611 3052 5611 3053 5611 3035 5612 3053 5612 3033 5612 3033 5613 3053 5613 3054 5613 3033 5614 3054 5614 3031 5614 3031 5615 3054 5615 3055 5615 3031 5616 3055 5616 3029 5616 3029 5617 3055 5617 3027 5617 3027 5618 3055 5618 3056 5618 3027 5619 3056 5619 3057 5619 3027 5620 3057 5620 3025 5620 3025 5621 3057 5621 3047 5621 3025 5622 3047 5622 3023 5622 3058 5623 3059 5623 3060 5623 3060 5624 3059 5624 3061 5624 3060 5625 3061 5625 3062 5625 3062 5626 3061 5626 3063 5626 3063 5627 3061 5627 3064 5627 3063 5628 3064 5628 3065 5628 3065 5629 3064 5629 3066 5629 3065 5630 3066 5630 3067 5630 3067 5631 3066 5631 3068 5631 3067 5632 3068 5632 3069 5632 3069 5633 3068 5633 3070 5633 3070 5634 3068 5634 3071 5634 3070 5635 3071 5635 3072 5635 3072 5636 3071 5636 3073 5636 3072 5637 3073 5637 3074 5637 3072 5638 3074 5638 3075 5638 3075 5639 3074 5639 3076 5639 3075 5640 3076 5640 3077 5640 3077 5641 3076 5641 3078 5641 3078 5642 3076 5642 3079 5642 3078 5643 3079 5643 3080 5643 3080 5644 3079 5644 3081 5644 3080 5645 3081 5645 3058 5645 3058 5646 3081 5646 3059 5646 3069 5647 3082 5647 3067 5647 3067 5648 3082 5648 3083 5648 3067 5649 3083 5649 3065 5649 3065 5650 3083 5650 3084 5650 3065 5651 3084 5651 3063 5651 3069 5652 3070 5652 3082 5652 3082 5653 3070 5653 3085 5653 3085 5654 3070 5654 3072 5654 3085 5655 3072 5655 3086 5655 3086 5656 3072 5656 3075 5656 3086 5657 3075 5657 3087 5657 3087 5658 3075 5658 3077 5658 3087 5659 3077 5659 3078 5659 3087 5660 3078 5660 3088 5660 3088 5661 3078 5661 3080 5661 3088 5662 3080 5662 3089 5662 3089 5663 3080 5663 3058 5663 3089 5664 3058 5664 3091 5664 3063 5665 3084 5665 3090 5665 3063 5666 3090 5666 3062 5666 3062 5667 3090 5667 3060 5667 3060 5668 3090 5668 3091 5668 3060 5669 3091 5669 3058 5669 54 5670 53 5670 1571 5670 1571 5671 53 5671 52 5671 1187 5672 3021 5672 1186 5672 1186 5673 3021 5673 2601 5673 2587 5674 2588 5674 1774 5674 1774 5675 2588 5675 1775 5675 2587 5676 52 5676 2598 5676 2598 5677 52 5677 1186 5677 2587 5678 1774 5678 1571 5678 2587 5679 1571 5679 52 5679 2601 5680 2600 5680 1186 5680 1186 5681 2600 5681 2599 5681 1186 5682 2599 5682 2598 5682 3092 5683 3093 5683 3094 5683 3092 5684 3094 5684 3095 5684 3092 5685 3095 5685 3096 5685 3096 5686 3095 5686 3097 5686 3096 5687 3097 5687 3098 5687 3098 5688 3097 5688 3099 5688 3098 5689 3099 5689 3100 5689 3100 5690 3099 5690 3101 5690 3100 5691 3101 5691 3102 5691 3100 5692 3102 5692 3103 5692 3103 5693 3102 5693 3104 5693 3103 5694 3104 5694 3105 5694 3105 5695 3104 5695 3106 5695 3106 5696 3104 5696 3107 5696 3106 5697 3107 5697 3108 5697 3108 5698 3107 5698 3109 5698 3108 5699 3109 5699 3110 5699 3108 5700 3110 5700 3111 5700 3111 5701 3110 5701 3112 5701 3092 5702 3113 5702 3093 5702 3093 5703 3113 5703 3114 5703 3114 5704 3113 5704 3112 5704 3112 5705 3113 5705 3115 5705 3112 5706 3115 5706 3111 5706 3112 5707 3116 5707 3114 5707 3114 5708 3116 5708 3117 5708 3114 5709 3117 5709 3093 5709 3093 5710 3117 5710 3118 5710 3093 5711 3118 5711 3094 5711 3094 5712 3118 5712 3119 5712 3094 5713 3119 5713 3095 5713 3095 5714 3119 5714 3120 5714 3095 5715 3120 5715 3097 5715 3097 5716 3120 5716 3121 5716 3097 5717 3121 5717 3099 5717 3099 5718 3121 5718 3122 5718 3099 5719 3122 5719 3101 5719 3101 5720 3122 5720 3102 5720 3102 5721 3122 5721 3123 5721 3102 5722 3123 5722 3104 5722 3104 5723 3123 5723 3124 5723 3104 5724 3124 5724 3107 5724 3107 5725 3124 5725 3125 5725 3107 5726 3125 5726 3109 5726 3109 5727 3125 5727 3126 5727 3109 5728 3126 5728 3110 5728 3110 5729 3126 5729 3127 5729 3110 5730 3127 5730 3112 5730 3112 5731 3127 5731 3116 5731 34 5732 38 5732 3128 5732 3022 5733 1189 5733 2605 5733 2605 5734 1189 5734 1190 5734 1740 5735 2593 5735 3129 5735 3129 5736 2593 5736 2602 5736 2604 5737 2605 5737 1190 5737 2602 5738 2603 5738 1190 5738 1742 5739 2592 5739 1740 5739 1740 5740 2592 5740 2593 5740 1190 5741 2603 5741 2604 5741 3128 5742 3129 5742 34 5742 34 5743 3129 5743 2602 5743 34 5744 2602 5744 1190 5744 1919 5745 1933 5745 2079 5745 1919 5746 2079 5746 2083 5746 2083 5747 2079 5747 3134 5747 2083 5748 3134 5748 3135 5748 3131 5749 3130 5749 1572 5749 1572 5750 3130 5750 3136 5750 1572 5751 3136 5751 1569 5751 1569 5752 3136 5752 3137 5752 3132 5753 3138 5753 1570 5753 1570 5754 3138 5754 3139 5754 2079 5755 3133 5755 3140 5755 1569 5756 3137 5756 1570 5756 1570 5757 3137 5757 3132 5757 2079 5758 3140 5758 3134 5758 3135 5759 3141 5759 2083 5759 2083 5760 3141 5760 3130 5760 2083 5761 3130 5761 3131 5761 1570 5762 3139 5762 2079 5762 2079 5763 3139 5763 3133 5763 1570 5764 2079 5764 49 5764 49 5765 2079 5765 2078 5765 2081 5766 1188 5766 49 5766 2081 5767 49 5767 2078 5767 1950 5768 2085 5768 1957 5768 1957 5769 2085 5769 2089 5769 2085 5770 3153 5770 3142 5770 2089 5771 3143 5771 3144 5771 2085 5772 3142 5772 2089 5772 2089 5773 3142 5773 3145 5773 2089 5774 3145 5774 3143 5774 2089 5775 3144 5775 3146 5775 3144 5776 3147 5776 3146 5776 3146 5777 3147 5777 3148 5777 3146 5778 3148 5778 1573 5778 1573 5779 3148 5779 3149 5779 1573 5780 3149 5780 1574 5780 1574 5781 3149 5781 3150 5781 1574 5782 3150 5782 3151 5782 3151 5783 3150 5783 3152 5783 3151 5784 3152 5784 2085 5784 2085 5785 3152 5785 3153 5785 3142 5786 3154 5786 3145 5786 3145 5787 3154 5787 3155 5787 3145 5788 3155 5788 3143 5788 3143 5789 3155 5789 3156 5789 3143 5790 3156 5790 3144 5790 3144 5791 3156 5791 3157 5791 3144 5792 3157 5792 3158 5792 3144 5793 3158 5793 3147 5793 3147 5794 3158 5794 3159 5794 3147 5795 3159 5795 3148 5795 3148 5796 3159 5796 3160 5796 3148 5797 3160 5797 3149 5797 3149 5798 3160 5798 3161 5798 3149 5799 3161 5799 3150 5799 3150 5800 3161 5800 3162 5800 3150 5801 3162 5801 3152 5801 3152 5802 3162 5802 3163 5802 3152 5803 3163 5803 3153 5803 3153 5804 3163 5804 3164 5804 3153 5805 3164 5805 3142 5805 3142 5806 3164 5806 3154 5806 3165 5807 3166 5807 3187 5807 3187 5808 3166 5808 3167 5808 3167 5809 3166 5809 3168 5809 3168 5810 3166 5810 3169 5810 3168 5811 3169 5811 3170 5811 3170 5812 3169 5812 3171 5812 3170 5813 3171 5813 3172 5813 3172 5814 3171 5814 3173 5814 3172 5815 3173 5815 3174 5815 3174 5816 3173 5816 3175 5816 3174 5817 3175 5817 3176 5817 3176 5818 3175 5818 3177 5818 3176 5819 3177 5819 3178 5819 3178 5820 3177 5820 3179 5820 3178 5821 3179 5821 3180 5821 3180 5822 3179 5822 3181 5822 3180 5823 3181 5823 3182 5823 3182 5824 3181 5824 3183 5824 3182 5825 3183 5825 3184 5825 3184 5826 3183 5826 3185 5826 3184 5827 3185 5827 3186 5827 3186 5828 3185 5828 3165 5828 3186 5829 3165 5829 3187 5829 3188 5830 3134 5830 3140 5830 3188 5831 3140 5831 3189 5831 3189 5832 3140 5832 3133 5832 3189 5833 3133 5833 3190 5833 3190 5834 3133 5834 3191 5834 3191 5835 3133 5835 3139 5835 3191 5836 3139 5836 3192 5836 3192 5837 3139 5837 3138 5837 3192 5838 3138 5838 3193 5838 3193 5839 3138 5839 3132 5839 3193 5840 3132 5840 3137 5840 3193 5841 3137 5841 3194 5841 3194 5842 3137 5842 3195 5842 3195 5843 3137 5843 3136 5843 3195 5844 3136 5844 3196 5844 3196 5845 3136 5845 3130 5845 3196 5846 3130 5846 3197 5846 3197 5847 3130 5847 3141 5847 3197 5848 3141 5848 3198 5848 3198 5849 3141 5849 3135 5849 3198 5850 3135 5850 3188 5850 3188 5851 3135 5851 3134 5851 3115 5852 3199 5852 3111 5852 3111 5853 3199 5853 3200 5853 3111 5854 3200 5854 3108 5854 3108 5855 3200 5855 3201 5855 3108 5856 3201 5856 3106 5856 3106 5857 3201 5857 3202 5857 3106 5858 3202 5858 3105 5858 3105 5859 3202 5859 3203 5859 3105 5860 3203 5860 3103 5860 3103 5861 3203 5861 3100 5861 3100 5862 3203 5862 3204 5862 3100 5863 3204 5863 3098 5863 3098 5864 3204 5864 3205 5864 3098 5865 3205 5865 3096 5865 3096 5866 3205 5866 3206 5866 3096 5867 3206 5867 3207 5867 3096 5868 3207 5868 3092 5868 3092 5869 3207 5869 3208 5869 3092 5870 3208 5870 3113 5870 3113 5871 3208 5871 3199 5871 3113 5872 3199 5872 3115 5872 3091 5873 3209 5873 3210 5873 3091 5874 3210 5874 3089 5874 3089 5875 3210 5875 3211 5875 3089 5876 3211 5876 3088 5876 3088 5877 3211 5877 3212 5877 3088 5878 3212 5878 3087 5878 3087 5879 3212 5879 3213 5879 3087 5880 3213 5880 3086 5880 3086 5881 3213 5881 3214 5881 3086 5882 3214 5882 3085 5882 3085 5883 3214 5883 3215 5883 3085 5884 3215 5884 3082 5884 3082 5885 3215 5885 3216 5885 3082 5886 3216 5886 3083 5886 3083 5887 3216 5887 3217 5887 3083 5888 3217 5888 3084 5888 3084 5889 3217 5889 3218 5889 3084 5890 3218 5890 3090 5890 3090 5891 3218 5891 3219 5891 3090 5892 3219 5892 3091 5892 3091 5893 3219 5893 3209 5893 3066 5894 3064 5894 2135 5894 2136 5895 3034 5895 3032 5895 3034 5896 2136 5896 2152 5896 3034 5897 2152 5897 3037 5897 3068 5898 3066 5898 2136 5898 3074 5899 3073 5899 3032 5899 3123 5900 3122 5900 2152 5900 3071 5901 3068 5901 2136 5901 3066 5902 2135 5902 2136 5902 2153 5903 3124 5903 3123 5903 3123 5904 2152 5904 2153 5904 2152 5905 3039 5905 3037 5905 3032 5906 3073 5906 3071 5906 3032 5907 3071 5907 2136 5907 2153 5908 3125 5908 3124 5908 3074 5909 3032 5909 3030 5909 3039 5910 3121 5910 3120 5910 3040 5911 3120 5911 3119 5911 3039 5912 3120 5912 3040 5912 3118 5913 3045 5913 3043 5913 3026 5914 3024 5914 1976 5914 3076 5915 3028 5915 3079 5915 2152 5916 3122 5916 3121 5916 2152 5917 3121 5917 3039 5917 3061 5918 2132 5918 3064 5918 2105 5919 2096 5919 1975 5919 3081 5920 1976 5920 3059 5920 3045 5921 3118 5921 3117 5921 3028 5922 3076 5922 3030 5922 3030 5923 3076 5923 3074 5923 3118 5924 3043 5924 3119 5924 3119 5925 3043 5925 3040 5925 2006 5926 2007 5926 3127 5926 3127 5927 2007 5927 3116 5927 3125 5928 2175 5928 3126 5928 2135 5929 3064 5929 2132 5929 1976 5930 3024 5930 1989 5930 1989 5931 3024 5931 3046 5931 2007 5932 1989 5932 3116 5932 3116 5933 1989 5933 3117 5933 3117 5934 1989 5934 3046 5934 3117 5935 3046 5935 3045 5935 2196 5936 2006 5936 3127 5936 2196 5937 3127 5937 2175 5937 2175 5938 3127 5938 3126 5938 2175 5939 2169 5939 1688 5939 1641 5940 2131 5940 2097 5940 2096 5941 2097 5941 3061 5941 3061 5942 2097 5942 2132 5942 2096 5943 3061 5943 3059 5943 3059 5944 1976 5944 1975 5944 3125 5945 2174 5945 2169 5945 3125 5946 2169 5946 2175 5946 2097 5947 2131 5947 2132 5947 3059 5948 1975 5948 2096 5948 2105 5949 1975 5949 1954 5949 3028 5950 3026 5950 3079 5950 3079 5951 3026 5951 1976 5951 3079 5952 1976 5952 3081 5952 2006 5953 2196 5953 1979 5953 3125 5954 2153 5954 2174 5954 2587 5955 2598 5955 2124 5955 2124 5956 2598 5956 2133 5956 3220 5957 2606 5957 2258 5957 2255 5958 2610 5958 3221 5958 83 5959 91 5959 969 5959 969 5960 91 5960 3220 5960 969 5961 3220 5961 3221 5961 3221 5962 3220 5962 2258 5962 3221 5963 2258 5963 2255 5963 3222 5964 3223 5964 3224 5964 3224 5965 3223 5965 3225 5965 3224 5966 3225 5966 3226 5966 3224 5967 3226 5967 3227 5967 3227 5968 3226 5968 3228 5968 3227 5969 3228 5969 3229 5969 3229 5970 3228 5970 3230 5970 3229 5971 3230 5971 3231 5971 3231 5972 3230 5972 3232 5972 3231 5973 3232 5973 3233 5973 3231 5974 3233 5974 3234 5974 3234 5975 3233 5975 3235 5975 3234 5976 3235 5976 3236 5976 3236 5977 3235 5977 3237 5977 3236 5978 3237 5978 3238 5978 3238 5979 3237 5979 3239 5979 3238 5980 3239 5980 3240 5980 3240 5981 3239 5981 3241 5981 3240 5982 3241 5982 3242 5982 3242 5983 3241 5983 3243 5983 3242 5984 3243 5984 3244 5984 3244 5985 3243 5985 3245 5985 3244 5986 3245 5986 3223 5986 3244 5987 3223 5987 3222 5987 3246 5988 3247 5988 3222 5988 3222 5989 3247 5989 3244 5989 3244 5990 3247 5990 3248 5990 3244 5991 3248 5991 3242 5991 3242 5992 3248 5992 3249 5992 3242 5993 3249 5993 3240 5993 3240 5994 3249 5994 3250 5994 3240 5995 3250 5995 3238 5995 3238 5996 3250 5996 3251 5996 3238 5997 3251 5997 3252 5997 3238 5998 3252 5998 3236 5998 3236 5999 3252 5999 3253 5999 3236 6000 3253 6000 3234 6000 3234 6001 3253 6001 3254 6001 3234 6002 3254 6002 3231 6002 3231 6003 3254 6003 3255 6003 3231 6004 3255 6004 3256 6004 3231 6005 3256 6005 3229 6005 3229 6006 3256 6006 3257 6006 3229 6007 3257 6007 3227 6007 3227 6008 3257 6008 3258 6008 3227 6009 3258 6009 3224 6009 3224 6010 3258 6010 3246 6010 3224 6011 3246 6011 3222 6011 3259 6012 3260 6012 3261 6012 3261 6013 3260 6013 3262 6013 3261 6014 3262 6014 3263 6014 3261 6015 3263 6015 3264 6015 3264 6016 3263 6016 3265 6016 3264 6017 3265 6017 3266 6017 3266 6018 3265 6018 3267 6018 3266 6019 3267 6019 3268 6019 3268 6020 3267 6020 3269 6020 3268 6021 3269 6021 3270 6021 3270 6022 3269 6022 3271 6022 3270 6023 3271 6023 3272 6023 3272 6024 3271 6024 3273 6024 3272 6025 3273 6025 3274 6025 3274 6026 3273 6026 3275 6026 3275 6027 3273 6027 3276 6027 3275 6028 3276 6028 3277 6028 3277 6029 3276 6029 3278 6029 3277 6030 3278 6030 3279 6030 3279 6031 3278 6031 3280 6031 3279 6032 3280 6032 3259 6032 3259 6033 3280 6033 3260 6033 3282 6034 3272 6034 3284 6034 3284 6035 3272 6035 3274 6035 3284 6036 3274 6036 3275 6036 3284 6037 3275 6037 3285 6037 3285 6038 3275 6038 3277 6038 3285 6039 3277 6039 3286 6039 3286 6040 3277 6040 3279 6040 3286 6041 3279 6041 3281 6041 3281 6042 3279 6042 3259 6042 3270 6043 3283 6043 3268 6043 3287 6044 3288 6044 3261 6044 3261 6045 3288 6045 3259 6045 3259 6046 3288 6046 3281 6046 3272 6047 3282 6047 3270 6047 3270 6048 3282 6048 3283 6048 3287 6049 3261 6049 3264 6049 3287 6050 3264 6050 3289 6050 3289 6051 3264 6051 3290 6051 3290 6052 3264 6052 3266 6052 3290 6053 3266 6053 3268 6053 3290 6054 3268 6054 3291 6054 3291 6055 3268 6055 3283 6055 12 6056 16 6056 1564 6056 3220 6057 1181 6057 2606 6057 2606 6058 1181 6058 1182 6058 1182 6059 2607 6059 2606 6059 1756 6060 2591 6060 1566 6060 1566 6061 2591 6061 2609 6061 2609 6062 2608 6062 1182 6062 1756 6063 2590 6063 2591 6063 1564 6064 1566 6064 12 6064 12 6065 1566 6065 2609 6065 12 6066 2609 6066 1182 6066 1182 6067 2608 6067 2607 6067 3292 6068 3293 6068 3294 6068 3294 6069 3293 6069 3295 6069 3295 6070 3293 6070 3296 6070 3295 6071 3296 6071 3297 6071 3297 6072 3296 6072 3298 6072 3297 6073 3298 6073 3299 6073 3299 6074 3298 6074 3300 6074 3299 6075 3300 6075 3301 6075 3301 6076 3300 6076 3302 6076 3301 6077 3302 6077 3303 6077 3303 6078 3302 6078 3304 6078 3303 6079 3304 6079 3305 6079 3305 6080 3304 6080 3306 6080 3305 6081 3306 6081 3307 6081 3307 6082 3306 6082 3308 6082 3307 6083 3308 6083 3309 6083 3309 6084 3308 6084 3310 6084 3310 6085 3308 6085 3311 6085 3310 6086 3311 6086 3312 6086 3312 6087 3311 6087 3313 6087 3312 6088 3313 6088 3314 6088 3314 6089 3313 6089 3315 6089 3315 6090 3313 6090 3292 6090 3315 6091 3292 6091 3294 6091 3307 6092 3316 6092 3305 6092 3305 6093 3316 6093 3317 6093 3305 6094 3317 6094 3303 6094 3303 6095 3317 6095 3318 6095 3303 6096 3318 6096 3301 6096 3301 6097 3318 6097 3299 6097 3299 6098 3318 6098 3319 6098 3299 6099 3319 6099 3297 6099 3297 6100 3319 6100 3320 6100 3297 6101 3320 6101 3295 6101 3295 6102 3320 6102 3321 6102 3295 6103 3321 6103 3294 6103 3294 6104 3321 6104 3322 6104 3294 6105 3322 6105 3315 6105 3315 6106 3322 6106 3314 6106 3314 6107 3322 6107 3323 6107 3314 6108 3323 6108 3312 6108 3312 6109 3323 6109 3324 6109 3312 6110 3324 6110 3310 6110 3310 6111 3324 6111 3325 6111 3310 6112 3325 6112 3309 6112 3309 6113 3325 6113 3326 6113 3309 6114 3326 6114 3307 6114 3307 6115 3326 6115 3316 6115 30 6116 29 6116 3327 6116 3327 6117 29 6117 28 6117 1178 6118 1179 6118 3221 6118 1723 6119 1725 6119 3327 6119 1178 6120 2612 6120 28 6120 28 6121 2612 6121 2595 6121 3221 6122 2610 6122 1178 6122 28 6123 2595 6123 2596 6123 28 6124 2596 6124 3327 6124 3327 6125 2596 6125 1723 6125 1178 6126 2610 6126 2611 6126 1178 6127 2611 6127 2612 6127 1847 6128 2073 6128 1818 6128 1818 6129 2073 6129 2077 6129 3336 6130 3328 6130 2073 6130 1568 6131 3329 6131 1567 6131 3331 6132 3330 6132 2077 6132 3328 6133 3331 6133 2073 6133 2073 6134 3331 6134 2077 6134 2077 6135 3332 6135 1565 6135 1565 6136 3332 6136 3333 6136 1577 6137 1565 6137 3334 6137 3333 6138 3334 6138 1565 6138 1577 6139 3334 6139 3335 6139 1577 6140 3335 6140 3329 6140 1577 6141 3329 6141 1568 6141 3329 6142 3336 6142 1567 6142 1567 6143 3336 6143 2073 6143 3330 6144 3332 6144 2077 6144 2076 6145 2077 6145 17 6145 17 6146 2077 6146 1565 6146 1180 6147 2074 6147 17 6147 17 6148 2074 6148 2076 6148 1864 6149 2091 6149 1917 6149 1917 6150 2091 6150 2095 6150 3349 6151 3337 6151 2091 6151 2095 6152 3338 6152 3339 6152 2095 6153 3339 6153 3340 6153 3340 6154 3339 6154 3341 6154 2091 6155 3337 6155 2095 6155 2095 6156 3337 6156 3338 6156 3340 6157 3341 6157 3342 6157 3340 6158 3342 6158 1575 6158 1575 6159 3342 6159 3343 6159 1575 6160 3343 6160 1576 6160 1576 6161 3343 6161 3344 6161 1576 6162 3344 6162 3346 6162 3346 6163 3344 6163 3347 6163 3346 6164 3347 6164 3345 6164 3345 6165 3348 6165 3346 6165 3346 6166 3348 6166 2091 6166 2091 6167 3348 6167 3349 6167 3337 6168 3360 6168 3350 6168 3337 6169 3350 6169 3338 6169 3338 6170 3350 6170 3351 6170 3338 6171 3351 6171 3339 6171 3339 6172 3351 6172 3352 6172 3339 6173 3352 6173 3341 6173 3341 6174 3352 6174 3353 6174 3341 6175 3353 6175 3342 6175 3342 6176 3353 6176 3354 6176 3342 6177 3354 6177 3343 6177 3343 6178 3354 6178 3344 6178 3344 6179 3354 6179 3355 6179 3344 6180 3355 6180 3356 6180 3344 6181 3356 6181 3347 6181 3347 6182 3356 6182 3357 6182 3347 6183 3357 6183 3345 6183 3345 6184 3357 6184 3348 6184 3348 6185 3357 6185 3358 6185 3348 6186 3358 6186 3349 6186 3349 6187 3358 6187 3359 6187 3349 6188 3359 6188 3360 6188 3349 6189 3360 6189 3337 6189 3362 6190 3361 6190 3363 6190 3363 6191 3361 6191 3364 6191 3363 6192 3364 6192 3365 6192 3365 6193 3364 6193 3366 6193 3365 6194 3366 6194 3367 6194 3365 6195 3367 6195 3368 6195 3368 6196 3367 6196 3369 6196 3368 6197 3369 6197 3370 6197 3370 6198 3369 6198 3371 6198 3370 6199 3371 6199 3372 6199 3372 6200 3371 6200 3373 6200 3372 6201 3373 6201 3374 6201 3374 6202 3373 6202 3375 6202 3374 6203 3375 6203 3376 6203 3376 6204 3375 6204 3377 6204 3376 6205 3377 6205 3378 6205 3376 6206 3378 6206 3379 6206 3379 6207 3378 6207 3380 6207 3379 6208 3380 6208 3381 6208 3381 6209 3380 6209 3382 6209 3381 6210 3382 6210 3383 6210 3383 6211 3382 6211 3362 6211 3362 6212 3382 6212 3361 6212 3384 6213 3331 6213 3385 6213 3385 6214 3331 6214 3328 6214 3385 6215 3328 6215 3386 6215 3386 6216 3328 6216 3336 6216 3386 6217 3336 6217 3387 6217 3387 6218 3336 6218 3329 6218 3387 6219 3329 6219 3388 6219 3388 6220 3329 6220 3389 6220 3389 6221 3329 6221 3335 6221 3389 6222 3335 6222 3390 6222 3390 6223 3335 6223 3334 6223 3390 6224 3334 6224 3391 6224 3391 6225 3334 6225 3392 6225 3392 6226 3334 6226 3333 6226 3392 6227 3333 6227 3393 6227 3393 6228 3333 6228 3332 6228 3393 6229 3332 6229 3394 6229 3394 6230 3332 6230 3330 6230 3394 6231 3330 6231 3395 6231 3395 6232 3330 6232 3331 6232 3395 6233 3331 6233 3384 6233 3306 6234 3396 6234 3397 6234 3306 6235 3397 6235 3308 6235 3308 6236 3397 6236 3398 6236 3308 6237 3398 6237 3311 6237 3311 6238 3398 6238 3399 6238 3311 6239 3399 6239 3313 6239 3313 6240 3399 6240 3400 6240 3313 6241 3400 6241 3292 6241 3292 6242 3400 6242 3401 6242 3292 6243 3401 6243 3402 6243 3292 6244 3402 6244 3293 6244 3293 6245 3402 6245 3403 6245 3293 6246 3403 6246 3296 6246 3296 6247 3403 6247 3404 6247 3296 6248 3404 6248 3298 6248 3298 6249 3404 6249 3405 6249 3298 6250 3405 6250 3300 6250 3300 6251 3405 6251 3406 6251 3300 6252 3406 6252 3302 6252 3302 6253 3406 6253 3407 6253 3302 6254 3407 6254 3304 6254 3304 6255 3407 6255 3396 6255 3304 6256 3396 6256 3306 6256 3408 6257 3288 6257 3419 6257 3288 6258 3408 6258 3281 6258 3281 6259 3408 6259 3409 6259 3281 6260 3409 6260 3286 6260 3286 6261 3409 6261 3410 6261 3286 6262 3410 6262 3285 6262 3285 6263 3410 6263 3411 6263 3285 6264 3411 6264 3284 6264 3284 6265 3411 6265 3412 6265 3284 6266 3412 6266 3413 6266 3284 6267 3413 6267 3282 6267 3282 6268 3413 6268 3414 6268 3282 6269 3414 6269 3415 6269 3282 6270 3415 6270 3283 6270 3283 6271 3415 6271 3291 6271 3291 6272 3415 6272 3416 6272 3291 6273 3416 6273 3290 6273 3290 6274 3416 6274 3417 6274 3290 6275 3417 6275 3289 6275 3289 6276 3417 6276 3418 6276 3289 6277 3418 6277 3287 6277 3287 6278 3418 6278 3419 6278 3287 6279 3419 6279 3288 6279 2256 6280 3273 6280 3271 6280 3239 6281 3269 6281 3267 6281 2282 6282 2277 6282 2283 6282 1886 6283 2210 6283 1882 6283 3260 6284 1846 6284 1844 6284 3273 6285 2259 6285 3276 6285 3273 6286 2256 6286 2259 6286 2256 6287 3271 6287 3269 6287 2256 6288 3269 6288 2244 6288 3278 6289 2283 6289 3280 6289 2260 6290 3278 6290 3276 6290 2260 6291 3276 6291 2259 6291 3239 6292 3267 6292 3241 6292 3241 6293 3267 6293 3265 6293 3241 6294 3265 6294 3243 6294 3260 6295 1844 6295 3262 6295 3262 6296 1844 6296 1845 6296 3262 6297 1845 6297 3263 6297 3263 6298 1845 6298 3223 6298 3223 6299 3245 6299 3263 6299 3263 6300 3245 6300 3243 6300 3269 6301 3239 6301 3237 6301 2283 6302 2277 6302 1610 6302 3243 6303 3265 6303 3263 6303 1884 6304 3316 6304 1885 6304 1846 6305 2304 6305 1812 6305 2304 6306 1846 6306 3260 6306 2304 6307 3260 6307 2284 6307 2284 6308 3260 6308 3280 6308 2284 6309 3280 6309 2283 6309 2271 6310 2282 6310 3278 6310 3278 6311 2282 6311 2283 6311 1885 6312 3316 6312 3326 6312 1885 6313 3326 6313 1845 6313 1845 6314 3326 6314 3325 6314 2215 6315 1648 6315 2239 6315 3317 6316 2215 6316 2238 6316 3317 6317 2238 6317 3318 6317 2215 6318 3317 6318 2210 6318 2210 6319 3317 6319 3316 6319 3278 6320 2260 6320 2271 6320 3225 6321 3223 6321 1845 6321 3320 6322 3319 6322 2243 6322 3319 6323 3318 6323 2242 6323 2242 6324 3318 6324 2238 6324 2215 6325 2239 6325 2238 6325 1884 6326 1883 6326 3316 6326 3316 6327 1883 6327 2210 6327 2210 6328 1883 6328 1882 6328 2244 6329 3235 6329 3233 6329 3325 6330 3226 6330 1845 6330 1845 6331 3226 6331 3225 6331 3319 6332 2242 6332 2243 6332 3226 6333 3325 6333 3228 6333 3228 6334 3325 6334 3324 6334 3269 6335 3237 6335 2244 6335 2244 6336 3237 6336 3235 6336 2244 6337 3320 6337 2243 6337 3233 6338 3232 6338 2244 6338 3322 6339 3321 6339 2244 6339 2244 6340 3321 6340 3320 6340 3230 6341 3323 6341 3232 6341 3228 6342 3324 6342 3230 6342 3230 6343 3324 6343 3323 6343 3323 6344 3322 6344 3232 6344 3232 6345 3322 6345 2244 6345 33 6346 1019 6346 1785 6346 59 6347 1571 6347 108 6347 108 6348 1571 6348 1774 6348 108 6349 1774 6349 1019 6349 1774 6350 1776 6350 1019 6350 1019 6351 1776 6351 1782 6351 1019 6352 1782 6352 1785 6352 1985 6353 2052 6353 1964 6353 1964 6354 2052 6354 2059 6354 1173 6355 1172 6355 1735 6355 1173 6356 1735 6356 113 6356 113 6357 1735 6357 1736 6357 113 6358 1736 6358 1739 6358 113 6359 1739 6359 1740 6359 3129 6360 69 6360 1740 6360 1740 6361 69 6361 113 6361 1826 6362 2025 6362 1852 6362 1852 6363 2025 6363 2008 6363 2609 6364 2591 6364 2266 6364 2591 6365 2273 6365 2266 6365 2981 6366 3015 6366 2960 6366 2960 6367 3015 6367 2952 6367 2952 6368 3015 6368 2997 6368 2952 6369 2997 6369 2953 6369 2953 6370 2997 6370 2977 6370 2953 6371 2977 6371 2956 6371 2956 6372 2977 6372 2986 6372 2956 6373 2986 6373 2945 6373 2945 6374 2986 6374 2982 6374 2945 6375 2982 6375 2947 6375 2947 6376 2982 6376 2989 6376 2947 6377 2989 6377 2949 6377 2949 6378 2989 6378 3012 6378 2949 6379 3012 6379 2942 6379 2942 6380 3012 6380 3017 6380 2942 6381 3017 6381 2950 6381 2950 6382 3017 6382 3016 6382 2950 6383 3016 6383 2938 6383 2938 6384 3016 6384 3005 6384 2938 6385 3005 6385 2941 6385 2941 6386 3005 6386 3018 6386 2941 6387 3018 6387 2959 6387 2959 6388 3018 6388 2981 6388 2959 6389 2981 6389 2960 6389 2988 6390 3002 6390 2926 6390 2926 6391 3002 6391 2922 6391 2922 6392 3002 6392 2998 6392 2922 6393 2998 6393 2920 6393 2920 6394 2998 6394 2995 6394 2920 6395 2995 6395 2980 6395 2920 6396 2980 6396 2918 6396 2918 6397 2980 6397 2994 6397 2918 6398 2994 6398 2916 6398 2916 6399 2994 6399 2913 6399 2913 6400 2994 6400 2975 6400 2913 6401 2975 6401 2908 6401 2908 6402 2975 6402 2974 6402 2908 6403 2974 6403 2910 6403 2910 6404 2974 6404 2992 6404 2910 6405 2992 6405 2907 6405 2907 6406 2992 6406 2990 6406 2907 6407 2990 6407 2905 6407 2905 6408 2990 6408 2983 6408 2905 6409 2983 6409 2987 6409 2905 6410 2987 6410 2924 6410 2924 6411 2987 6411 2988 6411 2924 6412 2988 6412 2926 6412 2876 6413 2993 6413 2889 6413 2889 6414 2993 6414 2979 6414 2889 6415 2979 6415 2978 6415 2889 6416 2978 6416 2887 6416 2887 6417 2978 6417 2976 6417 2887 6418 2976 6418 2885 6418 2885 6419 2976 6419 3004 6419 2885 6420 3004 6420 2883 6420 2883 6421 3004 6421 2882 6421 2882 6422 3004 6422 2991 6422 2882 6423 2991 6423 2877 6423 2877 6424 2991 6424 3003 6424 2877 6425 3003 6425 2879 6425 2879 6426 3003 6426 2999 6426 2879 6427 2999 6427 3020 6427 2879 6428 3020 6428 2873 6428 2873 6429 3020 6429 3009 6429 2873 6430 3009 6430 2871 6430 2871 6431 3009 6431 3019 6431 2871 6432 3019 6432 2874 6432 2874 6433 3019 6433 2984 6433 2874 6434 2984 6434 2876 6434 2876 6435 2984 6435 2993 6435 2857 6436 3006 6436 2853 6436 2853 6437 3006 6437 3011 6437 2853 6438 3011 6438 2985 6438 2853 6439 2985 6439 2851 6439 2851 6440 2985 6440 2996 6440 2851 6441 2996 6441 2850 6441 2850 6442 2996 6442 2847 6442 2847 6443 2996 6443 3010 6443 2847 6444 3010 6444 3001 6444 2847 6445 3001 6445 2840 6445 2840 6446 3001 6446 2841 6446 2841 6447 3001 6447 3000 6447 2841 6448 3000 6448 3014 6448 2841 6449 3014 6449 2844 6449 2844 6450 3014 6450 3013 6450 2844 6451 3013 6451 2839 6451 2839 6452 3013 6452 3008 6452 2839 6453 3008 6453 2837 6453 2837 6454 3008 6454 2855 6454 2855 6455 3008 6455 3007 6455 2855 6456 3007 6456 2857 6456 2857 6457 3007 6457 3006 6457 2602 6458 2593 6458 2159 6458 2159 6459 2593 6459 2594 6459 2241 6460 2231 6460 2612 6460 2612 6461 2231 6461 2595 6461 2211 6462 1657 6462 1647 6462 2807 6463 2784 6463 2785 6463 2807 6464 2785 6464 2786 6464 2807 6465 2786 6465 2813 6465 2813 6466 2786 6466 2787 6466 2813 6467 2787 6467 2806 6467 2806 6468 2787 6468 2791 6468 2791 6469 2787 6469 2788 6469 2791 6470 2788 6470 2790 6470 2790 6471 2788 6471 2789 6471 2790 6472 2789 6472 2793 6472 2793 6473 2789 6473 2779 6473 2793 6474 2779 6474 2780 6474 2793 6475 2780 6475 2804 6475 2804 6476 2780 6476 2781 6476 2804 6477 2781 6477 2805 6477 2805 6478 2781 6478 2817 6478 2817 6479 2781 6479 2782 6479 2817 6480 2782 6480 2827 6480 2827 6481 2782 6481 2783 6481 2827 6482 2783 6482 2801 6482 2801 6483 2783 6483 2784 6483 2801 6484 2784 6484 2807 6484 2815 6485 2742 6485 2745 6485 2815 6486 2745 6486 2792 6486 2792 6487 2745 6487 2816 6487 2816 6488 2745 6488 2753 6488 2816 6489 2753 6489 2802 6489 2802 6490 2753 6490 2752 6490 2802 6491 2752 6491 2750 6491 2802 6492 2750 6492 2821 6492 2821 6493 2750 6493 2751 6493 2821 6494 2751 6494 2803 6494 2803 6495 2751 6495 2749 6495 2803 6496 2749 6496 2818 6496 2818 6497 2749 6497 2748 6497 2818 6498 2748 6498 2819 6498 2819 6499 2748 6499 2747 6499 2819 6500 2747 6500 2829 6500 2829 6501 2747 6501 2746 6501 2829 6502 2746 6502 2824 6502 2824 6503 2746 6503 2823 6503 2823 6504 2746 6504 2744 6504 2823 6505 2744 6505 2743 6505 2823 6506 2743 6506 2812 6506 2812 6507 2743 6507 2742 6507 2812 6508 2742 6508 2815 6508 2828 6509 2709 6509 2716 6509 2828 6510 2716 6510 2832 6510 2832 6511 2716 6511 2715 6511 2832 6512 2715 6512 2835 6512 2835 6513 2715 6513 2810 6513 2810 6514 2715 6514 2714 6514 2810 6515 2714 6515 2811 6515 2811 6516 2714 6516 2713 6516 2811 6517 2713 6517 2826 6517 2826 6518 2713 6518 2707 6518 2826 6519 2707 6519 2800 6519 2800 6520 2707 6520 2708 6520 2800 6521 2708 6521 2825 6521 2825 6522 2708 6522 2710 6522 2825 6523 2710 6523 2831 6523 2831 6524 2710 6524 2711 6524 2831 6525 2711 6525 2834 6525 2834 6526 2711 6526 2833 6526 2833 6527 2711 6527 2712 6527 2833 6528 2712 6528 2830 6528 2830 6529 2712 6529 2828 6529 2828 6530 2712 6530 2709 6530 2822 6531 2674 6531 2673 6531 2822 6532 2673 6532 2820 6532 2820 6533 2673 6533 2680 6533 2820 6534 2680 6534 2794 6534 2794 6535 2680 6535 2795 6535 2795 6536 2680 6536 2681 6536 2795 6537 2681 6537 2682 6537 2795 6538 2682 6538 2796 6538 2796 6539 2682 6539 2677 6539 2796 6540 2677 6540 2797 6540 2797 6541 2677 6541 2798 6541 2798 6542 2677 6542 2679 6542 2798 6543 2679 6543 2814 6543 2814 6544 2679 6544 2678 6544 2814 6545 2678 6545 2808 6545 2808 6546 2678 6546 2676 6546 2808 6547 2676 6547 2799 6547 2799 6548 2676 6548 2675 6548 2799 6549 2675 6549 2809 6549 2809 6550 2675 6550 2674 6550 2809 6551 2674 6551 2822 6551 2723 6552 2721 6552 1800 6552 1800 6553 2721 6553 2719 6553 2766 6554 2764 6554 2718 6554 2723 6555 1800 6555 1801 6555 2655 6556 2768 6556 2766 6556 2770 6557 2768 6557 2654 6557 2654 6558 2768 6558 2655 6558 2689 6559 2687 6559 2731 6559 1801 6560 2730 6560 2727 6560 1801 6561 2727 6561 2725 6561 2762 6562 2760 6562 2719 6562 2719 6563 2760 6563 1800 6563 1800 6564 2760 6564 2758 6564 1801 6565 2725 6565 2723 6565 2758 6566 2756 6566 1800 6566 1806 6567 2671 6567 2669 6567 2739 6568 2655 6568 2718 6568 2718 6569 2655 6569 2766 6569 2571 6570 2695 6570 2693 6570 2775 6571 2773 6571 2652 6571 2770 6572 2654 6572 2652 6572 2686 6573 2737 6573 2735 6573 1806 6574 2755 6574 2777 6574 1806 6575 2777 6575 2775 6575 2652 6576 2773 6576 2770 6576 2687 6577 2734 6577 2731 6577 2775 6578 2652 6578 2651 6578 2718 6579 2764 6579 2762 6579 2718 6580 2762 6580 2719 6580 2686 6581 2735 6581 2734 6581 2686 6582 2734 6582 2687 6582 1806 6583 2651 6583 2671 6583 2571 6584 2693 6584 2692 6584 2571 6585 2692 6585 2554 6585 1800 6586 2756 6586 1806 6586 1806 6587 2756 6587 2755 6587 2775 6588 2651 6588 1806 6588 1806 6589 2669 6589 2667 6589 1806 6590 2667 6590 1811 6590 2705 6591 2657 6591 2655 6591 2554 6592 2692 6592 2689 6592 2554 6593 2689 6593 1801 6593 1801 6594 2689 6594 2731 6594 1801 6595 2731 6595 2730 6595 2737 6596 2686 6596 2684 6596 2737 6597 2684 6597 2739 6597 2705 6598 2659 6598 2657 6598 2661 6599 2703 6599 2701 6599 2568 6600 2701 6600 2699 6600 2568 6601 2699 6601 2697 6601 2568 6602 2697 6602 2571 6602 2571 6603 2697 6603 2695 6603 2705 6604 2703 6604 2659 6604 2659 6605 2703 6605 2661 6605 2667 6606 2665 6606 1811 6606 1811 6607 2665 6607 2560 6607 2560 6608 2665 6608 2663 6608 2560 6609 2663 6609 2567 6609 2567 6610 2663 6610 2661 6610 2567 6611 2661 6611 2568 6611 2568 6612 2661 6612 2701 6612 2739 6613 2684 6613 2655 6613 2655 6614 2684 6614 2705 6614 16 6615 15 6615 1564 6615 3128 6616 37 6616 36 6616 36 6617 42 6617 3146 6617 1573 6618 71 6618 3146 6618 3146 6619 71 6619 69 6619 3146 6620 69 6620 36 6620 36 6621 69 6621 3129 6621 36 6622 3129 6622 3128 6622 1566 6623 87 6623 1756 6623 1756 6624 87 6624 86 6624 1751 6625 1020 6625 31 6625 1020 6626 1751 6626 86 6626 1751 6627 1754 6627 86 6627 86 6628 1754 6628 1756 6628 3387 6629 1036 6629 1046 6629 3387 6630 1046 6630 3386 6630 3386 6631 1046 6631 1045 6631 3386 6632 1045 6632 3385 6632 3385 6633 1045 6633 3384 6633 3384 6634 1045 6634 1044 6634 3384 6635 1044 6635 3395 6635 3395 6636 1044 6636 1043 6636 3395 6637 1043 6637 3394 6637 3394 6638 1043 6638 1042 6638 3394 6639 1042 6639 3393 6639 3393 6640 1042 6640 1041 6640 3393 6641 1041 6641 3392 6641 3392 6642 1041 6642 1040 6642 3392 6643 1040 6643 3391 6643 3391 6644 1040 6644 3390 6644 3390 6645 1040 6645 1039 6645 3390 6646 1039 6646 3389 6646 3389 6647 1039 6647 1038 6647 3389 6648 1038 6648 1037 6648 3389 6649 1037 6649 3388 6649 3388 6650 1037 6650 1036 6650 3388 6651 1036 6651 3387 6651 1025 6652 1024 6652 3191 6652 3191 6653 1024 6653 3190 6653 3190 6654 1024 6654 1035 6654 3190 6655 1035 6655 3189 6655 3189 6656 1035 6656 1034 6656 3189 6657 1034 6657 3188 6657 3188 6658 1034 6658 1033 6658 3188 6659 1033 6659 3198 6659 3198 6660 1033 6660 1032 6660 3198 6661 1032 6661 1031 6661 3198 6662 1031 6662 3197 6662 3197 6663 1031 6663 1030 6663 3197 6664 1030 6664 3196 6664 3196 6665 1030 6665 1029 6665 3196 6666 1029 6666 3195 6666 3195 6667 1029 6667 1028 6667 3195 6668 1028 6668 3194 6668 3194 6669 1028 6669 1027 6669 3194 6670 1027 6670 3193 6670 3193 6671 1027 6671 1026 6671 3193 6672 1026 6672 3192 6672 3192 6673 1026 6673 1025 6673 3192 6674 1025 6674 3191 6674 79 6675 3327 6675 80 6675 80 6676 3327 6676 1725 6676 1727 6677 1175 6677 1174 6677 80 6678 1734 6678 1728 6678 1727 6679 1174 6679 80 6679 1727 6680 80 6680 1728 6680 80 6681 1725 6681 1734 6681 3356 6682 1090 6682 1088 6682 3356 6683 1088 6683 3357 6683 3357 6684 1088 6684 1086 6684 3357 6685 1086 6685 1085 6685 3357 6686 1085 6686 3358 6686 3358 6687 1085 6687 3359 6687 3359 6688 1085 6688 1107 6688 3359 6689 1107 6689 1105 6689 3359 6690 1105 6690 3360 6690 3360 6691 1105 6691 1103 6691 3360 6692 1103 6692 3350 6692 3350 6693 1103 6693 1100 6693 3350 6694 1100 6694 3351 6694 3351 6695 1100 6695 1099 6695 3351 6696 1099 6696 3352 6696 3352 6697 1099 6697 1097 6697 3352 6698 1097 6698 3353 6698 3353 6699 1097 6699 1095 6699 3353 6700 1095 6700 1093 6700 3353 6701 1093 6701 3354 6701 3354 6702 1093 6702 1092 6702 3354 6703 1092 6703 3355 6703 3355 6704 1092 6704 1090 6704 3355 6705 1090 6705 3356 6705 3160 6706 1067 6706 1065 6706 3160 6707 1065 6707 3161 6707 3161 6708 1065 6708 3162 6708 3162 6709 1065 6709 1063 6709 3162 6710 1063 6710 3163 6710 3163 6711 1063 6711 1083 6711 3163 6712 1083 6712 3164 6712 3164 6713 1083 6713 1082 6713 3164 6714 1082 6714 1080 6714 3164 6715 1080 6715 3154 6715 3154 6716 1080 6716 3155 6716 3155 6717 1080 6717 1078 6717 3155 6718 1078 6718 3156 6718 3156 6719 1078 6719 1076 6719 3156 6720 1076 6720 3157 6720 3157 6721 1076 6721 1074 6721 3157 6722 1074 6722 3158 6722 3158 6723 1074 6723 1071 6723 3158 6724 1071 6724 3159 6724 3159 6725 1071 6725 1070 6725 3159 6726 1070 6726 1067 6726 3159 6727 1067 6727 3160 6727 112 6728 3021 6728 126 6728 126 6729 3021 6729 1187 6729 37 6730 3128 6730 38 6730 124 6731 123 6731 1136 6731 1136 6732 123 6732 1189 6732 1136 6733 1189 6733 1134 6733 1134 6734 1189 6734 3022 6734 1191 6735 1576 6735 79 6735 79 6736 1576 6736 3346 6736 3346 6737 24 6737 79 6737 79 6738 24 6738 25 6738 79 6739 25 6739 3327 6739 3327 6740 25 6740 30 6740 3220 6741 91 6741 1181 6741 1181 6742 91 6742 90 6742 969 6743 3221 6743 967 6743 967 6744 3221 6744 1179 6744 967 6745 1179 6745 75 6745 75 6746 1179 6746 76 6746 1575 6747 1192 6747 3340 6747 3340 6748 1192 6748 1061 6748 3340 6749 1061 6749 5 6749 3151 6750 40 6750 67 6750 3151 6751 67 6751 1574 6751 1574 6752 67 6752 66 6752 1572 6753 58 6753 3131 6753 3131 6754 58 6754 57 6754 3131 6755 57 6755 8 6755 3420 6756 3199 6756 3421 6756 3421 6757 3199 6757 3208 6757 3421 6758 3208 6758 3422 6758 3422 6759 3208 6759 3207 6759 3422 6760 3207 6760 3423 6760 3423 6761 3207 6761 3206 6761 3423 6762 3206 6762 3424 6762 3424 6763 3206 6763 3205 6763 3424 6764 3205 6764 3204 6764 3424 6765 3204 6765 3425 6765 3425 6766 3204 6766 3426 6766 3426 6767 3204 6767 3203 6767 3426 6768 3203 6768 3427 6768 3427 6769 3203 6769 3428 6769 3428 6770 3203 6770 3202 6770 3428 6771 3202 6771 3429 6771 3429 6772 3202 6772 3201 6772 3429 6773 3201 6773 3430 6773 3430 6774 3201 6774 3200 6774 3430 6775 3200 6775 3420 6775 3420 6776 3200 6776 3199 6776 3184 6777 2081 6777 3182 6777 3180 6778 3182 6778 2080 6778 2080 6779 3182 6779 2081 6779 3184 6780 3186 6780 2081 6780 3187 6781 3167 6781 1188 6781 1188 6782 3167 6782 3168 6782 11 6783 3174 6783 10 6783 3186 6784 3187 6784 2081 6784 2081 6785 3187 6785 1188 6785 1188 6786 3168 6786 46 6786 46 6787 3168 6787 3170 6787 46 6788 3170 6788 11 6788 11 6789 3170 6789 3172 6789 11 6790 3172 6790 3174 6790 10 6791 3174 6791 3176 6791 10 6792 3176 6792 2080 6792 2080 6793 3176 6793 3178 6793 2080 6794 3178 6794 3180 6794 3175 6795 904 6795 2087 6795 904 6796 3175 6796 903 6796 903 6797 3175 6797 3173 6797 903 6798 3173 6798 3171 6798 903 6799 3171 6799 1047 6799 3181 6800 2087 6800 3183 6800 3183 6801 2087 6801 2086 6801 2087 6802 3181 6802 3179 6802 3171 6803 3169 6803 1047 6803 1047 6804 3169 6804 64 6804 64 6805 3169 6805 3166 6805 2087 6806 3179 6806 3177 6806 2087 6807 3177 6807 3175 6807 2086 6808 3165 6808 3185 6808 2086 6809 3185 6809 3183 6809 3166 6810 3165 6810 64 6810 64 6811 3165 6811 2086 6811 2088 6812 2089 6812 42 6812 42 6813 2089 6813 3146 6813 64 6814 2086 6814 42 6814 42 6815 2086 6815 2088 6815 3210 6816 3209 6816 3431 6816 3431 6817 3209 6817 3219 6817 3431 6818 3219 6818 3432 6818 3432 6819 3219 6819 3218 6819 3432 6820 3218 6820 3433 6820 3433 6821 3218 6821 3217 6821 3433 6822 3217 6822 3434 6822 3434 6823 3217 6823 3216 6823 3434 6824 3216 6824 3435 6824 3435 6825 3216 6825 3215 6825 3435 6826 3215 6826 3436 6826 3436 6827 3215 6827 3214 6827 3436 6828 3214 6828 3437 6828 3437 6829 3214 6829 3213 6829 3437 6830 3213 6830 3438 6830 3438 6831 3213 6831 3212 6831 3438 6832 3212 6832 3439 6832 3439 6833 3212 6833 3211 6833 3439 6834 3211 6834 3440 6834 3440 6835 3211 6835 3210 6835 3440 6836 3210 6836 3441 6836 3441 6837 3210 6837 3431 6837 33 6838 1785 6838 1779 6838 3442 6839 3419 6839 3443 6839 3443 6840 3419 6840 3444 6840 3444 6841 3419 6841 3418 6841 3444 6842 3418 6842 3417 6842 3444 6843 3417 6843 3445 6843 3445 6844 3417 6844 3416 6844 3445 6845 3416 6845 3446 6845 3446 6846 3416 6846 3415 6846 3446 6847 3415 6847 3447 6847 3447 6848 3415 6848 3448 6848 3448 6849 3415 6849 3414 6849 3448 6850 3414 6850 3449 6850 3449 6851 3414 6851 3413 6851 3449 6852 3413 6852 3412 6852 3449 6853 3412 6853 3450 6853 3450 6854 3412 6854 3411 6854 3450 6855 3411 6855 3451 6855 3451 6856 3411 6856 3410 6856 3451 6857 3410 6857 3452 6857 3452 6858 3410 6858 3409 6858 3452 6859 3409 6859 3408 6859 3452 6860 3408 6860 3442 6860 3442 6861 3408 6861 3419 6861 3374 6862 2 6862 3372 6862 3368 6863 3370 6863 2075 6863 2075 6864 3370 6864 3372 6864 2075 6865 3372 6865 3 6865 3 6866 3372 6866 2 6866 2 6867 3374 6867 21 6867 21 6868 3374 6868 3376 6868 21 6869 3376 6869 3379 6869 3381 6870 1180 6870 3379 6870 3379 6871 1180 6871 21 6871 1180 6872 3381 6872 3383 6872 2074 6873 3363 6873 3365 6873 1180 6874 3383 6874 3362 6874 2074 6875 3365 6875 3368 6875 2074 6876 3368 6876 2075 6876 1180 6877 3362 6877 2074 6877 2074 6878 3362 6878 3363 6878 2092 6879 3371 6879 3369 6879 3366 6880 3364 6880 2093 6880 3361 6881 3382 6881 55 6881 56 6882 55 6882 3380 6882 6 6883 3373 6883 4 6883 3382 6884 3380 6884 55 6884 4 6885 3373 6885 2092 6885 2092 6886 3373 6886 3371 6886 3369 6887 3367 6887 2092 6887 2092 6888 3367 6888 2093 6888 2093 6889 3367 6889 3366 6889 3364 6890 3361 6890 2093 6890 2093 6891 3361 6891 55 6891 3380 6892 3378 6892 56 6892 56 6893 3378 6893 3377 6893 56 6894 3377 6894 3375 6894 56 6895 3375 6895 6 6895 6 6896 3375 6896 3373 6896 3346 6897 2091 6897 24 6897 24 6898 2091 6898 2090 6898 2093 6899 55 6899 24 6899 2093 6900 24 6900 2090 6900 3453 6901 3396 6901 3407 6901 3453 6902 3407 6902 3454 6902 3454 6903 3407 6903 3406 6903 3454 6904 3406 6904 3455 6904 3455 6905 3406 6905 3405 6905 3455 6906 3405 6906 3456 6906 3456 6907 3405 6907 3404 6907 3456 6908 3404 6908 3457 6908 3457 6909 3404 6909 3403 6909 3457 6910 3403 6910 3458 6910 3458 6911 3403 6911 3402 6911 3458 6912 3402 6912 3459 6912 3459 6913 3402 6913 3460 6913 3460 6914 3402 6914 3401 6914 3460 6915 3401 6915 3400 6915 3460 6916 3400 6916 3461 6916 3461 6917 3400 6917 3399 6917 3461 6918 3399 6918 3462 6918 3462 6919 3399 6919 3398 6919 3462 6920 3398 6920 3463 6920 3463 6921 3398 6921 3397 6921 3463 6922 3397 6922 3464 6922 3464 6923 3397 6923 3396 6923 3464 6924 3396 6924 3453 6924 2082 6925 2083 6925 8 6925 8 6926 2083 6926 3131 6926 10 6927 2080 6927 8 6927 8 6928 2080 6928 2082 6928 3151 6929 2085 6929 40 6929 40 6930 2085 6930 2084 6930 2087 6931 904 6931 40 6931 2087 6932 40 6932 2084 6932 2094 6933 2095 6933 5 6933 5 6934 2095 6934 3340 6934 4 6935 2092 6935 5 6935 5 6936 2092 6936 2094 6936 1567 6937 2073 6937 1 6937 1 6938 2073 6938 2072 6938 2075 6939 3 6939 1 6939 2075 6940 1 6940 2072 6940 3466 6941 3465 6941 3473 6941 3467 6942 3465 6942 3469 6942 3467 6943 3469 6943 3468 6943 3468 6944 3470 6944 3471 6944 3468 6945 3471 6945 3467 6945 3467 6946 3472 6946 3465 6946 3465 6947 3472 6947 3473 6947 3466 6948 3474 6948 3465 6948 3466 6949 3475 6949 3474 6949 3473 6950 3047 6950 3057 6950 3473 6951 3057 6951 3466 6951 3466 6952 3057 6952 3056 6952 3466 6953 3056 6953 3475 6953 3475 6954 3056 6954 3055 6954 3475 6955 3055 6955 3474 6955 3474 6956 3055 6956 3054 6956 3474 6957 3054 6957 3465 6957 3465 6958 3054 6958 3053 6958 3465 6959 3053 6959 3469 6959 3469 6960 3053 6960 3052 6960 3469 6961 3052 6961 3468 6961 3468 6962 3052 6962 3051 6962 3468 6963 3051 6963 3050 6963 3468 6964 3050 6964 3470 6964 3470 6965 3050 6965 3471 6965 3471 6966 3050 6966 3049 6966 3471 6967 3049 6967 3467 6967 3467 6968 3049 6968 3048 6968 3467 6969 3048 6969 3472 6969 3472 6970 3048 6970 3047 6970 3472 6971 3047 6971 3473 6971 3480 6972 3476 6972 3477 6972 3477 6973 3478 6973 3479 6973 3477 6974 3476 6974 3478 6974 3480 6975 3481 6975 3484 6975 3480 6976 3484 6976 3485 6976 3481 6977 3480 6977 3477 6977 3477 6978 3479 6978 3486 6978 3477 6979 3486 6979 3482 6979 3477 6980 3482 6980 3483 6980 3483 6981 3247 6981 3246 6981 3483 6982 3246 6982 3477 6982 3477 6983 3246 6983 3258 6983 3477 6984 3258 6984 3481 6984 3481 6985 3258 6985 3257 6985 3481 6986 3257 6986 3484 6986 3484 6987 3257 6987 3256 6987 3484 6988 3256 6988 3485 6988 3485 6989 3256 6989 3255 6989 3485 6990 3255 6990 3254 6990 3485 6991 3254 6991 3480 6991 3480 6992 3254 6992 3253 6992 3480 6993 3253 6993 3476 6993 3476 6994 3253 6994 3252 6994 3476 6995 3252 6995 3251 6995 3476 6996 3251 6996 3478 6996 3478 6997 3251 6997 3250 6997 3478 6998 3250 6998 3479 6998 3479 6999 3250 6999 3249 6999 3479 7000 3249 7000 3486 7000 3486 7001 3249 7001 3248 7001 3486 7002 3248 7002 3482 7002 3482 7003 3248 7003 3247 7003 3482 7004 3247 7004 3483 7004 3488 7005 3489 7005 3490 7005 3488 7006 3490 7006 3492 7006 3488 7007 3487 7007 3493 7007 3488 7008 3492 7008 3494 7008 3487 7009 3488 7009 3491 7009 3491 7010 3495 7010 3487 7010 3488 7011 3493 7011 3489 7011 3494 7012 3496 7012 3488 7012 3495 7013 3497 7013 3487 7013 3508 7014 3496 7014 3498 7014 3498 7015 3496 7015 3494 7015 3498 7016 3494 7016 3499 7016 3499 7017 3494 7017 3492 7017 3499 7018 3492 7018 3500 7018 3500 7019 3492 7019 3490 7019 3500 7020 3490 7020 3501 7020 3501 7021 3490 7021 3489 7021 3501 7022 3489 7022 3493 7022 3501 7023 3493 7023 3502 7023 3502 7024 3493 7024 3487 7024 3502 7025 3487 7025 3503 7025 3503 7026 3487 7026 3504 7026 3504 7027 3487 7027 3497 7027 3504 7028 3497 7028 3505 7028 3505 7029 3497 7029 3495 7029 3505 7030 3495 7030 3506 7030 3506 7031 3495 7031 3491 7031 3506 7032 3491 7032 3507 7032 3507 7033 3491 7033 3488 7033 3507 7034 3488 7034 3508 7034 3508 7035 3488 7035 3496 7035 3506 7036 3509 7036 3505 7036 3505 7037 3509 7037 3510 7037 3505 7038 3510 7038 3504 7038 3504 7039 3510 7039 3511 7039 3504 7040 3511 7040 3503 7040 3503 7041 3511 7041 3502 7041 3502 7042 3511 7042 3512 7042 3502 7043 3512 7043 3513 7043 3502 7044 3513 7044 3501 7044 3501 7045 3513 7045 3514 7045 3501 7046 3514 7046 3500 7046 3500 7047 3514 7047 3515 7047 3500 7048 3515 7048 3499 7048 3499 7049 3515 7049 3516 7049 3499 7050 3516 7050 3517 7050 3499 7051 3517 7051 3498 7051 3498 7052 3517 7052 3518 7052 3498 7053 3518 7053 3508 7053 3508 7054 3518 7054 3519 7054 3508 7055 3519 7055 3507 7055 3507 7056 3519 7056 3520 7056 3507 7057 3520 7057 3506 7057 3506 7058 3520 7058 3509 7058 3429 7059 3518 7059 3428 7059 3428 7060 3518 7060 3517 7060 3428 7061 3517 7061 3427 7061 3427 7062 3517 7062 3516 7062 3427 7063 3516 7063 3515 7063 3427 7064 3515 7064 3426 7064 3426 7065 3515 7065 3425 7065 3425 7066 3515 7066 3514 7066 3425 7067 3514 7067 3513 7067 3425 7068 3513 7068 3424 7068 3424 7069 3513 7069 3512 7069 3424 7070 3512 7070 3423 7070 3423 7071 3512 7071 3511 7071 3423 7072 3511 7072 3422 7072 3422 7073 3511 7073 3510 7073 3422 7074 3510 7074 3421 7074 3421 7075 3510 7075 3509 7075 3421 7076 3509 7076 3420 7076 3420 7077 3509 7077 3520 7077 3420 7078 3520 7078 3430 7078 3430 7079 3520 7079 3519 7079 3430 7080 3519 7080 3429 7080 3429 7081 3519 7081 3518 7081 3524 7082 3525 7082 3523 7082 3524 7083 3523 7083 3522 7083 3521 7084 3523 7084 3526 7084 3524 7085 3527 7085 3525 7085 3525 7086 3527 7086 3528 7086 3525 7087 3531 7087 3529 7087 3525 7088 3529 7088 3530 7088 3521 7089 3522 7089 3523 7089 3525 7090 3528 7090 3531 7090 3543 7091 3528 7091 3532 7091 3532 7092 3528 7092 3527 7092 3532 7093 3527 7093 3533 7093 3533 7094 3527 7094 3524 7094 3533 7095 3524 7095 3534 7095 3534 7096 3524 7096 3522 7096 3534 7097 3522 7097 3535 7097 3535 7098 3522 7098 3521 7098 3535 7099 3521 7099 3536 7099 3536 7100 3521 7100 3537 7100 3537 7101 3521 7101 3526 7101 3537 7102 3526 7102 3538 7102 3538 7103 3526 7103 3523 7103 3538 7104 3523 7104 3539 7104 3539 7105 3523 7105 3525 7105 3539 7106 3525 7106 3540 7106 3540 7107 3525 7107 3541 7107 3541 7108 3525 7108 3530 7108 3541 7109 3530 7109 3529 7109 3541 7110 3529 7110 3542 7110 3542 7111 3529 7111 3543 7111 3543 7112 3529 7112 3531 7112 3543 7113 3531 7113 3528 7113 3543 7114 3544 7114 3542 7114 3542 7115 3544 7115 3545 7115 3542 7116 3545 7116 3541 7116 3541 7117 3545 7117 3546 7117 3541 7118 3546 7118 3540 7118 3540 7119 3546 7119 3539 7119 3539 7120 3546 7120 3547 7120 3539 7121 3547 7121 3538 7121 3538 7122 3547 7122 3548 7122 3538 7123 3548 7123 3537 7123 3537 7124 3548 7124 3549 7124 3537 7125 3549 7125 3550 7125 3537 7126 3550 7126 3536 7126 3536 7127 3550 7127 3551 7127 3536 7128 3551 7128 3535 7128 3535 7129 3551 7129 3552 7129 3535 7130 3552 7130 3534 7130 3534 7131 3552 7131 3533 7131 3533 7132 3552 7132 3553 7132 3533 7133 3553 7133 3532 7133 3532 7134 3553 7134 3554 7134 3532 7135 3554 7135 3543 7135 3543 7136 3554 7136 3544 7136 3439 7137 3554 7137 3438 7137 3438 7138 3554 7138 3553 7138 3438 7139 3553 7139 3437 7139 3437 7140 3553 7140 3552 7140 3437 7141 3552 7141 3436 7141 3436 7142 3552 7142 3551 7142 3436 7143 3551 7143 3435 7143 3435 7144 3551 7144 3550 7144 3435 7145 3550 7145 3434 7145 3434 7146 3550 7146 3549 7146 3434 7147 3549 7147 3548 7147 3434 7148 3548 7148 3433 7148 3433 7149 3548 7149 3547 7149 3433 7150 3547 7150 3432 7150 3432 7151 3547 7151 3546 7151 3432 7152 3546 7152 3431 7152 3431 7153 3546 7153 3545 7153 3431 7154 3545 7154 3441 7154 3441 7155 3545 7155 3440 7155 3440 7156 3545 7156 3544 7156 3440 7157 3544 7157 3439 7157 3439 7158 3544 7158 3554 7158 3557 7159 3556 7159 3558 7159 3557 7160 3559 7160 3556 7160 3556 7161 3559 7161 3560 7161 3560 7162 3561 7162 3562 7162 3562 7163 3563 7163 3560 7163 3560 7164 3563 7164 3556 7164 3564 7165 3555 7165 3558 7165 3558 7166 3555 7166 3557 7166 3564 7167 3565 7167 3555 7167 3561 7168 3566 7168 3567 7168 3561 7169 3567 7169 3562 7169 3562 7170 3567 7170 3568 7170 3562 7171 3568 7171 3563 7171 3563 7172 3568 7172 3569 7172 3563 7173 3569 7173 3556 7173 3556 7174 3569 7174 3570 7174 3556 7175 3570 7175 3558 7175 3558 7176 3570 7176 3571 7176 3558 7177 3571 7177 3564 7177 3564 7178 3571 7178 3572 7178 3564 7179 3572 7179 3565 7179 3565 7180 3572 7180 3555 7180 3555 7181 3572 7181 3573 7181 3555 7182 3573 7182 3557 7182 3557 7183 3573 7183 3574 7183 3557 7184 3574 7184 3559 7184 3559 7185 3574 7185 3575 7185 3559 7186 3575 7186 3560 7186 3560 7187 3575 7187 3566 7187 3560 7188 3566 7188 3561 7188 3575 7189 3576 7189 3566 7189 3566 7190 3576 7190 3577 7190 3566 7191 3577 7191 3567 7191 3567 7192 3577 7192 3578 7192 3567 7193 3578 7193 3568 7193 3568 7194 3578 7194 3569 7194 3569 7195 3578 7195 3579 7195 3569 7196 3579 7196 3570 7196 3570 7197 3579 7197 3580 7197 3570 7198 3580 7198 3571 7198 3571 7199 3580 7199 3581 7199 3571 7200 3581 7200 3572 7200 3572 7201 3581 7201 3582 7201 3572 7202 3582 7202 3573 7202 3573 7203 3582 7203 3583 7203 3573 7204 3583 7204 3584 7204 3573 7205 3584 7205 3574 7205 3574 7206 3584 7206 3585 7206 3574 7207 3585 7207 3575 7207 3575 7208 3585 7208 3586 7208 3575 7209 3586 7209 3576 7209 3576 7210 3445 7210 3446 7210 3576 7211 3446 7211 3577 7211 3577 7212 3446 7212 3447 7212 3577 7213 3447 7213 3578 7213 3578 7214 3447 7214 3448 7214 3578 7215 3448 7215 3579 7215 3579 7216 3448 7216 3449 7216 3579 7217 3449 7217 3580 7217 3580 7218 3449 7218 3450 7218 3580 7219 3450 7219 3581 7219 3581 7220 3450 7220 3451 7220 3581 7221 3451 7221 3582 7221 3582 7222 3451 7222 3452 7222 3582 7223 3452 7223 3583 7223 3583 7224 3452 7224 3584 7224 3584 7225 3452 7225 3442 7225 3584 7226 3442 7226 3585 7226 3585 7227 3442 7227 3443 7227 3585 7228 3443 7228 3444 7228 3585 7229 3444 7229 3586 7229 3586 7230 3444 7230 3445 7230 3586 7231 3445 7231 3576 7231 3587 7232 3588 7232 3589 7232 3589 7233 3588 7233 3590 7233 3591 7234 3589 7234 3590 7234 3592 7235 3593 7235 3589 7235 3589 7236 3591 7236 3592 7236 3597 7237 3596 7237 3594 7237 3596 7238 3597 7238 3589 7238 3589 7239 3597 7239 3587 7239 3596 7240 3595 7240 3594 7240 3595 7241 3607 7241 3598 7241 3595 7242 3598 7242 3594 7242 3594 7243 3598 7243 3599 7243 3594 7244 3599 7244 3597 7244 3597 7245 3599 7245 3587 7245 3587 7246 3599 7246 3600 7246 3587 7247 3600 7247 3588 7247 3588 7248 3600 7248 3601 7248 3588 7249 3601 7249 3590 7249 3590 7250 3601 7250 3602 7250 3590 7251 3602 7251 3591 7251 3591 7252 3602 7252 3603 7252 3591 7253 3603 7253 3592 7253 3592 7254 3603 7254 3604 7254 3592 7255 3604 7255 3593 7255 3593 7256 3604 7256 3605 7256 3593 7257 3605 7257 3589 7257 3589 7258 3605 7258 3606 7258 3589 7259 3606 7259 3596 7259 3596 7260 3606 7260 3607 7260 3596 7261 3607 7261 3595 7261 3604 7262 3608 7262 3609 7262 3604 7263 3609 7263 3605 7263 3605 7264 3609 7264 3606 7264 3606 7265 3609 7265 3610 7265 3606 7266 3610 7266 3607 7266 3607 7267 3610 7267 3611 7267 3607 7268 3611 7268 3598 7268 3598 7269 3611 7269 3612 7269 3598 7270 3612 7270 3599 7270 3599 7271 3612 7271 3613 7271 3599 7272 3613 7272 3614 7272 3599 7273 3614 7273 3600 7273 3600 7274 3614 7274 3615 7274 3600 7275 3615 7275 3601 7275 3601 7276 3615 7276 3616 7276 3601 7277 3616 7277 3602 7277 3602 7278 3616 7278 3617 7278 3602 7279 3617 7279 3603 7279 3603 7280 3617 7280 3618 7280 3603 7281 3618 7281 3608 7281 3603 7282 3608 7282 3604 7282 3611 7283 3456 7283 3457 7283 3611 7284 3457 7284 3612 7284 3612 7285 3457 7285 3458 7285 3612 7286 3458 7286 3613 7286 3613 7287 3458 7287 3614 7287 3614 7288 3458 7288 3459 7288 3614 7289 3459 7289 3460 7289 3614 7290 3460 7290 3615 7290 3615 7291 3460 7291 3461 7291 3615 7292 3461 7292 3616 7292 3616 7293 3461 7293 3462 7293 3616 7294 3462 7294 3617 7294 3617 7295 3462 7295 3463 7295 3617 7296 3463 7296 3618 7296 3618 7297 3463 7297 3464 7297 3618 7298 3464 7298 3608 7298 3608 7299 3464 7299 3453 7299 3608 7300 3453 7300 3609 7300 3609 7301 3453 7301 3454 7301 3609 7302 3454 7302 3610 7302 3610 7303 3454 7303 3455 7303 3610 7304 3455 7304 3611 7304 3611 7305 3455 7305 3456 7305 3619 7306 3620 7306 3621 7306 3619 7307 3622 7307 3623 7307 3619 7308 3623 7308 3624 7308 3619 7309 3624 7309 3625 7309 3619 7310 3621 7310 3622 7310 3619 7311 3625 7311 3626 7311 3619 7312 3626 7312 3627 7312 3619 7313 3627 7313 3628 7313 3628 7314 3629 7314 3619 7314 3621 7315 3630 7315 3622 7315 3622 7316 3630 7316 3631 7316 3622 7317 3631 7317 3632 7317 3622 7318 3632 7318 3623 7318 3623 7319 3632 7319 3633 7319 3623 7320 3633 7320 3624 7320 3624 7321 3633 7321 3634 7321 3624 7322 3634 7322 3625 7322 3625 7323 3634 7323 3635 7323 3625 7324 3635 7324 3626 7324 3626 7325 3635 7325 3636 7325 3626 7326 3636 7326 3627 7326 3627 7327 3636 7327 3637 7327 3627 7328 3637 7328 3628 7328 3628 7329 3637 7329 3638 7329 3628 7330 3638 7330 3629 7330 3629 7331 3638 7331 3639 7331 3629 7332 3639 7332 3619 7332 3619 7333 3639 7333 3640 7333 3619 7334 3640 7334 3620 7334 3620 7335 3640 7335 3641 7335 3620 7336 3641 7336 3621 7336 3621 7337 3641 7337 3630 7337 3640 7338 3642 7338 3641 7338 3641 7339 3642 7339 3643 7339 3641 7340 3643 7340 3630 7340 3630 7341 3643 7341 3631 7341 3631 7342 3643 7342 3644 7342 3631 7343 3644 7343 3632 7343 3632 7344 3644 7344 3645 7344 3632 7345 3645 7345 3633 7345 3633 7346 3645 7346 3646 7346 3633 7347 3646 7347 3647 7347 3633 7348 3647 7348 3634 7348 3634 7349 3647 7349 3648 7349 3634 7350 3648 7350 3635 7350 3635 7351 3648 7351 3649 7351 3635 7352 3649 7352 3636 7352 3636 7353 3649 7353 3650 7353 3636 7354 3650 7354 3637 7354 3637 7355 3650 7355 3651 7355 3637 7356 3651 7356 3638 7356 3638 7357 3651 7357 3639 7357 3639 7358 3651 7358 3652 7358 3639 7359 3652 7359 3653 7359 3639 7360 3653 7360 3640 7360 3640 7361 3653 7361 3642 7361 3665 7362 3654 7362 3649 7362 3649 7363 3654 7363 3650 7363 3650 7364 3654 7364 3651 7364 3651 7365 3654 7365 3655 7365 3651 7366 3655 7366 3656 7366 3651 7367 3656 7367 3652 7367 3652 7368 3656 7368 3657 7368 3652 7369 3657 7369 3653 7369 3653 7370 3657 7370 3642 7370 3642 7371 3657 7371 3658 7371 3642 7372 3658 7372 3659 7372 3642 7373 3659 7373 3643 7373 3643 7374 3659 7374 3660 7374 3643 7375 3660 7375 3644 7375 3644 7376 3660 7376 3661 7376 3644 7377 3661 7377 3662 7377 3644 7378 3662 7378 3645 7378 3645 7379 3662 7379 3663 7379 3645 7380 3663 7380 3646 7380 3646 7381 3663 7381 3647 7381 3647 7382 3663 7382 3664 7382 3647 7383 3664 7383 3648 7383 3648 7384 3664 7384 3665 7384 3648 7385 3665 7385 3649 7385 3654 7386 3665 7386 3660 7386 3660 7387 3659 7387 3654 7387 3654 7388 3659 7388 3658 7388 3654 7389 3658 7389 3657 7389 3660 7390 3665 7390 3664 7390 3662 7391 3661 7391 3663 7391 3663 7392 3661 7392 3660 7392 3654 7393 3657 7393 3656 7393 3660 7394 3664 7394 3663 7394 3654 7395 3656 7395 3655 7395</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Camera_003" name="Camera_003" type="NODE"> + <matrix sid="transform">0.6858804 -0.3173701 0.6548619 7.481132 0.7276337 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953431 0.4452454 5.343665 0 0 0 1</matrix> + <instance_camera url="#Camera_003-camera"/> + </node> + <node id="Lamp_003" name="Lamp_003" type="NODE"> + <matrix sid="transform">-0.2908648 -0.7711007 0.5663931 4.076245 0.9551712 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1</matrix> + <instance_light url="#Lamp_003-light"/> + </node> + <node id="Link4" name="Link4" type="NODE"> + <matrix sid="transform">-7.58967e-10 -0.001 0 0.072 0.001 -7.58967e-10 0 -0.015 0 0 0.001 -0.019 0 0 0 1</matrix> + <instance_geometry url="#Link4-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="Material_002_001-material" target="#Material_002_001-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/arm/link4.stl b/kinton_description/meshes/arm/link4.stl new file mode 100644 index 0000000000000000000000000000000000000000..5b106e0bc5ffd37532829be5e162f70a2cef4cbc Binary files /dev/null and b/kinton_description/meshes/arm/link4.stl differ diff --git a/kinton_description/meshes/arm/link5.dae b/kinton_description/meshes/arm/link5.dae new file mode 100644 index 0000000000000000000000000000000000000000..7313764416de3d88bb7ad05d9dbad1d213bd3c94 --- /dev/null +++ b/kinton_description/meshes/arm/link5.dae @@ -0,0 +1,107 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor/> + <created>2019-07-22T14:47:22.347830</created> + <modified>2019-07-22T14:47:22.347837</modified> + <unit name="meter" meter="1.0"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_effects> + <effect name="effect_Mesh001" id="effect_Mesh001"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color>0.0 0.0 0.0 1.0</color> + </emission> + <ambient> + <color>0.0 0.0 0.0 1.0</color> + </ambient> + <diffuse> + <color>0.0446155406535 0.0446155406535 0.0446155406535 1.0</color> + </diffuse> + <specular> + <color>1 1 1 1.0</color> + </specular> + <shininess> + <float>0.0</float> + </shininess> + <reflective> + <color>0.0 0.0 0.0 1.0</color> + </reflective> + <reflectivity> + <float>0.0</float> + </reflectivity> + <transparent> + <color>0.0 0.0 0.0 1.0</color> + </transparent> + <transparency> + <float>1.0</float> + </transparency> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>0</double_sided> + </technique> + </extra> + </profile_COMMON> + </effect> + </library_effects> + <library_geometries> + <geometry id="geometry0" name="Mesh001"> + <mesh> + <source id="cubenormals-array0"> + <float_array count="13635" id="cubenormals-array0-array">0.02427706 -0.9997053 -1.157623e-07 -2.024609e-07 -0.9906434 -0.1364757 4.202959e-06 1.063027e-05 -1 1.78242e-05 -4.32678e-07 -1 1.092987e-05 -2.383826e-06 -1 1.298178e-05 -1.365307e-05 -1 1.390958e-05 -1.39072e-05 -1 7.669493e-06 -2.239018e-05 -1 -6.926254e-06 -4.651551e-06 -1 6.750759e-06 4.533692e-06 -1 5.942659e-06 1.477608e-05 -1 1.447161e-06 1.354819e-05 -1 0 0 -1 2.150926e-05 -3.417445e-06 -1 1.986222e-05 -6.803884e-06 -1 1.057843e-05 2.400999e-06 -1 -2.628275e-05 -5.965426e-06 -1 -2.622608e-05 -6.51238e-06 -1 9.4077e-06 -3.164528e-05 -1 1.99978e-05 -2.030226e-05 -1 1.778756e-05 -5.011645e-06 -1 -2.703607e-06 7.617411e-07 -1 -1.483495e-06 -0 -1 -1.483495e-06 0 -1 4.778004e-06 5.985042e-05 1 -9.965905e-06 4.395737e-05 1 0 -0 1 0 0 1 -0 0 1 0 -0 1 -0 0 1 1.53577e-05 -1.875512e-07 1 1.836525e-05 -2.515642e-05 1 -1.528683e-06 -1.378174e-05 1 1.765208e-06 -5.13326e-06 1 0 0 1 5.23898e-06 2.035724e-06 1 5.754943e-06 2.946337e-06 1 9.027946e-06 4.701815e-07 1 6.420182e-06 -8.061886e-07 1 5.058926e-06 1.442323e-06 1 0 0 1 0 -0 1 2.002324e-05 4.250407e-05 1 0.9992681 -0.0377343 -0.006273129 0.9989051 -0.01270873 0.04502366 0.9991834 0 0.04040487 0.9996114 0.002739476 0.02774066 0.9999715 -0.005196415 0.005481599 0.9999651 -0.00386842 0.007410819 1 0 0 0.99986 -0.005979244 -0.01562639 0.9990239 -0.01500261 0.04154904 0.9908792 0.05085443 -0.124789 -1.244163e-06 0.5446395 -0.8386703 -0.0317387 0.6876298 -0.7253674 0.9205105 -0.3904858 0.01346694 0.8485705 -0.5288689 -0.01502473 0.69231 -0.7213997 0.01700866 0.3648461 -0.9310533 -0.005215296 0.3855473 -0.9226881 -0.0001574054 0.9615871 0.2639934 0.07521696 0.9575697 0.2761323 0.08253036 0.1657472 0.985999 -0.01827227 0.9967397 0.08056244 -0.004420646 0.494941 0.8672211 0.05441425 0.2365834 0.9707097 -0.0418456 0.3169357 0.9483563 -0.01312096 0.5032773 0.8522706 -0.142642 0.6527378 0.7551397 0.0608067 -0.03205829 0.02198166 0.9992442 -3.530996e-05 0 1 0.001282668 -0.9999748 -0.006978284 4.221595e-05 -1 0 0.003158288 -0.9999821 0.005079858 0.00148054 -0.9999942 0.00306293 0.002573882 -0.999994 -0.002299193 0.007493444 -0.9999415 -0.007807605 0.00459738 -0.9999893 -0.0006304364 -0.004935556 -0.9999858 -0.002015897 0.004272526 -0.9999908 -2.458497e-05 -0.0006166238 -0.9999926 0.003778624 -0.0005062158 -0.9999999 0.0001406074 -0.002273485 -0.9999965 0.001388916 -0.001553896 -0.9999973 0.001795402 -0.0002230062 -0.9999591 0.0090495 -0.002977975 -0.9999933 0.002112831 -0.003332532 -0.9999814 -0.005093997 -0.006232101 -0.9999763 -0.002932305 0.005993641 -0.999957 0.007065205 2.053493e-05 -0.9934212 -0.1145178 -0.0004823916 -0.9999762 -0.006886652 -0.01136458 -0.9999353 -0.0002498968 -0.0102138 -0.9999478 -0.000167787 0.0002531491 0.9999999 -0.0004394804 -0.0002820926 0.9999996 0.0006786776 0.00190917 0.9999894 -0.004178838 -0.00224363 0.9999968 0.001164263 -0.001164779 0.9999989 0.0008384142 0.0006283402 0.9999998 -7.842639e-05 -0.002817959 0.9999846 -0.004784068 -0.001591182 0.9999954 -0.002618775 -0.001723961 0.9999887 -0.004424774 -0.001990594 0.9999519 0.009598622 -0.001651466 0.9999864 0.004965539 0.01974905 0.9987603 0.0456943 -0.003805361 0.9999897 -0.002457956 0.001080608 0.9999993 -0.000519769 -0.001414274 0.9999865 -0.005012163 -0.004275652 0.9999842 -0.003641837 -0.003199607 0.9999929 0.001974881 0.0007834515 0.9999996 -0.0005503478 -0.001080301 0.9999976 0.001922455 -0.002331583 0.9999942 0.002491332 -0.005004249 0.9999722 -0.005536227 0.0009661478 0.9999987 0.001234883 0.00202662 0.9999972 0.001258311 -0.004362317 0.9999905 0 0.00138263 0.9990878 0.0426799 0 1 0 -0.001268976 0.9999873 -0.004889523 -0.005692035 0.9999837 -0.0003786451 0.2263707 -0.0005217679 0.9740411 0.2313974 -0.0001066392 0.9728593 0.06866128 0.002640106 0.9976366 0.4070466 -0.007510586 0.9133765 0.3904336 -0.003924735 0.9206228 0.366099 -0.0001625035 0.9305759 0.3727894 0.0004264462 0.9279159 0.4492935 -0.001023397 0.8933836 0.5290875 0.0005714495 0.848567 0.5385563 0.001635425 0.8425879 0.6187157 -0.003067782 0.7856089 0.6556655 -0.0009847488 0.7550508 0.6702635 0.002028623 0.7421205 0.7033444 0.01466156 0.7106979 0.825761 -0.002732693 0.5640135 0.8545038 0.01255766 0.5192934 0.9251034 -0.00648914 0.3796598 0.9562334 0.009519285 0.2924503 0.9651424 0.0002116973 0.2617253 0.4902894 0.003662093 0.8715519 0.6125792 -0.002848504 0.7904041 0.608978 -0.0002526667 0.7931871 0.007607359 -0.9999084 0.01120191 0.5039338 -0.8630989 -0.03333044 0.6189574 -0.7843382 0.04129212 0.9068916 -0.4204997 -0.02697257 0.9456899 -0.3239499 0.0269658 0.9858834 0.1613795 -0.04461516 0.9474628 0.3155354 0.05245647 0.6038845 0.7961547 -0.03822524 0.5135617 0.857201 0.03821999 -0.08916809 0.9944088 -0.05657053 -0.2179901 0.9753137 0.03526526 -0.7071562 0.7070353 0.005573951 -0.7864703 0.6135936 -0.07047903 -0.9742151 0.2124782 0.075882 -0.9837636 -0.1564619 -0.08791279 -0.8514494 -0.518985 0.07542218 -0.6332995 -0.7707499 -0.06983196 -0.3704332 -0.9276318 0.04773328 0.06030392 -0.9977952 -0.02771494 0.6001779 0.001851142 -0.7998644 0.6159286 -0.009683516 -0.7877424 0.5103733 0.004876759 -0.8599391 0.3529342 0.0008006216 -0.9356479 0.3557015 0.001122578 -0.9345989 0.3639814 -0.0005111501 -0.9314061 0.4004942 -0.01018695 -0.9162427 0.5238132 0.002994587 -0.8518279 0.4925226 -0.0002487972 -0.8702996 0.616703 0.002388088 -0.7871923 0.6488973 -0.007620658 -0.7608378 0.7310469 0.01031116 -0.6822494 0.7380507 0.01399041 -0.6746002 0.8437727 -0.002636824 -0.5366942 0.9139295 0.01511167 -0.4055914 0.8969355 -0.004128797 -0.4421423 0.9697581 0.001357544 -0.2440646 0.09227012 0.001778876 -0.9957324 0.1951425 -0.0007715659 -0.9807746 0.2159232 0.0006768064 -0.9764101 0.01173827 0.006044859 -0.9999128 0.001540838 -0.003262192 -0.9999935 0.005887603 -0.0007734781 -0.9999824 0.004506293 0.0004046237 -0.9999897 0.001790413 0.004060786 -0.9999901 0.03097052 0.9981461 -0.05239411 -0.3521321 0.9336008 0.06627551 -0.625238 0.7765457 -0.07780846 -0.8465527 0.5285828 0.06283984 -0.9913046 0.1244791 -0.04266313 -0.9995899 -0.009622295 0.02697262 -0.8893929 -0.4553393 -0.04057458 -0.8069884 -0.5891715 0.04057918 -0.4337048 -0.9005229 -0.03096403 -0.3352798 -0.9415023 0.03407311 0.2559253 -0.96504 -0.0565686 0.3796273 -0.9244681 0.0352402 0.8165578 -0.577237 0.005557565 0.8658493 -0.497524 -0.05267701 0.9934253 -0.1056236 0.04415835 0.9809227 0.1866217 -0.05443244 0.8923041 0.4471232 0.06224462 0.6436018 0.761568 -0.07609903 0.3325501 0.9397694 0.07901809 1.695421e-06 0.001014288 0.9999995 0.001313587 -0 0.9999991 0.6876371 -0.2786563 0.6704519 0.8101138 -0.3152954 0.4942716 0.8972476 -0.3514941 0.267205 0.9315723 -0.2629121 0.2510981 0.6459919 -0.3498082 0.6784753 0.8152316 -0.3032876 0.4933703 0.9555424 -0.01527111 -0.2944581 0.8341506 -0.04646349 -0.5495763 0.6666185 -0.4216518 -0.6146783 0.9557566 -0.2095494 -0.206442 0.8333211 -0.3254593 -0.4468244 -0.01180181 0.2082758 0.9779989 -0.01601816 0.2223158 0.9748431 0.02029669 0.715152 0.6986741 -0.02680502 0.8488555 0.527945 0.01849742 0.9726522 0.2315287 -0.01623164 0.9925379 -0.1208511 0.02132418 0.9451512 -0.3259364 -0.02773317 0.7716978 -0.6353845 0.03004587 0.4607905 -0.8870003 -0.02355195 0.2283442 -0.9732956 0.02354645 -0.2283558 -0.973293 -0.01017725 -0.3771347 -0.9261025 -0.00175945 -0.7461973 -0.6657227 0.008565771 -0.7719551 -0.6356193 -0.001817342 -0.9926652 -0.1208818 0.00181206 -0.9910948 -0.1331462 -0.008561831 -0.9071934 0.4206268 0.02326431 -0.8489312 0.527991 -0.02764796 -0.4657388 0.8844902 0.01837965 -0.2748837 0.9613018 0.02728661 0.2503556 0.9677694 -0.03338921 0.5092912 0.8599463 0.02992955 0.7729068 0.6338133 -0.03797741 0.9819435 0.185323 0.0379792 0.9941238 -0.1013681 -0.03397781 0.8062135 -0.5906482 0.03052375 0.6040635 -0.7963515 -0.01806591 0.2883526 -0.9573538 0.01378808 -0.03282173 -0.9993661 -0.009709865 -0.1624329 -0.9866718 0.01699227 -0.5649905 -0.8249224 -0.01699773 -0.6873436 -0.7261336 0.01129006 -0.9395735 -0.3421611 -0.01129063 -0.970043 -0.2426708 0.01868875 -0.9694454 0.2445941 -0.02966924 -0.9057971 0.4226716 0.03269178 -0.508949 0.8601757 -0.03251975 -0.3066061 0.9512808 0.002972964 0.007656777 0.9999663 0.001145502 0.4802398 0.8771366 -0.004724612 0.5031281 0.864199 0.005191965 0.8547299 0.519047 -0.01427256 0.8917141 0.4523742 0.02029797 0.9969593 -0.07523372 -0.02681134 0.9571206 -0.2884462 0.02633308 0.7825058 -0.6220862 -0.02635423 0.5648788 -0.824753 0.02356833 0.1103902 -0.9936089 0.0006804517 0.03283805 -0.9994604 -0.00950165 -0.5547791 -0.8319435 0.02209215 -0.651349 -0.7584565 -0.02144854 -0.9149162 -0.4030736 0.0166959 -0.9788044 -0.2041155 -0.01109255 -0.9688361 0.247454 -0.007126272 -0.9721282 0.2343418 0.007461694 -0.6348345 0.7726122 -0.002013724 -0.6114508 0.7912798 -0.004635595 -0.02056547 0.9997779 3.44431e-06 -6.216473e-06 1 -8.263325e-06 7.009296e-06 1 1.314961e-06 2.414437e-07 1 -0.003965569 -0.002389544 0.9999893 2.2242e-06 -5.61864e-07 1 -0.009657605 0.001494901 0.9999522 3.992818e-06 -3.149499e-07 1 2.182021e-06 -6.852262e-07 1 0 0 1 3.168263e-06 7.433061e-07 1 -0.002576869 -0.005190535 0.9999832 0 0 1 -4.681739e-06 8.449849e-06 1 2.84333e-07 1.89648e-06 1 -0.003604074 0.009961062 0.999944 -0.00741663 0.001882193 0.9999707 -0.007552435 0.0006866738 0.9999712 -0.002938642 0.003125477 0.9999908 0.002085107 0.001586385 0.9999966 0 0 1 1.720144e-06 -7.005165e-07 1 8.599278e-07 -2.280294e-06 1 0.001261092 0.001024673 0.9999986 0.0008021584 9.918724e-05 0.9999996 8.504562e-07 1.505903e-06 1 1.050824e-06 4.105825e-07 1 -1.618416e-07 3.289403e-06 1 1.426954e-06 1.732948e-06 1 1.57397e-06 1.372362e-06 1 -1.313201e-06 -4.851908e-06 1 0.007235264 0.01233246 0.9998978 0.001844426 0.002336954 0.9999955 0.002280565 -7.420794e-05 0.9999974 0.0006092878 -0.0003528126 0.9999997 0.0004015712 -0.0009683679 0.9999995 0.000548164 -0.0004649758 0.9999996 0.0005387344 -0.0006045272 0.9999996 0.0004723989 -0.002923151 0.9999956 0.0001167608 -0.0218105 0.9997621 7.994951e-07 -8.970948e-07 1 -0.004116723 -0.002281317 0.9999889 0.0003179673 -0.001967441 0.999998 -0.003336682 -0.00306041 0.9999897 -0.00512406 -0.002369951 0.9999841 -0.008675778 -0.01895799 0.9997826 -0.007348906 -0.006412904 0.9999524 -0.01811453 -0.00372255 0.999829 -0.00943842 0.01708232 0.9998096 1.036821e-06 1.340695e-06 1 1.259481e-06 9.218937e-07 1 0 0 1 2.741154e-06 4.30658e-07 1 -0.004300494 0.002426941 0.9999878 -0.00829812 0.01010565 0.9999145 -0.001084186 0.006503769 0.9999782 0.001412742 0.01487214 0.9998884 0.001811381 0.006059359 0.99998 1.531412e-06 -1.613635e-06 1 1.678066e-06 -1.333046e-06 1 6.140485e-07 -2.170117e-06 1 -0.009700507 0.004676761 0.999942 0.9915258 0.1221889 -0.04411798 0.9431475 0.3260162 0.06470162 0.7730257 0.6321283 -0.05333929 0.5024741 0.8622861 0.06310686 0.2609031 0.9640075 -0.05117694 -0.1509063 0.9874877 0.04577497 -0.2985642 0.9537951 -0.03367794 -0.7172545 0.6959974 0.03366834 -0.7978454 0.6020505 -0.0312721 -0.9725536 0.2311025 0.02703854 -0.9961544 0.07858108 -0.03874803 -0.9520637 -0.3015893 0.05117023 -0.8690361 -0.4931403 -0.03986125 -0.5636381 -0.8255973 0.02648187 -0.5748566 -0.8180771 0.0170216 0.01815464 -0.9996902 -0.01702598 0.03623402 -0.9993339 -0.004349351 0.5423176 -0.8399536 0.01922376 0.60001 -0.7997977 -0.01765612 0.8916643 -0.4526441 0.006939414 0.9102905 -0.4125548 0.03420228 0.8746519 0.4827254 0.04427475 0.8275816 0.5609248 -0.02172427 0.3402447 0.9403201 0.005621628 0.4070757 0.9119128 -0.05200456 -0.03570241 0.9977171 0.05732188 -0.3743892 0.9251807 -0.06223702 -0.6361783 0.7686188 0.06709767 -0.8453888 0.5293671 -0.07133111 -0.9927371 0.08899109 0.08095383 -0.9774383 -0.1982906 -0.07276794 -0.7946137 -0.602739 0.07276493 -0.5890676 -0.8040187 -0.08095197 -0.1310287 -0.9880682 0.0809487 0.1292518 -0.989909 -0.05808797 0.5442635 -0.8376652 0.04576306 0.6649175 -0.746157 -0.03367916 0.9594275 -0.2788174 0.0419489 0.9851787 -0.1665323 -0.04110771 0.8973724 0.4404778 -0.026497 0.8481725 0.5290045 0.02752198 0.5185946 0.8540571 -0.04057243 0.3208685 0.9444129 0.07160646 -0.1025952 0.9918566 -0.07546318 -0.4449032 0.8923979 0.07541226 -0.6840646 0.7276243 -0.05117063 -0.9199994 0.3892362 0.04578596 -0.9747809 0.2177979 -0.04864375 -0.9592419 -0.2748085 0.06584296 -0.8555522 -0.5125778 -0.07276317 -0.5737818 -0.8165723 0.0631199 -0.2876949 -0.9547486 -0.07541043 0.06649437 -0.9949293 0.07546083 0.5005598 -0.8618818 -0.08123849 0.6970147 -0.7137197 0.06909922 0.9725586 -0.2223889 -0.06835795 0.9980271 -0.04823731 0.0401879 0.9403263 0.3375739 -0.04278144 0.8303956 0.5535356 0.06357373 0.5666651 0.821288 -0.06615635 0.274834 0.9606338 0.04060845 0.06381137 0.9975434 -0.02890132 -0.2039833 0.9782946 0.03647635 -0.4801037 0.8749603 -0.06280836 -0.736428 0.6722929 0.07547266 -0.9418689 0.3301646 -0.06224459 -0.9966824 0.06050261 0.05443966 -0.9719631 -0.2309513 -0.04414878 -0.7956223 -0.6034949 0.05271607 -0.6968064 -0.7161151 -0.04049735 -0.1313338 -0.9903439 0.04438809 -0.01210853 -0.9990587 -0.04165312 0.5187635 -0.8542544 0.03367487 0.6415828 -0.7656875 -0.04576282 0.8810173 -0.4710829 0.04346699 0.9745181 -0.2198831 -0.04434088 0.9994413 0.006234803 0.03283862 -0.9991102 -0.03970543 -0.01422513 -0.977921 -0.1957755 0.07309213 -0.8622044 -0.5034347 -0.05618667 -0.5530378 -0.8317348 0.04864848 -0.4204233 -0.9067887 -0.03128183 0.009597664 -0.9994646 0.03127902 0.1330784 -0.9905333 -0.03367339 0.6135453 -0.788759 0.03770071 0.7044328 -0.7087695 -0.0376855 0.9728704 -0.2282571 0.03770834 0.9933385 -0.1088917 -0.03770069 0.9132437 0.4060198 0.0336755 0.856095 0.5158704 -0.03129008 0.5770334 0.8162733 0.027026 0.4443535 0.8950136 -0.03873821 0.1056025 0.9934281 0.04414407 -0.214621 0.9746017 -0.0639489 -0.392496 0.9191737 0.03266121 -0.8279997 0.5607253 0.00194469 -0.8388495 0.5441761 -0.01428241 -0.8967261 -0.4396055 -0.0512775 -0.7731476 -0.6313205 0.06063963 -0.5182815 -0.8535454 -0.05333382 -0.2163896 -0.974849 0.05333768 0.1311851 -0.9892942 -0.06393284 0.3131316 -0.9491475 0.03267385 0.7764716 -0.6301489 0.00203133 0.7964883 -0.6041473 -0.02474668 0.9981589 0.06058708 0.002799294 0.9965966 0.08032503 0.01852517 0.718712 0.6950611 -0.01852503 0.7049352 0.7092661 -0.002808103 0.1331048 0.9908423 0.02268654 0.01211576 0.9985367 -0.05270357 -0.4200911 0.9060379 0.05117568 -0.6409686 0.7649688 -0.06310331 -0.8625215 0.5036235 0.04919222 -0.980126 0.1922327 -0.04898587 -0.999321 0.0148361 0.03372509 -0.9312268 -0.3641874 -0.01357141 -0.9129276 -0.4076393 0.01983554 -0.42282 -0.9059643 -0.02126126 -0.3485245 -0.9363362 0.04248808 0.2423931 -0.968968 -0.04844144 0.4183075 -0.9070183 0.04833777 0.7447829 -0.6655549 -0.04832403 0.8555101 -0.5155154 0.04843953 0.9994164 0.002480226 -0.03407201 0.9935678 0.1089244 0.03095911 0.8243414 0.5646368 -0.04057873 0.6813785 0.7284201 0.07160677 0.315058 0.9460677 -0.07546078 -0.06788711 0.9938185 0.08784138 -0.2989984 0.953525 -0.03728206 -0.6885048 0.7250839 -0.01464083 -0.7548892 0.6543336 0.04460783 -0.9753465 0.2190076 -0.02710913 -0.988655 0.1499179 0.009263104 -0.9946294 -0.09669086 -0.03692001 -0.9753462 -0.2190102 0.02710013 -0.7908064 -0.6109669 -0.03666802 -0.6413056 -0.7653526 0.05442864 -0.339594 -0.9384716 -0.06282429 -0.0181367 -0.9969842 0.0754552 0.3744586 -0.925151 -0.06226102 0.6130754 -0.7881482 0.05441504 0.8307603 -0.5540689 -0.053338 0.9566312 -0.2880932 0.04311636 0.9989186 0.0328206 -0.03293137 0.980662 0.1923184 0.03627139 0.8233991 0.5639739 -0.06282851 0.6210804 0.7812248 0.06282387 0.3154815 0.9473692 -0.05443449 0.1056249 0.9937299 0.03666221 -0.3239743 0.9456816 -0.02696299 -0.4475805 0.8932269 0.0426334 -0.7996334 0.596343 -0.0704367 -0.9289421 0.3632555 0.07149791 0.9999461 -0.003451626 -0.009792748 0.9999726 -0.005087229 -0.00537234 0.9987281 -0.04934065 0.01037197 0.9999668 -0.00377173 -0.007225491 1 -0 0 1 -6.94433e-05 0.0001814833 0.9999891 -0.0008415108 -0.004586654 0.9991746 0.01668643 0.037035 -0.003733562 -0.001655249 0.9999917 -0.002886025 0.0004545967 0.9999958 -0.004439986 -0.0002695021 0.9999901 -3.578617e-07 2.663646e-06 1 2.651108e-07 7.961094e-07 1 1.504598e-06 4.943586e-08 1 1.738828e-06 -1.944083e-07 1 -0.007514164 0.003231687 0.9999666 0.002038339 -0.009256171 0.999955 -0.001208663 -2.999511e-06 0.9999993 -0.001042826 0.0004486277 0.9999993 -0.0004682604 0.007094631 0.9999747 1.251975e-06 8.575199e-07 1 2.687903e-06 -1.808121e-06 1 7.534977e-07 4.399616e-07 1 -8.277878e-06 8.46759e-06 1 0.02662036 -0.02288624 0.9993836 -0.0061888 -0.009448037 0.9999362 -0.005235569 -0.01054544 0.9999306 -0.002194883 -0.01204618 0.999925 -0.001572916 -0.0009515514 0.9999983 -0.001715574 0.0001880646 0.9999985 -0.001055866 -0.001629997 0.9999981 -0.003119913 -0.001390505 0.9999942 -0.002453399 -0.002376149 0.9999942 0.0001458523 -0.0001087723 1 7.647763e-05 -0.0002158356 0.9999999 -0.0008742337 -0.001882829 0.9999979 9.00973e-07 3.580539e-08 1 -0.0004415053 -0.0003411004 0.9999999 -1.460481e-08 -1.203675e-06 1 1.388252e-06 -9.258833e-07 1 5.132088e-07 -1.636655e-06 1 3.345922e-07 -8.266557e-07 1 3.473705e-06 1.877597e-06 1 3.083033e-06 8.894675e-07 1 5.235329e-07 -6.248143e-07 1 2.53416e-07 7.609667e-07 1 3.875973e-06 -1.657985e-06 1 -0.002298097 0.002057422 0.9999952 -0.0005412031 0.002163464 0.9999975 -0.0004369999 -0.0001709034 0.9999999 -0.0006474194 -6.29377e-05 0.9999998 -0.0002137403 -0.000570183 0.9999998 -0.001900023 0.001441194 0.9999972 -0.001518339 0.002165337 0.9999965 2.768496e-06 -1.819521e-06 1 0.001657325 0.0035452 0.9999923 -0.0006462213 0.001266609 0.999999 3.740728e-06 4.107216e-06 1 -0.0003220924 -0.0005262849 0.9999998 -0.0004985188 0.0001119391 0.9999998 4.150998e-07 6.83618e-07 1 1.055515e-06 -1.180111e-07 1 4.162912e-06 2.055847e-06 1 3.649528e-06 -1.413961e-06 1 -0.2047836 -0.9787378 -0.01167111 -0.1803697 -0.9832864 0.02479373 -0.152123 0.988176 0.01914212 -0.170381 0.9853783 -9.400952e-05 -0.3095514 0.9508632 0.0060995 -0.3269291 0.9449238 -0.01537636 -0.4114063 0.9104005 -0.04376922 -0.5022808 0.8647045 -0.0001079769 -0.5089698 0.8607683 -0.005261977 -0.6127034 0.7903118 -0.001280247 -0.6189036 0.7854365 -0.006905545 -0.7001666 0.7139579 -0.005538782 -0.7070962 0.7071148 0.00195982 -0.8092954 0.5873935 0.003114927 -0.8036721 0.5949944 0.009643109 -0.837301 0.5466176 0.01166701 -0.8517189 0.5239564 -0.006676211 -0.9218507 0.3875218 -0.004277275 -0.9212668 0.3889224 -0.002599175 -0.9825528 0.1859836 -9.932992e-06 -0.9798681 0.1991573 0.01395714 -0.9962776 0.08389661 0.0198052 -0.9986426 0.05196102 -0.003611687 -0.998283 -0.0584631 0.003596901 -0.9941539 -0.103844 -0.02957062 -0.9817477 -0.1885845 -0.02464584 -0.9882047 -0.1531328 -0.001355283 -0.9492902 -0.314396 0.001783925 -0.9544069 -0.2978123 0.02037711 -0.9030846 -0.4289479 -0.02102633 -0.8614001 -0.5075105 0.02056755 -0.8444775 -0.5354151 -0.01372447 -0.7925466 -0.6083238 -0.04256788 -0.7236122 -0.690102 0.01202555 -0.6946871 -0.7191005 -0.01744322 -0.6191788 -0.7851644 -0.01159573 -0.5931874 -0.8048854 0.01697274 -0.5040222 -0.8634783 -0.019151 -0.426903 -0.9041301 0.0173934 -0.3869238 -0.9220244 -0.01268258 -0.3041063 -0.9523385 0.02388802 -3.817755e-07 3.118943e-06 -1 -0.001714945 0.003520957 -0.9999923 -0.001331749 0.003704494 -0.9999923 -0.009157397 0.00252111 -0.9999549 -0.005449275 0.005293928 -0.9999712 -0.007595725 0.00472048 -0.99996 -0.007083329 -0.001976035 -0.999973 -0.01972326 0.003507831 -0.9997993 -0.008137509 -0.003360909 -0.9999612 -0.005641424 -0.008430958 -0.9999486 -1.209299e-06 2.837019e-07 -1 -2.945227e-07 9.98653e-07 -1 -0.004161114 -0.02499342 -0.999679 -0.004601941 -0.005403505 -0.9999748 -0.002066271 0.00149919 -0.9999967 -0.001036362 -5.398564e-05 -0.9999995 0.00355573 -0.01751758 -0.9998403 -0.009109027 -0.006802638 -0.9999353 0.00057064 0.0002323779 -0.9999998 -0.003722349 0.008119566 -0.9999601 -1.036473e-06 6.412912e-09 -1 -0.00587589 0.005164918 -0.9999694 -9.63973e-07 4.035197e-06 -1 -0.0001440261 0.01660923 -0.9998621 -0.000495704 0.01546968 -0.9998802 -0.006754289 0.00489563 -0.9999652 -1.086229e-06 -8.106279e-08 -1 -9.849178e-07 4.904684e-07 -1 -2.519269e-06 -1.501269e-06 -1 -3.122972e-06 -1.861025e-06 -1 0.0004664308 0.0004914629 -0.9999998 -1.006589e-07 1.11721e-06 -1 -9.285488e-07 4.266706e-07 -1 -1.143416e-06 -3.906278e-07 -1 -2.176177e-06 -8.699431e-06 -1 -1.093389e-06 2.270058e-07 -1 -9.94469e-07 -4.049818e-07 -1 -6.645794e-07 -3.986711e-06 -1 -1.461782e-06 -2.604179e-07 -1 -2.203726e-07 8.295756e-07 -1 0.0005864014 -0.0001375713 -0.9999998 0.0006654748 3.150293e-05 -0.9999998 0.0004485557 0.0008817037 -0.9999995 -7.061979e-07 -4.442145e-07 -1 -1.787641e-07 1.521678e-06 -1 -2.410324e-06 -1.59171e-06 -1 -1.705871e-06 6.402735e-08 -1 -0.006581597 -0.01191243 -0.9999074 -2.470257e-06 -1.358432e-06 -1 0.0004798436 0.0004044594 -0.9999998 0.0003025883 0.0009583757 -0.9999995 -1.669602e-06 2.607301e-06 -1 -1.213479e-06 -5.4974e-07 -1 -1.830022e-06 -1.208495e-06 -1 -1.021458e-06 -4.49009e-07 -1 -9.92492e-07 -1.906402e-07 -1 -8.939437e-06 4.153445e-06 -1 0.0004546187 -0.0006270325 -0.9999997 0.0004087353 -0.04263825 -0.9990905 -0.0003828029 -0.03783707 -0.9992839 0.0004654587 -0.0004366707 -0.9999998 0.0004301109 -0.0005529434 -0.9999998 -2.534219e-06 1.495269e-06 -1 -0.9730512 0.2282803 0.032551 -0.9692416 0.2459712 0.008304617 -0.7287323 0.6839437 -0.03420916 -0.6114069 0.786014 0.0914517 -0.377713 0.9222461 -0.08243182 0.0465965 0.9916891 0.1199231 0.2042018 0.9767826 -0.06478713 0.6765918 0.7362832 -0.01052498 0.704797 0.7084644 0.03659768 0.9462503 0.3232701 -0.01033364 0.9495909 0.3127705 -0.02125239 0.9787828 -0.2032118 0.02625205 0.9835914 -0.1581257 0.08685669 0.845015 -0.5261543 -0.0954532 0.5906668 -0.8028071 0.08132339 0.5058473 -0.8623616 -0.02124068 0.08971885 -0.9957873 0.01892683 -0.009578971 -0.9979754 -0.06287581 -0.3020304 -0.9507073 0.07023829 -0.5880196 -0.8054561 -0.07398257 -0.6880714 -0.7249985 0.03057656 -0.9260709 -0.3771193 -0.01317925 -0.9310092 -0.3637805 -0.02975775 0 -0 -1 -3.193652e-06 1.400143e-07 -1 -3.191097e-06 1.763511e-07 -1 -0 0 -1 -0 0 -1 -2.511773e-06 -2.657485e-07 -1 -2.80433e-06 5.402233e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.322207e-06 -7.82332e-07 -1 -6.124311e-06 1.84436e-06 -1 -7.367808e-06 1.184476e-06 -1 -6.09475e-06 -1.195246e-06 -1 -7.510654e-06 -2.473814e-06 -1 -6.903144e-06 -3.164624e-06 -1 0 0 -1 0 0 -1 -0 0 -1 0 0 -1 -0 0 -1 -0.9991178 -0.03749135 -0.01892471 -0.9084062 0.4174151 0.02372153 -0.9146175 0.4020225 0.04304175 -0.6637464 0.7440803 -0.07606061 -0.5170937 0.8525421 0.07606614 -0.1165678 0.9922495 -0.04304406 -0.1027118 0.9929513 -0.05914341 0.3774457 0.9227874 0.07744692 0.4912214 0.8697954 -0.04644934 0.8068835 0.5906133 -0.01072203 0.8449522 0.5314941 0.0597483 0.9876938 0.147628 -0.05164208 0.9972427 -0.006170188 0.07395209 0.9198635 -0.379921 -0.09752543 0.8058223 -0.5840745 0.09750554 0.5281193 -0.8459408 -0.07398811 0.416188 -0.908765 0.03055561 0.03202537 -0.9994336 -0.01033672 -0.009571441 -0.9986268 -0.05150634 -0.4543443 -0.8874546 0.07743191 -0.5878728 -0.8052387 -0.07743552 -0.8753883 -0.4813894 0.04426713 -0.9068173 -0.4213653 -0.01156019 -0.9971603 -0.07441575 0.01156097 -3.138458e-06 -8.177049e-07 -1 -3.053149e-06 -1.094331e-06 -1 0 0 -1 0 0 -1 -6.519768e-07 3.401862e-06 -1 -1.284524e-06 3.005323e-06 -1 -0 0 -1 0 -0 -1 -5.141605e-06 3.453689e-06 -1 0 0 -1 0 0 -1 -3.264228e-06 9.437018e-06 -1 -2.295332e-05 9.480154e-06 -1 -1.639711e-05 -1.028931e-05 -1 0 0 -1 0 0 -1 -3.821719e-06 -4.315107e-07 -1 -3.830441e-06 -7.027847e-07 -1 -0 0 -1 0 0 -1 -0 0 -1 -0.9909416 -0.06014745 -0.1200701 -0.9665244 0.2267469 0.1200679 -0.8461821 0.5265015 -0.0822928 -0.6547796 0.754085 0.05118061 -0.5556849 0.8308097 -0.03113621 -0.28256 0.9580907 0.04713939 -0.1055058 0.9921489 -0.0671497 0.1638399 0.9849249 0.05549305 0.4196064 0.9050599 -0.06926136 0.5552361 0.8297855 0.05629314 0.8681767 0.4920701 -0.06431335 0.9226194 0.3810553 0.05975195 0.998436 -0.02141292 -0.05164181 0.9818534 -0.1746251 0.07395869 0.8758583 -0.4774249 -0.07026901 0.7163138 -0.6958933 0.05125279 0.6241062 -0.7807229 -0.03103509 0.3370896 -0.939914 0.05414871 0.2206308 -0.9743491 -0.04433667 -0.2041548 -0.9789063 -0.007959183 -0.2424888 -0.9693676 0.03905886 -0.6883663 -0.7253539 -0.003697454 -0.7364628 -0.6722952 -0.0751112 -0.9230104 -0.3758812 0.08225022 -3.852195e-07 5.13432e-06 -1 -6.076617e-06 3.780921e-06 -1 0 0 -1 -0 0 -1 -2.792566e-06 3.463226e-06 -1 0 0 -1 0 0 -1 -6.399422e-06 3.313829e-06 -1 -1.745019e-06 1.917906e-06 -1 -2.317145e-06 8.728736e-07 -1 0 0 -1 -0 0 -1 -3.763801e-06 4.090093e-07 -1 -3.920204e-06 -8.878126e-08 -1 0 -0 -1 0 0 -1 0 -0 -1 0 -0 -1 0 0 -1 -1.06808e-06 -3.367116e-06 -1 0 0 -1 0 0 -1 -0.9973156 0.03743276 0.06293218 -0.9667491 0.2453349 -0.07215915 -0.9060498 0.4209693 0.04311258 -0.6837782 0.727235 -0.05980335 -0.5884078 0.8060036 0.06429954 -0.1641567 0.9848261 -0.05630181 -0.009562656 0.9975535 0.06925137 0.2563489 0.9649901 -0.05549164 0.4826276 0.8740639 0.05552267 0.6755951 0.7352037 -0.05519847 0.7997845 0.5972806 0.06000526 0.9543642 0.2822731 -0.09752311 0.9938859 0.05177299 0.09752155 0.9309399 -0.3545834 -0.08730177 0.8950985 -0.4457402 0.0106925 0.652139 -0.7568038 0.04430211 0.5552501 -0.8299197 -0.05413539 0.2566169 -0.9660136 0.03107541 0.1640657 -0.9859587 -0.03111099 -0.164189 -0.9849451 0.05408427 -0.3125255 -0.9473259 -0.07001017 -0.6650403 -0.7454952 0.04425373 -0.7146603 -0.6993761 -0.01155897 -0.9153967 -0.402387 0.01155226 -0.9396953 -0.3391344 -0.04427991 1.600881e-06 -5.365458e-06 -1 -0 0 -1 -4.194458e-06 -1.203101e-06 -1 -3.886155e-06 -2.391024e-06 -1 0 -0 -1 0 0 -1 -2.565391e-06 -1.541335e-06 -1 -2.043395e-06 -4.76501e-06 -1 6.547344e-06 1.52678e-05 -1 2.008908e-06 1.889828e-05 -1 -6.058561e-06 1.695428e-05 -1 -2.35321e-05 8.963084e-06 -1 -3.871226e-06 -7.762086e-06 -1 0 0 -1 0 0 -1 -5.641192e-07 3.733436e-06 -1 -2.401986e-06 3.098992e-06 -1 -8.038446e-06 1.037103e-05 -1 0 0 -1 0 0 -1 -0 0 -1 0 0 -1 -0.1865596 -0.9821701 -0.02318338 -0.07077099 -0.9969239 -0.03367604 -0.07048098 0.9967161 -0.03986846 -0.1690181 0.9853991 0.0205311 -0.2714576 0.9620886 -0.02638413 -0.3224421 0.9464555 0.01591104 -0.410408 0.9116075 -0.02317666 -0.5022272 0.8645297 0.01887441 -0.5343705 0.8452018 -0.009057766 -0.6159955 0.787736 -0.00464186 -0.6156175 0.7880333 -0.004320311 -0.7130165 0.7011377 -0.003669645 -0.7014086 0.7127188 0.007607566 -0.7892981 0.6139759 0.006486559 -0.7936106 0.6084254 0.0008943373 -0.8557121 0.5174497 -0.001624559 -0.8611548 0.5082567 -0.009354727 -0.9016511 0.4322544 -0.01346462 -0.9167291 0.3993367 0.01174328 -0.9542806 0.2988346 0.006824709 -0.9583784 0.2854695 -0.00423991 -0.9845791 0.1746678 -0.0097523 -0.9822961 0.1873341 0.0006425805 -0.998297 0.05790803 -0.00704909 -0.999213 0.0394254 0.004349088 -0.9991826 -0.04022089 -0.004024652 -0.9984418 -0.05551412 0.005675151 -0.9830222 -0.1834262 -0.004717504 -0.9793749 -0.201871 0.008533682 -0.9571539 -0.2895543 0.003833029 -0.944964 -0.3257599 0.03038974 -0.7840984 -0.6206365 9.919643e-06 -0.9014278 -0.4321623 -0.02576297 -0.8586016 -0.5126426 -0.0009261449 -0.8699092 -0.4929824 0.01504856 -0.7783796 -0.6277627 0.006268709 -0.2092459 -0.9778277 0.008319604 -0.2940388 -0.9555021 -0.02359748 -0.4096739 -0.9119228 0.02375236 -0.3897597 -0.9209135 -0.002392311 -0.4981012 -0.8670974 0.006112983 -0.5143788 -0.8575371 -0.006674445 -0.6376629 -0.7702926 0.005945827 -0.6198958 -0.7845906 -0.01211165 -0.6982869 -0.7157891 -0.006424724 -0.6957872 -0.7181917 -0.008986439 -1.642734e-06 -5.203758e-07 -1 -2.684588e-05 7.400688e-06 -1 -7.737257e-07 1.274104e-06 -1 -7.150751e-07 1.434315e-06 -1 -6.72247e-07 -9.566734e-07 -1 -6.212436e-06 3.321811e-06 -1 -1.574036e-06 -8.045082e-08 -1 3.728057e-05 -1.656842e-05 -1 -0.0004022551 -0.0001152398 -0.9999999 0.0006579271 -0.009844293 -0.9999513 -0.001257841 0.008479012 -0.9999633 4.182174e-07 3.153636e-06 -1 -9.91107e-07 4.193202e-07 -1 -0.0004694638 2.286017e-05 -0.9999999 -0.0005636361 -8.879125e-05 -0.9999998 -0.0003441776 -0.000489814 -0.9999998 -0.001087343 0.00850853 -0.9999632 -0.002044476 0.00212863 -0.9999956 -0.003001262 0.0001222284 -0.9999955 -0.001480709 0.001912018 -0.9999971 -0.02460261 0.004904894 -0.9996853 -0.006248886 0.008908533 -0.9999408 -0.006392379 0.009838383 -0.9999312 -0.006866656 0.001974745 -0.9999745 -4.630577e-07 -3.491849e-06 -1 -0.0004026297 -0.0002991362 -0.9999999 -5.389168e-07 -1.586195e-06 -1 -9.784228e-06 -1.400203e-05 -1 0 0 -1 -0.0002911164 0.0002657635 -0.9999999 -0.0003352842 -0.0004074989 -0.9999998 -0.00769675 0.0008543588 -0.99997 1.795074e-06 -5.333746e-06 -1 -1.343179e-06 -1.018842e-06 -1 2.015176e-07 -5.631472e-06 -1 8.759356e-06 -6.506268e-06 -1 -5.450084e-06 1.696321e-06 -1 -5.186673e-06 -1.161895e-05 -1 -0.001749173 -0.002135632 -0.9999962 -1.966218e-06 1.76256e-07 -1 -1.669225e-06 -8.531596e-08 -1 -8.496541e-08 2.343345e-06 -1 -0.003637766 -0.00498717 -0.9999809 -0.005318745 -0.001817335 -0.9999843 -0.004601141 -0.002453472 -0.9999864 -0.003546774 -0.008339307 -0.9999589 -0.0002816919 0.0002823421 -0.9999999 -0.002503139 -0.001358549 -0.999996 -6.062514e-06 -4.43808e-06 -1 7.323904e-07 -3.512499e-06 -1 -0.0002820024 0.0002806009 -0.9999999 -0.002887478 -0.004966317 -0.9999835 0.001058437 -0.006963345 -0.9999751 -0.000947419 -0.004898611 -0.9999875 -8.65247e-06 -1.274597e-06 1 0 0 1 -0 0 1 0 -0 1 0 -0 1 8.155313e-06 -3.109892e-06 1 1.229878e-05 -4.689934e-06 1 1.173996e-05 -1.001783e-05 1 0 0 1 -6.076056e-06 -1.483425e-05 1 -7.618932e-07 -1.191044e-05 1 3.443941e-06 -1.647254e-05 1 0 0 1 0 -0 1 0 0 1 0 -0 1 0 0 1 0 0 1 8.974231e-06 1.544338e-06 1 -1.140617e-06 -7.257819e-06 1 -7.35567e-06 -5.2464e-06 1 7.001609e-06 4.993868e-06 1 -0.9914437 -0.1225941 -0.04483367 -0.9743938 -0.2188038 0.0517845 -0.77181 -0.6311195 -0.07744271 -0.68782 -0.7243934 0.04645356 -0.3284335 -0.9444667 0.0106887 -0.26079 -0.9635448 -0.05974964 0.14809 -0.9876246 0.05164347 0.2719039 -0.9609392 -0.05161428 0.5856942 -0.8093821 0.04316083 0.6878571 -0.7247889 -0.03916185 0.8686892 -0.4930011 0.04825858 0.9246765 -0.3765679 -0.05630305 0.9914677 0.1086891 0.07196245 0.9710411 0.2278159 -0.0719657 0.7464142 0.6630974 0.05628195 0.6341329 0.7701157 -0.06926261 0.378114 0.9231378 0.06961641 0.1477548 0.9854307 -0.08423197 -0.2040863 0.976155 0.07396071 -0.3775543 0.9230307 -0.07393897 -0.6741683 0.7337605 0.08421695 -0.8574601 0.5036429 -0.1053852 -0.94807 0.3099353 0.07143678 4.69009e-06 9.353264e-06 1 0 0 1 6.483029e-06 3.680145e-06 1 1.180801e-05 -2.638294e-06 1 0 -0 1 0 0 1 0 -0 1 0 0 1 -2.654441e-06 1.218661e-05 1 8.230892e-06 -5.415787e-06 1 4.629529e-06 -3.046152e-06 1 1.148118e-05 8.54655e-06 1 7.101708e-06 1.385449e-05 1 -3.697805e-06 5.095169e-06 1 6.851053e-06 -9.439998e-06 1 2.705562e-06 -1.559235e-05 1 -2.219374e-06 1.279042e-05 1 -9.123524e-06 9.766352e-06 1 -0 0 1 0 -0 1 -0 0 1 -0.9971147 0.03094308 -0.06931617 -0.9962549 -0.07980653 0.03327155 -0.7960004 -0.6040682 -0.03853547 -0.8011056 -0.5963403 -0.05106804 -0.4548348 -0.8873221 0.07605751 -0.2855855 -0.9553297 -0.07606681 0.1642212 -0.9851232 0.05063342 0.08933637 -0.9947147 -0.05061201 0.517092 -0.852543 0.0760669 0.6817295 -0.725073 -0.09753904 0.9061739 -0.4163886 0.07395601 0.9666197 -0.245309 -0.07395921 0.9908175 0.1057696 0.08422293 0.9279563 0.3625751 -0.08623466 0.8333749 0.5506952 0.04712568 0.6113172 0.7904829 -0.03778776 0.5557932 0.8311054 0.01891975 0.1482361 0.9887234 -0.02126424 0.07514366 0.9958413 0.05151201 -0.3519905 0.933383 -0.06999207 -0.5418881 0.8340275 0.1037075 -0.7788641 0.6187248 -0.1027159 -0.9280694 0.3615983 0.08907282 -1.685874e-06 1.0298e-05 1 2.179016e-06 -1.866957e-05 1 -2.535383e-05 -1.165983e-05 1 -1.926159e-06 1.052729e-05 1 -7.241793e-07 1.051926e-05 1 0 0 1 0 0 1 -5.660163e-06 -1.21071e-05 1 -6.293335e-06 -6.370718e-06 1 -0 0 1 -3.587656e-06 3.581453e-06 1 -7.86934e-06 -9.939558e-06 1 3.967978e-06 -1.267399e-05 1 1.522067e-06 -1.240983e-05 1 -3.403549e-06 2.775006e-05 1 -1.108229e-05 2.57521e-05 1 -9.610205e-06 8.859542e-06 1 -1.110784e-05 6.955529e-06 1 4.404953e-06 4.317817e-06 1 -6.405402e-06 -6.278694e-06 1 -0.9825422 -0.1804072 -0.04543218 -0.9341524 -0.3502965 0.06820358 -0.8056884 -0.5897344 -0.0554935 -0.6192385 -0.782144 0.06924269 -0.4909678 -0.8693568 -0.05629737 -0.04852004 -0.9967502 0.06430343 0.04911369 -0.9982269 -0.03363001 0.4835734 -0.8752053 0.0131291 0.4958139 -0.8679197 0.02973182 0.9004786 -0.4336796 -0.03256138 0.9204755 -0.3894428 0.03254326 0.9790968 0.2012052 -0.02976474 0.9690017 0.2459142 0.0237072 0.7537929 0.6568393 -0.01893268 0.706448 0.706756 0.03777785 0.4155182 0.9079751 -0.05408979 0.241607 0.965771 0.09440558 -0.1588318 0.9827793 -0.09443071 -0.3931631 0.9135995 0.1037242 -0.6618872 0.7426883 -0.101585 -0.8510528 0.5185962 0.0822625 -0.9682552 0.2445948 -0.05152964 -0.9918052 0.1243063 0.02950415 -3.754897e-06 3.453191e-06 1 -7.718118e-07 -7.433045e-06 1 1.111256e-06 1.070211e-05 1 5.307462e-06 -4.881008e-06 1 5.033442e-06 -8.750705e-07 1 -0 0 1 -1.009511e-05 1.361015e-05 1 -7.981826e-06 -9.985864e-06 1 -9.259182e-06 -8.465271e-06 1 5.536468e-06 5.061755e-06 1 4.608989e-06 6.175871e-06 1 0 0 1 0 -0 1 0 0 1 1.338874e-05 -7.330615e-06 1 1.28086e-05 5.467319e-06 1 -4.098828e-06 7.517056e-06 1 3.524058e-06 -6.462956e-06 1 -1.270478e-05 -6.671166e-06 1 -1.294218e-05 -5.524335e-06 1 8.766711e-06 2.385281e-05 1 1.620092e-05 -1.102919e-05 1 2.443592e-06 -6.69027e-06 1 0 0 1 -0.9563544 -0.2850212 -0.06441371 -0.8843856 -0.4643828 0.04701819 -0.7527075 -0.656294 -0.0520536 -0.6231304 -0.7795829 0.06292048 -0.2861517 -0.9571601 -0.04429271 -0.2208256 -0.9752448 0.01156109 0.1373501 -0.9904552 -0.01155624 0.2039581 -0.9779778 0.04427834 0.5547583 -0.8296285 -0.06292649 0.7157957 -0.6945721 0.07215407 0.8335038 -0.550828 -0.04312532 0.9641525 -0.2618182 0.04314183 0.9943047 -0.07842986 -0.07215922 0.9892954 0.13166 0.06293072 0.855382 0.51543 -0.05151276 0.797191 0.6015257 0.0515104 0.4433365 0.8930036 -0.07744151 0.2978306 0.9514734 0.07743026 -0.1593245 0.985882 -0.05150037 -0.2005122 0.9796373 -0.01027735 -0.5638354 0.8253205 0.03058917 -0.6634936 0.7445226 -0.07390773 -0.8744194 0.478763 0.07859245 -0.9727034 0.2184138 -0.07838028 -0.9979736 0.03966084 0.04975771 -0.1663033 0.9477041 0.272397 -0.2221055 -0.4745704 0.8517348 -0.7182521 0.06276211 0.6929466 -0.6856499 0.04321615 0.7266475 -0.447974 -0.001361785 0.8940455 -0.7513934 0.1324078 0.6464333 -0.6879838 0.2085042 0.695129 -0.7013704 0.2048072 0.6827398 -0.7378447 0.3281939 0.5898085 -0.2023011 0.09393383 0.974808 -0.8397673 -0.1227809 0.5288817 -0.8539928 -0.09764121 0.5110406 -0.2704538 0.8081104 0.5232709 -0.2747819 0.859481 0.4310306 -0.3587151 -0.8761579 0.3219799 -0.3777617 -0.6911385 0.6161361 -0.4439168 -0.7130818 0.5426346 -0.4799818 -0.5931766 0.6463428 -0.4869232 -0.6748794 0.5544761 -0.5770995 -0.5895787 0.5651135 -0.5976047 -0.5057269 0.6221808 -0.8248037 -0.3093009 0.4733201 -0.7461606 -0.4102996 0.5243077 -0.2581129 -0.3077879 0.9157754 -0.1584088 -0.2130282 0.9641191 -0.5592501 -0.4381709 0.703737 -0.5545508 -0.3645212 0.7480627 -0.6615813 -0.1556614 0.7335392 -0.6447328 -0.1690899 0.7454718 -0.2722023 -0.1244577 0.9541574 -0.5530429 0.35829 0.752178 -0.6767848 0.3714731 0.6355864 -0.5529307 0.429023 0.7142876 -0.4871509 0.4490303 0.7490366 -0.5005507 0.5410758 0.6757855 -0.4647788 0.5864336 0.6633824 -0.4576881 0.5854896 0.6691215 -0.1376935 0.2415826 0.9605615 -0.4149397 0.7438025 0.5240067 -0.1805659 0.4125246 0.8928714 -0.3066301 0.7048186 0.6396942 -0.004958738 -0.467708 -0.8838692 0.0005266755 -0.7100128 -0.7041886 -0.002178444 -0.881257 -0.4726323 -0.001386271 -0.9025331 -0.4306183 -0.0301894 -0.8996016 -0.4356669 -0.08554127 0.8557095 -0.5103371 -0.1577267 0.7742195 -0.612949 -0.2402062 0.8265293 -0.5090681 -0.2665363 0.7922171 -0.548954 -0.3708819 0.8244565 -0.4274555 -0.4168769 0.7507109 -0.5124908 -0.7769721 0.3036302 -0.5514735 -0.7823627 0.2917009 -0.5502901 -0.8356544 -0.08518952 -0.5426089 -0.8388709 -0.132492 -0.5279597 -0.7889206 -0.2685959 -0.5526848 -0.7910732 -0.3150744 -0.524339 -0.7066979 -0.4710891 -0.5278761 -0.6910622 -0.4969114 -0.5248924 -0.4932854 -0.6912299 -0.5280821 -0.4524483 -0.7036029 -0.5479357 -0.4653647 0.5472761 -0.6956468 -0.5474929 0.5458848 -0.6342408 -0.58223 0.4856149 -0.6520633 -0.7271778 0.1125253 -0.6771637 -0.726647 0.07157735 -0.6832722 -0.7178547 -0.2014795 -0.6664013 -0.3508104 -0.6438222 -0.6800184 -0.3009778 -0.6656284 -0.682899 -0.3165629 -0.673191 -0.6682827 -0.2396604 -0.7731371 -0.5872154 -0.1335042 -0.735536 -0.6642014 -0.1534851 -0.7602925 -0.6311874 -0.3658194 0.560311 -0.7431204 -0.4013356 0.5150715 -0.7573844 -0.5501621 0.4023141 -0.7317547 -0.6192611 0.3750068 -0.6898447 -0.6180882 0.319302 -0.7183405 -0.6659359 0.1489883 -0.73098 -0.6629167 0.0161534 -0.748519 -0.6364105 -0.3560482 -0.6842597 -0.4965771 -0.4587562 -0.7368541 -0.4805051 -0.4769882 -0.7359328 -0.4843432 -0.4773433 -0.7331815 -0.188522 0.4089719 -0.8928614 -0.4636599 -0.1380242 -0.8751965 -0.1000252 -0.5839717 -0.805588 -0.08425341 0.4896351 -0.8678473 -0.3509429 -0.2005539 -0.9146678 -0.3097866 -0.1875803 -0.932119 -0.2246605 -0.2778969 -0.9339706 -0.08049582 0.2270504 -0.9705506 -0.2625965 0.09830501 -0.959885 -0.207865 -0.02715182 -0.9777806 -0.08753677 -0.2751133 -0.9574184 -0.04172004 0.02529296 -0.9988091 -1.83488e-05 0.248283 -0.9686875 -0.002861997 0.4738244 -0.8806148 -0.000518912 0.737084 -0.6758009 -0.002938635 0.6800764 -0.7331353 0.0004343781 0.9244263 -0.3813605 -0.2817909 -0.01715116 -0.9593225 -0.2169851 0.625521 -0.7494271 -0.1618549 0.923456 -0.3478964 -0.319121 -0.6565077 -0.6834905 -0.3451028 -0.163294 -0.9242506 -0.5412259 -0.3351125 -0.771216 -0.03442356 -0.02065242 -0.999194 -0.5865688 -0.518278 -0.6223544 -0.4973156 -0.3838197 -0.7780486 -0.5757138 -0.5875158 -0.568664 -0.2380285 -0.2249607 -0.9448466 -0.4991333 -0.6854801 -0.5300784 -0.4906016 -0.5987438 -0.6331002 -0.2831371 -0.362273 -0.8880269 -0.2679211 0.5836879 -0.7665028 -0.8160077 0.04293842 -0.576444 -0.8152636 0.04252572 -0.5775265 -0.8285812 0.001601272 -0.5598666 -0.7056694 -0.1912839 -0.6822326 -0.7048188 -0.1972316 -0.6814176 -0.7889085 -0.2734802 -0.5503017 -0.792698 -0.3446714 -0.5028235 -0.2393808 0.8838627 -0.4018503 -0.3863342 0.6281826 -0.6753758 -0.264319 0.6081328 -0.7485386 -0.6409199 0.547401 -0.5381208 -0.6262236 0.594838 -0.5039958 -0.4954028 0.5967785 -0.6312143 -0.4205005 0.5491979 -0.7221919 -0.7788295 0.3015955 -0.5499681 -0.5370935 0.3129479 -0.7833225 -0.5428432 0.3882066 -0.7447261 -0.2509778 0.2925396 -0.9227301 -0.07693579 0.1111088 -0.9908258 -0.5625495 0.3554243 -0.7464661 -0.5875882 0.3229313 -0.741927 -0.7621109 0.2212536 -0.6084684 -0.8788803 0.1719878 -0.4449603 -0.2978845 0.08506013 -0.9508047 -0.3989592 0.09430913 -0.9121061 -0.5071548 0.04312319 -0.8607755 -0.6270758 -0.1132037 -0.7706885 -0.705271 -0.377797 -0.5998853 -0.2337386 -0.3413396 -0.9104139 -0.3233332 -0.6526777 -0.685177 -0.4547634 -0.7189868 -0.5255933 -0.3561779 -0.88249 -0.3071623 -4.563485e-05 -0.4984248 0.866933 -0.003821061 -0.6410072 0.7675254 0.0008310548 -0.8887893 0.4583152 -0.002054801 -0.9783759 0.2068244 -0.08938184 -0.9099269 0.4050233 -0.1206123 -0.9137772 0.3878967 -0.5496338 -0.710654 0.4391736 -0.6451382 -0.6316963 0.4298331 -0.7872096 -0.4672732 0.4024386 -0.8181165 0.332768 0.4689892 -0.3725983 -0.7570382 0.5367156 -0.5059099 -0.6880217 0.5202704 -0.629113 -0.5839821 0.5130125 -0.7099186 -0.4632761 0.5304627 -0.7611659 -0.300918 0.5745213 -0.8041576 -0.282553 0.5229669 -0.8234782 -0.1305709 0.5521186 -0.8344492 -0.04927661 0.5488773 -0.8259708 -0.04089747 0.5622273 -0.8474094 0.01367071 0.5307642 -0.8380569 0.1949895 0.5095485 -0.6292019 0.5609661 0.5379795 -0.6196893 0.5950984 0.5117059 -0.4118469 0.7492455 0.5186647 -0.3224857 0.7168948 0.6181139 -0.2843052 0.8650756 0.4132974 -0.1502126 0.8228589 0.5480323 -0.1406702 0.8038068 0.5780195 -0.1926111 -0.715447 0.6715925 -0.2178228 -0.7115703 0.6679977 -0.2170779 -0.7129867 0.6667287 -0.3253687 -0.7129791 0.6211248 -0.7601017 -0.1595516 0.6299116 -0.6739746 0.3319124 0.6599943 -0.671856 0.3459374 0.6549326 -0.4748479 0.6038632 0.6402098 -0.4616099 0.5962746 0.65679 0.01900536 -0.6347589 0.7724764 -0.6919816 0.1194172 0.7119698 -0.2336416 0.55733 0.7967402 -0.3374257 -0.2081749 0.9180452 -0.4268703 -0.1994806 0.882037 -0.4676734 0.19276 0.8626269 -0.5004448 0.3705142 0.7824795 -0.1168325 0.494288 0.8614114 -0.05578763 -0.4725465 0.8795383 -0.182318 -0.2817445 0.9420086 -0.2918408 -0.3817597 0.8769768 -0.4427684 -0.4200706 0.7921469 -0.3303122 -0.2012604 0.9221649 -0.4041291 -0.009223295 0.9146554 -0.3659224 0.05154739 0.9292167 -0.4896223 0.09259124 0.8670046 -0.3002975 0.2459378 0.9215943 -0.2662224 0.3324192 0.9047779 -0.08831163 -0.1564118 0.9837359 -0.3158061 -0.06613392 0.9465161 -0.2643359 -0.04553977 0.9633549 -0.1375729 0.211693 0.9676052 -0.07216918 0.3671423 0.9273608 -0.1124101 0.07218911 0.9910362 -0.001373754 0.3474498 0.9376976 -0.0007121266 0.3829769 0.9237576 -0.001620066 0.7812551 0.6242098 -0.005413491 0.6791411 0.7339877 -0.0007709506 0.931721 0.3631741 0.004074346 0.7233782 0.69044 0.0004308071 0.695087 0.7189255 0.0004862795 0.6977555 0.7163358 4.873931e-05 0.4613263 0.8872306 0.000949169 0.4917229 0.8707513 -0.0005663229 0.2963135 0.9550906 2.188473e-05 0.7950121 -0.6065935 0.0008888107 0.6773626 -0.7356488 0.0004286885 0.6630857 -0.7485433 -0.001141887 0.4149573 -0.9098403 0.001150348 0.3055796 -0.9521658 0.5529902 -0.1542225 -0.8187901 0.5093952 -0.05317504 -0.8588883 0.3553421 0.02015903 -0.9345189 0.2284236 0.1010489 0.9683036 0.156779 0.2926308 0.9432855 0.2133055 0.07889824 0.9737945 0.3864032 -0.03361439 0.9217172 0.2313364 0.4212549 0.8769423 0.535125 -0.1197191 0.8362467 0.4284601 0.1335156 0.8936418 0.3022752 0.4410243 0.8450604 0.5040382 0.004493084 0.8636697 0.5981846 -0.1527917 -0.7866575 0.3361677 0.293217 -0.8949944 0.3887892 0.3043862 -0.869593 0.1006963 0.5450466 -0.8323367 0.1673281 0.5587392 -0.812288 0.06555113 0.2222157 -0.9727915 0.143355 0.1952591 -0.9702181 0.1512691 0.238535 -0.9592804 0.3474598 0.00268086 -0.937691 -0.9999947 0.002977574 -0.001329134 -1 8.526201e-07 4.679043e-06 -0.9999927 0.003774849 -0.0004995235 -0.9999998 0.0005213771 0.0002580789 -0.9999897 0.004536049 2.237324e-05 -0.9999991 0.0013343 0.0002461781 -1 9.42756e-07 1.151865e-06 -1 -1.844016e-05 1.15029e-05 -0.9999989 0.001439765 7.573035e-05 -0.9999972 0.00231388 -0.0005202656 -0.9999994 0.0008887885 0.0007221241 -1 2.979973e-05 -6.757709e-05 -0.9999813 0.0006304485 -0.00608065 -0.9999997 -8.217887e-05 -0.0008012858 -0.9999939 0.001774039 -0.002997839 -1 6.831919e-06 8.293763e-06 -1 1.144657e-05 5.588451e-06 -0.9999982 0.001892305 -0.0001241 -0.9999894 0.004495392 -0.0009953436 -1 -0.0002138549 -6.986418e-05 -1 -1.164493e-05 2.010706e-07 -0.9999986 0.0004658289 0.001557259 -0.9999982 0.000357025 0.001873891 -1 3.827383e-05 -0.0002147399 -1 7.908335e-05 -1.016862e-05 -1 -0.0001200018 -0.0001362379 -1 -8.399255e-06 -2.892738e-06 -0.9999999 -0.0001845278 -0.0001979456 -1 -7.084209e-06 -6.804209e-06 -1 -5.45478e-06 -6.670934e-06 -1 6.651032e-05 -6.610728e-05 -1 8.410919e-05 -1.40214e-05 -1 0.0001075008 3.514723e-05 -1 0.0001285689 7.121557e-05 -1 -7.662337e-05 -0.0001573582 -1 -0.0002191111 -2.899051e-05 -0.9999999 -0.000211102 -9.812999e-05 -1 -0.0002466244 3.073548e-05 -0.9999998 -0.0004269 0.0003324451 -0.9999999 -0.0002559933 1.242929e-05 -1 1.671382e-05 1.44542e-05 -1 -1.274184e-06 1.625904e-05 -1 1.182949e-06 1.295089e-05 -0.03173475 0.6876234 0.7253736 1.423401e-06 0.5446404 0.8386697 0.02370553 0.09093696 0.9955745 0.005951128 0.106111 0.9943365 -0.03423356 0.551029 0.8337836 0.04813758 0.6326326 0.7729546 -0.04828606 0.8469964 0.5294012 0.03423126 0.8970489 0.4406036 -0.003699582 0.999981 0.004932145 -0.07512064 0.9949537 -0.06651374 0.08223092 0.9100612 -0.4062347 -0.1016704 0.750838 -0.6526143 0.1036629 0.5059937 -0.8562852 -0.04436257 0.3426051 -0.9384316 -0.01071085 -0.04737455 -0.9988198 0.05976892 -0.1172955 -0.9912969 -0.04311165 -0.4781095 -0.8772415 0.05523306 -0.6104457 -0.7901299 -0.05548261 -0.7799458 -0.6233829 0.06715927 -0.9176017 -0.3917868 -0.08624207 -0.9835141 -0.1589412 0.08422352 -0.9908608 0.1053628 -0.08729092 -0.8783702 0.4699427 0.03680487 -0.8159793 0.5769083 -0.005877439 -0.4313728 0.9021546 -0.02370987 -0.417417 0.9084057 -1 1.025452e-05 -2.399545e-05 -1 1.615413e-06 -3.64304e-05 -1 -4.223527e-05 2.051865e-05 -1 1.845647e-05 5.057046e-05 -1 0 0 -1 2.462521e-07 -8.560328e-06 -1 -9.730074e-07 2.276824e-06 -1 -1.665926e-05 -1.950969e-06 -1 -1.025796e-05 8.155003e-06 -1 -2.194139e-05 2.913736e-05 -1 -2.781125e-05 2.397493e-05 -1 5.012322e-06 -4.320916e-06 -1 -6.914408e-07 -1.457797e-05 -1 2.301581e-05 -1.762417e-05 -1 2.25642e-05 2.627465e-05 -1 -5.459828e-05 1.423178e-05 -1 -4.425819e-05 -2.240205e-05 -1 1.299541e-05 1.022817e-05 -1 7.970798e-06 1.897965e-06 -1 1.630003e-05 -8.72079e-06 -1 1.186957e-05 5.578364e-05 -1 -1.945736e-05 8.267093e-06 0.05060951 -0.1222245 0.9912113 -0.06774939 0.2968496 0.9525179 0.1036988 0.5367795 0.8373258 -0.04431954 0.6836735 0.728441 -0.01075061 0.9131864 0.4074003 0.05975506 0.9379599 0.3415561 -0.05973956 0.9937599 -0.094193 0.06430586 0.9742142 -0.2162671 -0.06430338 0.7532011 -0.6546397 0.0873388 0.6444486 -0.7596434 -0.0975189 0.2822717 -0.9543651 0.07606393 0.07790183 -0.9940552 -0.04308443 -0.3426676 -0.9384683 0.01324793 -0.2971812 -0.9547291 -0.03358364 -0.6867297 -0.7261367 0.03672218 -0.7358394 -0.6761597 -0.008280784 -0.9788049 -0.2046277 0.05060799 -0.967656 -0.247145 -0.07606548 -0.9761042 0.2035548 0.09756751 -0.9107471 0.4012732 -0.08724469 -0.67166 0.7357045 0.03678208 -0.5772423 0.8157441 -0.008258044 -0.07865282 0.9968679 -1 1.402681e-05 -3.476593e-05 -1 2.96361e-08 -2.523207e-06 -1 -6.270535e-07 -2.199915e-06 -1 1.305359e-05 4.579638e-05 -1 3.029936e-05 4.31248e-05 -1 -1.456387e-05 -2.335737e-05 -1 -3.981645e-07 3.389959e-05 -1 -3.44766e-05 4.545134e-05 -1 -3.443017e-05 4.563919e-05 -1 6.583175e-06 5.529612e-06 -1 0.0001038772 8.72528e-05 -1 9.090809e-05 0.0001155892 -1 -5.399369e-05 6.681348e-05 -1 -4.768626e-05 -3.747935e-06 -1 -1.378547e-06 -1.269438e-05 -1 0 0 -1 1.283099e-05 2.593306e-06 -1 1.3034e-05 5.362195e-06 -1 -1.112567e-05 1.880352e-05 -1 8.472643e-06 -6.171914e-07 -1 -1.130582e-05 1.840288e-05 -0.03919393 0.1318076 0.9905002 0.06000184 0.287829 0.9558004 -0.09752151 0.5994533 0.7944466 0.09752249 0.7682794 0.6326422 -0.07396611 0.9517224 0.297915 0.0305556 0.9843086 0.1737902 -0.01033424 0.9752577 -0.2208295 -0.02126622 0.9725943 -0.2315342 0.02364721 0.746344 -0.6651402 0.005972757 0.7363708 -0.6765518 -0.03421331 0.3427002 -0.9388216 0.04821519 0.2452077 -0.9682708 -0.03920249 -0.04733833 -0.9981093 0.04313039 -0.1791023 -0.9828846 -0.05973332 -0.5315164 -0.8449392 0.0643065 -0.6317012 -0.7725402 -0.06431496 -0.9236542 -0.3777917 0.03360043 -0.9575681 -0.2862417 -0.0131671 -0.9863022 0.1644221 -0.0297661 -0.9835101 0.1783867 0.03256619 -0.7088767 0.7045802 0.008330123 -0.6963617 0.7176426 -0.03416224 -0.2618416 0.964506 0.04823514 -0.1622364 0.9855723 -1 2.912824e-05 4.901748e-05 -1 1.297176e-05 -3.155103e-05 -1 1.869997e-05 9.324503e-06 -1 1.957109e-05 8.779958e-06 -1 1.287737e-06 -7.404432e-06 -1 -1.097247e-06 6.309126e-06 -1 -6.316868e-06 5.1685e-06 -1 -9.421696e-06 2.46343e-05 -1 -6.886156e-06 2.408503e-05 -1 -1.204264e-05 -1.921805e-05 -1 -7.282621e-07 -1.535511e-05 -1 -2.672821e-06 -1.139204e-05 -1 -5.407685e-07 -1.028363e-05 -1 2.277755e-07 4.331535e-06 -1 -6.853951e-06 5.405149e-06 -1 -6.637567e-06 5.697304e-06 -1 7.533435e-06 -6.466265e-06 -1 3.259468e-06 -7.927962e-06 -1 -9.672597e-06 4.647033e-05 -1 1.44596e-05 -9.955519e-06 -1 2.422333e-05 -7.216904e-06 -1 1.87785e-05 -3.143814e-05 -0.9692084 0.0008035502 -0.2462403 -0.9674425 0.00595828 0.2530206 -0.9750317 0.002362807 -0.2220528 -0.9176182 0.001583308 -0.3974598 -0.9034345 -0.0008197388 -0.4287253 -0.8265082 -0.001358571 -0.562923 -0.7665855 0.001174805 -0.6421412 -0.582927 0.0009315618 -0.812524 -0.7737792 0.001707206 -0.6334532 -0.5968236 -1.794673e-05 -0.8023725 -0.3783937 0.001269473 -0.9256439 -0.3753273 0.000991367 -0.9268919 -0.1938774 -0.004795926 -0.9810141 -0.9892197 -0.001164069 0.1464344 -0.9680834 0.00139006 0.2506245 -0.9557954 -0.0006232963 0.294032 -0.8851756 -0.0003962853 0.4652569 -0.865077 -0.002336292 0.5016336 -0.7800896 0.0009322073 0.6256672 -0.7554508 -0.0007239603 0.655205 -0.6149264 -0.001331269 0.7885834 -0.5708307 0.001430644 0.8210665 -0.4331244 -0.001343139 0.9013332 -0.3952494 0.0004367596 0.9185737 -0.1690798 -0.001998219 0.9856003 -0.2045642 0.0001082332 0.9788531 0.3274772 0.9447545 -0.01405836 -0.1504371 0.9886159 -0.002684876 -0.1857896 0.9824153 0.01850557 -0.5589499 0.8291978 -0.002449729 -0.5320334 0.8462197 -0.02919826 -0.8771386 0.4787066 0.03831244 -0.9067773 0.4197989 -0.03903531 -0.9893607 -0.1451829 0.009341362 -0.9935195 -0.08920892 -0.07043368 -0.8523824 -0.5144845 0.09354106 -0.6807019 -0.7265655 -0.09352778 -0.511023 -0.8575307 0.05913202 -0.0970089 -0.994742 -0.03282567 -0.112463 -0.9924871 -0.04818187 0.3042751 -0.9513296 0.04887233 0.4863244 -0.8733976 -0.0257922 0.8164202 -0.5773303 0.01215837 0.8209077 -0.5708375 0.01597237 0.9938738 -0.1089874 -0.01834868 0.9994397 0.01801232 0.02821089 0.8538422 0.5195884 -0.03132934 0.7818093 0.6230672 0.02369637 0.3461892 0.9381614 0.002471284 5.086563e-05 0.0001493751 -1 -0.0002329398 -0.0001881095 -0.9999999 -0.0001956425 -0.000202376 -0.9999999 -2.953797e-05 -1.480114e-05 -1 -3.610541e-05 3.838822e-06 -1 -6.257879e-06 -1.24235e-05 -1 0 0 -1 -2.470549e-05 4.614037e-05 -1 -4.46617e-05 2.195029e-05 -1 2.942964e-06 -1.27482e-05 -1 -7.080193e-05 -9.42789e-05 -1 -5.552011e-05 -0.0001559065 -1 -3.461747e-05 -0.0001521864 -1 2.764429e-05 2.018273e-05 -1 2.755324e-05 2.024415e-05 -1 -6.31135e-06 -6.075459e-08 -1 -1.17495e-05 1.946237e-05 -1 -3.189798e-05 1.991692e-05 -1 4.633603e-05 0.000266425 -0.9999999 -0.0001379957 0.0003658653 -0.9999999 -0.0001969574 0.0002415836 -0.9999999 0.0108257 -0.0005106124 0.9999413 0.008691303 0.001348626 0.9999613 0.0144055 0.005414366 0.9998816 0.004402665 -0.004459793 0.9999803 0.004391482 0.007941386 0.9999588 0.04390326 0.01317423 0.9989489 -1.760565e-05 3.396217e-05 1 -2.704931e-05 -2.465926e-05 1 -1.645123e-05 -2.698061e-05 1 -3.413292e-06 -5.597921e-06 1 -1.444033e-05 -4.627952e-07 1 -1.444214e-05 -7.401119e-07 1 6.871438e-06 3.521384e-07 1 -4.547325e-05 0.0002013166 0.9999999 -9.686306e-05 0.0001869924 1 4.888786e-06 1.582497e-06 1 -1.285934e-05 -4.162562e-06 1 -1.349024e-05 -1.778539e-05 1 7.918262e-05 -1.64027e-05 1 0.0001008003 1.650002e-05 1 3.977731e-05 5.438066e-05 1 -1.12229e-05 5.20374e-06 1 -4.437663e-06 -5.556904e-06 1 2.532792e-05 3.171598e-05 1 -3.716435e-05 6.365223e-05 1 -1.386806e-05 8.681322e-05 1 1.271303e-05 3.956174e-05 1 -0.5653292 0.8242288 -0.0324002 -0.6464393 0.7614465 0.04811708 -0.1385945 0.9901584 0.0194392 -0.1548316 0.9879156 0.007069143 0.4204837 0.9072118 -0.01266044 0.405947 0.9138952 0.001626435 0.8371355 0.5469134 -0.009478354 0.8734648 0.4865927 0.01693214 0.9958254 0.08904308 -0.02007818 0.9986163 -0.04917287 0.01864324 0.9322115 -0.3615403 -0.01643773 0.8600943 -0.5097774 0.01910101 0.59236 -0.8054448 0.01919126 0.7008734 -0.713172 -0.01273388 0.4005179 -0.9160004 -0.02299394 0.1008249 -0.9941951 0.03755583 0.123445 -0.9920982 0.02241461 -0.2815697 -0.9575253 -0.06216007 -0.4942512 -0.8632674 0.1023967 -0.8885403 0.4555815 -0.05423647 -0.9107099 0.4130248 -0.004238649 -0.9989011 -0.03201358 0.03423136 -0.9861344 -0.1530181 -0.06422184 -0.8940434 -0.4430251 0.06644572 -0.7513986 -0.6520565 -0.1011062 0.7956274 0.4041746 -0.4512427 0.7399663 0.5775452 -0.3448065 0.61975 0.6873531 -0.3787555 0.1125073 0.9933197 -0.02565499 0.1460899 0.9882091 -0.04583111 0.3034474 0.9518198 -0.04425568 0.4767568 0.8724272 -0.107582 0.5172574 0.8490886 -0.107207 0.6145345 0.7706673 -0.16858 0.6980117 0.6544698 -0.290601 0.7511927 0.643814 -0.1456465 0.7774104 0.602474 -0.1807151 0.8545769 0.3190287 -0.4097792 0.8982204 0.3911946 -0.200417 0.9168637 0.3095117 -0.2521178 0.8448324 -0.007196866 -0.5349827 0.8867892 0.2333553 -0.3989365 0.9689052 0.1200493 -0.2163585 0.6453169 0.6898787 0.3280754 0.1279042 0.9906087 0.04832097 0.4068844 0.8869495 0.2185535 0.7768125 0.3596036 0.51696 0.8097373 0.4746678 0.3449869 0.7193789 0.5649408 0.4041485 0.8800138 0.28461 0.3802274 0.8810266 0.198811 0.4292625 0.5227194 0.8305296 0.1923149 0.7757407 0.60098 0.1924823 0.2521791 0.9666233 0.04522396 0.4348014 0.8954139 0.09582205 0.6393943 0.7677113 0.04235818 0.7673431 0.6141676 0.1843442 0.8657081 0.4677284 0.1782687 0.8983238 0.3650928 0.24438 0.9632968 0.1984324 0.1807865 0.60248 0.002791044 0.7981291 0.3897714 0.007167277 0.9208837 0.3329456 -0.02009473 0.9427319 0.1312875 -0.01104456 0.9912828 0.3188876 0.01659689 0.9476472 0.1453959 -0.01291303 0.9892893 0.4576595 -0.008679162 0.8890851 0.5649068 0.004819923 0.8251407 0.1318325 -0.01085768 -0.9912125 0.3771933 0.002640637 -0.9261308 0.3569603 -0.0062754 -0.9340984 0.4258907 0.004621993 -0.9047629 0.5071378 -0.001316127 -0.861864 0.4097551 0.009079652 -0.9121504 0.2185952 0.005645585 -0.9757993 0.07437969 0.003565355 -0.9972236 0.1744542 0.01555419 -0.9845425 -0.4011016 -0.8179191 -0.4124631 -0.2887129 -0.9206322 -0.262833 -0.2304205 -0.96451 -0.128946 -0.3864647 -0.8679633 -0.311905 -0.2105176 -0.5345147 -0.8185209 -0.6918929 -0.2753908 -0.667416 -0.1600378 -0.6492941 -0.7435087 -0.8551798 -0.2713987 -0.4415996 -0.2990533 -0.7153193 -0.6315737 -0.394231 -0.6397737 -0.6597512 -0.2389169 -0.7732202 -0.5874088 -0.9056575 -0.3957891 -0.1521033 -0.8531319 -0.2941509 -0.430861 -0.6453797 -0.4980769 -0.5791412 -0.655549 -0.3903132 -0.6464605 -0.2149653 -0.8362287 -0.5044914 -0.948596 -0.1863216 -0.2558316 -0.5397426 -0.2303553 -0.8097001 -0.5180542 -0.4640616 -0.7185169 -0.3178826 -0.4217078 -0.8491838 -0.184106 -0.7121654 -0.6774404 -0.05412755 -0.9521527 -0.3007913 -0.4669941 -0.8673359 -0.1721772 -0.5888078 -0.7543739 -0.2902162 -0.7271358 -0.6648077 -0.171185 -0.7701376 -0.5629246 -0.3000067 -0.5781457 -0.6383309 -0.5082136 -0.6670393 -0.6659351 -0.3340493 -0.2408097 -0.9200378 -0.3090973 -0.3438495 -0.9390245 -0.0007876941 -0.4019106 -0.9156753 -0.002563041 -0.5758333 -0.817567 0.000362559 -0.8010865 -0.5985485 -0.0001437329 -0.780722 -0.624877 -0.001368783 -0.9615971 -0.2744602 0.001653767 -0.9438589 -0.330349 -3.059195e-05 -0.5179393 -0.3955117 0.7584915 -0.2575927 -0.5421691 0.7998117 -0.4510964 -0.4801881 0.7522842 -0.2415972 -0.887839 0.3916281 -0.3349249 -0.6838666 0.6481912 -0.2803293 -0.8518326 0.4424892 -0.09704161 -0.9182764 0.3838637 -0.08117602 -0.871336 0.4839257 -0.9510815 -0.2954879 0.09017108 -0.8248989 -0.4758489 0.3051386 -0.759052 -0.619049 0.2015399 -0.3409111 -0.1834268 0.9220273 -0.6644428 -0.318201 0.6762129 -0.6377445 -0.6912646 0.3397577 -0.3297869 -0.9256327 0.1855931 -0.6490702 -0.6807141 0.3396117 -0.3567274 -0.9008716 0.2473378 -0.8369597 -0.3238036 0.4411913 -0.7970401 -0.3825028 0.4673529 -0.657901 -0.7442234 0.1153158 -0.45524 -0.8855264 0.09273364 -0.347975 -0.9296715 0.1209306 -0.4553843 -0.5270213 0.7175469 -0.248443 -0.5108751 0.8229719 -0.3550836 -0.8617014 0.3624726 -0.1348255 -0.602932 0.7863174 -0.6398031 -0.4404105 0.6298338 -0.5025495 -0.6385785 0.5828049 -0.2377369 -0.91742 0.3190949 -0.5055559 0.401889 -0.7634779 -0.5622376 -0.4756401 -0.6765023 -0.2576794 0.6594798 -0.7061784 -0.1637333 0.9474975 -0.2746635 -0.1294954 0.9107124 -0.3922168 -0.2456889 0.6422958 -0.7260118 -0.08526116 0.944343 -0.3177212 -0.5094984 0.7312 -0.4536055 -0.4516994 0.7955806 -0.4037564 -0.1936449 0.9541982 -0.2280514 -0.1550699 0.3136434 -0.936793 -0.1732986 0.2815478 -0.9437682 -0.37275 0.2762283 -0.8858642 -0.7780666 0.3030266 -0.5502611 -0.5841427 0.792121 -0.1769793 -0.7204015 0.6289821 -0.2922381 -0.5588655 0.788653 -0.2563117 -0.6037451 0.7575016 -0.2483608 -0.338464 0.9279482 -0.1560586 -0.3148745 0.9367828 -0.1526173 -0.6407069 0.4702254 -0.6069454 -0.7288658 0.1221968 -0.6736636 -0.2707449 0.7758301 -0.5698989 -0.02438914 0.9733385 -0.228073 -0.1038887 0.7385245 -0.6661747 -0.2597186 0.612615 -0.7464912 -0.3793591 0.6945344 -0.6113172 -0.6445067 0.4648086 -0.6070948 -0.8346592 0.2618833 -0.4845215 -0.835648 0.383891 -0.3928359 -0.8778399 0.4577997 -0.1407714 -0.8786758 0.4555207 -0.142933 -0.8826169 0.470093 0.0001113423 -0.01850772 0.9998285 0.0004298374 -0.3031826 0.9529324 -0.0001251368 -0.3577319 0.9338239 0.0009473955 -0.4932396 0.8698931 -0.0008236811 -0.6826783 0.7307162 0.002005555 -0.7475961 0.6641535 -0.0002622837 -0.8828768 0.4696046 9.403547e-05 -0.9903882 0.1382993 -0.002104891 -0.9618883 0.2734366 0.001863854 -0.3335035 0.9123321 0.2375406 -0.4898679 0.7667994 0.4147868 -0.5215487 0.8280942 0.2055407 -0.4863615 0.8498982 0.2027941 -0.7748502 0.5181359 0.3621357 -0.1404193 0.9861243 0.0885511 -0.1679707 0.340947 0.9249546 -0.169741 0.3372808 0.925975 -0.354295 0.3716869 0.8580931 -0.3824661 0.3294358 0.8632449 -0.7999825 0.3264543 0.5034437 -0.0756216 0.8045565 0.5890416 -0.9584424 0.2201749 0.1814144 -0.8045655 0.274492 0.5266198 -0.6585566 0.3145666 0.6836307 -0.3135335 0.6424987 0.6992082 -0.1397522 0.9027374 0.4068593 -0.6720017 0.518898 0.5283547 -0.2086277 0.7925721 0.5729783 -0.8784126 0.4749399 0.05313581 -0.9086057 0.3734093 0.1870861 -0.864502 0.4076549 0.2940303 -0.8472175 0.2738904 0.4551995 -0.1631181 0.8507546 0.4996091 -0.6564862 0.2951311 0.6942072 -0.5031958 0.4378482 0.7450389 -0.4464161 0.8041846 0.392428 -0.6563447 0.7463138 0.1105769 -0.7091881 0.6186739 0.3380751 -0.4401979 0.6426308 0.6270977 -0.3402659 0.8209241 0.4585878 -0.0966711 0.9853649 0.1403951 -0.769235 0.5485595 0.3276583 -0.6470041 0.5983785 0.4725768 -0.3506322 0.812737 0.4653122 0.01491389 -0.9247518 -0.3802786 0.01230404 -0.9310648 -0.3646463 0.01499323 -0.7448224 -0.6670943 0.01813041 -0.7302642 -0.6829242 0.01653531 -0.5315397 -0.846872 -0.001045739 -0.4243583 -0.9054937 0.01693037 -0.2336918 -0.9721633 0.1809482 -0.807795 -0.5610036 0.2022191 -0.5072342 -0.8377475 0.2871975 -0.3446308 -0.8937266 0.1437207 -0.9390038 -0.3124361 0.1824486 -0.8062313 -0.5627644 0.3010975 -0.3639815 -0.8813953 0.2693034 -0.8399767 -0.4710783 0.3594764 -0.6442398 -0.6750791 0.4551424 -0.2302047 -0.860146 0.1425595 -0.9692159 -0.2007421 0.3144249 -0.8489025 -0.4248546 0.322444 -0.8425305 -0.4314768 0.4329894 -0.6626272 -0.6111017 0.4935144 -0.5730539 -0.6542574 0.5572211 -0.336991 -0.7589082 0.5859122 -0.2749116 -0.7623192 0.162359 -0.2794309 -0.9463392 0.1776738 -0.3233017 -0.9294665 0.1583966 -0.613071 -0.773986 0.2960815 -0.6162049 -0.7298132 0.2172608 -0.6885492 -0.6918799 0.1688891 -0.844002 -0.509055 0.1242045 -0.893495 -0.4315552 0.1093747 -0.9223905 -0.3704497 0.3887348 -0.2956282 -0.8726335 0.3836932 -0.2718067 -0.8825535 -0.0008068091 -0.9977077 -0.06766553 -0.0006623088 -0.8846274 -0.4662983 -3.718395e-05 -0.8712487 -0.4908421 0.001023148 -0.985927 -0.1671729 0.001508816 -0.2904126 -0.9569003 -0.001266288 -0.4372147 -0.8993562 0.001612596 -0.6884789 -0.7252547 0.001815932 -0.6793995 -0.7337663 0.02017752 -0.1287204 0.9914756 -0.004161925 -0.3538038 0.9353104 0.01692497 -0.5532187 0.832864 0.006615503 -0.7470436 0.6647422 0.007266072 -0.7494169 0.6620585 0.009487311 -0.9462009 0.3234408 0.01874234 -0.9215135 0.3878939 0.2528988 -0.9093308 0.3303932 0.5469905 -0.4430677 0.7102763 0.5570633 -0.3301816 0.7620109 0.3089085 -0.7622243 0.5688494 0.3979861 -0.3839869 0.8331633 0.04823675 -0.9532874 0.2981884 0.3511442 -0.4268777 0.8333505 0.1998306 -0.7521618 0.6279492 0.1523731 -0.6490518 0.7453282 0.1874183 -0.3080431 0.9327292 0.4919632 -0.5516314 0.673554 0.4451379 -0.6975361 0.561512 0.3359526 -0.8156277 0.4710492 0.1576238 -0.9590975 0.2351314 0.5243255 -0.2614596 0.8103836 0.4157408 -0.2531641 0.8735374 0.3686455 -0.3613293 0.8564705 0.317199 -0.644259 0.6959276 0.3072112 -0.6152033 0.7260483 0.2728586 -0.7857198 0.5551509 0.1405005 -0.9139677 0.3806871 0.1261255 -0.9424791 0.3095569 0.1996121 -0.2742494 0.9407137 0.1704283 -0.3239336 0.9306027 0.1288982 -0.568992 0.8121783 0.1688188 -0.6615911 0.7306144 0.08127765 -0.87011 0.4861096 0.0003198416 -0.9969533 0.07799918 4.83993e-05 -0.996064 0.08863663 0.001098203 -0.898494 0.4389844 -0.0001815374 -0.8778817 0.4788776 -8.768996e-05 -0.6676921 0.7444375 0.00173278 -0.5833123 0.8122461 0.0008640317 -0.268429 0.9632991 -0.0006754593 -0.3555981 0.9346387 0.4908895 0.5535097 0.672796 0.2209217 0.1582402 0.9623687 0.1537798 0.3352475 0.9294949 0.1450693 0.5173869 0.8433657 0.2080016 0.5283585 0.823148 0.08415098 0.6757951 0.7322701 0.3891924 0.7355754 0.5544891 0.5331309 0.7737972 0.3420663 0.07375066 0.6750818 0.7340472 -0.02885828 0.3090889 0.9505953 0.09853254 0.6261675 0.7734376 0.1486223 0.9057869 0.3968143 0.1415101 0.9107991 0.38784 0.4149635 0.850827 0.3223332 0.6876571 0.1606882 0.7080304 0.6387885 0.3447259 0.6878324 0.6322896 0.4978106 0.5936282 0.6593903 0.5055091 0.5564755 0.5465588 0.6788422 0.4903536 0.6491235 0.14022 0.7476476 0.6507711 0.1409071 0.7460845 0.3306324 0.1115778 0.9371406 0.2735268 0.4251068 0.8628252 0.5183149 0.3617669 0.7749028 0.4798867 0.1080038 0.8706572 0.1683006 0.3883675 -0.9060053 0.3889646 0.7393894 -0.5495544 0.1565132 0.7776546 -0.6088982 0.3655385 0.6888468 -0.6259966 0.03932616 0.9299124 -0.3656724 0.221778 0.9331162 -0.2830348 0.3157726 0.8713161 -0.3756272 0.4629985 0.8401185 -0.2825479 0.1724498 0.4241848 -0.8890041 0.221385 0.6087825 -0.7618219 0.02244495 0.7288588 -0.6842961 0.3613528 0.7114563 -0.6027056 0.4606919 0.8439087 -0.2749201 0.7415931 0.3032715 -0.5983861 0.7087238 0.1971099 -0.6773908 0.61642 0.3483688 -0.7061626 0.5996597 0.5451384 -0.5858604 0.6060917 0.4190713 -0.6760414 0.4715685 0.5050282 -0.7228897 0.3742685 0.2706963 -0.8869309 0.31004 -0.09673955 -0.9457889 0.3724483 0.2884642 -0.8820831 0.4906146 0.1688505 -0.8548607 0.4583417 -0.8887758 0.0006743993 0.5104768 -0.8598162 -0.01138529 0.8209943 -0.5709305 0.002591073 0.8331137 -0.5530953 -0.002665101 0.9576195 -0.2877694 -0.01239053 0.9366854 -0.2072528 -0.2822529 0.8200373 -0.4012868 -0.4080536 0.791373 -0.5176833 -0.3251656 0.507351 -0.4463119 -0.7371572 0.4353162 -0.6913726 -0.5766314 0.4898991 -0.7748567 -0.3994946 0.472767 -0.801944 -0.3652087 0.2210334 -0.2286438 -0.9480855 0.7533364 -0.332752 -0.5672393 0.4357702 -0.3740676 -0.8186438 0.3482449 -0.3701768 -0.861217 0.9971932 0.005297988 -0.07468352 0.9709774 0.001396835 -0.2391674 0.9543177 -0.002640394 -0.2987822 0.8262364 0.0002993525 -0.5633234 0.7816328 -0.003465871 -0.6237292 0.639136 0.002369485 -0.7690902 0.5182204 -0.004017522 -0.8552376 0.2906596 0.002900822 -0.9568222 0.2878544 0.002813739 -0.9576701 0.2659285 0.001516521 -0.9639916 0.8171023 0.311344 -0.4851895 0.7895659 0.479371 -0.3831307 0.7894539 0.4789815 -0.3838478 0.809357 0.3293221 -0.4863006 0.04457368 0.402076 -0.9145206 0.4129432 0.8194636 -0.3974384 0.5830309 0.2912295 -0.7584592 0.5882565 0.7767553 -0.2249562 0.5819955 0.2920022 -0.7589571 0.0877617 0.4837946 -0.8707702 0.1917911 0.4761735 -0.8581812 0.1457052 0.8444131 -0.5154964 0.4309527 0.5530228 -0.7130537 0.395168 0.2438841 -0.8856425 0.3667136 0.7944317 -0.4841481 0.4518624 0.6695737 -0.5894839 0.2958571 0.9548474 -0.02711277 0.3379103 -0.3826268 0.8598915 0.4765424 -0.4338848 0.764625 0.4753076 -0.4351404 0.76468 0.7763422 -0.2415633 0.5821854 0.483969 -0.5817606 0.6537038 0.8432096 -0.3971615 0.3622987 0.7059145 -0.5911397 0.3901776 0.3301607 -0.7365878 0.5902815 0.2776752 -0.2377226 0.9307978 0.3625256 -0.8799068 0.3071469 0.3909604 -0.8792785 0.2720647 0.6464447 -0.7256463 0.2356839 0.9034168 -0.3393965 0.262008 0.3351393 0.006195638 0.9421482 0.4229686 0.0002873679 0.9061443 0.6106529 -0.002000903 0.7918959 0.694742 0.002521982 0.7192547 0.7684729 -0.002363487 0.639878 0.9237857 0.005857763 0.3828651 0.9635299 -0.001204502 0.2675978 0.10959 0.8860608 0.4504291 0.302022 0.2577724 0.9177887 0.4027583 0.4231256 0.8116345 0.6224601 0.3890603 0.679099 0.4350066 0.8193769 0.3733507 0.2725129 0.5811596 0.7668052 0.4905725 0.7346714 0.4686113 0.8225628 0.4346626 0.3666861 0.6879226 0.4961141 0.5297484 0.1742862 0.9846314 -0.01119344 0.4544588 0.8811011 0.1308739 0.6448731 0.755489 -0.1156505 -1.483353e-06 -0 -1 -0.03206235 0.02219744 -0.9992394 -1 9.673745e-08 -2.944317e-06 -1 9.765822e-06 2.67981e-07 -1 -1.289006e-05 -3.537122e-07 -1 1.221258e-05 -6.33018e-06 -1 4.931644e-06 -1.486243e-06 -1 -5.933472e-06 -3.077202e-06 -1 -6.578144e-06 -2.898053e-06 -1 -1.768569e-05 4.263323e-06 -1 -2.332882e-05 3.360406e-06 -1 -6.617089e-06 3.568278e-06 -1 -6.85004e-06 3.657561e-06 -1 4.334214e-05 9.080446e-06 -1 1.090499e-05 -5.056179e-06 -1 3.74586e-05 2.311447e-06 -1 1.212688e-05 -4.916539e-06 -1 -2.186765e-05 -1.360056e-05 -1 6.191503e-07 3.760927e-06 -1 -1.917821e-05 4.202042e-06 -1 5.927833e-06 1.000924e-05 -1 -1.399053e-06 4.340725e-06 -1 1.278467e-05 6.460161e-06 -1 5.218894e-06 1.015279e-05 -1 8.471722e-06 7.065599e-06 -0.9999957 0.00245563 0.001589907 -1 1.191294e-05 4.788469e-08 -1 -4.306192e-07 1.696926e-06 -1 -1.419153e-06 1.418583e-06 -0.9999832 0.002447236 -0.005273366 -0.9999983 0.001522454 -0.00106155 -0.9999273 -0.01073983 -0.005477486 -0.9999294 0.01183286 0.001066073 -0.9999726 0.002990982 -0.006766003 -0.9999969 -0.001936588 0.00155773 -0.9999499 -0.00988678 0.001547982 -1 3.654944e-06 -4.898115e-05 -0.9997703 0.02076303 0.005294624 -0.9999854 -0.002959089 0.004528185 -1 1.347152e-05 -4.282995e-05 -1 8.121754e-05 -4.139348e-05 -0.9245545 0.3766902 -0.05747565 -0.9980712 0.06188131 -0.004948223 -0.9995529 0.01924509 0.02288063 -0.9999843 -0.001340301 0.005435212 -0.9999841 -0.001410044 0.005453602 -0.9999959 -0.002351584 0.001691864 -0.9999856 -0.004807446 -0.002373399 -1 0 0 -1 3.169649e-05 1.025112e-05 -0.9999982 0.001221877 0.001444332 -0.9999956 -0.002939019 0.0003963501 -0.9999977 -0.001796065 0.001059585 -0.9999855 -0.005288083 -0.001038885 -0.9999816 -0.006066421 0.0001274792 -0.9999949 -0.0006690979 -0.003153847 -0.999985 -0.004829456 -0.002588992 -1 8.926701e-06 2.109676e-05 -1 2.28081e-05 2.878291e-05 -1 -1.076311e-06 8.109782e-06 -0.9999935 -0.003588643 -0.0003099611 -0.9999909 -0.004210901 -0.0007386415 -0.9999986 -0.00141941 0.0008464953 -0.9999812 -0.003998153 -0.004626525 -0.9999844 -0.004247167 -0.003619587 -1 -6.888191e-06 -7.212376e-06 -0.9999956 -0.002960664 -0.0001011586 -1 -1.38068e-05 2.041073e-06 -1 1.880159e-05 1.074031e-06 -0.1376485 -0.03003824 0.9900255 0.1743693 0.4111436 0.8947382 -0.17429 0.6561342 0.7342417 0.1515412 0.8715488 0.4663024 -0.06513233 0.9510332 0.3021483 -0.007701313 0.9885625 -0.1506151 -0.04236629 0.990139 -0.1335281 0.1489125 0.8057994 -0.5731601 -0.1925225 0.6427302 -0.7415072 0.119185 0.2477749 -0.9614585 0.01520756 0.1792336 -0.983689 -0.04939387 -0.2452043 -0.9682122 0.01592271 -0.2881685 -0.9574474 0.06369307 -0.6353532 -0.7695904 -0.1512338 -0.7576842 -0.6348567 0.1229924 -0.9129207 -0.3891641 -0.1084201 -0.9929297 -0.04833048 0.04491009 -0.9957989 0.07979814 -0.01937233 -0.8751045 0.4835461 0.06324803 -0.8957751 0.4399849 -0.1115171 -0.6294805 0.7689723 0.1114935 -0.4788291 0.8707997 -0.06323498 -0.07426353 0.9952317 -0.1164796 0.3023176 0.9460637 0.06668688 0.388815 0.9188991 -0.001544028 0.8550093 0.5186106 -0.1283927 0.8835289 0.4504353 0.1204881 0.9887376 0.0887726 -0.1485459 0.9679834 -0.2023418 0.1515366 0.8540398 -0.4976471 -0.1027222 0.7324369 -0.673041 0.08669367 0.3545583 -0.9310062 0.06322785 0.3422751 -0.93747 -0.1114924 -0.0776514 -0.9907268 0.1114944 -0.2568328 -0.9600031 -0.05273258 -0.6154835 -0.7863837 -0.01942752 -0.5981995 -0.8011116 0.01717617 -0.8568121 -0.5153427 -0.02781409 -0.8751398 -0.4830701 0.02783125 -0.9955803 -0.08969603 -0.05551266 -0.9982376 -0.02097792 0.06921548 -0.9507788 0.3020413 -0.1262547 -0.8613576 0.4920597 0.1234018 -0.7018431 0.7015612 -0.1278284 -0.3864646 0.913403 0.09435429 -0.2448709 0.9649537 0.1351487 0.1994733 0.9705386 -0.1773071 0.4013422 0.8986027 0.09934074 0.6536711 0.7502303 -0.06329487 0.8957816 0.4399649 0.0193712 0.8751016 0.4835513 -0.04491155 0.9957991 0.0797944 0.07581851 0.9969016 -0.0209486 -0.09934387 0.8896129 -0.4457799 0.0155325 0.8624573 -0.5058914 0.08799428 0.5265121 -0.8456016 -0.1313201 0.3626686 -0.9226193 0.08803359 0.1310532 -0.9874589 -0.1029872 -0.1578606 -0.9820762 0.1101427 -0.463513 -0.879218 0.005407854 -0.528543 -0.8488893 -0.05032784 -0.8449434 -0.5324827 0.1025289 -0.9028051 -0.4176491 -0.1036313 -0.9856925 -0.1329312 0.1201391 -0.9866506 0.109942 -0.1277835 -0.8745175 0.4678573 0.05403523 -0.8153774 0.5764024 -0.01218959 -0.4062021 0.913702 -0.1069376 -0.3594918 0.9270005 -0.7898558 0.006706517 -0.6132558 -0.5523966 -0.8335814 -0.0002670072 -0.6151301 -0.7884247 -0.001268701 -0.9994467 -0.03326011 0.0003383892 -0.7181571 0.007100549 0.6958448 -0.7018123 0.3883266 0.5972118 -0.7161196 0.3793775 0.5858714 -0.9994813 0.01871327 0.02620906 -0.9976228 0.06891011 9.341577e-05 -0.977065 0.2129384 -0.001146284 -0.7488461 0.6627408 0.002049851 -0.7647768 0.6442932 0.001643926 -0.9939759 0.06399673 -0.08897497 -0.7889453 0.3339579 -0.5157882 -0.683199 0.4036956 -0.6084973 -1 -6.422777e-05 -5.675258e-05 -1 -1.656209e-05 -1.853367e-05 -1 -9.884965e-06 7.21818e-06 -1 -3.500609e-05 -5.438761e-06 -1 1.661259e-06 4.35981e-06 -1 1.835817e-06 4.817922e-06 -1 -7.746974e-05 -8.590766e-06 -1 -2.752705e-05 2.869159e-05 -1 -4.051015e-05 6.054655e-05 -1 -3.725484e-06 4.997755e-05 -1 6.853572e-06 -7.087785e-06 -1 -3.354726e-05 -8.098421e-06 -1 2.934687e-06 7.469432e-06 -1 -2.790727e-06 -7.103021e-06 -1 -0.000131284 0.0001519722 -1 -0.0001580766 9.782997e-05 -1 6.701026e-06 7.372015e-06 -1 0 -0 -1 0 0 -1 -1.688853e-05 -9.18286e-06 -1 -1.584838e-05 -8.617297e-06 -1 -9.235376e-06 -5.123978e-05 -1 9.083741e-05 5.53948e-05 -1 4.52714e-05 2.757941e-05 -1 2.594272e-05 9.982007e-06 -1 -3.856819e-05 4.555635e-05 -1 9.115602e-05 4.855832e-05 -1 4.458239e-05 -1.987539e-05 -1 4.521371e-05 -1.978086e-05 -1 4.584339e-05 -2.175244e-05 -1 7.842375e-06 -1.755755e-05 -1 3.464679e-06 -2.195949e-05 -1 6.796113e-06 5.238053e-05 -1 -3.368442e-05 -9.711483e-06 -1 -9.926672e-07 4.239303e-06 -1 -7.967508e-07 3.402619e-06 -1 1.287405e-06 3.061092e-06 -1 0 -0 -1 1.689269e-05 -1.917302e-05 -1 9.286744e-06 1.183585e-05 -1 3.768629e-07 4.808261e-06 -1 -3.289268e-06 1.57337e-05 -1 4.083065e-05 1.524491e-05 -1 -1.562124e-05 6.628148e-06 -1 2.068946e-05 1.143229e-05 -1 -2.683761e-05 -6.60637e-06 -1 2.582454e-06 4.263823e-05 -1 2.375548e-05 5.461598e-06 -1 4.655172e-06 -6.139192e-06 -1 -9.167926e-06 1.209056e-05 -1 8.765642e-07 1.102976e-05 -1 5.592898e-07 -1.92752e-05 -1 -5.161105e-06 -2.629999e-05 -1 -4.688742e-06 -1.251526e-05 -1 -1.593451e-06 -4.253262e-06 -1 0.0001802839 -4.025359e-05 -1 9.936934e-06 -9.612847e-05 -1 7.919801e-06 -9.376269e-06 -1 1.220615e-05 -1.445089e-05 -1 0 0 -1 0 0 -1 -1.292115e-05 -1.135307e-05 -1 -8.855468e-06 -1.789966e-05 -0.02256583 0 -0.9997454 -0.01106206 -0.004805027 -0.9999273 -0.007395028 0 -0.9999727 -1.271566e-06 0 -1 -1.271296e-06 -0.02060238 -0.9997877 0.003269763 -0.002971915 -0.9999902 -0.02256583 0 -0.9997454 0.01178428 0 -0.9999305 0.01178428 0 -0.9999306 0.005860548 -0.0008467867 -0.9999825 0.003391624 0 -0.9999942 0.003391624 0 -0.9999943 -0.0001779164 -5.432241e-05 -1 0 0 -1 -2.85225e-06 -1.166846e-06 -1 3.48758e-05 -3.143054e-05 -1 3.127717e-05 -4.360468e-05 -1 0.002862432 0.0008805179 -0.9999955 -3.448697e-06 1.237262e-06 -1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.190651e-07 8.863668e-07 -1 0 0 -1 0 0 -1 -0.002565395 -8.254006e-05 -0.9999967 -5.329405e-07 -9.758907e-07 -1 -2.60459e-06 1.370613e-06 -1 -2.875246e-06 -1.540545e-06 -1 9.591829e-05 4.892311e-05 -1 -1.271566e-06 -8.014027e-08 -1 -1.567791e-06 -3.788545e-07 -1 -2.854404e-07 6.157198e-07 -1 -2.197849e-06 -4.63141e-07 -1 -1.11262e-06 3.580375e-08 -1 -2.428471e-07 1.994475e-06 -1 0.0002897077 -0.9999993 -0.001172139 -3.380994e-05 -0.9999986 -0.001706034 -0.02623579 -0.007448431 0.9996281 -0.02871814 0 0.9995875 7.393048e-06 -6.510315e-06 1 0 0 1 1.271566e-06 -1.155737e-06 1 0.002342661 -0.0106417 0.9999406 0.008467043 -0 0.9999642 0.00732185 -0.0004012791 0.9999731 0.004448904 0 0.9999901 0.004448904 0 0.9999901 0.004448905 0 0.9999902 1.271566e-06 -0 1 1.271566e-06 0 1 1.271566e-06 -0 1 -5.594591e-05 -2.909363e-05 1 -7.794396e-05 -3.788618e-05 1 -0.004416625 0 0.9999903 -0.004416625 0 0.9999902 -2.974101e-05 2.618992e-05 1 -1.159129e-05 0 1 1.960859e-05 8.506971e-06 1 -0.004133962 -5.253109e-05 0.9999915 0.005553817 0.001858647 0.9999829 -2.825424e-06 -4.896416e-06 1 1.271567e-06 1.173955e-07 1 6.074672e-07 1.411636e-06 1 4.085085e-06 -1.395702e-06 1 4.548187e-07 -1.625147e-06 1 3.561827e-06 1.538519e-06 1 -2.185158e-06 8.760818e-06 1 1.255296e-05 -5.293059e-06 1 -2.112503e-05 8.907544e-06 1 1.096309e-05 -6.241917e-12 1 0 0 1 0 0 1 6.430054e-07 -1.892576e-06 1 1.265928e-06 1.691382e-07 1 -0.005112986 0.5505316 0.8347986 0.01370828 0.5618877 0.8270999 -0.007115377 0.9999747 -5.506664e-05 0.008162166 0.9999619 -0.003113604 -0.000751338 0.5451627 -0.83833 -0.007652566 0.5493711 -0.8355434 0.0007442614 0.175607 -0.9844601 0.05910721 0.247227 -0.9671532 -0.05538556 0.5899748 -0.8055198 0.06851883 0.7984452 -0.5981558 -0.08207538 0.9542458 -0.2875387 0.06223112 0.9952319 -0.07510513 -0.04912779 0.8777939 0.4765128 -0.005578185 0.8547326 0.5190386 0.02468613 0.4687119 0.8830061 -0.02260354 0.4056976 0.9137278 0.00885666 -0.03782144 0.9992453 -0.004004708 -0.02143051 0.9997623 0.02626649 -0.5322917 0.8461534 -0.02632411 -0.5867168 0.8093643 0.003976395 -0.9196559 0.3927051 -0.008861973 -0.9130759 0.4076934 0.02259877 -0.9991052 -0.03575185 -0.0246984 -0.9940928 -0.1056855 0.003985588 -0.8165208 -0.5773023 -0.008861369 -0.825841 -0.5638335 0.02460363 -0.4666148 -0.8841184 -0.02915553 -0.4061048 -0.9133613 -0.0736239 0.006675593 -0.9972637 0.07542871 0.4700935 -0.8793876 -0.005095692 0.4078269 -0.9130451 0.03179535 0.9156951 -0.4006139 -0.0619316 0.9464891 -0.3167379 0.06193306 0.9162205 0.3958586 -0.002580529 0.8918135 0.4523959 -0.04530014 0.4564783 0.8885806 0.07265306 0.33648 0.9388838 -0.03872696 -0.2286875 0.9727293 0.03016372 -0.3271613 0.944487 -0.03639098 -0.6567152 0.7532601 0.06364542 -0.782434 0.6194726 -0.07216 -0.969618 0.233739 0.07216772 -0.9972279 0.01812046 -0.06363997 -0.9132761 -0.402339 0.05348568 -0.806506 -0.5888015 -0.05352204 -0.5540666 -0.83075 0.07993379 -0.3344196 -0.9390283 0.08491953 0.1360413 -0.987057 -0.09192525 0.5117571 -0.854198 0.07217139 0.7074174 -0.7031017 -0.07216579 0.9462994 -0.3151344 0.07216015 0.9920983 -0.1026356 -0.07216507 0.9342271 0.3493022 0.0721518 0.8363722 0.5433926 -0.08093657 0.4821863 0.872322 0.0188462 0.3684601 0.9294525 0.04792398 -0.07803787 0.9957979 -0.1126553 -0.3067844 0.9450884 0.06376705 -0.5971435 0.7995958 -0.02495956 -0.903112 0.4286791 -0.03180831 -0.9057184 0.4226847 0.0007369493 -0.9761212 -0.217225 0.08280387 -0.9450503 -0.3162649 -0.06673752 -0.7792056 -0.6232052 0.06250912 -0.4425623 -0.8945565 -0.07798274 -0.2468628 -0.9659076 -1.79124e-07 0.9899495 -0.1414218 -1 -0 0 -1 0 0 0.9999999 0.0004224881 -0.0001261608 0.9992746 0.003502344 -0.03792026 0.9834164 0.1618451 0.08184353 0.8874465 0.439062 -0.1402259 0.6949298 0.699213 0.1678501 0.3401565 0.9267439 -0.159497 0.1325813 0.986986 0.09099976 -0.3758457 0.9233308 -0.07874157 -0.4205876 0.9072441 -0.003765723 -0.8688441 0.4924509 0.05101058 -0.9168576 0.3813957 -0.1179385 -0.9948623 -0.0213558 0.09895933 -0.943618 -0.3078462 -0.1217206 -0.8594637 -0.5045369 0.08224773 -0.5435014 -0.8365238 -0.06952775 -0.4789995 -0.8771167 0.03501096 0.07518958 -0.9965545 -0.03500976 0.1208202 -0.9922825 0.027893 0.6220294 -0.7823848 -0.03087852 0.6356506 -0.7719678 -0.003743404 0.9564023 -0.2879975 0.0484988 0.9813265 -0.1657343 -0.09762451 -0 1 0 0 1 -0 -1 -5.784577e-06 0 -1 0 2.543132e-06 -1 6.531412e-07 0 0 -1 0 0 -1 0 1 0 -2.543132e-06 1 0 -2.543132e-06 1 -2.311476e-06 -3.559349e-06 1 7.734639e-06 -1.590724e-06 1 7.55254e-06 -5.875003e-06 1 -4.382841e-07 -7.902883e-06 1 -6.274558e-06 5.80827e-05 1 1.008124e-05 -1.993916e-05 1 -4.420731e-07 -7.971206e-06 1 4.802087e-07 -7.228861e-06 1 1.81966e-05 1.962718e-07 1 -5.316818e-06 -1.548976e-06 1 2.413628e-05 1.277485e-05 1 8.353892e-06 6.265234e-07 1 1.256114e-05 1.469744e-05 1 -1.023939e-05 -5.841846e-05 1 -4.818869e-05 -3.599059e-05 1 -5.659788e-06 2.031371e-05 1 1.5128e-05 1.34694e-06 1 -3.986725e-06 -6.050193e-06 1 0 -1.813233e-06 1 -1.881925e-05 -1.108833e-05 1 1.723638e-05 -1.340745e-05 1 1.256086e-06 -1.162741e-05 1 -6.159084e-06 -1.540738e-06 1 5.074532e-06 -1.329594e-06 1 -9.289734e-06 -5.804404e-06 1 -8.916981e-06 -7.437992e-06 1 4.736776e-06 3.951124e-06 1 5.525856e-06 -4.833112e-06 1 -7.918651e-06 3.523721e-06 1 -1.929216e-05 -2.19795e-05 1 5.799439e-06 -1.212341e-06 1 9.248207e-06 -1.010876e-06 1 7.416091e-05 1.402436e-06 1 -3.046288e-06 -5.760751e-08 1 -1.522788e-05 3.033433e-06 1 -3.991363e-06 6.156125e-06 1 2.695795e-05 -3.753044e-06 1 0 -1.971968e-06 1 -4.089689e-07 -1.300322e-06 1 -1.992451e-05 -9.367433e-06 1 -1.676738e-05 -4.128297e-05 1 -1.774765e-05 -1.264196e-05 1 -6.906062e-06 -5.44259e-07 1 -3.467965e-06 -2.733065e-07 1 0.0001081227 -5.624669e-05 -1 -3.452807e-09 2.542673e-06 -1 0 2.55683e-06 -8.458284e-08 -0.9977852 -0.06651867 1 2.311472e-06 -3.559352e-06 1 0 -2.543133e-06 1 0 -2.543133e-06 0 1 -0 0.001634542 0.9999824 -0.005719279 -7.705262e-09 0.999976 -0.006925331 0.001003195 0.9999869 -0.005000784 -0.005599909 0.9999843 1.993203e-08 5.050763e-07 0.9999939 -0.003486746 -1 0 0 -1 5.86876e-07 2.285117e-06 -1 -2.31147e-06 3.559349e-06 -1.589457e-07 -1 -0 -1.589457e-07 -1 -0 1 0 -0 1 0 0 -1 -6.479413e-06 4.830475e-06 -1 0 -3.846639e-06 -1 0 0 -1 -8.841565e-06 -1.703385e-06 -1 2.115746e-05 -2.953893e-05 -1 0 0 -1 8.26484e-07 4.022158e-06 -1 -9.305638e-07 3.168829e-06 -1 4.639764e-06 1.123228e-05 -1 1.451e-06 2.562544e-06 -1 -7.79044e-06 1.987524e-06 -1 2.320735e-05 2.439373e-05 -1 5.167301e-05 -4.394915e-05 -1 -3.804649e-06 -4.731965e-05 -1 -4.464989e-07 -7.885411e-07 -1 1.489553e-05 -2.48264e-06 -1 1.979033e-05 -1.899667e-06 -1 8.821101e-05 5.709294e-05 -1 4.6773e-05 2.876073e-05 -1 1.128133e-07 2.982575e-06 -1 -6.778142e-05 -5.899828e-06 -1 0 -0 -1 1.804126e-05 -1.00056e-05 -1 -2.472154e-06 -3.074696e-05 -1 5.218605e-05 5.128439e-06 -1 5.212763e-05 4.985492e-06 -0.9999969 0.002370739 0.000793879 -1 3.637544e-05 1.38122e-05 -1 2.88209e-05 1.316931e-05 -1 7.142293e-06 -1.576715e-06 -1 -0.0001540158 -2.994992e-05 -1 -7.888149e-06 1.991409e-06 -1 6.635507e-05 2.582989e-06 -1 4.453399e-05 -1.018986e-05 -1 -2.480986e-06 -7.203581e-07 -1 -1.230071e-06 8.144311e-07 -1 3.568431e-06 1.538545e-06 -1 0 -0 -1 0.000104621 0.0001001915 -1 0.0001035458 0.0001051532 -1 -5.274096e-05 0.0001141749 -1 -0 -0 -1 1.745474e-06 2.432603e-06 -1 -1.729633e-05 2.32839e-05 -1 5.696258e-05 2.39397e-05 -1 5.494232e-05 -2.109152e-05 0.003534178 0.5500907 -0.8350974 -0.01553988 0.5618758 -0.8270757 0.6526194 0.001318728 -0.7576848 0.9027628 -0.001266978 -0.4301368 0.8463706 -0.2974534 -0.4417897 0.001778552 -0.9794092 -0.2018774 -0.002207665 -0.8876814 -0.4604529 0.002098173 -0.8059807 -0.5919381 0.6125947 -0.790396 0.001416591 0.7556966 -0.6548859 0.006856159 0.9078376 -0.4192853 -0.0055514 0.8630694 -0.5050843 -0.001004759 0.9999481 -0.0100745 -0.001474018 -0.0009142781 -0.5932599 0.8050104 0.0002088153 -0.8359335 0.5488306 -0.0007892192 -0.8521385 0.5233157 4.023568e-05 -0.9755039 0.2199823 0.0003094008 -0.9722024 0.2341421 0.6338827 -0.4300217 0.642864 0.7998185 -0.3265723 0.5036277 -1 0 0 -1 0 0 1.791238e-07 0.9899494 0.1414217 0.993044 0.01282871 0.1170423 0.9999951 0.003088871 0.000435821 0.9988104 -0.00247724 0.04869867 0.9994241 0.03285851 -0.008475676 0.8380755 0.5406079 -0.07329661 0.6928636 0.6991763 0.1763307 0.4134675 0.8965499 -0.1588806 -0.00746272 0.9872699 0.1588786 -0.3180722 0.9361908 -0.149589 -0.6084134 0.7758967 0.1667856 -0.8340113 0.5246065 -0.1709192 -0.9936332 0.02127669 0.1106361 -0.9955277 0.0339908 0.08814342 -0.8663554 -0.4910602 -0.09103925 -0.7786362 -0.6208445 0.09098304 -0.3943266 -0.9163387 -0.06949871 -0.3239022 -0.9454423 0.03501684 0.2693102 -0.9622925 -0.03827727 0.3157163 -0.9480805 0.03829588 0.8140741 -0.5795003 -0.03824768 0.8249894 -0.5650644 -0.009733631 -0 1 0 0 1 -0 1 -0 0 1 0 0 1 -0 0 -0 -1 -0 0 -1 0 -1 6.531412e-07 2.543132e-06 -1 0 -0 -1 0 0 -0.002674607 0.5447032 0.8386247 0.00505703 0.5493821 0.835556 1 -3.194226e-09 -2.543132e-06 1 0 -2.555794e-06 -1.589457e-07 -1 4.042199e-13 -1.589457e-07 -1 4.042199e-13 -1 2.31147e-06 3.559349e-06 -1 0 2.543132e-06 -1 0 2.543132e-06 5.086263e-07 1 -1.810378e-12 -0.001634037 0.9999823 0.005719273 8.805551e-09 0.999976 0.006924963 0.002382135 0.9999312 0.01149472 0.018679 0.9998255 -0 2.230792e-08 0.9999399 0.01096479 1 0 -2.543133e-06 1 -5.693574e-07 -2.503132e-07 1 0 0 8.590494e-08 -0.9977852 0.06651867 -1 0 -0 -1 -0 0 0.8328735 -0.0005296875 0.5534633 0.73466 0.0007394101 0.6784351 -0.02279355 0.7863982 0.6172992 -0.001154424 0.9385977 0.3450117 0.004677463 0.9444657 0.3285768 -0.01920064 0.9785264 -0.2052252 0.01465322 0.8502622 -0.5261554 -0.01096882 0.7979593 -0.6026114 1 -1.477648e-05 6.398736e-05 1 -7.819398e-05 9.494328e-05 1 -5.431223e-05 -3.186699e-05 1 1.210981e-05 -4.581925e-06 1 2.334495e-05 -8.832902e-06 1 1.407163e-05 4.439637e-05 1 -3.048287e-05 -2.263744e-05 1 1.21109e-05 -1.647606e-05 1 5.003865e-06 1.092258e-05 1 0 0 1 -5.364052e-06 8.725054e-07 1 -1.068221e-06 -2.380984e-06 1 -2.068224e-06 -4.609918e-06 1 1.698575e-05 -4.203685e-06 1 1.591042e-05 -1.303835e-06 1 6.694072e-05 5.254055e-05 1 2.13757e-05 7.534856e-05 1 2.388972e-05 9.152054e-06 1 1.128087e-05 4.321654e-06 1 -2.380541e-05 5.190363e-05 1 -0.0001042689 4.419098e-05 1 -5.709746e-05 2.419889e-05 1 -3.954044e-05 4.206755e-05 1 1.078927e-06 -7.495856e-06 1 1.324333e-05 6.556915e-08 1 9.610773e-06 4.233975e-06 1 1.07903e-05 5.734061e-06 1 -5.326413e-06 1.819959e-05 1 -1.634595e-05 -3.917521e-05 1 -3.576369e-05 -2.907418e-05 1 1.587256e-05 0.0001027017 1 -4.159102e-05 7.780288e-05 1 -7.329784e-05 0.0001024666 1 -9.353075e-05 6.908201e-05 1 -9.40477e-06 3.147259e-06 1 -2.79649e-06 1.692222e-05 1 1.921804e-06 1.663152e-05 1 -3.052025e-06 -2.641256e-05 1 1.261581e-05 -2.183742e-05 1 3.61312e-06 2.024846e-05 1 3.056072e-05 4.892086e-05 1 -2.716159e-05 0.0001021228 1 2.744812e-05 -1.556427e-05 1 2.520717e-05 -1.568928e-05 1 3.501347e-05 -3.179373e-05 1 5.433627e-05 -1.253853e-05 1 1.868358e-05 3.934719e-05 1 4.4336e-05 9.337063e-05 1 5.243365e-05 8.47043e-05 1 -1.414744e-05 2.053014e-05 1 0 -0 1 9.837448e-06 9.606884e-06 1 1.552961e-05 -2.59212e-05 1 3.024051e-05 -2.056419e-05 1 1.774497e-05 -8.874983e-06 1 2.096403e-05 -3.534428e-06 1 -2.491848e-05 4.20113e-06 1 -2.686079e-05 -6.347344e-06 1 8.231588e-06 1.945167e-06 1 8.573124e-06 -3.144063e-06 1 0 0 1 -0 0 1 2.781738e-05 -2.135646e-05 1.120247e-05 0 -1 -1.271566e-06 -6.966766e-05 -1 -0.002927321 0.0004351023 -0.9999956 5.52876e-05 -0.0001311303 -1 -0.003590978 0.00048667 -0.9999934 -2.387223e-06 -1.539383e-06 -1 0 0 -1 -4.108942e-06 -1.159597e-06 -1 -3.642556e-06 -1.188348e-06 -1 -1.329895e-06 -6.57962e-07 -1 -1.048117e-06 1.770144e-07 -1 -1.39823e-06 3.434998e-06 -1 0 0 -1 0 0 -1 -1.789113e-06 1.400733e-06 -1 -1.271567e-06 -1.205693e-06 -1 -5.646427e-07 3.695061e-06 -1 -2.580181e-06 -1.095727e-06 -1 0 0 -1 -1.091017e-06 -2.663567e-06 -1 -0 0 -1 0 -0 -1 0 0 -1 -3.416746e-06 1.801976e-06 -1 -1.271566e-06 -1.071492e-06 -1 -1.629341e-06 -4.82931e-06 -1 0 0 -1 -1.066424e-06 -0.5446403 -0.8386697 -1.06755e-06 -0.5446404 -0.8386697 0.1544518 -0.08822491 -0.9840534 -0.05745655 0.03278002 -0.9978097 0.01573684 0.5884312 -0.8083941 -0.007916871 0.5798936 -0.8146538 0.06946234 0.96837 -0.2396551 -0.005682104 0.9780573 -0.2082591 -0.09147627 0.9317457 0.3513999 0.1773263 0.8403379 0.512238 -0.1485381 0.6165 0.7732168 0.1485839 0.3352168 0.9303507 -0.1773381 -0.004435 0.98414 0.09150625 -0.1893375 0.977639 0.005728554 -0.6901233 0.7236691 -0.005691528 -0.693715 0.7202272 -0.09505395 -0.974409 0.203695 0.1748693 -0.9835066 0.04621157 -0.1381945 -0.9063362 -0.3993205 0.1856566 -0.7569709 -0.6265194 -0.1641987 -0.5473737 -0.8206223 0.05028547 0.07437067 -0.995962 -0.133743 0.2263519 -0.96482 0.1207523 0.4783488 -0.8698283 -0.1563707 0.7796017 -0.6064399 0.156316 0.8924937 -0.423108 -0.1563334 0.9875413 0.01794993 0.1134645 0.9725196 0.2033012 -0.07562788 0.7818 0.6189258 0.03132927 0.7359565 0.6763035 -0.03855557 0.2998013 0.9532223 -0.1271767 0.3401577 0.9317289 0.1395858 -0.04690125 0.9890986 -0.1376648 -0.4351317 0.8897802 0.09549748 -0.5553735 0.8260996 -0.1461139 -0.9087067 0.391028 0.1246154 -0.9620531 0.2427443 -0.07563358 -0.967328 -0.2419838 -0.01519868 -0.9590571 -0.2828047 0.04492424 -0.7741324 -0.6314275 -0.04493115 -0.7246172 -0.6876853 0.01931727 -0.3771406 -0.9259545 -0.008711938 -0.3922784 -0.9198052 -0.006659804 0.8902202 0.4554818 0.006427366 0.8791457 0.4765096 -0.006000744 0.6649134 0.7468964 0.00395141 0.6496922 0.760187 -0.002800584 0.9999514 0.009448627 -0.006771625 0.9999189 0.0107853 -0.02416248 0.9989671 0.03848407 0.002825831 0.9999241 -0.01199073 -0.005339864 0.9999496 -0.008504878 -0.02416647 0.9989668 -0.03849028 0 0.5927315 -0.8054001 0.008324597 0.6102635 -0.7921548 -0.01154594 0.8655837 -0.5006312 0.006819127 0.8795473 -0.4757625 -0.1528231 0.851922 -0.5008731 0.09650154 0.921679 -0.3757594 -0.1450855 0.972479 0.1823041 0.07423372 0.9479529 0.3096363 0.004065509 0.6967506 0.7173019 0.08948156 0.727776 0.6799523 -0.1042337 0.3878327 0.9158172 0.1062866 0.1746695 0.9788737 -0.1136 -0.0658542 0.9913417 0.1281304 -0.3205675 0.9385196 -0.02993005 -0.6641203 0.7470263 -0.1947994 -0.7193667 0.6667569 0.128195 -0.9163176 0.3793785 -0.02991163 -0.9995403 -0.004948833 -0.1468339 -0.9865425 -0.07192712 0.1233599 -0.8763128 -0.4656803 -0.1515299 -0.7010648 -0.696812 0.102623 -0.5392399 -0.835876 -0.08597212 -0.110515 -0.990149 0.04449686 -0.03412914 -0.9984263 -0.03265912 0.4396185 -0.8975907 0.1203819 0.5436686 -0.8306219 0 0 -1 0 0 -1 -2.446492e-06 6.09415e-07 -1 -0.002345886 0.004719856 -0.9999861 -0.004159998 0.002506619 -0.9999882 -0 0 -1 -0.009284572 0.001357884 -0.999956 0 -0 -1 -7.481152e-07 -3.932543e-06 -1 -0.001183132 0.01226194 -0.9999241 -1.908344e-06 5.19543e-06 -1 -1.271565e-06 9.415779e-07 -1 -9.726538e-07 2.495706e-06 -1 -2.963616e-06 -1.225532e-06 -1 -0.007912273 0.690404 -0.7233807 -1.547264e-06 0.5446431 -0.8386679 -5.761218e-07 0.5446392 -0.8386704 1 -1.496612e-06 2.304556e-06 1 -4.806006e-05 -1.099074e-06 1 -2.852763e-05 3.058509e-05 1 8.558434e-05 -0.0001120954 1 0.0001226928 -7.502721e-05 1 -4.347965e-05 -2.116589e-07 -0.004376318 0.6906545 -0.7231717 0.008950724 0.8435219 -0.5370201 -0.002888038 0.9172719 -0.3982512 -1 0 0 -1 -1.212188e-06 1.866591e-06 -1 -1.40455e-05 2.9735e-06 -1 -1.224326e-05 7.794552e-06 -1 -5.224435e-07 -5.343798e-06 -1.492991e-06 0.544642 -0.8386686 -9.336301e-07 0.5446392 -0.8386704 0.007880521 0.6898893 -0.7238719 0 0 -1 0.008348235 0.001255493 -0.9999644 0.005318959 0.001817499 -0.9999842 0.003222227 0.002864373 -0.9999907 0.001834674 0.005363466 -0.999984 -1.076674e-06 -2.103014e-06 -1 -3.815267e-06 6.60854e-07 -1 -1.271566e-06 -1.163402e-06 -1 -2.000787e-06 -6.013501e-06 -1 0.001093788 0.01121396 -0.9999366 -9.683226e-07 2.907924e-06 -1 -3.399082e-06 -1.289957e-06 -1 -0 0 -1 0 0 -1 0 0 -1 -0.1205007 0.1214888 -0.9852513 0.1485935 0.401803 -0.9035897 -0.1772184 0.6841599 -0.7074736 0.1351827 0.8261494 -0.5469944 -0.1187667 0.9927838 0.01657895 -0.1449599 0.9894269 0.004590704 0.1396151 0.9002698 0.412337 -0.1191973 0.6852567 0.7184812 0.07568696 0.5851995 0.8073494 -0.1134612 0.1618469 0.9802715 0.06823692 0.03770902 0.9969563 0.01173515 -0.4057418 0.9139124 -0.1055254 -0.4637431 0.8796628 0.1055118 -0.8591852 0.5006676 -0.1055005 -0.913435 0.3930726 0.09434365 -0.9882398 -0.1203392 -0.04938678 -0.9749336 -0.2169457 0.01933615 -0.7807981 -0.6244841 0.0437103 -0.7712385 -0.6350437 -0.03982961 -0.3265761 -0.9443313 0.1101286 -0.2270375 -0.9676392 -0.1515583 0.05989498 -0.986632 0.1381163 0.2990564 -0.944187 -0.1381966 0.6472144 -0.7496768 0.0793006 0.7784812 -0.6226383 -0.06588199 0.9558766 -0.2862857 -0.005428522 0.9689489 -0.2472016 0.06082371 0.9551166 0.2899182 -0.01062263 0.9459697 0.324081 -0.09871348 0.5977678 0.7955685 0.1573641 0.485486 0.859965 -0.09544757 -0.0868845 0.9916354 0.08674091 -0.1921371 0.9775271 -0.09233245 -0.5880992 0.8035011 0.1337753 -0.7595934 0.636492 -0.05030587 -0.85588 0.5147219 0.005417854 -0.9959512 0.08973239 0.01954174 -0.9965913 0.08014891 -0.01953939 -0.9442373 -0.3286853 -0.05277922 -0.9502947 -0.3068459 0.1115541 -0.7504016 -0.6515008 -0.1751427 -0.5709526 -0.8020836 0.1485244 -0.2550795 -0.9554449 -0.004243997 0.9218847 0.3874411 -0.002534728 0.9208448 0.3899212 0.01817374 0.6666489 0.7451503 -0.006697677 0.6316112 0.7752563 -0.002409943 0.9999725 0.007019776 0.002917911 0.9999849 0.004647392 0.0243383 0.998952 0.0387639 0.01284958 0.6959895 0.717937 0.01252865 0.7769787 0.6294023 -0.01444753 0.8502455 0.5261881 0.01818082 0.9402753 0.3399291 -0.001114096 0.9999986 0.001146188 -0.01129733 0.9999313 0.003113379 -0.01225536 0.9444001 -0.3285701 0.02842287 0.7783306 -0.627211 0.02067664 0.9997416 -0.009446613 0.001619321 0.9999954 -0.002579123 0.02433978 0.9989518 -0.03876643 -0.003606213 0.6852528 -0.7282963 -0.0224211 0.6647856 -0.7466977 0.03537821 0.8896487 -0.4552732 -0.03391889 0.9541769 -0.2973145 -0.1355454 0.8690677 0.4757612 0.1069625 0.9916307 -0.0723023 0.01220762 0.992594 -0.1208641 -0.05416691 0.7889479 -0.6120678 0.02633059 0.7552321 -0.6549284 0.0006894995 0.3888589 -0.9212971 0.008825949 0.393214 -0.9194046 -0.05401792 -0.105982 -0.9928997 0.08764404 -0.2005029 -0.9757649 -0.07585455 -0.5759729 -0.8139418 0.0757785 -0.6743746 -0.7344906 -0.08770463 -0.9116004 -0.4016125 0.09435163 -0.9536825 -0.2856351 -0.09433963 -0.9744779 0.203698 0.127827 -0.928989 0.3473322 -0.1233827 -0.7306933 0.671464 0.1515297 -0.502867 0.850978 -0.102637 -0.3112289 0.9447763 0.1046666 0.1883525 0.9765082 0.1660884 0.1565255 0.973609 -0.1210814 0.522284 0.8441319 0.09616294 0.7864459 0.6101276 0.6522343 0.409577 -0.6378379 0.7949556 0.3363617 -0.5048826 0.9999992 0.0007290873 -0.001005519 1 2.467468e-05 6.905927e-06 1 -8.79395e-06 -1.230287e-05 0.9999751 0.002074508 0.006751535 0.9999994 -0.0002516255 0.001058114 1 0.0001285771 -5.536602e-05 1 1.172788e-05 7.046418e-06 0.9999598 0.003565617 0.008227168 0.9999878 0.003605628 0.003355017 0.9998942 0.01441302 0.001941494 1 -7.565918e-05 -1.876605e-06 0.9999142 0.01254246 0.003805142 0.9999709 0.001101711 -0.007547157 0.9999965 0.0002300825 0.002620037 0.9999962 0.0002575108 0.002745322 0.9999995 0.0003983725 0.000961418 0.9999306 0.004442202 -0.01090834 0.9999758 0.004983237 -0.004854529 0.9999729 -0.003398048 -0.006535792 0.9999856 0.000695454 -0.005334878 0.9999999 0.0002476036 0.0001025339 0.9996112 -0.02740244 -0.005161767 0.9999837 -0.00570875 -9.239153e-05 0.9999937 0.002242594 0.002757677 0.999982 -0.003972217 0.004501701 1 -1.435687e-05 6.515695e-05 1 1.657702e-05 -1.356225e-06 1 -0.0001429184 3.832113e-05 1 5.631034e-06 1.38897e-05 0.9999874 -1.265671e-08 0.005008508 1 -2.329406e-06 8.578944e-06 1 -3.848391e-05 2.09297e-05 1 2.013103e-05 -1.305373e-05 1 1.801011e-05 -1.320273e-05 1 -1.547223e-06 -1.282688e-05 1 -5.689311e-06 -3.688797e-06 1 2.067008e-05 -4.711125e-05 1 -8.492453e-05 0.0001250004 1 -1.332974e-06 -1.340304e-05 0.9999641 -0.000717883 0.008450995 1 -3.713423e-07 -7.173516e-08 1 -2.88082e-05 0.0001915143 1 8.924848e-07 -2.457964e-05 1 -6.607135e-06 7.555664e-07 1 -5.284411e-06 -4.462908e-06 1 -1.638255e-05 1.308107e-05 1 -2.88646e-06 6.297711e-06 1 3.620385e-06 -2.486735e-05 0.9999863 -0.000499147 0.005219388 0.9999961 0.0009009413 0.002637349 0.9999956 0.001884011 0.002299146 0.9999925 1.225531e-05 0.003840454 0.9999812 -0.003314029 0.005171469 0.9999919 0.0007838114 -0.003964466 1 -4.870018e-06 1.466249e-05 1 -1.372701e-06 -5.406861e-06 1 3.124798e-06 -2.085538e-05 0.9993451 0.01870658 -0.03097619 0.9999094 -0.0131179 -0.00301784 0.8228505 -0.3187912 -0.470414 0.8152132 -0.5526068 -0.1733584 0.6380667 -0.7192746 -0.2747998 0.3229884 -0.7747371 -0.5435632 -0.5732566 -0.4886826 -0.6576977 -0.6270148 -0.4844367 -0.6100603 -0.9999378 0.004975713 0.00997801 -0.6403424 -0.6744788 -0.3674778 -0.5325189 -0.7586824 -0.3752658 0.02441558 -0.9996738 0.007485596 -0.01688644 -0.9986569 -0.04898132 0.01644296 -0.9776477 0.209606 -0.04635388 -0.9584977 0.2813067 0.03376422 -0.8491985 0.5269934 -0.02924042 -0.8045062 0.5932239 0.03293017 -0.6584155 0.7519339 -0.03508953 -0.5603237 0.8275301 0.02840131 -0.4594155 0.8877673 -0.02706168 -0.2502437 0.9678047 0.02536137 -0.1899062 0.9814746 -0.03086162 0.08647177 0.9957762 0.03329069 0.1598054 0.9865871 -0.03045762 0.3856072 0.9221602 0.03560276 0.4949554 0.8681887 -0.02120225 0.583221 0.8120368 0.03057343 0.7264411 0.6865482 -0.0190214 0.7865923 0.6171796 0.02114106 0.8694657 0.4935408 -0.02109459 0.9051735 0.4245186 0.03068872 0.9689267 0.245437 -0.03445863 0.9913123 0.1269354 0.03297785 0.9994532 0.002370274 -0.03707106 0.9768831 -0.210536 0.03392753 0.9527371 -0.3018959 -0.02671968 0.8512108 -0.5241433 0.03330039 0.8111485 -0.5838914 -0.03756626 0.6277881 -0.7774772 0.037933 0.5528629 -0.8324083 -0.02851166 0.3330253 -0.9424868 0.011325 0.2862777 -0.9580798 0.01129554 0.04102483 -0.9990943 -0.02513552 2.526244e-06 -0.9996841 0.02640631 -0.2640767 -0.9641401 -0.03055638 -0.3329615 -0.9424452 0.03817543 -0.5426745 -0.8390751 -0.03842073 -0.6277517 -0.7774649 0.04506672 -0.7930138 -0.6075345 -0.01893645 -0.8381466 -0.5451162 0.03531048 -0.9612328 -0.2734676 -0.01643001 -0.9427469 -0.333104 0.9959736 -0.0555184 0.0703878 0.5948491 -0.6132907 0.5196432 0.1381684 -0.8288206 0.5421862 0.858223 -0.4402343 0.2639073 0.5571384 -0.7856289 0.2690429 0.6863852 -0.6932806 0.2196302 -0.7451879 -0.5317957 0.4023534 -0.976544 -0.184728 0.1106231 -0.3960228 -0.7866303 0.4736863 -0.9786535 -0.1779477 0.1028201 -0.6565851 -0.741287 0.1392463 -0.5822077 -0.7925241 0.1814933 -0.004960984 0.0005770174 0.9999875 -0.02330557 0.001805994 0.9997268 1.271565e-06 0 1 -0.0001875211 0.001415945 0.999999 -0.02850206 0.03258107 0.9990625 0.01673045 -0.002881296 0.9998559 1.333024e-05 9.296802e-06 1 2.117793e-06 2.546161e-06 1 0 0 1 -3.556046e-06 -8.368824e-06 1 -2.821373e-06 3.552148e-06 1 -4.506393e-06 4.665968e-06 1 3.06463e-08 -4.054308e-06 1 2.898875e-06 6.99478e-07 1 2.27527e-06 -2.007659e-06 1 7.211613e-06 -6.363404e-06 1 9.131625e-07 -2.623326e-06 1 1.271567e-06 -7.036944e-07 1 4.278585e-07 4.749079e-06 1 3.197133e-06 -9.410994e-07 1 0 0 1 0 0 1 -2.097682e-05 0 1 1.397785e-05 5.569725e-06 1 0 0 1 2.232548e-06 1.027854e-05 1 1.271566e-06 1.265428e-06 1 1.073973e-06 2.725382e-06 1 1.066424e-06 -0.5446404 0.8386697 1.06755e-06 -0.5446404 0.8386697 0.6242691 0.4266222 0.6544323 0.4988381 0.4752995 0.7247419 1.740312e-06 -1.518614e-06 1 -6.402348e-06 5.586755e-06 1 0.00329509 0.00269428 0.9999909 -1.052728e-05 -5.155784e-06 1 2.266529e-05 -0 1 -1.420367e-05 -5.79302e-06 1 3.921343e-06 1.946915e-05 1 1.271566e-06 1.00591e-06 1 0.008178334 0.0009728798 0.9999661 0.006265354 0.001255995 0.9999796 2.258264e-06 9.210414e-07 1 7.38786e-07 -4.432113e-06 1 0.001107967 0.01033954 0.999946 0.001755705 0.005862625 0.9999813 0.007883027 0.6898913 0.7238702 1.818637e-06 0.5446389 0.8386707 1.706281e-06 0.5446384 0.838671 -1 -1.122445e-06 -1.728415e-06 -1 -5.705081e-05 2.359752e-06 -1 -4.876226e-05 6.725659e-05 -1 0.0001027483 7.294992e-05 -1 9.107008e-05 8.865574e-07 -0.007176356 0.8435304 0.5370334 0.003124715 0.7914495 0.6112264 1 1.212177e-06 1.866591e-06 1 -3.605209e-05 -1.34756e-06 1 -3.754745e-05 -2.843274e-05 1 -8.655707e-06 -2.878884e-05 1 9.881471e-06 3.286572e-05 1.130158e-06 0.5446389 0.8386707 1.210308e-06 0.5446392 0.8386704 -0.007910673 0.6904145 0.7233707 -0.007828581 0.001358543 0.9999684 -0.006750165 0.001508382 0.9999761 1.230101e-06 2.018061e-06 1 5.082487e-06 -9.144185e-07 1 4.506766e-06 1.372152e-06 1 1.055858e-06 -2.081143e-06 1 -0.003260918 0.003262344 0.9999893 -0.001567747 0.007198365 0.9999729 -0.001204316 0.01046293 0.9999446 0 0 1 0 0 1 0 0 1 1.271565e-06 -7.479868e-07 1 1.456939e-06 -2.111763e-06 1 -0.9995012 0.02223199 0.02242981 -0.8303335 0.4448916 0.3355857 -0.8246205 0.4533923 0.3382846 -0.5442044 0.7904338 0.281169 -0.5597342 0.7978374 -0.2239488 -0.695948 0.6665694 -0.2670982 -0.6921703 0.6429887 -0.3278198 -0.3992216 0.7367949 -0.5456697 0.9959726 0.03739531 -0.08148723 0.95895 0.271753 0.08102507 0.891528 0.444319 -0.0880824 0.725226 0.6807654 0.1029843 0.4939292 0.8645943 -0.09225319 0.3782399 0.9234201 0.06503841 -0.02090621 0.9944992 -0.102636 -0.2032428 0.972185 0.1163987 -0.4817291 0.8725209 -0.08151335 -0.6744385 0.7338706 0.08103455 -0.7980857 0.5960854 -0.0879852 -0.9491154 0.2807517 0.1426831 -0.9842562 0.02389142 -0.1751256 -0.9200651 -0.3504452 0.1751242 -0.7808022 -0.5997389 -0.1751032 -0.4956971 -0.8506557 0.1751263 -0.258562 -0.9554067 -0.1426317 0.1498176 -0.9804168 0.1278186 0.2471541 -0.9688479 -0.01576978 0.601724 -0.7960424 -0.06515078 0.7128028 -0.6916412 0.1163813 0.8977706 -0.4293079 -0.09850213 0.9681786 -0.2300529 0.098519 -0.001893686 0.9999864 0.004867932 0.001244701 0.9999518 0.009734423 0.002234614 0.99735 -0.07271916 -0.003140222 0.9989516 -0.04567155 -0.001091103 0.9999972 0.002087409 0 0.9999771 -0.006757418 -0.04725057 0.9987076 0.0187205 -0.002405426 0.9999971 -0.0001158688 -0.001672473 0.9999986 -0.000115871 -0.02325927 0.9989362 0.03981605 0.02645134 0.9986239 -0.04528344 0.001655809 0.9999985 0.0004753578 0.004319869 0.9999906 0.0004753495 -0.04290231 0.9988741 0.02024751 0.9818234 0.1076494 0.1563148 0.8483052 0.511166 -0.1381578 0.6968086 0.7010667 0.1515364 0.4397403 0.8857515 -0.1485688 0.1316798 0.9801009 0.1485347 -0.1847395 0.9710275 -0.1515817 -0.3623589 0.9297668 0.06503687 -0.7172681 0.6967 0.01164871 -0.7430713 0.6667379 -0.0574957 -0.9764795 0.215542 0.005412513 -0.9816191 0.1136418 0.1533287 -0.976687 -0.1779682 -0.1200412 -0.805715 -0.5897357 0.05509057 -0.7743855 -0.619531 0.1284858 -0.4881576 -0.8644001 -0.1204762 -0.1839975 -0.9672011 0.1751196 0.1012951 -0.9793242 -0.1751097 0.43971 -0.885772 0.1485361 0.6967947 -0.7010682 -0.1515931 0.8483158 -0.5111551 0.1381332 0.9818207 -0.1076312 -0.1563445 0.9943489 0.03732299 -0.09938321 0.905078 0.420528 0.06316619 0.8975527 0.4322856 0.08676541 0.5858619 0.8024198 -0.1135263 0.4527718 0.8843762 0.113474 -0.01809964 0.9960619 -0.08679261 -0.09426451 0.9945855 0.04374922 -0.6415371 0.7656001 -0.047819 -0.6779338 0.7335675 0.0477969 -0.9800905 0.1926965 -0.04786042 -0.9844746 0.1751025 -0.01219961 -0.9450834 -0.3229369 0.05028901 -0.8766592 -0.4621555 -0.1337195 -0.7441958 -0.6615469 0.09234963 -0.4194044 -0.904646 -0.07560265 -0.3231553 -0.9433185 0.07563604 0.1051735 -0.9891438 -0.1026304 0.3122914 -0.9378275 0.1515047 0.5727631 -0.8103903 -0.1233293 0.8036278 -0.588567 0.08815467 0.8992367 -0.4299019 -0.08097962 0.9793178 -0.1746636 0.1021246 -1 -2.243448e-05 -4.677317e-06 -1 3.176233e-06 -1.767093e-05 -1 -8.753734e-05 -4.658448e-05 -1 -8.109895e-05 -5.122273e-05 -1 -4.913226e-06 5.717662e-06 -1 2.338941e-05 -2.721893e-05 -1 2.951706e-05 -2.744847e-05 -1 3.044834e-05 -1.914225e-05 -1 4.448417e-06 4.699785e-06 -1 1.585573e-05 1.67517e-05 -1 2.053293e-05 -3.470008e-06 -1 -5.959642e-05 -3.982711e-05 -1 -4.175762e-05 1.237521e-05 -1 -1.539289e-05 1.544962e-06 -1 -6.453982e-05 -1.199648e-05 -1 -3.455764e-05 3.395972e-05 -1 -2.256161e-05 1.179818e-05 -1 1.733628e-05 7.843371e-07 -1 1.163588e-05 -1.961189e-05 -1 -2.226293e-05 -1.03256e-05 -1 -1.209453e-05 -1.69906e-05 -1 -9.68225e-06 -7.531736e-06 -1 -1.750785e-05 -6.094416e-06 -1 -8.476077e-06 7.92245e-06 -1 1.501841e-05 -4.914198e-06 -1 3.045398e-05 -9.929897e-05 -1 9.481679e-05 -9.942002e-05 -1 7.757766e-05 2.611409e-05 -1 9.541925e-06 9.906467e-06 -1 -1.745407e-06 -3.126864e-05 -1 -4.386109e-05 2.268282e-05 -1 1.255217e-05 5.058818e-05 -1 -1.138701e-05 -4.589231e-05 -1 -4.252943e-05 -4.162252e-05 -1 -1.365457e-05 -1.33634e-05 -1 -4.939848e-05 1.749153e-05 -1 -2.801025e-05 2.501948e-05 -1 -3.156575e-05 3.656302e-05 -1 1.607197e-05 2.342261e-05 -1 1.211786e-06 -1.996139e-05 -1 -3.254227e-06 -1.218901e-05 0.8280786 0.3170068 0.4623769 0.7138509 0.5805928 0.3915722 0.8261487 0.444515 0.3462438 0.4717775 0.8423718 0.2604533 0.526395 0.8074373 0.2663705 -1 -2.082757e-05 -9.353917e-06 -1 1.616475e-05 7.259787e-06 -1 1.669924e-05 -5.676583e-06 -1 -1.759311e-05 -7.750781e-06 -1 -1.247884e-05 4.445531e-06 -1 -1.440031e-05 5.649154e-06 -1 8.668397e-06 3.552419e-05 -1 1.789124e-05 1.615876e-05 -1 -1.947642e-05 -1.759044e-05 -1 -2.323739e-05 -1.329306e-05 -1 7.742258e-05 4.428995e-05 -1 1.808352e-05 0.0001747931 -0.9999999 8.957404e-05 0.0001990992 -1 0.0001100635 5.020388e-05 -1 2.217156e-05 4.985179e-05 -1 -9.618159e-06 1.565645e-06 -1 -5.905169e-06 -1.883206e-06 -1 -3.238171e-05 -1.032679e-05 -1 -3.328541e-05 6.848583e-06 -1 3.340637e-05 -6.873473e-06 -1 2.584412e-05 -2.222374e-05 -1 8.521818e-06 -7.328038e-06 -1 -1.219974e-05 -2.94914e-05 -0.06513238 0.0949967 -0.9933445 0.1515287 0.2722235 -0.9502281 -0.1232995 0.5378765 -0.833958 0.08812471 0.777908 -0.6221681 -0.1057461 0.8906813 -0.442159 0.09233844 0.9648235 -0.2461488 -0.07563621 0.9843636 0.1590827 0.03124716 0.9723369 0.231483 -0.03487492 0.7461175 0.6649002 -0.00872554 0.7363072 0.6765912 0.05027077 0.3425061 0.9381697 -0.1015481 0.2189486 0.9704378 0.0814665 -0.04721685 0.9955571 -0.09849164 -0.311337 0.9451817 0.06923719 -0.4774452 0.8759294 -0.04578473 -0.7177505 0.6947935 0.04574948 -0.7803454 0.623673 -0.06916578 -0.9295095 0.3622544 0.06922132 -0.9729669 0.2203267 -0.06589185 -0.9889424 -0.1328574 0.03987565 -0.9781638 -0.2039738 -0.04374799 -0.727845 -0.6843448 -0.01943974 -0.7186116 -0.6951399 0.04930651 -0.3389811 -0.9395002 -0.01575685 -0.297513 -0.9545877 0.02218082 -0.1506606 -0.9883367 -0.01699146 0.2620003 -0.9649182 0.06502333 0.3261134 -0.9430918 -0.1026237 0.6727155 -0.7327498 0.07946389 0.7785088 -0.6225829 -0.06587762 0.9558806 -0.2862736 0.03987176 0.9753471 -0.2170449 -0.03987393 0.9534273 0.2989756 0.1100904 0.9129795 0.392872 -0.1385626 0.6984145 0.7021522 0.1743454 0.4855028 0.8566743 -0.1192051 0.08176896 0.9894968 -0.01517356 0.01041387 0.9998307 0.04490202 -0.3770276 0.925113 0.06513224 -0.9732351 0.220389 0.01575166 -0.9846447 -0.1738589 -0.1278293 -0.955094 -0.2673109 0.1614898 -0.7424256 -0.6501732 -0.1426792 -0.5961374 -0.7901031 0.05507893 -0.1316868 -0.98976 0.1200622 -0.09453487 -0.9882552 -0.1532903 0.1964587 -0.9684555 -0.005320817 0.2975936 -0.9546778 0.05748193 0.7273429 -0.6838626 -0.01170113 0.7550204 -0.6555967 -0.06515662 0.9571233 -0.2822582 0.07938749 0.9832779 -0.1638974 -0.05551959 0.9803332 0.1893788 0.02782077 0.966103 0.2566534 -0.02780445 0.7808732 0.6240705 0.09235831 0.7122267 0.695847 -0.1204378 0.4509994 0.8843609 0.1485693 0.1731645 0.9736227 -0.1515628 -0.1433539 0.9779971 0.1380988 -0.3780797 0.9154149 -0.1381722 -0.7084094 0.6921449 0.07938514 -0.8284659 0.5543844 0.02371396 -0.5036468 -0.8635841 -0.06512031 -0.5409526 -0.8385282 0.8186795 0.1351089 -0.5581303 0.6480839 0.2170311 -0.7299896 0.6470395 0.4210452 -0.6356578 0.8547119 0.308364 -0.4175874 0.4553801 0.7237536 -0.5184686 0.8515057 0.4541947 -0.2620026 0.4309213 0.8596591 -0.2743955 0.8738074 0.4804237 -0.07519002 0.4448638 0.8955921 0.003301312 0.8058633 0.5781866 0.1276113 0.6806106 0.7087823 0.1854641 0.6806638 0.6399211 0.3566481 0.7942362 0.5204187 0.3136134 0.5647461 0.5971243 0.5696529 0.7940145 0.4045195 0.4537676 0.5058569 0.4286964 0.7485508 0.7215427 0.3187411 0.6146383 0.7919037 0.1187917 0.5989801 0.6268297 0.1252662 0.7690207 0.7551492 -0.1107177 0.6461355 0.6433527 -0.147231 0.7512792 0.7675993 -0.3028937 0.5648421 0.8339683 -0.2499762 0.4919439 0.4333199 -0.5946058 0.6772577 0.8707996 -0.3858063 0.3047318 0.4395961 -0.7639832 0.4723187 0.7972769 -0.5786583 0.1717679 0.6403112 -0.767806 -0.02180596 0.7493518 -0.6384329 -0.1757138 0.6704097 -0.712228 -0.2080436 0.802388 -0.4859307 -0.3464748 0.6247917 -0.6203203 -0.4741708 0.5415694 -0.4555914 -0.7064977 0.86936 -0.2318292 -0.436427 0.3826641 -0.2444469 -0.8909624 0.849955 -0.05214085 -0.5242689 0.4792351 0.03539377 -0.8769726 0.9840546 -0.08820572 0.1544553 0.997811 0.03278608 -0.05743057 0.8249641 0.5650533 0.01220227 0.846732 0.5268002 -0.07434058 0.5266649 0.8427324 0.1114731 0.3643384 0.9245682 -0.1114963 -0.07995839 0.9940225 0.07433627 -0.03625959 0.9992679 -0.01220624 -0.5669535 0.8217424 0.0574724 -0.6560835 0.7387111 -0.1544681 -0.9198033 0.3646866 0.1447951 -0.9883707 0.0816561 -0.1282791 -0.9948356 -0.0779485 0.06501052 -0.8786018 -0.4663967 -0.1026307 -0.7986588 -0.5965167 0.07944758 -0.5416028 -0.8387975 -0.05554444 -0.4831549 -0.8750929 0.02781802 -0.08969478 -0.9955805 -0.02782739 0.009546088 -0.9956912 0.09223837 0.3263498 -0.9375352 -0.1205133 0.6246058 -0.7546326 0.2009907 0.8009902 -0.5701883 -0.1824829 0.9965985 -0.03277101 0.07561352 0.902799 0.4148196 -0.1134833 0.8471696 0.5269424 0.06808309 0.5299015 0.8479801 0.01158048 0.4691253 0.8768054 -0.1055167 -0.09621596 0.9885195 0.1164965 -0.2134184 0.9690619 -0.1239823 -0.7692135 0.6268454 0.1239976 -0.8393618 0.5309418 -0.116501 -0.995519 0.006173526 0.09436016 -0.9892431 -0.1170556 -0.08772576 -0.8431842 -0.5304441 0.08757587 -0.7707006 -0.6301748 -0.09434205 -0.3768987 -0.9214371 0.09434478 -0.2860755 -0.9569336 -0.04938383 0.16439 -0.9862056 0.01935383 0.2073011 -0.9736128 0.09541715 0.6973658 -0.7016546 -0.1461567 0.8021801 -0.5839267 0.1246469 0.987802 -0.136122 -0.07561734 0.9190918 0.377421 0.1132409 0.8485249 0.5083673 -0.146861 0.5728465 0.8103272 0.123356 0.2839364 0.9423051 -0.1773168 0.07456368 0.988018 0.1351322 -0.4503802 0.8877193 -0.09545761 -0.5645635 0.8138427 0.1375804 -0.840567 0.5233967 -0.1396529 -0.979309 0.1574861 0.1270912 -0.9783902 0.2031325 0.03859759 -0.9402264 -0.3387611 -0.03486221 -0.9080803 -0.4077757 0.09544245 -0.5139911 -0.843236 -0.1573728 -0.403016 -0.9098548 0.09870315 0.1482253 -0.9888321 0.015497 0.2120449 -0.9721944 -0.09937375 0.6100054 -0.7887648 0.0757864 0.704918 -0.7052261 -0.07580908 0.9373921 -0.3338138 0.09931999 0.9696502 -0.2166766 -0.1132686 -1 3.821448e-05 7.7462e-07 -1 1.544002e-05 5.207744e-06 -7.051097e-06 2.76404e-05 -1 7.53908e-06 1.562238e-05 -1 -2.102881e-06 2.026804e-06 -1 0 0 -1 0 0 -1 1.191851e-06 8.720085e-06 -1 2.971015e-05 -7.211717e-07 -1 1.610723e-05 -1.233445e-05 -1 1.57286e-05 -1.174759e-05 -1 1.293721e-05 -3.077058e-05 -1 -7.981544e-06 -2.106587e-05 -1 0 -0 -1 -2.830408e-06 2.048651e-07 -1 -3.885022e-06 -5.528595e-06 -1 -7.827635e-06 -3.90113e-06 -1 -3.121179e-06 2.367211e-06 -1 -0 0 -1 -2.91924e-06 -2.562667e-06 -1 -8.150587e-06 3.897556e-06 -1 -1.12486e-05 2.635483e-06 -1 -1.36627e-05 1.201747e-05 -1 1 3.130238e-05 -7.704562e-06 1 3.355619e-05 -8.453473e-06 4.730774e-07 6.761965e-06 -1 0 0 -1 -0 -0 -1 -5.510767e-06 -9.196347e-06 -1 -3.036453e-05 3.328684e-06 -1 -1.356279e-05 8.667002e-06 -1 -1.920232e-05 1.932009e-05 -1 1.10187e-06 1.815343e-05 -1 -2.374893e-06 1.081966e-06 -1 0 0 -1 0 0 -1 -4.489373e-06 1.110191e-06 -1 -6.016411e-06 -2.485096e-06 -1 -8.383168e-06 -1.527549e-06 -1 -6.988542e-06 1.242772e-06 -1 -7.527556e-06 1.661586e-06 -1 -7.144392e-06 2.972011e-06 -1 0 0 -1 0 -0 -1 -2.69561e-06 4.965517e-06 -1 -4.262804e-06 5.480576e-06 -1 -2.612247e-06 -1.502401e-06 -1 0 0 -1 0 0 -1 -3.846008e-06 -2.21107e-06 -1 -3.747487e-06 4.205891e-07 -1 0 0 -1 0 0 -1 0 -0 -1 0 0 -1 8.448429e-06 5.606506e-06 -1 1.942731e-05 -2.318424e-05 -1 -8.128065e-06 -1.430642e-05 -1 -2.315565e-06 3.535339e-06 -1 -0 0 -1 -5.486916e-06 -3.134562e-06 -1 -5.496442e-06 -1.011219e-05 -1 -2.241774e-05 -1.041599e-05 -1 -2.680422e-05 -1.006099e-06 -1 -1.091317e-05 7.307848e-06 -1 -8.150423e-06 3.896507e-06 -1 0.05881323 0.2749577 -0.9596558 -0.02466341 0.3921187 -0.919584 0.004055335 0.7911066 -0.6116649 0.01596181 0.8002086 -0.5995093 -0.01594625 0.9925394 -0.1208775 -0.003982031 0.9943867 -0.1057315 0.0262942 0.9069198 0.4204821 -0.04845644 0.8629838 0.5029024 0.05352998 0.438724 0.8970261 -0.05703411 0.328368 0.9428264 0.05202681 -0.2996208 0.9526387 -0.04563742 -0.4137405 0.9092503 0.04016808 -0.7834048 0.6202126 -0.04329102 -0.8539407 0.5185664 0.04844698 -0.9986609 0.01814663 -0.04844313 -0.9935245 -0.1027738 0.04328607 -0.8069167 -0.5890771 -0.05882896 -0.7080238 -0.7037339 0.06573033 -0.3631668 -0.9294027 -0.06574161 -0.1362427 -0.9884918 0.06572619 0.3013048 -0.9512599 -0.07463706 0.4884979 -0.8693671 0.04978548 0.7993158 -0.5988454 -0.04979335 0.8945815 -0.4441223 0.07459038 0.9962084 -0.04477768 -0.08453812 0.9788675 0.1862034 0.06250804 0.771768 0.6328245 -0.05883919 0.6457912 0.7612435 0.05671565 0.3123267 0.9482802 -0.06992177 0.0242272 0.9972582 0.04711509 -0.1898865 0.980675 -0.03981338 -0.6086463 0.7924421 0.04379056 -0.6894932 0.7229671 -0.06737761 -0.969943 0.2338178 0.0809301 -0.9956214 0.04677973 -0.08093053 -0.8879715 -0.4527216 0.06739802 -0.7875141 -0.6126001 -0.05460783 -0.2763948 -0.9594915 -0.03469427 -0.2577904 -0.9655777 -0.05732477 0.1193317 -0.9911981 0.04360281 0.2457585 -0.9683499 0.007056501 0.7072825 -0.7068956 -0.04556837 0.7515203 -0.6581343 0.03474651 0.9616445 -0.2720894 -0.03473788 0.9883524 -0.1481648 0.03473869 0.9722218 0.2314695 -0.03473226 0.9351032 0.3526693 0.03476951 0.7358955 0.6762018 -0.03475058 0.6443232 0.7639632 0.03473873 0.3126705 0.9492263 -0.03474304 0.1899538 0.9811782 0.04021974 -0.2198361 0.9747074 -0.04328889 -0.33866 0.9399125 0.04331302 -0.7458451 0.6647097 -0.02260946 -0.8077696 0.5890646 0.008834135 -0.9847782 0.1735912 0.04378876 -0.9906323 0.1293451 -0.06738379 -0.9015319 -0.4274338 0.05729978 -0.8228972 -0.5652937 -0.03462282 -0.4584653 -0.8880376 0.03465837 -0.3637538 -0.9308501 1 -0.0001069627 0.0001581452 1 -3.778351e-05 2.788309e-07 1 -1.050681e-05 1.36138e-05 1 6.065236e-06 -7.858799e-06 1 3.619055e-05 1.356162e-05 1 2.790234e-05 2.376615e-05 1 7.01998e-05 0.0001145716 1 7.542444e-05 0.0001049414 1 -1.448331e-05 1.207326e-05 1 -1.230475e-05 1.025721e-05 1 -1.44796e-05 -2.340445e-05 1 4.957628e-05 9.084311e-06 1 -0.0001097471 5.653664e-05 1 -0.0001023141 6.636674e-05 1 -2.058317e-05 -7.251243e-06 1 -2.133929e-05 -8.164489e-06 1 1.361414e-05 -1.811882e-05 1 -7.175605e-07 -5.363255e-05 1 -3.613762e-05 -5.043904e-05 1 -4.191187e-05 7.688146e-05 1 2.87634e-05 -7.436046e-06 1 2.28139e-05 -1.642388e-05 1 -0.0001710961 0.0001231732 1 3.990165e-05 -0.0001003271 1 -6.526585e-05 0.0001068111 1 -0.0001619003 -2.564708e-05 1 3.811486e-06 6.626596e-06 1 -1.844584e-05 -3.206969e-05 1 -5.638112e-06 -3.692512e-05 1 5.042632e-05 7.385682e-05 1 1.944653e-06 5.95584e-05 1 6.964779e-06 4.568911e-05 1 -1.132575e-05 2.312958e-05 1 -2.074759e-05 3.29743e-05 1 -2.199756e-05 3.040068e-05 1 0.0001158463 -1.065186e-05 1 6.897365e-05 -7.265624e-05 1 -1.851274e-06 -2.24766e-05 1 -2.725712e-06 -3.309324e-05 1 6.613039e-05 2.845713e-05 1 -3.190476e-05 6.687671e-05 1 -4.592029e-05 -8.102677e-05 1 8.163267e-06 -5.650625e-05 1 -1.84041e-05 -1.359182e-05 1 8.132008e-06 6.00566e-06 1 9.504286e-05 -7.342088e-05 1 -3.73621e-05 4.86445e-05 1 -0.0001570788 5.741561e-05 1 -0.0001449298 2.046561e-05 1 -2.709446e-05 5.415483e-05 1 -4.037227e-06 -1.049472e-05 1 4.144225e-05 3.499508e-05 1 3.589666e-05 5.564326e-05 1 5.640032e-06 3.585192e-05 1 1.817574e-05 -1.765031e-06 1 3.06462e-05 -2.976027e-06 1 3.126733e-05 1.35781e-06 1 -2.924712e-05 1.696009e-05 1 -1.498857e-05 -2.500526e-05 1 1.338847e-05 -1.459816e-05 1 1.118278e-05 -1.219318e-05 1 2.463307e-05 -7.954075e-07 1 1.374208e-05 3.13164e-05 1 -1.389268e-05 1.841997e-05 1 8.491795e-06 -1.125906e-05 1 2.867402e-05 2.172567e-05 1 -3.728733e-05 6.346273e-05 0.9999996 4.923488e-05 0.000833658 0.9999998 1.436838e-05 0.0006699315 1 3.955323e-05 5.886739e-05 1 -8.525901e-05 2.129609e-05 0.9999999 -6.753153e-05 0.0003208517 0.9999997 -0.0003230062 0.0006596848 1 1.51683e-05 -4.59375e-05 1 8.55632e-05 0.0002047194 1 -6.599694e-06 1.349399e-05 1 -6.138105e-05 3.337895e-05 1 -8.947543e-06 9.733393e-06 1 -3.962249e-05 1.731347e-06 1 0.0001705076 0.0001107447 0.9999999 0.0003901422 4.010568e-05 1 1.707422e-05 0.0001560223 1 5.9826e-05 -0.0001221795 0.9999989 0.001051236 0.0009978953 1 9.67384e-05 -2.347942e-05 0.9999999 0.0004024075 0.0001200139 0.9958616 -0.09088045 0.0006103129 0.9817821 -0.1876225 0.03002883 0.9911718 -0.1244665 0.04567964 1 6.200426e-05 -1.264049e-05 1 5.731164e-06 1.609813e-05 1 -3.778844e-06 -8.822993e-06 1 4.586343e-05 6.054561e-06 1 8.857406e-05 0.0001558847 1 9.325245e-05 -2.286681e-05 1 2.401373e-06 -4.095108e-05 1 3.434003e-05 -3.218947e-05 0.9999999 9.704519e-05 0.0002265849 1 2.519426e-05 -1.156735e-05 0.9999849 0.0007087448 0.005450683 0.999991 -0.0003335915 0.004237934 1 -4.633364e-05 1.39474e-05 0.9999933 -0.0001029332 0.003675707 1 1.193887e-05 1.790097e-05 1 -3.4451e-05 -5.078706e-06 1 -2.618938e-06 -4.373254e-06 1 4.076747e-07 -1.185446e-05 1 -2.720587e-06 6.430813e-06 1 -5.391146e-06 -3.898554e-06 1 -1.653121e-05 -1.073171e-05 1 -0.0001029541 -7.15372e-06 1 -2.162058e-06 1.096528e-06 1 -8.472225e-05 -5.246441e-05 1 -3.814157e-05 -0.000106484 1 -8.852553e-05 -1.588098e-05 0.9999994 -0.001151545 -0.0001711112 1 -4.588901e-05 -1.25376e-05 0.9999996 -0.0008430055 5.634288e-05 0.9999998 -0.0007144967 1.752586e-05 1 7.540588e-06 4.925797e-06 1 -6.925509e-05 0.0001811228 1 3.729904e-05 3.446396e-05 1 2.150435e-05 3.474629e-05 1 -0.0001732918 8.51911e-05 1 -0.0001638858 0.0001022383 1 -2.207957e-05 4.853967e-05 1 -3.336908e-05 2.233701e-05 1 2.945197e-05 -2.163605e-05 1 1.712596e-06 -5.738564e-06 1 -3.977566e-05 1.826206e-05 1 1.158811e-05 -8.085736e-07 1 -3.629287e-06 -1.549136e-05 1 0 0 1 -1.3512e-05 5.648771e-05 1 -3.427237e-06 2.449389e-05 1 0 0 1 1.356293e-05 -0.0001749763 1 0 0 1 2.154071e-05 -2.151404e-05 1 -3.70356e-06 -3.924794e-06 1 2.836823e-06 1.802344e-05 1 3.351759e-06 1.696989e-05 1 0 -0 1 0.0001481685 2.877803e-05 0.9999999 0.0003322265 3.905453e-05 1 0 0 1 -0 0 1 0 0 1 0 0 1 -9.441976e-05 1.382938e-05 1 6.919364e-05 0.0001534989 1 0 -0 0.9999998 -6.225879e-05 -0.0004596416 1 5.585235e-06 2.516083e-06 1 1.191759e-05 -1.525656e-05 1 -1.67817e-06 -1.583397e-05 1 8.134629e-06 -4.713103e-05 1 -3.796105e-06 -1.925761e-06 1 -7.967706e-06 -1.252213e-06 1 0 0 1 0 -0 1 0 0 1 7.972378e-07 4.116018e-05 1 -5.618696e-05 1.213066e-05 1 6.171671e-06 -1.332452e-06 1 -0.0001384888 -1.332452e-06 1 -0.0001836853 -1.767305e-06 1 -2.016008e-05 1.235448e-05 1 4.211999e-05 1.908597e-05 1 6.897855e-05 -4.053898e-06 1 -1.770315e-05 0.0003485099 1 0 -0 1 -1.287493e-06 -2.418212e-05 1 -1.077006e-05 -9.533062e-06 1 3.560541e-06 3.151593e-06 1 0.0001031546 -1.252213e-06 1 -0.0001021845 9.97614e-06 1 9.638557e-06 -1.013024e-05 1 6.89511e-06 5.551271e-06 1 8.783732e-06 -2.66017e-05 1 -2.75718e-05 3.473745e-06 1 2.98875e-05 2.218582e-06 1 -1.124864e-05 4.827629e-06 1 -2.214786e-05 -0.0001583514 1 3.718885e-06 2.658905e-05 1 4.844355e-05 2.331702e-05 1 7.769668e-05 3.739724e-05 1 -0.0001525159 1.261293e-05 1 2.783048e-05 9.187023e-06 1 -2.150723e-07 1.577455e-05 -8.554184e-06 -9.361201e-06 1 2.77829e-07 -2.897856e-05 1 1.401419e-05 -8.005794e-06 1 4.917338e-06 -2.809095e-06 1 3.042106e-06 2.441817e-06 1 0 0 1 0 0 1 1.95684e-06 -2.185759e-06 1 1.678156e-06 -2.547306e-06 1 0 0 1 0 0 1 0 0 1 1.463223e-06 3.050154e-06 1 5.741109e-07 3.674639e-06 1 -0 0 1 0 0 1 -2.221542e-06 -6.079902e-06 1 -1.34036e-05 -2.383738e-06 1 -1.340491e-05 -2.401061e-06 1 0 0 1 1.013953e-06 -5.503024e-06 1 0 0 1 -0 0 1 0 -0 1 -0 -0 1 4.567489e-06 3.334503e-07 1 4.253038e-06 3.574855e-06 1 0 0 1 0 -0 1 0 0 1 1.487109e-05 -2.43401e-06 1 1.536152e-05 -3.251458e-06 1 1.057048e-05 -5.469065e-06 1 3.393907e-06 -1.755974e-06 1 3.678728e-06 -1.303146e-06 1 0 0 1 0 0 1 0 0 1 2.500983e-06 -5.081599e-06 1 3.683555e-06 -4.762785e-07 1 -0 0 1 2.563253e-06 3.152181e-07 1 8.569312e-06 -2.24836e-05 1 1.060728e-05 -2.229797e-05 1 4.700599e-06 -6.322497e-06 1 1.019222e-05 6.721244e-06 1 -1.867624e-05 3.877544e-06 1 -8.667589e-06 -1.109008e-05 1 2.221149e-06 -1.451501e-06 1 0 -0 1 -0 -0 1 3.746346e-06 2.373111e-07 1 2.766404e-06 1.783934e-06 1 0 0 1 0 -0 1 -4.55668e-06 -8.574711e-06 1 2.577514e-05 -9.178759e-06 1 1.423738e-05 1.272321e-05 1 0 0 1 0 0 1 0 0 1 0.9840328 0.1754777 -0.02978179 0.9524618 0.3017031 0.04232937 0.8054947 0.5900095 -0.05538201 0.5730603 0.8154956 0.08104794 0.3149218 0.9456515 -0.08103996 -0.09644749 0.9909467 0.09339423 -0.3233158 0.9440076 -0.06570007 -0.7814687 0.6229762 0.0347459 -0.7927659 0.6070769 0.0545885 -0.9973459 -0.004482643 -0.07267074 -0.9898906 -0.1344046 0.04529908 -0.7443128 -0.6678135 0.004849477 -0.6776072 -0.7310631 -0.07997042 -0.1563545 -0.9833048 0.09308539 0.04479096 -0.9964871 -0.07076137 0.5770398 -0.8161712 0.02982504 0.5904368 -0.8058229 0.04509789 0.9124967 -0.4057446 -0.05216241 0.9648393 -0.257617 0.05213908 0.9949068 0.09087853 -0.04360526 0.9743324 0.2176948 0.05731887 0.7565218 0.6530495 -0.03465626 0.6615367 0.7479086 0.0547902 0.2859939 0.954828 -0.08068985 -0.03776157 0.9945887 0.09678508 -0.3490478 0.9335946 -0.0810349 -0.6764608 0.7320055 0.08104765 -0.844629 0.5313001 -0.06574133 -0.9833333 0.1748661 0.04977281 -0.9987401 -0.006136202 -0.04980492 -0.9222579 -0.3809414 0.06575684 -0.7904301 -0.6071715 -0.08101206 -0.5018477 -0.8611501 0.08105087 -0.2335849 -0.9689529 -0.08104528 0.1801494 -0.9791955 0.09339359 0.4268411 -0.9003683 -0.08451904 0.8399428 -0.536747 0.0799927 0.888564 -0.4587272 -0.004830152 0.9972994 0.03274997 -0.06573699 0.8078648 0.5880298 0.03969129 0.8468585 0.5303319 -0.03973359 0.4022544 0.913166 0.06572074 0.1801488 0.9791951 -0.09339975 -0.233585 0.9689526 0.08104907 -0.4782981 0.8757328 -0.06575029 -0.7731332 0.6322903 0.04973951 -0.874908 0.4817173 -0.04984376 -0.9874165 0.1476123 0.05673888 -0.9913978 -0.1172875 -0.0580855 -0.9345669 -0.3529044 0.04520126 -0.7730325 -0.6321027 -0.05354315 -0.6194225 -0.7824755 0.06362193 -0.2337432 -0.9696161 -0.07217101 -0.01810718 -0.9972282 0.07216675 0.4023208 -0.9132854 -0.06362136 0.6124485 -0.787409 0.06995648 0.8300663 -0.5534416 -0.06849968 0.9757611 -0.1979267 0.09335557 -0.0008228947 0.001079207 -0.999999 -0.02002268 0.07991859 -0.9966003 0.02149523 0.7639235 -0.6449487 -0.02011146 0.9093978 -0.4154409 0.01960305 0.9997162 -0.01353307 -0.02473948 0.9286486 0.3701349 0.02620219 0.630926 0.7754004 -0.02178055 0.3572452 0.9337566 0.02178771 -0.1942347 0.9807131 -0.01323024 -0.4140164 0.9101733 0.009391067 -0.8973809 0.4411567 -0.01627306 -0.849069 0.5280312 0.02318303 -0.9882571 -0.1510316 -0.03215878 -0.8367698 -0.5466096 0.01000318 -0.674343 -0.7383505 0.03280222 0.9162731 0.3992086 -0.02047323 0.8101562 0.5858564 0.01039952 -0.03436781 0.9993551 -0.00117452 0.003876819 0.9999918 0.007870049 -0.880273 0.4744021 0.000692254 -0.8918551 0.4523208 -0.01257977 -0.9041682 -0.4269911 0.009106607 -0.8567117 -0.515715 -0.000390704 -0.2765682 -0.9609943 0.006662538 -0.3044151 -0.9525161 -0.01999336 0.3895447 -0.9207905 0.03817959 0.7134898 -0.6996245 -0.02690556 0.9186116 -0.3942445 0.01947274 0.1640771 -0.9862553 -0.03688512 0.4731338 -0.8802181 0.03620846 0.8758808 -0.4811671 -0.03102434 0.9919722 0.1225911 -0.0004450887 0.9646029 0.2637064 0.007133319 0.4096727 0.9122047 0.0001840715 0.3856269 0.9226547 -0.01226441 -0.4393188 0.8982475 0.03606994 -0.6486591 0.7602238 -0.02318421 -0.918348 0.3950942 0.0162825 -0.9547088 -0.297096 -0.001546667 -0.9730713 -0.2304988 0.005717271 -0.5373009 -0.8433712 -0.01489971 -0.4329947 -0.9012733 0.009436318 0.5631791 -0.826281 -0.01824963 0.4788451 -0.8777097 0.02337745 0.9481196 -0.317053 -0.0313861 0.9994128 -0.01374549 0.02562342 0.7529846 0.6575391 -0.02668439 0.5755299 0.8173453 0.03671483 -0.1950352 0.9801087 -0.04230279 -0.5558036 0.8302366 0.03114821 -0.9259915 0.3762572 -0.03547951 -0.9907744 -0.1307949 0.01576539 -0.9079955 -0.4186832 0.006287924 -0.4350672 -0.900376 -0.0202563 -0.3353244 -0.9418849 0.2031827 -0.9613821 0.1856375 0.06169267 -0.498729 0.8645596 0.04093698 0.4442095 -0.8949872 -0.1733572 0.3749326 -0.9106991 0.1386601 0.6944848 -0.7060199 -0.1480123 0.8432419 -0.5167547 0.09110529 0.9139529 -0.3954615 -0.1698317 0.9811866 -0.09181444 0.1701096 0.9823949 0.07722009 -0.1182943 0.8707973 0.4771986 0.06052177 0.8407032 0.5381032 -0.04105546 0.5288475 0.8477233 0.09396758 0.4727879 0.8761516 -0.1270608 0.1342396 0.9827692 0.1513983 0.009134167 0.9884307 -0.1218759 -0.4396157 0.8898789 -0.05468645 -0.8552058 0.5153955 -0.1818937 -0.8201509 0.5424639 -0.2125847 -0.9738501 -0.08014794 0.1162111 -0.9613893 -0.2494503 -0.1532439 -0.7889902 -0.594988 -0.00267383 -0.7643412 -0.6448064 -0.0718576 0.06667101 -0.9951841 0.0891548 -0.029972 -0.9955668 -0.1069543 -0.330492 -0.9377291 0.09304011 -0.4161604 -0.9045186 0.02520855 -0.7588996 0.6507195 -0.01218965 -0.74659 0.6651728 0.05743947 -0.9855627 0.1592698 -0.1054998 -0.9922057 0.06631479 0.09433706 -0.8916876 -0.4427117 -0.1495112 -0.8002627 -0.5807115 0.1736161 -0.5055506 -0.8451485 -0.1564097 -0.2237999 -0.9620029 0.1711188 0.1056402 -0.9795706 -0.1992546 0.4147761 -0.8878392 0.1382536 0.6576948 -0.7404887 -0.02991359 0.9128435 -0.4072123 -0.1948555 0.9301339 -0.3112587 0.1833179 0.9786682 0.09275287 -0.1727558 0.8783997 0.4456113 0.07932885 0.7726912 0.6298056 -0.05559277 0.505537 0.8610121 0.06503188 0.4170752 0.9065424 -0.09501046 0.0404468 0.9946542 0.1436166 -0.1913584 0.9709564 -0.06525617 -0.3737363 0.9252366 0.1841688 0.7230231 0.6658224 -0.1613241 0.550401 0.8191662 0.1084296 0.1740764 0.9787443 -0.07581627 0.02138088 0.9968925 0.07584611 -0.35225 0.9328276 -0.07580174 -0.4675176 0.8807278 0.07623956 -0.7629596 0.6419346 -0.1112812 -0.8518366 0.5118505 0.1226136 -0.9738398 0.1913166 -0.1261138 -0.98919 -0.07482228 0.1262673 -0.9321194 -0.339426 -0.1485926 -0.791398 -0.5929666 0.1203997 -0.5866434 -0.8008455 -0.09225371 -0.3006884 -0.94925 0.02780568 -0.2057984 -0.9781993 -0.03856652 0.2853611 -0.9576439 0.05545109 0.330304 -0.9422444 -0.05963711 0.8655023 -0.4973422 -0.01585017 0.8765559 -0.4810391 0.05780965 0.9935659 0.09739055 -0.1515888 0.9649752 0.2141115 0.1304739 0.6738899 -0.7272199 -0.04239529 0.9245517 -0.3786908 -0.1164859 0.9323832 -0.3421879 0.09435275 0.9744743 0.2037093 -0.04937863 0.9530234 0.2988446 0.01932119 0.7251322 0.6883386 -0.008506492 0.7363371 0.6765615 0.05074717 0.3269495 0.9436783 -0.1433293 0.1917681 0.970918 0.1070684 -0.151695 0.9826113 -0.1100356 -0.463519 0.8792282 0.03994756 -0.5539875 0.831566 -0.04368484 -0.9063687 0.4202231 0.034866 -0.924988 0.3783935 -0.03124426 -0.9939103 -0.1056702 0.03123641 -0.9884675 -0.1481766 -0.03125577 -0.8161555 -0.5769866 0.07560126 -0.7697653 -0.6338342 -0.09234822 -0.4526461 -0.8868953 0.1057755 -0.2564968 -0.9607399 -0.06345069 -0.07416225 -0.9952255 0.06423989 0.2573288 -0.9641863 -0.1566715 0.4343357 -0.8870212 0.06516279 0.9973646 0.03189879 0.01578034 0.9090688 0.4163472 -0.04939843 0.888802 0.4556214 0.01516259 0.6200228 0.7844373 0.03123999 0.6110997 0.790937 -0.0312081 0.1900189 0.9812843 0.07564328 0.117199 0.9902235 -0.124628 -0.3629741 0.9234271 0.09512782 -0.4801337 0.872022 0.01559295 -0.8624488 0.5059041 -0.09935333 -0.8896252 0.4457532 0.08892971 -0.9959564 -0.01274381 -0.01332234 -0.9965293 -0.08217006 -0.0672269 -0.8887461 -0.4534433 0.1177684 -0.803273 -0.5838519 -0.1164493 -0.5510824 -0.8262855 0.1026041 -0.3902333 -0.9149811 -0.07564031 0.03276718 -0.9965967 0.03122179 0.1060987 -0.9938654 -0.03872996 0.5887038 -0.8074205 -0.06699076 0.5762721 -0.8145077 0.1370578 0.8950682 -0.4243444 -0.1802716 0.9679314 -0.1749597 0.9889649 0.1362784 0.05810874 0.8933688 0.442027 -0.08064957 0.7238694 0.685206 0.0806582 0.343853 0.9368812 -0.0633952 0.2426542 0.9699063 0.02001791 -0.376915 0.9259417 -0.02381218 -0.3668973 0.9296143 -0.03469227 -0.8250287 0.5606365 0.0708122 -0.9099593 0.4086157 -0.07076322 -0.9839591 -0.1749904 0.03468363 -0.9908841 -0.1345224 -0.007235215 -0.7234024 -0.6898642 0.02786339 -0.69884 -0.7152618 -0.00482405 -0.2044277 -0.9779094 -0.04361673 -0.04677086 -0.995622 0.08092831 0.402339 -0.9132755 -0.06364843 0.58889 -0.8064376 0.05354503 0.8154955 -0.5770009 -0.04513299 0.9188649 -0.3919739 0.04520721 0.9933366 -0.1060174 -0.04519594 0.9913775 0.07988874 0.103868 0.939428 0.3345322 -0.0745871 0.7253213 0.6866081 0.04978384 0.6114163 0.7905463 -0.03473499 0.2424637 0.9693272 0.04020006 0.1481883 0.9886504 -0.02470898 -0.3785746 0.9255539 0.005586007 -0.39516 0.9183517 0.0218812 -0.8749531 0.4836217 -0.02381456 -0.8979874 0.4391721 0.02732272 -0.9668062 -0.25425 -0.02535369 -0.9537713 -0.3000117 0.01769931 -0.6559148 -0.7546666 -0.01594076 -0.6443961 -0.7646816 -0.003972101 -0.1594794 -0.9868508 0.02630453 -0.06659958 -0.9966034 -0.04843748 0.4157748 -0.9086788 0.03786852 0.5514128 -0.8329256 -0.04667914 0.791586 -0.6084644 0.05623756 0.9211715 -0.3782345 -0.09155109 0.9775474 0.200875 -0.06364097 0.9124506 0.405673 0.05351111 0.7166175 0.6954104 -0.05351405 0.5508811 0.8321551 0.06362191 0.1221538 0.9892056 -0.08093657 -0.06653453 0.9955069 0.06737269 -0.5960695 0.8017376 -0.04379432 -0.6781528 0.733845 0.03975304 -0.9436306 0.3268618 -0.05217767 -0.9868536 0.1446174 0.07215157 -0.9382907 -0.3362435 -0.08093801 -0.8416026 -0.5324003 0.09085719 -0.4464677 -0.8910151 -0.08221135 -0.2143477 -0.9733013 0.08209493 0.10556 -0.9927934 -0.05673084 0.4971041 -0.8650442 0.06771943 0.5772457 -0.8165399 -0.007071393 0.9128869 -0.4058753 -0.04361863 0.9634194 -0.2554867 0.08092796 -1.209162e-06 -5.434662e-09 -1 -2.05308e-06 1.098049e-06 -1 -2.796354e-06 1.495574e-06 -1 -9.590229e-07 -1.710178e-07 -1 9.012715e-07 -3.050925e-06 -1 0 0 -1 -4.651482e-06 3.708098e-06 -1 -6.578347e-07 -1.975355e-06 -1 -8.888802e-07 4.588905e-07 -1 -2.593619e-06 -1.097339e-06 -1 0 0 -1 -8.309734e-07 -1.339636e-05 -1 4.850262e-06 1.01699e-05 -1 -1.871313e-06 5.005184e-06 -1 0 0 -1 0 0 -1 -2.966875e-06 -3.012066e-07 -1 0 0 -1 -2.894848e-06 -1.373904e-06 -1 -4.027791e-07 9.143257e-07 -1 -3.772358e-06 -1.238792e-07 -1 -4.035934e-06 -2.201026e-07 -1 -3.098008e-05 5.999329e-06 -1 0 0 -1 1 3.347644e-05 9.138682e-06 1 1.3544e-06 -1.462615e-05 1 -8.361567e-06 -1.574281e-05 1 7.415019e-05 -3.13625e-05 1 -5.847212e-05 -1.178979e-06 1 -7.459782e-05 1.333442e-05 1 9.93041e-05 2.315463e-05 1 -8.74769e-06 -1.816502e-05 1 -5.763213e-05 3.105946e-05 1 -1.759959e-05 -1.650702e-05 1 0 0 1 -9.546039e-06 -1.365788e-05 1 6.290647e-05 -3.455782e-05 1 0.0001101073 6.816707e-05 1 -3.01897e-05 -2.148411e-05 1 0.0001459187 -2.610908e-05 1 -1.875851e-05 -1.984598e-06 1 -5.75256e-05 -1.675217e-05 1 -5.492374e-05 3.010107e-05 1 -1.59272e-05 -2.388594e-06 0.9562782 -0.01536061 -0.292055 0.9551097 0.1241437 0.2689867 0.9662107 0.1839421 0.1805607 0.9514958 -0.1463051 -0.2706485 0.9464492 -0.3218706 -0.02516575 0.9621171 -0.2030643 0.1819219 0.955673 -0.2704074 0.116486 0.9583621 0.007734187 0.2854508 0.9709663 -0.07804216 0.2261282 0.9549914 -0.2498387 -0.1599126 0.9682995 -0.1893761 -0.1628888 0.9763303 0.07781173 -0.2018028 0.967029 0.1676043 -0.1917388 0.9979624 0.04202815 -0.04800836 0.99352 -0.09999914 -0.05402067 0.9949449 -0.08744833 -0.04937112 0.9762222 0.2120506 -0.04499914 0.9636284 -0.2645782 0.03766537 0.9981229 -0.02279832 0.05684074 0.9820627 0.1790403 0.05913961 0.9807364 0.189568 0.04711735 0.9753609 -0.08942905 0.201677 1 0 0 1 0 0 1 -2.345355e-05 -5.059041e-05 1 -2.128257e-05 -5.106e-05 1 -2.362358e-05 1.908786e-05 1 -6.609073e-06 2.445899e-05 1 3.026533e-06 7.907093e-06 1 -0 0 1 0 0 1 -0 0 1 0 0 1 -2.000394e-06 -6.760786e-06 1 -7.831368e-05 -1.347506e-05 1 -5.508101e-05 -9.208108e-05 1 3.317162e-05 -2.339456e-05 1 2.970031e-06 1.454406e-05 1 0 0 1 0.0001977454 -8.942558e-05 1 0.000183336 -0.0002098986 1 -9.867485e-06 -6.197726e-06 1 -3.688725e-05 7.391474e-06 1 -4.578159e-05 2.77961e-05 1 -3.752779e-05 3.173757e-05 1 0 -0 1 -6.743763e-05 -5.724106e-05 1 -2.580065e-05 -7.531942e-05 1 9.527835e-06 5.429758e-05 1 5.305916e-06 5.96674e-05 1 -2.951659e-05 2.187251e-05 1 -8.899388e-06 -1.625527e-06 1 -1.876926e-05 -0.0001048684 0.9999999 0.000368725 -6.80723e-05 1 -1.205853e-05 1.177656e-05 1 -1.69997e-05 -1.666332e-06 1 -9.430871e-05 1.716763e-05 1 -6.123066e-05 -0.0001064633 1 0 0 1 -1.623846e-05 4.921516e-06 1 -1.06231e-05 -3.022443e-05 1 1.188184e-05 -3.146545e-05 1 1.374678e-05 1.552651e-05 1 -5.91798e-06 -6.514949e-06 1 -5.277262e-05 4.149748e-06 1 -5.329675e-05 2.030546e-05 1 6.977035e-05 5.643694e-05 1 6.947361e-05 5.731127e-05 1 0 0 1 8.665889e-06 -1.061525e-05 1 2.566492e-05 7.103952e-06 1 -7.687764e-05 7.291482e-05 1 -0.0001119918 9.611917e-06 1 2.946127e-05 4.693726e-06 1 2.991771e-05 -2.496813e-06 1 0.0001288315 5.572048e-05 1 0.0001266605 6.451196e-05 1 -1.614631e-05 1.210207e-05 1 -5.204916e-06 -1.949564e-05 1 3.703321e-07 -1.219046e-05 1 4.170978e-05 -5.930119e-05 1 4.734582e-05 -5.18638e-05 1 0.0001216248 -8.526249e-05 1 0.0001008756 -9.539234e-05 1 5.071161e-06 5.582709e-06 1 0.0001691157 -0.0001089528 1 -6.552126e-05 -6.941196e-05 1 -4.886405e-06 -5.176563e-06 1 1.932346e-05 -1.332411e-05 1 3.566016e-05 1.311152e-05 1 -1.712337e-05 1.035763e-05 1 -1.722008e-05 5.513963e-06 1 -3.124251e-05 1.000402e-05 1 -4.930891e-06 9.678818e-05 1 -3.479944e-05 0.0001115198 1 -3.365197e-05 -5.59149e-06 1 -1.49043e-05 -6.145651e-06 1 -1.486523e-05 -3.124238e-07 1 -1.519649e-05 -4.860304e-07 1 -1.70724e-05 5.849514e-05 1 6.243466e-05 5.420241e-05 1 6.221524e-05 3.635407e-05 1 1.887752e-05 1.794226e-05 1 2.165919e-05 8.808711e-06 1 8.187284e-06 -6.951585e-06 1 0.0001605841 -0.0001363473 5.727811e-07 3.833717e-06 1 7.602452e-06 -6.813312e-06 1 2.356446e-06 -3.226964e-06 1 6.955921e-06 -7.921356e-06 1 -4.559663e-06 3.465169e-06 1 7.153983e-07 6.822313e-07 1 7.452396e-06 -6.457237e-06 1 -1.330875e-05 1.832813e-05 1 1.179019e-05 -2.242309e-06 1 8.867763e-07 3.545177e-06 1 0 -0 1 5.008127e-06 2.949625e-07 1 4.678089e-06 3.769771e-07 1 1.595869e-06 3.410034e-06 1 -4.918507e-06 2.405458e-06 1 -1.835321e-05 -5.773058e-06 1 0 0 1 2.043194e-06 1.454469e-06 1 9.499827e-07 -2.519234e-07 1 1.090106e-06 4.846582e-07 1 1.511392e-06 -3.512379e-06 1 0 0 1 0 0 1 0.01857028 0.2460117 -0.9690889 -0.05765559 0.3876614 -0.919997 0.05417608 0.7274282 -0.6840417 -0.06654429 0.9462087 -0.3166403 0.07299296 0.9964439 -0.0420909 -0.07231531 0.8894754 0.451225 0.06225993 0.6531305 0.7546816 -0.01571891 0.5062723 0.8622304 0.003556172 -0.006186396 0.9999746 0.01394919 -0.0243011 0.9996073 -0.0151359 -0.6316491 0.7751067 -0.04253954 -0.5978645 0.8004676 0.04695762 -0.8888524 0.4557813 -0.05864435 -0.9935839 0.09670516 0.01988755 -0.9957952 -0.08942275 0.003407604 -0.855025 -0.5185755 -0.0167467 -0.8337276 -0.5519221 0.004573605 -0.3799023 -0.9250153 -0.002290807 -0.3896526 -0.920959 0.01772578 -0.002472913 -0.9998398 -0.01943946 0.06061399 -0.997972 0.0004665673 0.6334108 -0.7738156 0.03763527 0.6881849 -0.7245585 -0.03527628 0.9087819 -0.4157776 0.04365107 0.9901525 -0.1330127 -0.03700127 0.9865192 0.1594076 0.03700978 0.9066163 0.4203299 -0.0436544 0.7458576 0.6646733 0.05168314 0.4657326 0.883415 -0.05166469 0.1926293 0.9799105 0.0436472 -0.1627014 0.9857095 -0.03703734 -0.4413541 0.8965684 0.02877571 -0.64452 0.7640458 -0.03405023 -0.8542907 0.518679 0.02999749 -0.9352292 0.3527696 -0.02871381 -0.990911 -0.1314192 0.01613696 -0.9779472 -0.2082277 -0.0173929 -0.6042446 -0.7966091 -0.004609337 -0.5885389 -0.8084558 -0.0549293 0.030319 -0.9980299 0.05094114 0.3303669 -0.9424769 -0.06181587 0.6729173 -0.7371303 0.06174927 0.8891988 -0.4533348 -0.04189235 0.9830854 -0.1782923 0.03747059 0.9714634 0.2342111 -0.01570759 0.9355561 0.3528288 0.003537061 0.6233843 0.7819076 -0.003555643 0.6330033 0.774141 0.01674141 0.1174717 0.9929351 -0.01672568 0.05201631 0.9985061 0.003526765 -0.4930815 0.869976 0.01390949 -0.5087031 0.8608297 -0.01276504 -0.9071444 0.4206258 0.01014561 -0.9255217 0.3785587 -0.01014982 -0.9910476 -0.1331223 -0.002543577 -0.9889514 -0.1482186 0.01674502 -0.7718852 -0.6355414 -0.04545667 -0.6879544 -0.7243289 0.04834702 -0.2576525 -0.9650274 0.01773614 0.1665223 -0.9858782 -0.03631075 0.256137 -0.9659583 0.03636305 0.800787 -0.5978445 -0.01772104 0.8527218 -0.5220649 0.002546448 0.999776 0.02101238 0.02533339 0.9974555 0.06663904 -0.03321341 0.8478004 0.5292743 0.04598377 0.7336497 0.6779702 -0.04600048 0.3555565 0.9335221 0.05863506 0.1147943 0.9916573 -0.0617956 -0.3095437 0.9488751 0.0617637 -0.6235121 0.7793702 -0.06176953 -0.8522427 0.5194871 0.06179876 -0.9805071 0.1865118 -0.06653664 -0.9612513 -0.2675233 0.04292332 -0.8809242 -0.471307 -0.03127118 -0.4607717 -0.8869676 -0.003559524 -0.4175632 -0.9086409 1 1.316999e-05 -5.454932e-06 1 -1.951086e-06 2.612266e-06 1 -5.473584e-08 2.251517e-06 1 1.112907e-05 -2.579945e-06 1 -2.604804e-05 2.387128e-05 1 1.933853e-05 8.164046e-06 1 -1.372514e-05 -1.232523e-06 1 -2.62811e-05 1.276513e-06 1 -1.118693e-05 -6.838955e-06 1 -1.086523e-06 -2.060948e-06 1 3.143421e-07 -1.904409e-06 1 2.808997e-06 -2.957465e-06 1 3.908899e-06 6.542407e-06 1 -5.785147e-06 6.858e-06 1 3.199682e-05 -4.076606e-06 1 -1.08964e-05 -5.051843e-06 1 -5.659412e-05 2.204883e-06 1 -4.107886e-06 6.951383e-06 1 1.428941e-05 3.451853e-06 1 4.729956e-05 1.861933e-05 1 1.646196e-05 3.687716e-06 1 -1.341545e-05 5.529021e-06 1 2.186311e-07 -5.735674e-06 1 -3.962729e-05 9.231082e-06 1 6.164023e-06 -1.965905e-06 1 -2.482933e-07 -2.144896e-06 1 3.207626e-07 -1.899043e-06 1 -4.432609e-05 3.134465e-05 1 1.380464e-05 -5.379423e-06 1 -9.112795e-07 -1.982995e-06 1 0 0 -0.000286869 -0.5996542 -0.8002592 -0.0009709107 -0.5915029 -0.8063023 0.001554461 -0.546945 -0.8371671 0.001737697 -0.5453817 -0.8381861 0.002465606 -0.5423936 -0.8401209 0.002911504 -0.5447606 -0.8385865 -0.0004356354 -0.5780553 0.8159975 0.001519264 -0.5471957 0.8370034 0.001723881 -0.5454951 0.8381123 0.002412026 -0.5446473 0.8386618 0.002231867 -0.5436194 0.8393288 -0.8982826 0.4281278 -0.09896881 -0.9850613 0.110269 0.1322683 -0.9442917 -0.2873072 -0.1605234 -0.8673999 0.493837 0.06117574 -0.9774167 0.1787238 -0.1127585 -0.9866928 -0.1267696 0.1018178 -0.9263378 -0.3585865 -0.1153865 -0.9999556 -0.00936958 -0.001063839 -0.5883973 -0.3990631 0.7032335 -0.6999684 -0.4028794 0.5896883 1 0 -4.768382e-06 1 0 -4.768382e-06 1 -5.784576e-06 0 -0.22921 -0.9569834 -0.1778916 -0.452373 -0.8847823 0.1118881 -0.7829959 -0.6187984 -0.06329346 -0.7900698 -0.6068442 -0.08677459 -0.9723198 -0.2146241 0.09236043 -0.9907243 0.02404959 -0.1337419 -0.9825564 0.179027 0.05032015 -0.7740892 0.6329595 -0.01216693 -0.7818621 0.6233312 0.01223737 -0.32352 0.9444783 -0.05740502 -0.2038128 0.9667491 0.1544558 0.2829964 0.9449711 -0.1641425 0.520164 0.8401645 0.1534694 0.7330439 0.6730084 -0.09852139 0.8978106 0.4292386 0.09843963 0.971683 0.1997072 -0.1262906 0.9903601 -0.06295646 0.1233837 0.8935781 -0.4303338 -0.1277935 0.8540632 -0.5199342 0.01563737 0.5849246 -0.8084775 0.06501894 0.4228869 -0.8933018 -0.1522452 0.1224178 -0.9820035 0.1438161 -9.993462e-07 4.740218e-06 1 -2.550266e-05 -1.135961e-05 1 1.045223e-05 8.354543e-06 1 8.274996e-06 6.580171e-06 1 1.818578e-05 1.142147e-06 1 -1.242489e-05 -4.893636e-06 1 3.732119e-06 1.784307e-06 1 -1.108378e-06 -5.531542e-06 1 5.289576e-07 -7.311208e-07 1 2.704114e-05 -4.92704e-06 1 1 0 -0 1 0 -0 1 0 0 -0.1635655 0.9861699 -0.02674332 -0.2302472 0.971526 0.05588804 -0.5319391 0.8439458 -0.06925587 -0.651328 0.755636 0.06918205 -0.8609772 0.5056104 -0.0554648 -0.8947279 0.445744 0.02782826 -0.9993733 -0.006192761 -0.03484922 -0.9976912 -0.05196042 0.04373056 -0.8088792 -0.5863439 -0.0437624 -0.7355326 -0.6633604 0.13764 -0.361478 -0.9159343 -0.1743507 -0.04591097 -0.9770415 0.2080434 0.2653388 -0.9481174 -0.1751244 0.583092 -0.7987099 0.1485474 0.8052657 -0.5732114 -0.1515786 0.9150013 -0.3901848 0.102609 0.996595 0.03276967 -0.07566076 0.9938636 0.106113 0.03122961 0.8245315 0.564742 -0.0348485 0.7974891 0.6017431 0.0437762 0.3403307 0.9392764 -0.04398657 0.2973813 0.9541472 0.03416672 0 -0 -1 0 0 -1 -3.080538e-06 -1.004954e-06 -1 0 0 -1 0 0 -1 -8.333206e-07 5.931817e-07 -1 -4.779545e-06 -3.036421e-07 -1 -5.86332e-06 -3.633291e-08 -1 -2.380536e-06 1.540035e-07 -1 -1 -0 -0 -1 0 0 -1 0 0 1 0 -4.768382e-06 6.398546e-06 0.5446395 0.8386703 7.629395e-06 0 1 7.629395e-06 0 1 -7.629453e-06 0 -1 -0 -1 -0 0 -1 0 -1 -0 -0 1 0 -0 1 0 0 1 0 0 -6.398522e-06 0.5446395 -0.8386703 -7.629365e-06 0 -1 -7.629365e-06 0 -1 7.629365e-06 0 1 -0 -1 -0 0 -1 0</float_array> + <technique_common> + <accessor count="4545" source="#cubenormals-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <source id="cubeverts-array0"> + <float_array count="6843" id="cubeverts-array0-array">0.03690009 -0.006700784 0.01122297 0.04140009 -0.006732196 0.01099629 0.03690009 -0.006700784 0.01085123 0.03690009 -0.0002007838 0.01085123 0.04143754 -9.059533e-05 0.01085139 0.03690009 -0.0002007838 0.01165123 0.04140009 -0.0002007838 0.01165122 0.03513958 -0.001587074 0.01165123 0.03631815 -0.002411906 0.01165123 0.03593208 -0.002887254 0.01165122 0.03627702 -0.004106104 0.01165123 0.03564098 -0.004221914 0.01165122 0.03535641 -0.005260855 0.01165123 0.03492184 -0.004941184 0.01165122 0.03394632 -0.005743865 0.01165123 0.03360492 -0.005235525 0.01165123 0.03253164 -0.005320204 0.01165122 0.03229399 -0.004450124 0.01165123 0.0316718 -0.004383665 0.01165123 0.03186561 -0.003163835 0.01165123 0.03137172 -0.002923625 0.01165122 0.03225204 -0.002035765 0.01165123 0.03210701 -0.001396814 0.01165123 0.03320601 -0.001282943 0.0116512 0.03363633 -0.000672834 0.01165119 0.03422392 -0.001221424 0.01165121 0.03528585 -0.001067923 0.01165123 0.03690009 -0.006041324 0.01165123 0.04140009 -0.006041324 0.01165122 0.03384811 -0.005721465 -0.01234873 0.03449632 -0.005151775 -0.01234877 0.03319034 -0.005111253 -0.01234877 0.03243772 -0.005281884 -0.01234877 0.03214198 -0.004225284 -0.01234877 0.03153992 -0.004092036 -0.01234877 0.03188859 -0.002893416 -0.01234877 0.03140495 -0.002827844 -0.01234877 0.03190367 -0.001658313 -0.01234877 0.03264994 -0.001568424 -0.01234878 0.03309641 -0.0007875655 -0.01234877 0.03412179 -0.001178095 -0.01234877 0.03499765 -0.0008769054 -0.01234877 0.03534328 -0.001766384 -0.01234877 0.03627699 -0.002295434 -0.01234877 0.03588166 -0.002817983 -0.01234877 0.03635452 -0.003784085 -0.01234877 0.03571146 -0.004173394 -0.01234877 0.03587493 -0.004746754 -0.01234877 0.03508391 -0.005428584 -0.01234877 0.04137573 -0.009447195 0.0128651 0.04134619 -0.009639275 0.009314813 0.04140009 -0.008351117 0.01015122 0.04140008 -0.004523655 0.00935122 0.04140009 -0.004523655 0.01015122 0.04144011 -0.001858724 0.01015122 0.04134471 0.0002981368 0.01302068 0.04131648 0.0005498565 0.01015115 0.04103793 -0.0102387 0.01300457 0.04068599 -0.01067938 0.008639209 0.04046835 -0.01078838 0.01287443 0.03977673 -0.01106006 0.01299029 0.03971831 -0.01108368 0.008376651 0.04137243 0.0001465958 0.01085122 0.04121994 0.0006754249 0.01085121 0.04023912 0.001683926 0.01015111 0.03987414 0.001758255 0.01085122 0.03967598 0.001791565 0.01085121 0.04136697 0.0002523866 -0.01084885 0.04140048 -0.0002005938 -0.01154878 0.04137243 0.0001465362 -0.01154878 0.04084565 0.001234446 -0.01084891 0.04018945 0.001652867 -0.01154878 0.03996283 0.001738286 -0.01084878 0.04018941 0.001652876 -0.01154878 0.03987181 0.001767516 -0.01154882 0.03862377 0.001984317 -0.0108524 0.03987409 0.001758255 -0.01154879 0.03773694 0.002359616 -0.01173899 0.03693063 0.002984855 -0.01084813 0.03690362 0.003064916 -0.01155246 0.04142017 -0.0001949444 -0.01235471 0.03690005 -0.0002007838 -0.01234877 0.03690005 -0.0002007838 -0.01154878 0.03690005 -0.006700784 -0.01154878 0.04140005 -0.006732196 -0.01169386 0.03690005 -0.006700784 -0.01192052 0.033879 -0.01107745 0.01323395 0.02810144 -0.01110093 0.008358225 0.02811737 -0.01110097 -0.009055775 0.03452361 -0.01107349 -0.0138399 0.03985025 -0.01107071 -0.009082656 0.03992849 -0.01103389 -0.01372423 0.03063144 -0.01109371 0.01534467 0.02651409 -0.01108468 -0.01120635 0.02599651 -0.0110792 -0.01265362 0.03012798 -0.01109221 -0.01631939 0.02510356 -0.01108013 -0.01394488 0.02229412 -0.01108516 -0.01573442 -0.001014421 -0.01107642 -0.0161808 0.02063018 -0.01108735 -0.01601748 0.02430002 -0.01108121 0.01397438 0.02647673 -0.01108988 0.01130143 0.02791663 -0.0111012 -0.008880641 0.02789857 -0.01110386 0.008115411 2.309866e-05 -0.01109981 0.01539214 0.02121646 -0.01108886 0.01530097 0.03090006 0.01069922 -0.01154877 0.03031529 0.01069672 -0.01757535 0.02406865 0.0106983 -0.01757351 0.03425204 0.01069743 0.01488202 0.03545761 0.01069911 0.01290717 0.03090009 0.01069922 0.01085123 0.03600879 0.01068947 0.01085221 0.03076828 0.01069195 0.01684221 0.03251962 0.01069661 0.01621332 0.03338388 0.01069804 0.01570893 0.02406845 0.01069838 0.016875 0.02541513 0.01068345 0.01296089 0.02367416 0.01068566 0.01444845 -0.0001151394 0.01065227 0.01519712 -0.001053191 0.01065532 0.01693169 0.0210881 0.01068629 0.01530373 -0.001036455 0.01065711 -0.01762839 -0.000928144 0.01064116 -0.01594419 0.02105104 0.01068556 -0.01601144 0.03592277 0.0105999 -0.01154871 0.03554296 0.01069214 -0.0134007 0.03378286 0.01069907 -0.01607278 0.03302117 0.01069475 -0.01665115 0.03149529 0.01069557 -0.01733307 0.02647817 0.01067993 0.01074604 0.02413481 0.01069323 -0.01489922 0.02652111 0.01069058 -0.01217919 0.03090009 0.01069922 0.01015123 0.02792424 0.01070699 0.01006574 0.03090006 0.01069922 -0.01084877 0.02794594 0.01069922 -0.01078209 0.03047323 -0.009472288 0.01720966 0.03043075 0.009470897 0.01722968 0.02898838 0.009518987 0.01756492 0.0286813 -0.009314504 0.01763589 0.02859373 0.009643935 0.01759175 0.03203378 -0.009304494 0.01651558 0.03147314 -0.004029716 0.0168088 0.03136342 -0.002791004 0.01686061 0.0315665 0.01000825 0.01677315 0.0317446 -0.001799494 0.01667005 0.0324642 -0.001084283 0.01622089 0.03290146 0.01001509 0.01591987 0.03324716 -0.0007264931 0.01560566 0.03347323 0.005087106 0.01541693 0.03390439 0.005168647 0.0150273 0.03417025 0.01011973 0.01466205 0.03497177 0.005109865 0.01346428 0.03523373 0.01013115 0.0129118 0.03550741 0.005538435 0.01216644 0.03585936 0.01017207 0.01086482 0.03586456 0.005004157 0.01084984 0.03218716 -0.005129514 0.01641175 0.03363339 -0.005769923 0.01528859 0.03253232 -0.009491264 0.01613276 0.03453412 -0.001252674 0.01345121 0.03336163 -0.001261594 0.01345123 0.03240576 -0.001819694 0.01345123 0.03190413 -0.002901545 0.01345123 0.03212214 -0.004233355 0.01345123 0.03333974 -0.005156904 0.01345123 0.03485631 -0.005020915 0.01345122 0.03589818 -0.003685504 0.01345121 0.03565814 -0.002176244 0.01345122 0.03371 -0.005773515 -0.01593827 0.03379681 -0.009312343 -0.01588132 0.03203001 -0.009401146 -0.01720724 0.03242151 -0.005295385 -0.0169516 0.03145703 -0.004063666 -0.01751704 0.03142842 -0.002457295 -0.0175291 0.03016692 0.009901496 -0.01799437 0.03150199 0.009706077 -0.01749094 0.03022856 -0.009447154 -0.01799415 0.03298515 0.01017333 -0.01657726 0.03234243 -0.001128415 -0.01701222 0.03354716 0.005283205 -0.01604895 0.03368581 -0.0006446037 -0.01595832 0.03426738 0.005037427 -0.01528094 0.0345418 0.01015228 -0.01487463 0.03482988 0.005499195 -0.01439886 0.03549895 0.005536385 -0.01288983 0.0354652 0.009942146 -0.01299945 0.03583709 0.005225595 -0.01154801 0.02851261 -0.009287484 -0.0183357 0.02815666 0.009371926 -0.01833535 0.02896647 0.009462256 -0.01826014 0.0351071 -0.009443067 -0.01537972 0.03572942 -0.005003834 -0.01534558 0.03968466 -0.009337634 -0.01532535 0.0364487 -0.003685635 -0.01534877 0.03960338 1.328439e-05 -0.01533306 0.03633459 -0.002414845 -0.01534877 0.03569535 -0.001355184 -0.01534561 0.03597368 0.001371896 -0.0153151 0.03395182 -0.005229365 -0.01414877 0.0352163 -0.004752433 -0.01414877 0.03584207 -0.003750235 -0.01414877 0.03583059 -0.002557825 -0.01414877 0.03513399 -0.001603695 -0.01414877 0.03384712 -0.001145424 -0.01414877 0.03259886 -0.001658015 -0.01414877 0.03201163 -0.002488704 -0.01414877 0.03190411 -0.003499994 -0.01414877 0.0325161 -0.004721315 -0.01414877 0.04140005 -0.006041324 -0.01234878 0.03690005 -0.006041324 -0.01234877 0.03040005 -0.002906283 -0.008361645 0.02610005 -0.003175076 -0.008356292 0.02610007 -0.004149755 -0.008148723 0.03040006 -0.004395593 -0.008022003 0.02610006 -0.004983064 -0.007295761 0.03040006 -0.005199734 -0.006729066 0.02610005 -0.005218584 -0.006306339 0.03040004 -0.005056934 -0.005556263 0.02610005 -0.004778635 -0.005030572 0.03040007 -0.004299034 -0.004635766 0.02610006 -0.003422504 -0.004326072 0.03040006 -0.002979055 -0.004326087 0.02610006 -0.002102595 -0.004635751 0.03040004 -0.002052305 -0.004703485 0.03040006 -0.001362154 -0.005477063 0.02610006 -0.001344634 -0.005556289 0.02610005 -0.001201823 -0.006729033 0.03040006 -0.001204845 -0.006648023 0.03040006 -0.001706444 -0.007729855 0.02610006 -0.002005974 -0.008021988 0.03040006 -0.003430774 -0.002389505 0.02610006 -0.002969095 -0.002387699 0.02610005 -0.004294824 -0.002044741 0.03040006 -0.004884744 -0.001528412 0.02610007 -0.005150546 -0.001001228 0.03040007 -0.005198864 0.0001359731 0.02610006 -0.004978726 0.000683818 0.03040009 -0.004299034 0.001364209 0.02610006 -0.003761225 0.00160734 0.03040007 -0.003340704 0.001652855 0.02610007 -0.002569424 0.001568198 0.03040007 -0.002317844 0.001484465 0.02610008 -0.001594704 0.0009006113 0.03040008 -0.001459915 0.0006723665 0.02610007 -0.001186654 -0.0002198927 0.03040007 -0.001170514 -0.000484474 0.02610006 -0.001516795 -0.001528401 0.03040006 -0.001816703 -0.001869276 0.02610007 -0.002566744 0.003703103 0.0261001 -0.003739254 0.00371208 0.03040008 -0.003725976 0.003699195 0.0261001 -0.004565725 0.00416458 0.03040009 -0.004628213 0.004224468 0.02610007 -0.005178916 0.005174339 0.03040008 -0.005246214 0.005442664 0.02610007 -0.005089184 0.00636341 0.03040008 -0.004806845 0.006900578 0.02610007 -0.004249355 0.00741981 0.03040008 -0.003832143 0.007568158 0.02610008 -0.002566004 0.007606831 0.03040008 -0.002640376 0.007607315 0.03040008 -0.001657573 0.006951936 0.02610008 -0.001406655 0.006611202 0.03040008 -0.001176784 0.005860616 0.02610007 -0.001195034 0.005596407 0.02610007 -0.001442714 0.004626688 0.03040008 -0.001494504 0.004542604 0.03040009 -0.002554785 0.003723286 0.002152093 -0.004986973 0.01765128 0.002466022 -0.006040324 0.01765127 0.006172133 -0.002759622 0.01765128 0.002133622 -0.007520661 0.01765128 0.0001721028 0.003240379 0.01765128 -0.003732895 0.0008086488 0.01765129 -0.003541405 -0.00023425 0.01765129 -0.002625697 -0.006793361 0.01765128 -0.004503014 -0.009415302 0.01763757 -0.001841033 -0.008095551 0.01765128 -0.003866363 -0.00152063 0.01765129 -0.01028256 0.00168879 0.01762822 -0.01026016 -0.001958301 0.01763389 -0.008372795 -0.001407281 0.01765129 -0.002507247 -0.005291691 0.01765128 -0.001919829 -0.00440282 0.01765128 0.003715993 -0.001600942 0.01765127 0.003321173 8.193776e-05 0.01765127 -0.0004918091 -0.008765381 0.01765128 -0.001007934 -0.003793051 0.01765128 0.004889602 -0.002567321 0.01765127 -0.001110395 0.003432659 0.01765128 -0.008219145 0.006153028 0.01762626 -0.002689512 0.00564204 0.01765128 -0.006881743 0.00762031 0.01761646 -0.002318998 0.007102018 0.01765128 -0.003547209 0.009425669 0.01764041 -0.001211332 0.00814347 0.01765128 0.001313574 0.007974729 0.01765128 0.002387623 0.006559419 0.01765129 4.727207e-05 -0.003646722 0.01765128 0.003802403 0.001263617 0.01765127 0.001385532 0.003697978 0.01765128 0.007313583 0.001974707 0.01765127 0.008267112 0.0008086171 0.01765126 0.008451473 -0.0006823521 0.01765126 -0.002136222 0.004225979 0.01765128 -0.005491882 0.002321338 0.01765129 -0.004380858 0.001693889 0.01765129 -0.00681195 0.00225639 0.01765129 0.001313602 -0.004025303 0.01765128 0.002335953 0.004894389 0.01765128 0.005846001 0.002371918 0.01765127 0.007566312 -0.002189351 0.01765127 0.001009062 -0.008522831 0.01765128 -0.004990875 -0.0025228 0.01765129 -0.00649179 -0.002765371 0.01765129 -0.008048737 -0.00679595 0.01763375 -0.00765207 -0.00223439 0.01765129 -0.008678831 8.193962e-05 0.01765129 -0.007928787 0.001639308 0.01765129 4.726276e-05 0.008353279 0.01765128 0.004598172 0.002018837 0.01765127 -0.002149262 -0.006077301 0.01465131 -0.002100753 -0.005821042 0.01645127 -0.001956393 -0.006992482 0.01645126 -0.001651547 -0.007517159 0.01465128 -0.001208512 -0.007907059 0.01645127 -0.000480203 -0.008199729 0.01465129 -5.75101e-05 -0.008218572 0.01645127 0.0008600075 -0.00799492 0.01465128 0.00106994 -0.007865649 0.01645127 0.001682717 -0.007147083 0.01465129 0.001788191 -0.006913813 0.01645127 0.001917868 -0.006157493 0.01465128 0.0018811 -0.005736023 0.01645127 0.001557778 -0.005020752 0.01465128 0.00136952 -0.004834492 0.01645127 0.0005430002 -0.004270224 0.01645127 0.0004485175 -0.004241284 0.01465128 -0.0008125193 -0.004294841 0.01645127 -0.0007320624 -0.00428409 0.01465128 -0.001586612 -0.004835831 0.01465129 -0.001641816 -0.004916981 0.01645127 -0.008140664 -0.0004307218 0.01465132 -0.008104531 -0.0006612819 0.0164513 -0.007406772 -0.00176046 0.01465129 -0.007334505 -0.001797371 0.01645127 -0.006065567 -0.002256522 0.01645127 -0.006492923 -0.0021684 0.01465129 -0.005456974 -0.00213133 0.01465129 -0.004799287 -0.001744101 0.01645127 -0.004279747 -0.00115695 0.01465129 -0.004083067 -0.0006003119 0.01645127 -0.004143799 0.0003596097 0.01465129 -0.004386907 0.0008974094 0.01645128 -0.005067364 0.00157718 0.01465129 -0.005615151 0.001797289 0.01645127 -0.006576809 0.001777349 0.01465129 -0.006969666 0.00162043 0.01645127 -0.007713634 0.00103871 0.01465129 -0.0078517 0.0008344296 0.01645128 -0.002051949 0.00527402 0.01465127 -0.002113168 0.00550702 0.01645127 -0.001586609 0.004434278 0.01645127 -0.001406756 0.004239559 0.01465128 -0.000576769 0.00382109 0.01645127 4.017819e-05 0.003747957 0.01465128 0.0007717609 0.003960578 0.01645127 0.001402879 0.004427329 0.01465128 0.001640551 0.004777357 0.01645127 0.001931149 0.005675947 0.01465128 0.001934821 0.006094398 0.01645127 0.001557769 0.006979259 0.01465128 0.001149411 0.007405337 0.01645127 0.0004484886 0.007758718 0.01465128 -0.0003084894 0.007844647 0.01645127 -0.0009042416 0.007668311 0.01465128 -0.001773148 0.006994009 0.01645127 -0.001987349 0.00661055 0.01465124 0.003948048 -0.000725992 0.01465127 0.003886411 -0.0003261827 0.01645127 0.004286351 -0.001440233 0.01645126 0.004720468 -0.001884753 0.01465128 0.005267871 -0.002117453 0.01645127 0.005845199 -0.002206534 0.01465127 0.006282901 -0.002182383 0.01645127 0.006859979 -0.001994943 0.01465127 0.007465961 -0.001533221 0.01645126 0.007774049 -0.0009936727 0.01465127 0.007917871 -0.0002440438 0.01645126 0.007856198 0.0003595985 0.01465127 0.007682741 0.0007455088 0.01645126 0.006932648 0.001577169 0.01465127 0.006715532 0.001686638 0.01645126 0.00542317 0.001777347 0.01465127 0.005187452 0.001705158 0.01645126 0.004413388 0.001164136 0.01465127 0.00414828 0.0008344185 0.01645126 0.003941759 0.0002820976 0.01465127 0.001878596 -0.006653223 -0.01534873 0.001839217 -0.005662324 -0.01534873 0.001904514 -0.006660513 -0.01714873 0.001573284 -0.005005984 -0.01714873 0.001281056 -0.004706392 -0.01534873 0.0004494935 -0.004258752 -0.01714872 0.0001992462 -0.004204823 -0.01534872 -0.0007428471 -0.004270202 -0.01714872 -0.0009716339 -0.004362131 -0.01534872 -0.001812959 -0.005102601 -0.01714873 -0.001933227 -0.005317841 -0.01534872 -0.00212264 -0.00642251 -0.01714872 -0.002080965 -0.006665541 -0.01534872 -0.001642686 -0.007502049 -0.01714872 -0.001465514 -0.007686891 -0.01534872 -0.0008120863 -0.008089211 -0.01714872 -0.0004074145 -0.008212213 -0.01534872 0.0001992732 -0.008196719 -0.01714872 0.001079696 -0.00788473 -0.01534872 0.001134683 -0.00779729 -0.01714873 -0.004143631 0.0004161485 -0.01714872 -0.004087696 9.208918e-05 -0.01534872 -0.004613281 0.0011642 -0.01534871 -0.005075457 0.001557311 -0.01714871 -0.005623062 0.001777349 -0.01534871 -0.00622888 0.001813339 -0.01714871 -0.007132507 0.001577189 -0.01534871 -0.00719475 0.001494691 -0.01714871 -0.008055543 0.0004340187 -0.01714871 -0.008056073 0.0003595892 -0.01534871 -0.007973934 -0.0009936411 -0.01534871 -0.007933214 -0.00108372 -0.01714871 -0.006915413 -0.00208818 -0.01534871 -0.006971651 -0.002039412 -0.01714871 -0.005800708 -0.002196711 -0.01714871 -0.005387344 -0.002106721 -0.01534871 -0.00471892 -0.001695132 -0.01714871 -0.004348175 -0.001235999 -0.01534871 -0.004160784 -0.0007392503 -0.01714872 0.001907724 0.006004498 -0.01714873 0.001912547 0.005925087 -0.01534873 0.001420517 0.007183207 -0.01534873 0.001347285 0.007259628 -0.01714873 3.574695e-05 0.007829489 -0.01534872 -0.0002400754 0.007850478 -0.01714872 -0.001121046 0.007540111 -0.01534872 -0.001465532 0.00728531 -0.01714872 -0.002020272 0.006533841 -0.01534872 -0.002080968 0.006263979 -0.01714873 -0.002016881 0.005167799 -0.01534872 -0.001933223 0.004916301 -0.01714872 -0.001349257 0.004193101 -0.01534872 -0.0008171862 0.003872339 -0.01714872 -6.301329e-05 0.003764758 -0.01534872 0.0008726241 0.003987769 -0.01714872 0.000926137 0.004074927 -0.01534872 0.001651837 0.004764017 -0.01534873 0.001756545 0.005007528 -0.01714873 0.007912545 -0.0003266223 -0.01714873 0.007886617 -0.0007472131 -0.01534873 0.007756537 0.0005908776 -0.01534873 0.007651835 0.0008344278 -0.01714873 0.007134696 0.001395758 -0.01534873 0.006612694 0.001705147 -0.01714873 0.005865667 0.001854967 -0.01534873 0.005257156 0.001729807 -0.01714873 0.004599417 0.001342448 -0.01534873 0.004187014 0.0008973777 -0.01714873 0.003943947 0.0003596488 -0.01534873 0.003898424 -6.090291e-05 -0.01714873 0.003983106 -0.0008321926 -0.01534873 0.004131494 -0.001249364 -0.01714873 0.004650718 -0.001806902 -0.01534873 0.005187895 -0.002089212 -0.01714873 0.005936997 -0.002235243 -0.01534873 0.006199274 -0.002196712 -0.01714873 0.007065106 -0.001848772 -0.01534873 0.007420566 -0.001584744 -0.01714873 0.04137621 -0.009411186 -0.01359553 0.04149301 -0.001948904 -0.01004878 0.0414056 -0.004534146 -0.01004878 0.04140229 -0.001862723 -0.01084878 0.04140005 -0.004523655 -0.01084878 0.04132147 -0.009750753 -0.009939827 0.04140005 -0.008351117 -0.01084878 -0.01026842 -7.192045e-05 -0.01535575 -0.009620316 -0.003917292 -0.0153597 -0.009835769 0.003002029 -0.0153559 -0.001263257 0.009896359 -0.0153539 -0.003631301 0.009472359 -0.01537032 -0.0003546942 -0.01047079 -0.01536974 -0.007211867 0.00707539 -0.01535499 -0.002713333 -0.01021501 -0.01538192 -0.007525589 -0.007347101 -0.01535793 0.02032537 -0.01044114 -0.0153516 0.02039184 0.009944377 -0.01533996 -0.002714311 -0.01075908 -0.01596179 -0.003286579 -0.01061904 -0.0176642 -0.001376298 -0.01102795 -0.01689116 -0.002685317 0.01037216 -0.01602193 -0.002753374 0.01036024 -0.01761763 -0.004511459 0.00977774 -0.01603394 -0.003973101 0.00993483 -0.01782672 -0.005175493 0.009391799 -0.01781996 -0.006246048 0.008770179 -0.01595581 -0.006290973 0.00873237 -0.01779522 -0.007322891 0.007935319 -0.01596704 -0.007332477 0.00791206 -0.01775336 -0.008254717 0.007008249 -0.01767418 -0.008243576 0.007014781 -0.01601146 -0.009007644 0.00596098 -0.01580626 -0.009064775 0.005916448 -0.01782 -0.009738556 0.0048448 -0.01596649 -0.009742694 0.00481477 -0.01779532 -0.01051483 0.0029977 -0.01601004 -0.01051868 0.00297725 -0.01770409 -0.01087206 0.001110418 -0.01587538 -0.01091503 0.001025189 -0.01767574 -0.0109839 -0.0001833402 -0.01602061 -0.01098353 -0.0002914593 -0.01767684 -0.01090713 -0.001494279 -0.01602159 -0.01084118 -0.001593281 -0.01789125 -0.01065227 -0.00282946 -0.01595723 -0.01064473 -0.002862319 -0.01773863 -0.01006038 -0.004616929 -0.01601284 -0.01023806 -0.004161332 -0.01767608 -0.00967844 -0.005335732 -0.01775329 -0.008730669 -0.006874682 -0.01603328 -0.009028095 -0.006358391 -0.01787383 -0.008144001 -0.00751958 -0.01774009 -0.007311235 -0.008364059 -0.01609168 -0.00722237 -0.008409594 -0.01775362 -0.006212605 -0.009207081 -0.01767316 -0.005739092 -0.009520679 -0.01599572 -0.005087482 -0.00986211 -0.01775061 -0.003952593 -0.01036321 -0.01594389 0.003685732 -0.001482051 -0.01834873 0.004780471 -0.002571123 -0.01834873 -0.003521038 8.194894e-05 -0.01834872 -0.003457965 0.0095124 -0.01832846 -0.006272949 0.00238782 -0.01834872 -0.008123249 0.006250929 -0.01833194 -0.007474018 0.00195707 -0.01834871 -0.009300738 0.004400099 -0.01832582 -0.008394924 0.00100914 -0.01834871 -0.01028072 0.0008648187 -0.01833507 -0.01007399 -0.002861619 -0.01832917 -0.008658689 -0.0004739109 -0.01834871 -0.008078304 -0.00187915 -0.01834871 -0.00701778 -0.002588781 -0.01834871 -0.003915844 -0.00160094 -0.01834872 -0.001307392 -0.00392838 -0.01834872 -0.00260352 -0.005605921 -0.01834872 -0.00593565 -0.00276879 -0.01834872 -0.004913715 -0.002467401 -0.01834872 -0.006449666 -0.008156303 -0.0183446 -0.002524431 -0.007124191 -0.01834872 -0.00456139 -0.009531509 -0.01831379 -0.001760945 -0.008146532 -0.01834872 0.008478962 8.194707e-05 -0.01834873 0.007997764 0.001263598 -0.01834873 -0.0006766869 0.008291659 -0.01834872 -0.001674151 0.00783485 -0.01834872 -0.002575722 0.0050976 -0.01834872 -0.002566402 0.00660385 -0.01834872 0.003691083 0.001210799 -0.01834873 -0.004002262 0.001263639 -0.01834872 -0.004798084 0.00201888 -0.01834872 0.0003881026 0.008325779 -0.01834872 0.006186562 0.002341418 -0.01834873 0.002445033 0.005418796 -0.01834873 0.002365743 0.006481269 -0.01834873 -0.002114459 -0.00462383 -0.01834872 0.007202013 0.002018819 -0.01834873 0.005093971 0.002242977 -0.01834873 0.001816103 0.004050078 -0.01834873 0.003341312 -0.0004738923 -0.01834873 0.001011482 -0.003856544 -0.01834872 -0.0002471488 -0.003646731 -0.01834872 0.008084154 -0.001600932 -0.01834873 0.001728904 0.007639338 -0.01834873 -0.001766207 0.003810659 -0.01834872 -0.0003719768 0.003240381 -0.01834872 0.0006860728 0.003364678 -0.01834872 0.002385232 -0.006807944 -0.01834873 0.002426382 -0.005711582 -0.01834873 -0.0008005584 -0.008676824 -0.01834872 0.001997672 -0.004736302 -0.01834873 0.006719751 -0.002662243 -0.01834873 0.001936322 -0.007774129 -0.01834873 0.0007197717 -0.00866225 -0.01834872 0.008489655 -4.358217e-05 -0.01714873 0.008119123 -0.001503652 -0.01714873 0.007390065 -0.002280453 -0.01714873 0.006166963 -0.002781384 -0.01714873 0.004692513 -0.002473142 -0.01714873 0.003737665 -0.001595704 -0.01714873 0.003331954 -0.0003639422 -0.01714873 0.003501054 0.0006879084 -0.01714873 0.004080914 0.001619177 -0.01714873 0.005199443 0.002275288 -0.01714873 0.006719714 0.002260696 -0.01714873 0.007936336 0.001372507 -0.01714873 0.002385245 0.006406378 -0.01714873 0.002426385 0.005310018 -0.01714873 0.001997694 0.004334729 -0.01714873 0.001011444 0.003454959 -0.01714872 -0.0007079756 0.003277101 -0.01714872 -0.001818986 0.003904549 -0.01714872 -0.002466976 0.00478982 -0.01714872 -0.002658678 0.006072391 -0.01714872 -0.002078309 0.00747758 -0.01714872 -0.0008005556 0.008275279 -0.01714872 0.0007197149 0.008260708 -0.01714872 0.001936315 0.007372517 -0.01714873 -0.003710637 0.0008101109 -0.01714872 -0.003605911 -0.000915261 -0.01714872 -0.004279924 -0.00199852 -0.01714872 -0.005191882 -0.00260848 -0.01714871 -0.006481432 -0.002745612 -0.01714871 -0.007860766 -0.002106121 -0.01714871 -0.008603521 -0.0007956512 -0.01714871 -0.008575716 0.0005008485 -0.01714871 -0.008065813 0.001436289 -0.01714871 -0.00720894 0.00212127 -0.01714871 -0.006169848 0.002356561 -0.01714871 -0.004876024 0.002086729 -0.01714871 0.002489644 -0.006043553 -0.01714873 0.002119133 -0.007503561 -0.01714873 0.001011483 -0.008545022 -0.01714872 -0.0002471767 -0.008754824 -0.01714873 -0.001307452 -0.008473162 -0.01714872 -0.002262354 -0.007595681 -0.01714872 -0.002693561 -0.006137772 -0.01714872 -0.002078294 -0.00452242 -0.01714872 -0.001017656 -0.00381281 -0.01714872 6.434321e-05 -0.003632763 -0.01714872 0.001295944 -0.004039072 -0.01714873 0.002040993 -0.004800404 -0.01714873 -0.001407258 -0.01102623 0.01621981 -0.002695895 -0.01075868 0.01525494 -0.001488803 -0.01098824 0.01526653 -0.002038912 0.01052028 0.01529826 -0.002740508 0.01036643 0.01690664 -0.003935457 0.009985909 0.01532554 -0.004575828 0.009739829 0.01698607 -0.005176425 0.009427199 0.01532466 -0.006266479 0.00875644 0.01704318 -0.006326083 0.008698929 0.01519303 -0.007305877 0.007943651 0.01704342 -0.007307772 0.00793232 0.01524665 -0.00821103 0.00702351 0.0171097 -0.008210361 0.0070439 0.01526113 -0.009103058 0.00587678 0.01710794 -0.009077792 0.00591255 0.01519311 -0.009772736 0.00476912 0.01704224 -0.00971207 0.004837599 0.01517813 -0.01026847 0.003681589 0.01532557 -0.01028113 0.003601639 0.01705588 -0.01066364 0.00238044 0.0170436 -0.0106304 0.00246455 0.01519501 -0.01090866 0.0009991583 0.01704172 -0.01088994 0.00110347 0.01524754 -0.01096157 -0.0001379009 0.01519368 -0.01096118 -0.0003392193 0.0171085 -0.01090845 -0.001470361 0.01532106 -0.0108916 -0.00160338 0.01698324 -0.01066088 -0.002795581 0.01526026 -0.01062619 -0.002885791 0.01710695 -0.0102746 -0.00407155 0.01532898 -0.009961335 -0.00482451 0.01699862 -0.00819965 -0.007441491 0.01519712 -0.008121003 -0.007540822 0.01704627 -0.009010895 -0.006416552 0.01710537 -0.009705295 -0.005250051 0.01517822 -0.009080723 -0.006347781 0.01532171 -0.00330533 -0.01061363 0.01697547 -0.003920933 -0.01038179 0.0152587 -0.005192051 -0.00981066 0.01526223 -0.005078523 -0.009863332 0.01704165 -0.00619034 -0.009225152 0.01697074 -0.00630228 -0.009145193 0.01532446 -0.007290409 -0.00832833 0.01517825 -0.007225008 -0.008408982 0.01705552 0.02030106 0.009885397 0.0146434 -0.001306795 0.009993419 0.0146715 0.02079898 -0.010557 0.01464494 -0.005720614 0.008390821 0.01466266 -0.007696201 0.006912301 0.01470403 -0.01033731 0.00119685 0.01466962 -0.009623692 -0.00391143 0.01465976 -0.001572544 -0.01035802 0.01466516 -0.004999425 -0.009292532 0.01467231 -0.007763097 -0.00708281 0.01467961 0.00441012 -0.002280431 0.01645126 0.003562671 -0.001326501 0.01645126 0.008466031 -0.0003612321 0.01645126 0.008133611 0.001119128 0.01645126 0.007107541 -0.002473133 0.01645126 0.008062441 -0.001595784 0.01645125 0.005633161 -0.002781384 0.01645126 0.007208271 0.001997748 0.01645126 0.006172111 0.002358068 0.01645126 0.00488965 0.002165768 0.01645126 0.004026641 0.001541268 0.01645126 0.003374301 0.0003918167 0.01645127 0.0005080914 0.003277099 0.01645127 -0.001007997 0.003391499 0.01645127 0.001957581 0.004218869 0.01645127 0.002436562 0.005448209 0.01645126 -0.001919922 0.00400134 0.01645127 -0.002507241 0.004890138 0.01645127 0.002335961 0.006704049 0.01645127 0.001561082 0.007744998 0.01645127 0.0003849221 0.008347889 0.01645127 -0.0008859588 0.008233749 0.01645127 -0.002015961 0.007548369 0.01645127 -0.002644896 0.00617964 0.01645127 -0.008689515 -4.358962e-05 0.01645129 -0.008015962 0.0015484 0.01645127 -0.008318987 -0.00150362 0.01645128 -0.006695862 0.002302529 0.01645127 -0.005191292 0.00222929 0.01645128 -0.003540111 6.089918e-05 0.01645128 -0.003999367 0.00128562 0.01645128 -0.007401796 -0.002420411 0.01645127 -0.00592692 -0.002789382 0.01645128 -0.004339098 -0.002106071 0.01645128 -0.003675141 -0.00101647 0.01645127 -0.002507239 -0.00710988 0.01645127 -0.001591493 -0.008323502 0.01645127 0.001795621 -0.007941 0.01645127 0.0008898005 -0.008559831 0.01645127 -0.0001539802 -0.008773472 0.01645127 0.00186606 -0.004563743 0.01645127 0.00100905 -0.003878724 0.01645127 -3.003981e-05 -0.003643442 0.01645127 -0.001323822 -0.003913261 0.01645127 -0.002372789 -0.004994281 0.01645127 0.00237253 -0.006887324 0.01645127 0.002422741 -0.005623903 0.01645127 -0.00265197 -0.006022371 0.01645127 -0.002272124 0.01035792 0.0172222 -0.00586612 -0.009024221 0.01750002 -0.003960602 -0.01021349 0.01733428 -0.01067618 -0.001166802 0.01742664 -0.009676422 0.004129099 0.01751886 -0.003224516 0.009854379 0.01750759 -0.007548249 -0.0076917 0.01747376 -0.009835358 -0.00451274 0.01742188 -0.005430571 0.008898878 0.01750292 -0.0007713921 -0.01084325 0.01491743 0.02053677 -0.01097656 0.01506777 -0.001210116 0.01034054 0.01485796 -0.003049716 0.009918769 0.01479859 -0.00455289 0.00950007 0.01492419 -0.009971592 0.003495801 0.01480501 -0.01054667 -0.001658371 0.01479341 -0.009825108 -0.00438945 0.01484185 -0.008807529 -0.006236132 0.01485633 -0.006405185 -0.008696343 0.01483307 -0.003225499 -0.01023436 0.01478076 -0.00904288 0.005089059 0.01471411 0.02047073 0.01024316 0.0147351 0.02087204 0.01058008 0.01504603 -0.01062613 -0.0006364398 -0.01820677 -0.002456376 0.01027507 -0.01798188 -0.003719593 -0.01035753 -0.01791341 -0.00864986 -0.00595562 -0.01831428 -0.009794941 -0.00449724 -0.01814439 -0.007462482 -0.00775731 -0.01818444 -0.006004108 -0.008994128 -0.01814487 -0.01056038 0.001661209 -0.0181304 -0.005553912 0.00868794 -0.01825817 -0.007707477 0.007181098 -0.01815013 -0.009991046 0.003444528 -0.01819504 0.02080687 -0.01087135 -0.01559891 -0.0001142146 -0.01100004 -0.01581055 -0.00136763 -0.01078427 -0.01560241 -0.007186478 -0.00815459 -0.01559659 -0.009544144 -0.005128222 -0.01559669 -0.01024257 0.003080759 -0.01559404 -0.005655961 -0.009258102 -0.01556764 -0.008457719 -0.006759331 -0.01556725 -0.01015456 -0.00340349 -0.01550205 -0.0105696 -0.00142803 -0.0155025 -0.01067027 0.00022256 -0.01553034 -0.007659622 0.007216139 -0.01553845 -0.0054178 0.008910958 -0.0155015 -0.003201796 0.01001092 -0.0156211 -0.001134627 0.01028358 -0.01549719 -0.004159623 -0.009840381 -0.01545219 -0.009150345 0.004953079 -0.01542027 0.02029372 0.01033029 -0.01550003 0.021168 0.0105704 -0.01571575 0.02993612 0.01031367 0.01724344 0.02918462 0.01010735 -0.01809809 0.03164812 0.01020814 -0.01743536 0.03049809 0.01022606 -0.01786144 0.03098764 0.01019583 0.01702266 0.02488399 -0.009275716 0.01026472 0.02490008 -0.005189385 0.007317513 0.02490008 -0.005709505 0.006152324 0.02490007 -0.003793325 -0.002874557 0.02490006 -0.002191436 -0.003981728 0.02490006 -0.003239445 -0.003790759 0.02490008 -0.005704094 0.005055323 0.02489399 -0.009438775 -0.01098307 0.02490008 -0.005234325 0.004098896 0.02490006 -0.005758114 -0.006278854 0.02490005 -0.005567364 -0.007359218 0.02490008 -0.004211694 0.003261913 0.02490007 -0.005442364 0.0009574108 0.02490006 -0.004124165 0.002075713 0.02490007 -0.005768795 -0.0005130544 0.02490006 -0.005522825 -0.005239736 0.02490006 -0.004600895 -0.008532897 0.02490006 -0.002291685 -0.002756078 0.02490004 -0.001233203 -0.002007067 0.02490094 0.008997197 -0.0107896 0.02490008 -0.003701225 0.008196894 0.02489769 0.008844828 0.009890396 0.0249001 -0.002191395 0.008018244 0.02490005 -0.004520655 -0.004115216 0.02490006 -0.005248575 -0.001941647 0.02490006 -0.003379144 -0.008900814 0.02490006 -0.002075063 -0.008686148 0.02490007 -0.0006201733 -0.000615716 0.0249001 -0.0009284243 0.0008587539 0.02490007 -0.001805814 0.001813583 0.02490008 -0.002711605 0.003124893 0.02490006 -0.001541745 0.003684271 0.02490007 -0.001165183 0.007225402 0.02490006 -0.001025243 -0.004935317 0.02490006 -0.0008565449 -0.007460199 0.02490006 -0.0006467253 -0.006201576 0.02490008 -0.0006559454 0.00603272 0.0249001 -0.000793064 0.004743204 0.02490006 -0.002806515 0.002178974 0.02610007 -0.002820335 0.003106251 0.02610007 -0.004109826 0.00324386 0.02610011 -0.004998624 0.003831249 0.02610007 -0.005699145 0.004952017 0.02610008 -0.005583845 0.006676737 0.02610009 -0.004595695 0.00781361 0.02610007 -0.003594903 0.008178983 0.02610007 -0.002499165 0.008127011 0.0261001 -0.001563653 0.007617142 0.02610005 -0.0008787345 0.00676021 0.02610007 -0.0006361846 0.00525932 0.02610007 -0.001451625 0.003735181 0.02610004 -0.002189815 -0.0027381 0.02610005 -0.003456233 -0.00289426 0.02610006 -0.004503565 -0.002567861 0.02610003 -0.005280305 -0.001838859 0.02610007 -0.005727345 -0.0008368194 0.02610006 -0.005583886 0.0006767101 0.0261001 -0.004595755 0.001813609 0.02610007 -0.003137775 0.002244838 0.02610016 -0.001919543 0.001865637 0.02610005 -0.0009592026 0.0009574182 0.02610007 -0.0006434433 -0.0002788827 0.02610007 -0.0009132438 -0.001572654 0.02610005 -0.003022345 -0.00890081 0.02610004 -0.004109884 -0.00875609 0.02610005 -0.005323494 -0.007840354 0.02610005 -0.005773474 -0.006402843 0.02610006 -0.005473165 -0.005141351 0.02610007 -0.004595755 -0.004186362 0.02610005 -0.003594935 -0.00382103 0.02610005 -0.002499133 -0.003873002 0.02610006 -0.001212176 -0.004682574 0.02610005 -0.0006419346 -0.006076742 0.02610006 -0.0009132754 -0.007572741 0.02610008 -0.001994314 -0.008621722 0.02496132 0.009304027 0.01012287 0.02465664 -0.009485893 0.01126081 0.02470931 0.009128978 0.01111421 0.02416049 -0.009624135 0.01230659 0.0243038 0.009204597 0.01205074 0.02386874 0.009247268 0.01268941 0.02326912 -0.009962056 0.01337008 0.02239316 0.009819647 0.0140212 0.02332943 0.009668528 0.01334932 0.02245761 -0.01018237 0.01397371 0.02140194 0.009781378 0.01442635 0.02480745 0.009109858 -0.01142022 0.02457213 -0.009677205 -0.01222499 0.02455441 0.009166437 -0.01224267 0.02415154 -0.009680365 -0.0130252 0.02390728 0.009300696 -0.01335802 0.02337017 -0.01011771 -0.01399877 0.0234009 0.009547016 -0.0139416 0.02256633 0.009694837 -0.01459214 0.02226762 -0.01014379 -0.01476524 0.02148503 0.009863137 -0.0151115 0.02128862 -0.01044104 -0.01518635 0.0323095 -0.005261434 -0.01414862 0.03375364 -0.005762014 -0.01414886 0.03475377 -0.005609825 -0.01414902 0.03491143 -0.005555535 -0.01544833 0.03581517 -0.004942495 -0.01414879 0.03644487 -0.003582325 -0.01414878 0.03621164 -0.001992954 -0.01414875 0.03500149 -0.0008591748 -0.01414888 0.03466811 -0.0007549245 -0.01551815 0.03332 -0.0006686431 -0.01414878 0.03217345 -0.001307065 -0.01414874 0.03151482 -0.002238454 -0.01414877 0.03135528 -0.003693365 -0.01414875 0.03646467 -0.003592763 0.01465123 0.03989889 -0.009178646 0.0146112 0.03970761 0.0001304653 0.01461802 0.03623806 -0.002132373 0.01465123 0.03575393 -0.004979305 0.01464817 0.03513553 -0.009387992 0.01468096 0.03579428 0.001213726 0.0146266 0.0352352 -0.0009812042 0.01468012 0.03442526 -0.0006632544 0.01345119 0.03581523 -0.001459055 0.01345124 0.0363925 -0.002624014 0.01345122 0.03642663 -0.003688956 0.01345122 0.03595199 -0.004735526 0.01345121 0.03500165 -0.005542336 0.01345133 0.03353113 -0.005748166 0.01345123 0.03213509 -0.005101114 0.01345121 0.03138006 -0.003745794 0.0134513 0.03144507 -0.002425464 0.01345122 0.0319974 -0.001493584 0.01345123 0.03291867 -0.0008160435 0.01345119 0.03488705 -0.005569635 0.01475641 0.03399972 -0.000644505 0.01508997 0.035489 0.004790164 -0.01334845 0.03514775 0.003851447 -0.01479095 0.03597606 0.003795475 -0.01310712 0.035799 0.003149787 -0.01456861 0.03670246 0.002523767 -0.01422638 0.03984128 0.001710584 -0.01388704 0.03862184 0.001854787 -0.01365147 0.03764183 0.002162056 -0.01376257 0.03686386 0.002667146 -0.01351579 0.03630478 0.003838267 -0.01155037 0.03616806 0.003526557 0.01242609 0.03567978 0.003271185 0.01392351 0.0365881 0.002676455 0.01338747 0.03885307 0.001780136 0.01326374 0.0388061 0.001937667 0.0101586 0.03692619 0.003047276 0.0108671 0.03713217 0.002369696 0.01323343 0.03803485 0.002004256 0.01303596 0.03505282 0.003866406 0.01420746 0.03572421 0.004419016 0.01223993 0.03772292 0.002379335 0.0109464 0.03637984 0.003734076 0.01085313 0.03386776 -0.009564095 0.01512494 0.0345748 0.003113717 0.01483063 0.03395983 0.004215855 -0.0158045 0.03459166 0.003375065 -0.01551138 0.03528191 0.002115425 -0.01536404 0.02388265 -0.01082788 0.01354549 0.02489401 -0.01059813 0.0121064 0.02508628 -0.01092768 0.01257293 0.02592191 -0.01088627 0.01076988 0.02190341 -0.01059741 0.01438728 0.02430893 -0.01014264 0.01236665 0.0220469 -0.0109533 0.01472242 0.02498581 -0.01015129 0.0110323 0.02268905 -0.01071991 0.01415402 0.02363437 -0.01035954 0.01323969 0.02509281 -0.01000879 0.01002433 0.02555579 -0.01062854 0.01046459 0.0256585 -0.0107103 -0.01079024 0.0250908 -0.0100011 -0.01074998 0.02245427 -0.010325 -0.01473228 0.02238262 -0.01082769 -0.01509611 0.02332183 -0.01064079 -0.01441363 0.02431108 -0.01098711 -0.01426787 0.02510262 -0.01039163 -0.01190499 0.02431713 -0.01025533 -0.01313305 0.02551354 -0.01074759 -0.0118579 0.02476555 -0.01077295 -0.01331353 0.02238876 0.01035481 0.01433346 0.02359237 0.0100851 0.01339449 0.02142636 0.01021052 0.01454988 0.02293319 0.01051091 0.01428732 0.02398495 0.0104998 0.01362202 0.02483273 0.01017537 0.0121468 0.02517416 0.01050297 0.01241035 0.02428988 0.009625927 0.01230244 0.02522226 0.01005543 0.01092843 0.02585494 0.01044136 0.01056751 0.0252834 0.009908757 0.01007014 0.02526592 0.009880867 -0.01073247 0.0260885 0.01055305 -0.01133365 0.0256347 0.01029573 -0.01134359 0.02502202 0.009422307 -0.01066582 0.02499639 0.01061538 -0.01375957 0.02417995 0.01035181 -0.01389354 0.02540911 0.01048939 -0.01269622 0.02484355 0.01013752 -0.01271367 0.02160369 0.01025845 -0.01523373 0.02307924 0.01027316 -0.0145856 0.02448369 0.009578136 -0.01262199 0.02399764 0.009848038 -0.01350527 0.02311632 0.01063459 -0.01518895 0.02503606 0.009828688 -0.01174468 0.03488719 -0.0108068 -0.01447417 0.03985306 -0.01076785 -0.01440604 0.03534811 -0.01037912 -0.01494132 0.03993525 -0.01030618 -0.01489754 0.03968293 -0.009815324 -0.01521055 0.03370824 -0.01053862 -0.01524059 0.03433912 -0.01001215 -0.01540707 0.03319951 -0.01095251 -0.01481256 0.03352349 -0.01001612 -0.01583759 0.03104363 -0.01092973 -0.01645361 0.03127909 -0.01064705 -0.01684415 0.03171236 -0.01010031 -0.01713002 0.02855057 -0.01007261 -0.01809736 0.030249 -0.01002102 -0.01779063 0.02897168 -0.01070887 -0.0175072 0.02870243 -0.01097126 -0.01704144 0.03960287 -0.009833936 0.01453215 0.03532638 -0.01020438 0.01437299 0.03988131 -0.01030716 0.01421216 0.03515927 -0.01090059 0.01359225 0.03976584 -0.01085344 0.01359506 0.03366244 -0.01078344 0.0142089 0.0313956 -0.01089947 0.01562471 0.03346689 -0.01028362 0.01498481 0.03190683 -0.009966235 0.01638422 0.03445688 -0.01021002 0.01454584 0.03195663 -0.0105061 0.0159057 0.03012461 -0.01005597 0.01711347 0.03006357 -0.01073398 0.01651361 0.02915951 -0.01103273 0.01613003 0.0284432 -0.009939428 0.01746197 0.02851987 -0.01062251 0.01697125 0.03665487 0.002199776 0.01397296 0.03607089 0.002600046 0.01406974 0.03689267 0.001572575 0.01431545 0.03601266 0.001807017 0.01447892 0.03825534 0.001149787 0.0142425 0.03813876 0.001675054 0.01377114 0.03992607 0.001333805 0.01388067 0.03977234 0.0006557852 0.01444918 0.03983481 0.001703575 0.01317548 0.03444198 0.003771676 0.01482222 0.03837487 0.0009648371 -0.01504355 0.03833391 0.0004545245 -0.01526991 0.03773271 0.001455206 -0.0148383 0.03645366 0.002101697 -0.01487378 0.03897051 0.001542095 -0.01440916 0.03792681 0.001814187 -0.01432993 0.03984455 0.001160936 -0.01478647 0.0356187 0.002590585 -0.0150769 0.04070989 -0.01062761 -0.00937055 0.04080175 -0.01051532 -0.01373248 0.04124218 -0.009851985 -0.01371665 0.04116518 -0.009447426 -0.01426924 0.0407163 -0.01021843 -0.0144131 0.04069539 -0.009507995 -0.01485763 0.04012405 -0.009414974 -0.01520426 0.04130781 0.0003521163 -0.01381619 0.04121648 1.087599e-05 -0.01418897 0.04089241 0.0001207441 -0.01466423 0.04036571 3.215671e-05 -0.01510221 0.03983947 0.0003073457 -0.01526123 0.04064159 0.001175296 -0.0141592 0.04092427 0.001104146 -0.01366566 0.04067529 0.0007870346 -0.01457438 0.040286 0.001578156 -0.01369802 0.04018132 0.0005797464 -0.01503369 0.04033712 -0.009467344 0.01440673 0.04073007 -0.009570215 0.01410345 0.04081418 -0.009961877 0.01382879 0.04118264 -0.009424366 0.01356048 0.0404454 -0.01059245 0.01354064 0.04042746 0.0002003871 0.0143615 0.04103097 0.0002526641 0.01377837 0.04033078 0.0009882543 0.01399874 0.04078903 0.001170987 0.01323253 0.03701294 0.002863646 0.01015123 0.02790007 0.02319506 0.0004415214 0.02790018 0.02265669 0.001336619 0.02791162 0.02356853 0.0071286 0.02790007 0.02266718 -0.004622459 0.02790007 0.02297535 -0.00162508 0.02790007 0.02329156 -0.0006296896 0.02790007 0.0206451 -0.002887588 0.02790007 0.02207642 -0.002524369 0.02790639 0.01988367 -0.0106307 0.02790006 0.02107636 -0.008877121 0.0279013 0.02343965 -0.008016203 0.02790005 0.02315974 -0.007238969 0.02790004 0.02242579 -0.008277211 0.02789171 0.02329809 -0.005988289 0.02790008 0.02042628 0.003156152 0.02790008 0.02146784 0.003233872 0.02789591 0.02279487 0.007195171 0.02790008 0.02329415 0.006025247 0.02789562 0.02199186 0.00785809 0.02790009 0.02095928 0.008168947 0.02791135 0.01989003 0.009958729 0.02790007 0.02260322 0.003858186 0.02790007 0.02320824 0.004953127 0.0279168 0.0229168 0.008005422 0.02790009 0.01930573 0.007742818 0.02790007 0.01845808 0.006551102 0.02790005 0.018345 -0.006933019 0.02790006 0.01880546 -0.007870529 0.02790008 0.01908436 0.00377278 0.02790008 0.02073746 0.002193987 0.02790011 0.02198908 0.00185914 0.02790007 0.01828491 0.005267009 0.02790007 0.01830053 0.0001265891 0.02790009 0.01915376 0.001590863 0.02790005 0.01837171 -0.00566192 0.02790009 0.01961634 -0.008577049 0.02790007 0.01908436 -0.002227191 0.02790005 0.02116811 -0.003832169 0.02790005 0.01992793 -0.003996763 0.02790006 0.0184124 -0.00111936 0.02790007 0.01901502 -0.004565179 0.02870008 0.02179032 0.003308766 0.02870008 0.01988095 0.003250834 0.02870008 0.01862315 0.004374828 0.02870008 0.01830688 0.005370308 0.02870009 0.01853491 0.006866965 0.0287001 0.01980958 0.007971834 0.02870008 0.02083715 0.008159063 0.02870007 0.02209327 0.007840946 0.02870007 0.02318165 0.006541997 0.02870008 0.02325344 0.005066987 0.0287 0.02279298 0.004129529 0.02870007 0.02095334 -0.002887592 0.02870005 0.01913368 -0.002306115 0.02870006 0.01826922 -0.0006104857 0.02870004 0.01857137 0.000834994 0.02870006 0.01943165 0.001771186 0.02870008 0.02041279 0.002129406 0.02870008 0.0217046 0.002028156 0.02870012 0.02270698 0.001279667 0.02870006 0.02322674 0.0003380589 0.02870007 0.02325345 -0.0009329952 0.02870007 0.02251411 -0.002227224 0.02870006 0.02073307 -0.008917965 0.02870005 0.01899522 -0.008141793 0.02870005 0.0183902 -0.007046875 0.02870005 0.01830429 -0.005974743 0.02870007 0.01906925 -0.004448164 0.02870007 0.02063919 -0.003831044 0.02870005 0.02167054 -0.003996823 0.02870008 0.02258348 -0.004565243 0.02870005 0.02314036 -0.005448904 0.02870006 0.02331353 -0.006732996 0.02870007 0.02251411 -0.008227274 0.02805989 0.01994194 -0.01082776 0.02808874 -0.01215847 -0.007725194 0.02811916 -0.01218329 0.006821618 0.02792986 -0.01205782 0.006762229 0.02792405 -0.01203006 -0.007673901 0.02808635 0.01994227 0.01013881 0.02806064 0.02319344 0.007994574 0.02794772 0.02365487 -0.007600032 0.02804988 0.02376983 -0.007445823 0.02808155 0.02377085 0.006888736 0.02793124 0.02322128 -0.00850771 0.02809717 0.02312679 -0.008756704 0.0287001 0.02216548 0.007120677 0.02870007 0.01943433 0.004164498 0.02870008 0.01882108 0.005174376 0.02870009 0.02272978 0.006294146 0.02870006 0.01891081 0.006363407 0.02870007 0.01961909 0.007308845 0.02870008 0.02109439 0.007685967 0.02870008 0.02033268 0.003687643 0.02870008 0.02276685 0.005258165 0.02870009 0.02235884 0.004344367 0.02870008 0.02134953 0.003709439 0.02870006 0.02203321 0.001248267 0.02870008 0.01941526 -0.001869276 0.02870007 0.01874347 -0.0003144145 0.02870008 0.02272978 0.0002941452 0.02870007 0.01935597 0.001085576 0.02870007 0.02074629 0.001706585 0.02870006 0.02084863 -0.002382968 0.02870007 0.02270515 -0.001061384 0.02870007 0.02196498 -0.001996275 0.02870007 0.02230712 -0.004951105 0.02870004 0.0195597 -0.007962476 0.02870006 0.01882108 -0.006825615 0.02870006 0.02284465 -0.006557334 0.02870005 0.01896059 -0.005477093 0.02870007 0.01991633 -0.004515484 0.02870005 0.02049006 -0.008331295 0.02870001 0.02232527 -0.007651545 0.02870006 0.02152351 -0.008250307 0.02870007 0.02109753 -0.004352685 0.03090006 0.01159922 -0.01084877 0.03090006 0.01777422 -0.01084877 0.03090006 0.01994956 -0.01084877 0.04890005 -0.0002007857 -0.01084879 0.04290005 0.01179922 -0.01084878 0.04890005 0.01179921 -0.01084879 0.04890005 -0.006700786 -0.01084879 0.05177975 -0.008347873 -0.01081485 0.04290005 -0.006700786 -0.01084878 0.05169418 0.01994599 -0.01083931 0.04890005 0.01777422 -0.01084879 0.04890005 0.01994956 -0.01084879 0.03690006 0.01169922 -0.01084878 0.04184181 0.01534949 -0.01084878 0.04290006 0.01829922 -0.01084878 0.04128106 0.01330479 -0.01084878 0.04186364 0.01433265 -0.01084878 0.04290005 -0.0002007857 -0.01084878 0.0413269 0.01622663 -0.01084878 0.03818697 0.01589735 -0.01084878 0.03789844 0.01493916 -0.01084878 0.03690006 0.01829922 -0.01084878 0.03806677 0.01391633 -0.01084878 0.04189709 -0.002830043 -0.01084878 0.0417716 -0.003951164 -0.01084878 0.03902842 0.01296057 -0.01084878 0.04019928 0.01280329 -0.01084878 0.04028033 0.01679817 -0.01084878 0.03910756 0.01665537 -0.01084878 0.05171703 -0.01217645 0.006818835 0.05177186 -0.01215963 -0.007510886 0.03090009 0.01169922 0.01015123 0.04173973 -0.004026175 0.01015122 0.04290009 -0.0002007857 0.01015122 0.04191278 -0.003079794 0.01015121 0.04290009 -0.006700786 0.01015122 0.04890009 -0.006700786 0.01015121 0.05175277 -0.008342475 0.01012706 0.04890009 -0.0002007857 0.01015121 0.05171355 0.0199427 0.01013869 0.04890009 0.01994956 0.01015121 0.04890009 0.01777422 0.01015121 0.04890009 0.01179921 0.01015121 0.04290009 0.01179922 0.01015122 0.03690009 0.01159922 0.01015123 0.03090009 0.01777422 0.01015123 0.03090009 0.01994956 0.01015123 0.03690009 0.01829922 0.01015123 0.03794396 0.01535963 0.01015121 0.03873019 0.0164641 0.01015122 0.04003578 0.01682949 0.01015122 0.04290009 0.01829922 0.01015122 0.04128104 0.01629362 0.01015122 0.04186367 0.01526572 0.01015122 0.04120693 0.01323958 0.01015122 0.0418419 0.01424903 0.01015122 0.03975996 0.01274797 0.01015122 0.03853444 0.01331315 0.01015121 0.03798315 0.01416779 0.01015123 0.0309001 0.02344892 0.007773951 0.03090008 0.0237909 0.006790981 0.03090006 0.02374537 -0.0078291 0.03090005 0.02319877 -0.008712407 0.03010008 0.02102096 0.007673927 0.03010008 0.02000043 0.007491887 0.03010008 0.01919309 0.006900578 0.03010007 0.01875379 0.005442675 0.03010006 0.01948289 0.004099585 0.03010007 0.02043031 0.003678929 0.03010006 0.02143028 0.003716778 0.03010003 0.02239576 0.004416667 0.03010008 0.02279516 0.005351998 0.03010009 0.02268763 0.006363425 0.03010006 0.02210041 0.007193975 0.03010005 0.0213596 0.001607336 0.03010007 0.02032301 0.001600396 0.03010007 0.0192913 0.001048878 0.03010007 0.01875379 -0.0005573258 0.03010009 0.01937177 -0.001775563 0.03010006 0.02057217 -0.002392225 0.03010001 0.02175117 -0.002115045 0.03010006 0.0225055 -0.001457393 0.03010007 0.02282322 -0.0001393929 0.03010007 0.02234251 0.0009517856 0.03010006 0.02050405 -0.004314035 0.03010006 0.01919312 -0.005099423 0.03010005 0.01876476 -0.006385744 0.03010007 0.01923956 -0.007655613 0.03010006 0.02057218 -0.008392237 0.03010006 0.02218322 -0.007869277 0.03010006 0.02282949 -0.006484464 0.0301001 0.02260432 -0.005472623 0.03010008 0.02197923 -0.004691057 0.03690005 0.01149922 -0.01154878 0.03090006 0.01149922 -0.01154877 0.037904 0.01450083 -0.01004878 0.0385024 0.01329133 -0.01004878 0.03993702 0.01276476 -0.01004878 0.04134732 0.01333882 -0.01004878 0.04193426 0.0147498 -0.01004878 0.04151376 0.01603873 -0.01004878 0.04037692 0.01677735 -0.01004878 0.03918786 0.01668764 -0.01004878 0.03813148 0.01584777 -0.01004878 0.04290005 -0.0002007857 -0.01234878 0.04890005 -0.0002007857 -0.01234879 0.04290005 -0.006700786 -0.01192052 0.04290005 -0.006041326 -0.01234878 0.04890005 -0.006700786 -0.01192053 0.04890005 -0.006041326 -0.01234879 0.03090008 0.02001008 0.008047424 0.03090007 0.02149973 0.008096363 0.03090006 0.01838602 -0.005545135 0.03090006 0.01942655 -0.004207488 0.03090007 0.01929922 -0.003721867 0.03090007 0.0210764 -0.003820427 0.03090008 0.0203379 -0.002814077 0.03090008 0.01928974 0.003011994 0.03090008 0.0217972 0.003282871 0.03090006 0.0198939 0.003274292 0.03090009 0.0193083 -0.002378058 0.03090008 0.02179719 -0.002717137 0.03090009 0.01783107 0.004880913 0.03090007 0.01864617 0.007054635 0.03090008 0.02332922 0.005912941 0.03090009 0.0192269 0.00163766 0.03090006 0.020231 0.002129443 0.03090005 0.01841681 -0.007239558 0.03090005 0.01783717 -0.005599428 0.03090008 0.01845942 0.003721621 0.03090011 0.01873918 0.004194983 0.03090008 0.01829055 0.005384512 0.03090008 0.02272828 0.007276893 0.03090007 0.02323643 -0.00116434 0.03090006 0.02297535 -0.005072478 0.03090006 0.02333706 -0.006518401 0.03090005 0.02266718 -0.008075122 0.03090006 0.02095117 -0.008914307 0.03090006 0.01934199 -0.008408196 0.03090008 0.02302705 0.004467443 0.03090008 0.02309752 0.000740841 0.03090009 0.02223493 -0.004292298 0.03090012 0.01853382 -0.004311517 0.03090008 0.02190281 0.001942843 0.03090005 0.01179922 -0.01234877 0.03090005 0.01771674 -0.01234073 0.03690005 0.01179922 -0.01234877 0.03690005 0.01829922 -0.01192052 0.03690005 0.01763976 -0.01234877 0.03315005 0.01829922 -0.01192051 0.03315007 0.01833442 -0.005766638 0.04665006 0.01832022 -0.005897235 0.04290005 0.01829922 -0.01192052 0.04665005 0.01829922 -0.01192053 0.04290005 0.01179922 -0.01234878 0.04290005 0.01763976 -0.01234878 0.04890005 0.01179921 -0.01234879 0.04890005 0.0177163 -0.01234136 0.04890006 0.01877293 -0.007929724 0.04890005 0.02043034 -0.008865397 0.04890008 0.01880357 0.004107859 0.04890008 0.02001035 0.003233131 0.04890008 0.01929922 0.003024299 0.04890003 0.02209318 -0.008538559 0.04890006 0.0234489 -0.0084715 0.04890008 0.02329791 0.005175881 0.04890008 0.02374537 0.007131487 0.04890008 0.02379089 -0.00748853 0.04890007 0.02198206 0.001879558 0.04890007 0.02052203 0.00217957 0.04890006 0.01930206 0.00166465 0.04890005 0.01827697 -0.0062958 0.04890005 0.01778668 -0.00601818 0.04890005 0.01818096 -0.0047528 0.04890005 0.01854288 -0.005253501 0.04890009 0.01932419 -0.004276629 0.04890007 0.01928974 -0.003709551 0.04890007 0.02074514 -0.00382657 0.04890005 0.02318164 -0.00723958 0.04890007 0.02217191 -0.004207481 0.04890007 0.02128977 -0.002844538 0.04890009 0.02302146 -0.005185991 0.04890008 0.02126038 0.00318585 0.04890009 0.02291858 0.00101969 0.04890012 0.02274883 -0.00198235 0.04890007 0.0233423 -0.0003950186 0.04890003 0.01937967 -0.002476107 0.04890006 0.02328193 -0.005992643 0.04890009 0.02244465 0.003711618 0.04890006 0.02311939 0.006641861 0.04890009 0.02052203 0.008179567 0.04890008 0.022172 0.007792432 0.04890008 0.01917274 0.007579573 0.04890008 0.01834984 0.006336719 0.04890008 0.01780961 0.005110297 0.04890008 0.01836715 0.003783669 0.04890021 0.02319865 0.008014914 0.04890011 0.01835565 0.0050858 0.05174592 0.02312405 -0.008745663 0.05188671 0.01989752 -0.01067356 0.05190705 -0.008382626 -0.01054757 0.05186947 -0.01175211 -0.008350916 0.05166478 -0.01204876 -0.008049726 0.02811302 -0.01170192 -0.008605473 0.05172143 -0.0115234 -0.008764863 0.05185953 -0.01207716 0.0005965345 0.0518959 -0.01196753 0.007058475 0.05190436 -0.01194392 -0.002135463 0.05189627 -0.01194686 -0.007604096 0.05190884 -0.01118519 -0.004283011 0.05168248 -0.01159795 0.008018728 0.02807685 -0.01164347 0.007958367 0.05167226 -0.01206696 0.007304374 0.0280938 -0.01208117 0.007245678 0.05186159 -0.01154235 0.007879306 0.05189754 -0.008323855 0.009909216 0.03090009 0.01149922 0.01085123 0.03690009 0.01149922 0.01085123 0.03798314 0.01543061 0.009351228 0.03797976 0.01406458 0.009351216 0.03918285 0.01287234 0.009351224 0.04053231 0.01288255 0.009351224 0.0417439 0.0138326 0.009351228 0.04180164 0.01552348 0.00935122 0.04106508 0.01644723 0.009351213 0.03993705 0.01683368 0.009351224 0.03865077 0.01640534 0.009351228 0.04290009 -0.0002007857 0.01165122 0.04890009 -0.0002007857 0.01165121 0.04890009 -0.006700786 0.01122295 0.04890009 -0.006041326 0.01165121 0.04290009 -0.006700786 0.01122296 0.04290009 -0.006041326 0.01165122 0.05168557 0.02301505 0.008143048 0.04890009 0.01179921 0.01165121 0.04890009 0.0177163 0.01164378 0.04290009 0.01179922 0.01165122 0.04290009 0.01829922 0.01122296 0.04290009 0.01763976 0.01165122 0.04665009 0.01829922 0.01122295 0.0466501 0.01833442 0.005069085 0.03315007 0.01836928 0.004833922 0.03690009 0.01829922 0.01122297 0.03315009 0.01829922 0.01122297 0.03690009 0.01179922 0.01165123 0.03690009 0.01763976 0.01165123 0.03090009 0.01179922 0.01165123 0.03090009 0.01771675 0.01164319 0.05189015 0.01997769 0.009947427 0.02806952 0.02351463 0.007585727 0.02811587 0.02363813 -0.008079935 0.03010008 0.0218874 0.003375217 0.03010007 0.02312311 0.004553646 0.03010008 0.02321244 0.006454855 0.03010007 0.02199446 0.007926445 0.03010008 0.02009876 0.008096404 0.03010008 0.01871816 0.007113654 0.03010008 0.01825924 0.005259283 0.0301001 0.01924989 0.003634099 0.03010007 0.02063926 0.003133494 0.03010006 0.02205525 -0.002519772 0.03010009 0.02285926 -0.001804985 0.03010006 0.02325876 -0.0008400642 0.03010006 0.02325344 0.0002355166 0.03010006 0.02265684 0.001358185 0.03010007 0.02158851 0.002047386 0.03010002 0.02010739 0.002098013 0.03010001 0.01888278 0.001296464 0.03010006 0.01822954 -0.000305824 0.03010009 0.01868363 -0.001696046 0.03010007 0.01961183 -0.002597652 0.03010007 0.02106703 -0.002857316 0.03010004 0.02290418 -0.007823315 0.03010006 0.02331688 -0.006187685 0.03010008 0.02302149 -0.005185966 0.03010004 0.02234162 -0.004352443 0.03010006 0.02117211 -0.003853671 0.03010006 0.02013044 -0.003931455 0.03010007 0.01899516 -0.004555784 0.03010006 0.01826922 -0.006087057 0.03010005 0.01857141 -0.007532586 0.03010007 0.01943171 -0.008468773 0.03010006 0.02041276 -0.008826938 0.03010006 0.0214871 -0.008775994 0.04844279 -0.003139026 -0.01234879 0.04783957 -0.001555307 -0.01234879 0.04637539 -0.0007020962 -0.01234879 0.04470012 -0.0009580944 -0.01234879 0.04367175 -0.002017936 -0.01234878 0.04802001 -0.004568295 -0.01234879 0.04443932 -0.005239647 -0.01234879 0.04563837 -0.005730787 -0.01234879 0.04337783 -0.003254877 -0.01234878 0.04372448 -0.004478117 -0.01234878 0.04708391 -0.005428586 -0.01234879 0.0331501 0.01783717 0.004901882 0.03315 0.0184087 0.00378485 0.03315008 0.01929603 0.002994921 0.03315009 0.01777422 0.01156391 0.03315007 0.01783106 -0.005578469 0.03315005 0.01777422 -0.01226145 0.03315007 0.01929922 -0.003721867 0.03315007 0.01861262 -0.004227169 0.03090007 0.01828491 3.546104e-05 0.03090007 0.01859404 -0.001613557 0.03615 0.01361302 -0.01234877 0.03636968 0.01551058 -0.01234877 0.03518065 0.01699682 -0.01234877 0.03219307 0.0166569 -0.01234877 0.03351582 0.01731353 -0.01234877 0.03142377 0.01538017 -0.01234877 0.03160847 0.0136956 -0.01234877 0.03281044 0.01250093 -0.01234877 0.03427405 0.01230429 -0.01234877 0.03524718 0.01268355 -0.01234877 0.04665005 0.01777422 -0.01226147 0.04665004 0.01783717 -0.005599447 0.04665004 0.01877525 -0.004849199 0.04665012 0.01840882 -0.004482378 0.04665007 0.01929603 -0.003692497 0.04665007 0.01929922 -0.004348784 0.03315007 0.01927338 -0.004291769 0.04814998 0.01361301 -0.01234879 0.0484086 0.01506705 -0.01234879 0.04807085 0.01605549 -0.01234879 0.04735637 0.01685923 -0.01234879 0.04594625 0.0173423 -0.01234879 0.04410706 0.01299519 -0.01234879 0.04542154 0.01232222 -0.01234879 0.04337169 0.01452205 -0.01234878 0.04690544 0.01246286 -0.01234879 0.0443384 0.01680689 -0.01234879 0.04359917 0.01579755 -0.01234878 0.04970008 0.02104975 0.008146796 0.04970007 0.0198082 0.007993706 0.04970009 0.01843997 0.006670557 0.04970008 0.01847532 0.004553646 0.04970006 0.01971095 0.003375158 0.04970008 0.02116805 0.003134586 0.04970011 0.02266718 0.003924906 0.04970008 0.02333706 0.005481575 0.04970004 0.02305561 0.006746378 0.04970006 0.02227424 0.007723335 0.04970007 0.02149969 -0.003903653 0.04970007 0.01980808 -0.004006345 0.04970007 0.01867982 -0.004980404 0.04970006 0.01825614 -0.006395016 0.0497001 0.01873923 -0.007805135 0.04970007 0.02008779 -0.008818407 0.04970006 0.02178886 -0.008669365 0.04970014 0.02265681 -0.008034084 0.04970007 0.02319505 -0.007139102 0.04970007 0.02329156 -0.006067883 0.04970007 0.0228803 -0.004886426 0.04665008 0.01780427 0.005098354 0.04665007 0.01831977 0.003880933 0.04665009 0.0192968 0.003006831 0.04665009 0.01777422 0.01156389 0.05176131 0.02317698 0.007984716 0.05171029 0.02354762 0.007528186 0.05167858 0.0237775 0.006894003 0.05164129 0.02379385 -0.007401727 0.05167759 0.02358939 -0.008171294 0.04970003 0.01902035 -0.002139036 0.04890007 0.01836201 -0.001164362 0.04970008 0.01830053 -0.0008241236 0.04890008 0.01850092 0.0007408187 0.04970007 0.01847903 0.0006417967 0.04970005 0.01925888 0.001647025 0.04970007 0.02042622 0.002146274 0.04970006 0.0216905 0.002011325 0.04970007 0.02272828 0.001276955 0.04970007 0.02332922 -8.708611e-05 0.04970007 0.02302706 -0.001532584 0.04970004 0.02216682 -0.002468716 0.04970007 0.02095921 -0.002866525 0.0497 0.01992823 -0.002700765 0.05189526 0.02287263 -0.008678026 0.05190014 0.003504043 -0.006249934 0.05189995 0.001155354 -0.008146417 0.05190007 0.01852271 0.004564006 0.05190005 0.02291492 0.004304115 0.05190007 0.0228803 0.001113538 0.05190007 0.02333706 -0.0005184337 0.05190007 0.02256184 -0.004564472 0.05190005 0.02302703 -0.007532586 0.0519001 0.02216676 0.003531229 0.05190007 0.02062432 0.002153218 0.05190008 0.02169032 0.002011389 0.05190008 0.02104969 0.008146785 0.05190011 0.02207642 0.007826787 0.05190015 -0.006879976 0.007790237 0.05190008 -0.003928026 0.008553516 0.0518966 0.02304239 0.007834699 0.05190007 0.02309752 0.006740786 0.05190008 0.02329415 0.005277164 0.05189269 0.02354884 0.007193856 0.05190006 0.02129858 -0.003827732 0.05190007 0.02198533 -0.008598763 0.05190006 0.02030861 -0.008844536 0.05190007 -0.0009501856 0.008294925 0.05190008 0.001139704 0.007421024 0.05189999 0.01919416 -0.008276205 0.05190007 0.01852271 -0.007436045 0.0519001 -0.01117637 0.003672484 0.05191049 -0.009396575 0.006086678 0.05190007 0.01828156 -0.006187715 0.05190001 0.018577 -0.005185876 0.05190006 0.02138239 -0.002803273 0.05190009 0.01942655 -0.004207492 0.05190007 0.01968063 -0.002662644 0.05190006 -0.001691205 -0.009152245 0.05190006 -0.004710306 -0.009152252 0.05190007 0.02095918 0.003133457 0.05190007 0.01961634 0.001879524 0.0519001 0.0195052 0.003461506 0.05190008 0.01867985 0.001019757 0.05190006 0.01864384 -0.001631375 0.05190007 0.01825614 -0.0003950149 0.05190008 0.005723104 -0.0007279366 0.05189996 0.005087076 -0.003679074 0.0519001 0.0189416 0.007358257 0.05190007 0.002979584 0.006099586 0.05190008 0.004377823 0.004317537 0.05190007 0.01828491 0.006035436 0.05190008 0.02001002 0.008047358 0.05189997 -0.007556643 -0.008146651 0.05190004 -0.009905774 -0.006249886 0.05190004 0.005339645 0.002266705 0.0279182 -0.01163983 -0.008454542 0.05471918 -0.01202297 -0.001494147 0.05481668 -0.01200412 0.0007052198 0.05468235 -0.01153091 0.002922922 0.0546936 -0.009935699 0.005492721 0.05470045 -0.008185219 0.007025193 0.05468948 -0.006234115 0.008035232 0.05469807 -0.003360776 0.008590974 0.0546944 -0.0002218559 0.008082662 0.05468365 0.002401043 0.006587785 0.05469987 0.003954545 0.004943293 0.05468036 0.005072065 0.002975404 0.0547001 0.005627135 0.0007816516 0.05470697 0.005632656 -0.001641851 0.05469371 0.004789144 -0.004305336 0.05470841 0.002995484 -0.00679627 0.05470375 0.0004714038 -0.008472908 0.05470005 -0.001696797 -0.009120818 0.05469679 -0.004173916 -0.00922257 0.05469374 -0.006814836 -0.00849931 0.05470004 -0.009210657 -0.006949518 0.05469532 -0.01121664 -0.004331466 0.05178695 -0.01186474 0.007584274 0.02797338 -0.01195364 0.007356785 0.02794933 -0.0114718 0.007949088 0.04345494 -0.002500296 0.01165122 0.04443774 -0.001119686 0.01165121 0.04669038 -0.000804957 0.01165121 0.04775845 -0.001494596 0.01165121 0.04835453 -0.002617488 0.0116512 0.04561914 -0.0007084459 0.01165121 0.04433842 -0.005208427 0.01165121 0.04350389 -0.003990045 0.01165122 0.04821392 -0.004319327 0.01165121 0.04679088 -0.005583197 0.01165121 0.04554398 -0.005683496 0.01165121 0.04551587 0.01228491 0.01165121 0.04402157 0.01308442 0.01165122 0.04340501 0.01442628 0.01165121 0.0472859 0.01693204 0.01165121 0.04822067 0.01578882 0.01165121 0.04839582 0.01430863 0.01165122 0.04737465 0.01269427 0.0116512 0.04360849 0.01590287 0.01165122 0.04481047 0.0170975 0.01165121 0.04604441 0.01730319 0.01165121 0.03315008 0.01928973 0.003642075 0.04665007 0.01927339 0.003594216 0.03135667 0.01443025 0.01165123 0.03172455 0.01607655 0.01165123 0.03429205 0.0173392 0.01165123 0.03591723 0.01634858 0.01165123 0.03641782 0.01495921 0.01165123 0.0356835 0.01301497 0.01165123 0.03625197 0.01392793 0.01165123 0.03416081 0.01224244 0.01165123 0.03262371 0.01697532 0.01165123 0.03233844 0.01279156 0.01165123 0.04342324 -0.002721157 -0.01154878 0.0434636 -0.003796076 -0.01154878 0.04402156 -0.004915627 -0.01154878 0.0453158 -0.005655005 -0.01154879 0.04658684 -0.005628286 -0.01154879 0.04752837 -0.005108455 -0.01154879 0.04827698 -0.004106166 -0.01154879 0.0483181 -0.002411885 -0.01154879 0.04728579 -0.001067907 -0.01154879 0.04584703 -0.0006785374 -0.01154879 0.04480486 -0.0009443965 -0.01154879 0.04397173 -0.001574155 -0.01154878 0.0314238 0.0142183 -0.01154877 0.0321931 0.0129416 -0.01154877 0.03351583 0.01228492 -0.01154877 0.03518063 0.01260165 -0.01154877 0.03617608 0.01371107 -0.01154878 0.03640789 0.01476127 -0.01154878 0.03622063 0.01578895 -0.01154878 0.0355855 0.01665668 -0.01154877 0.03449614 0.01727188 -0.01154877 0.03281045 0.01709753 -0.01154877 0.03160847 0.01590287 -0.01154877 0.04342324 0.01527885 -0.01154878 0.04346358 0.01420411 -0.01154878 0.04390371 0.01325685 -0.01154878 0.04509643 0.01238602 -0.01154879 0.04679085 0.01241681 -0.01154879 0.04808972 0.01350519 -0.01154879 0.04841666 0.01516807 -0.01154879 0.04762634 0.01666721 -0.01154879 0.04627406 0.01729415 -0.01154879 0.04500988 0.01715973 -0.01154879 0.04397162 0.01642591 -0.01154878 0.04970009 0.0209225 0.007682279 0.04970007 0.02203321 0.007248264 0.04970009 0.02272979 0.006294098 0.04970008 0.02270515 0.004938576 0.04970008 0.02196497 0.004003636 0.04970008 0.02067765 0.003598753 0.04970005 0.01930485 0.004270177 0.04970008 0.01880327 0.005351998 0.04970006 0.01891081 0.006363377 0.04970007 0.01961915 0.007308845 0.04970007 0.02189732 -0.004635736 0.04970007 0.02272979 -0.005705904 0.04970006 0.02265833 -0.007226877 0.04970006 0.02166981 -0.008169625 0.04970005 0.0206712 -0.008362983 0.0497001 0.01970512 -0.008044794 0.04970006 0.01884945 -0.007001255 0.04970004 0.01891079 -0.005636636 0.04970005 0.01961921 -0.004691064 0.04970007 0.02075594 -0.004331011 0.0518546 0.02366479 0.006887827 0.04970008 0.0209225 0.001682278 0.04970006 0.02203321 0.001248237 0.04970008 0.02279729 0.0001359656 0.04970008 0.02262043 -0.001218595 0.04970004 0.02183436 -0.002100613 0.04970007 0.02067114 -0.002362967 0.04970011 0.01970521 -0.002044793 0.04970007 0.01901698 -0.001295805 0.04970007 0.01878142 -0.0003064051 0.04970005 0.01905833 0.0006722771 0.04970007 0.01977729 0.001391634 0.05110007 0.02095332 0.008190024 0.05110006 0.01932419 0.007723305 0.05110003 0.01854285 0.006746378 0.05110007 0.01827697 0.005704206 0.05110007 0.01857142 0.004467383 0.05110002 0.01943165 0.003531229 0.05110009 0.02041285 0.003173008 0.05110006 0.02148701 0.003223956 0.05110015 0.02240437 0.003723975 0.05110009 0.02307574 0.004564006 0.05110008 0.02330641 0.005582657 0.05110007 0.02304191 0.006851073 0.05110003 0.02217207 0.007750288 0.05110006 0.02199442 0.001926407 0.05110006 0.02054874 0.002146784 0.05110005 0.01932417 0.001723334 0.05110013 0.01854282 0.0007463135 0.05110006 0.01826138 -0.0005184263 0.05110006 0.01893127 -0.002075147 0.05110006 0.02021604 -0.002803266 0.05110008 0.02126044 -0.002814144 0.05110001 0.02225629 -0.002408285 0.05110008 0.02307574 -0.001435995 0.05110007 0.02330641 -0.0004173443 0.0511001 0.02311939 0.0006418265 0.05110004 0.02158854 -0.003952663 0.05110006 0.02054881 -0.003853202 0.05110009 0.01952192 -0.004173305 0.05110007 0.01850092 -0.005259223 0.05110006 0.01829525 -0.006493103 0.05110005 0.0185714 -0.007532615 0.05110007 0.01961301 -0.008598745 0.05110006 0.02106702 -0.008857347 0.05110007 0.02244462 -0.008288383 0.05110012 0.02314036 -0.007248685 0.05110006 0.02331353 -0.005964555 0.05110004 0.02265684 -0.004641846 0.05490022 -0.002610136 -0.00904829 0.05490019 0.0004013944 -0.008319322 0.05490045 0.003336763 -0.006151192 0.05490004 0.005036784 -0.003205471 0.05490033 0.005530725 -4.599988e-05 0.05490009 0.004881175 0.002898548 0.05490029 0.003449185 0.005274329 0.05490012 0.001671704 0.006859198 0.05490006 -0.0001267157 0.007791895 0.05489893 -0.003148276 0.008392639 0.05490002 -0.005923117 0.007915881 0.05490018 -0.008755219 0.006396968 0.05490033 -0.01106904 0.003467128 0.05490023 -0.01187906 -0.00124491 0.05490009 -0.01112478 -0.003986079 0.05490051 -0.009044111 -0.006903242 0.05490012 -0.005559296 -0.008755144 0.04362486 -0.002005577 0.01085122 0.04345493 -0.003901286 0.01085122 0.04411578 -0.004963467 0.01085122 0.04521458 -0.005650167 0.01085122 0.04669033 -0.005596617 0.01085122 0.04791716 -0.004750177 0.01085121 0.04837823 -0.003587276 0.01085121 0.04827702 -0.002295436 0.01085122 0.04752832 -0.001293026 0.01085121 0.04658694 -0.0007732772 0.01085122 0.04509642 -0.0007875674 0.01085122 0.04350392 0.01558845 0.01085123 0.04345493 0.01409876 0.01085122 0.04411562 0.01303657 0.01085122 0.04521454 0.01234986 0.01085122 0.04711583 0.01253491 0.01085121 0.04831814 0.01401029 0.01085121 0.0483273 0.01548725 0.01085121 0.04753367 0.01674879 0.01085121 0.04616679 0.01730789 0.01085122 0.0444967 0.01695229 0.01085122 0.03133088 0.01473306 0.01085123 0.03197167 0.01317262 0.01085123 0.03300982 0.01243871 0.01085123 0.03449615 0.01232655 0.01085122 0.03606572 0.01341536 0.01085123 0.03640864 0.01506701 0.01085123 0.03570914 0.01662472 0.01085123 0.03416681 0.01730789 0.01085123 0.03290942 0.01711941 0.01085123 0.03190371 0.01634162 0.01085123 0.04541526 -0.001202717 -0.0115488 0.04692455 -0.001442706 -0.01154879 0.04772087 -0.002330257 -0.01154879 0.04790244 -0.003667455 -0.0115488 0.04687264 -0.005012235 -0.0115488 0.04535161 -0.005160276 -0.01154879 0.04424234 -0.004380777 -0.01154879 0.04388227 -0.003244057 -0.01154878 0.04418703 -0.002102656 -0.01154879 0.03318279 0.01287236 -0.01154877 0.03215959 0.01377739 -0.01154877 0.03186532 0.01509444 -0.01154878 0.03277736 0.01652166 -0.01154878 0.03428033 0.01679817 -0.01154877 0.03545168 0.01611555 -0.01154877 0.03590689 0.01501348 -0.01154877 0.03570004 0.01385026 -0.01154877 0.03470435 0.01293013 -0.01154877 0.04418698 0.01589738 -0.01154879 0.04525717 0.01672977 -0.01154879 0.04661266 0.01670516 -0.01154879 0.04754754 0.0159651 -0.01154879 0.0479069 0.01501343 -0.01154879 0.04775649 0.01400733 -0.01154879 0.0470087 0.01309297 -0.0115488 0.04569066 0.01277523 -0.01154879 0.04459948 0.0132559 -0.01154879 0.04388319 0.01439971 -0.01154879 0.05110007 0.02050089 0.00764728 0.05110005 0.01956513 0.007248264 0.05110009 0.01894309 0.006443739 0.05110008 0.01880026 0.005270947 0.05110005 0.01948289 0.004099555 0.05110007 0.02092079 0.003598764 0.05110006 0.02216413 0.004164528 0.05110008 0.02277736 0.005174346 0.05110009 0.02263786 0.006522898 0.05110009 0.02168211 0.007484473 0.05110006 0.02050405 -0.004314065 0.05110009 0.01931309 -0.004983273 0.05110006 0.01878777 -0.006041393 0.05110004 0.01904113 -0.007373303 0.05110007 0.02007496 -0.008250337 0.05110003 0.02143027 -0.008283265 0.05110003 0.0225055 -0.007457424 0.05110005 0.02282322 -0.006139424 0.05110006 0.02213161 -0.004782907 0.05110008 0.02118287 0.001632657 0.05110007 0.01984299 0.001471348 0.05110008 0.01894308 0.000443738 0.05110006 0.01879228 -0.0005621538 0.05110003 0.01915122 -0.001513887 0.0511001 0.01992878 -0.002169672 0.05110008 0.02092725 -0.002362974 0.05110007 0.02203876 -0.001962483 0.05110002 0.02264948 -0.001125023 0.05110007 0.02282322 -0.0001394227 0.05110011 0.02224238 0.001085665 0.05490006 -0.003888667 -0.00877602 0.05490006 -0.002617577 -0.008803282 0.05490006 -0.005302006 -0.007826392 0.05490007 -0.0007287674 -0.00693275 0.05490003 -0.001494506 -0.008207124 0.05490007 -0.007426925 -0.003768872 0.05490004 -0.006812276 -0.004064165 0.05490007 -0.006027536 -0.003306802 0.05490007 -0.007394805 -0.005412422 0.05490007 -0.008082937 -0.005124815 0.05490007 -0.006845636 -0.005143832 0.05490007 -0.006631317 -0.004645672 0.05490007 -0.008199207 -0.004183989 0.05490007 -0.009560399 0.002145186 0.05490007 -0.01108569 0.001398318 0.05490007 -0.01135618 -0.001631364 0.05490007 -0.01049693 -0.002536543 0.05490007 -0.01174386 -0.000395041 0.05490008 -0.007561516 0.004707731 0.05490008 -0.006794346 0.004434608 0.05490008 -0.006679267 0.003562879 0.05490007 -0.007466987 0.003035538 0.05490007 -0.006027536 0.002419029 0.05490006 -0.008187037 0.003542557 0.05490009 -0.008176778 0.004288379 0.05490006 -0.0007934663 0.00633968 0.05490008 -0.001271637 0.007276889 0.05490008 -0.002500296 0.00809633 0.05490011 -0.003989928 0.00804735 0.05490006 -0.005361196 0.007047538 0.05490008 0.0009925328 0.004706256 0.05490008 0.001495823 0.00318132 0.05490007 -0.0002427958 0.00247794 0.05490008 0.0006839242 0.003153399 0.05490008 0.0004930738 0.004494957 0.05490008 0.0002028327 0.00381868 0.05490009 0.001574865 0.004520148 0.05490008 0.001864154 0.003907569 0.05489997 0.004209053 -0.002434723 0.05490007 0.005135585 -0.001354162 0.05490007 0.005248595 0.0003367066 0.05490004 0.004181964 0.001806609 0.05490007 0.001407873 -0.003845662 0.05490007 0.001886584 -0.00457849 0.05490007 0.001090474 -0.00541243 0.05490008 0.0004576836 -0.005170331 0.05490007 0.0002253354 -0.004587382 0.05490007 0.001587834 -0.005186193 0.05490009 -0.005699497 0.005175919 0.05490004 -0.004288968 0.00337515 0.05490008 -0.005108396 0.004022829 0.05490008 -0.0007058568 0.005277179 0.05490009 -0.001470756 0.003750611 0.05490007 -0.003040826 0.003133457 0.05490007 -0.008532219 0.002068568 0.05490009 -0.007574249 0.001579646 0.05490007 -0.007332817 -0.002075099 0.05490007 -0.008831911 -0.002865404 0.05490005 -0.006840266 0.0005414188 0.05490007 -0.006705856 -0.0007228218 0.05490007 -0.005715098 -0.005964629 0.05490007 -0.004763326 -0.004308302 0.05490007 -0.003146717 -0.003826581 0.05490007 -0.001725808 -0.004276674 0.05490007 -0.0002427958 -0.003614791 0.05490007 -0.0008402765 -0.005458541 0.0549001 0.003249533 -0.002822299 0.05490007 0.0009143147 0.001398247 0.05490007 0.002584104 0.00217833 0.05490005 0.002111334 -0.002776019 0.05490007 0.001014914 -0.002132263 0.05490007 0.0002424344 -0.000609532 0.05490007 -0.003853426 0.002376918 0.05490007 -0.002882756 0.002441947 0.0549001 -0.005111437 0.001752529 0.05490007 -0.005995756 -0.0008840598 0.0549001 -0.005863936 0.0005245991 0.05490001 -0.005196618 -0.002342351 0.05489998 -0.004186546 -0.00297248 0.05490007 -0.002784606 -0.003163964 0.05490009 -0.0004329253 -0.0009990633 0.05490007 -0.001293756 -0.002427459 0.05490006 -0.0005695261 0.0006608069 0.05490008 -0.001561567 0.001976308 0.05490004 0.0005320925 -0.003915891 0.04684713 -0.001418537 0.01085121 0.04569069 -0.001176786 0.0108512 0.04459945 -0.001657525 0.01085122 0.04401196 -0.002487846 0.01085122 0.04390401 -0.003499238 0.01085122 0.04450245 -0.004708726 0.01085122 0.04593704 -0.005235247 0.01085122 0.04734737 -0.004661156 0.01085121 0.04790693 -0.003415065 0.01085121 0.04770007 -0.002251886 0.01085121 0.04720694 0.01323954 0.01085121 0.04794354 0.01457218 0.01085121 0.04759613 0.01589326 0.01085121 0.04670436 0.01666833 0.01085122 0.04535168 0.01675873 0.01085122 0.04435727 0.01610041 0.01085122 0.04384473 0.01485215 0.01085122 0.04430295 0.01356538 0.01085122 0.04510757 0.01294308 0.01085122 0.04611351 0.0127923 0.01085122 0.03294017 0.01300508 0.01085123 0.03445135 0.01281847 0.01085123 0.0355476 0.0136335 0.01085123 0.03593427 0.01474981 0.01085122 0.03542061 0.01618319 0.01085123 0.03419929 0.01679517 0.01085123 0.03318785 0.01668762 0.01085123 0.03235739 0.01610053 0.01085123 0.03187741 0.01502097 0.01085122 0.03211743 0.01385291 0.01085123 0.04387738 -0.002979027 -0.01014878 0.04405937 -0.003999567 -0.01014878 0.04465072 -0.004806887 -0.01014879 0.045937 -0.005235247 -0.01014879 0.04706512 -0.004848877 -0.01014879 0.04780158 -0.003925046 -0.01014879 0.04779474 -0.002402416 -0.01014879 0.04655251 -0.001251016 -0.01014879 0.04518783 -0.001312356 -0.01014879 0.04435741 -0.001899466 -0.01014879 0.0319186 0.0151829 -0.01014877 0.03202607 0.01400636 -0.01014878 0.03280522 0.01310376 -0.01014877 0.03393702 0.01276476 -0.01014877 0.03520691 0.01323954 -0.01014877 0.03584178 0.01424882 -0.01014877 0.03583452 0.01543037 -0.01014877 0.03500866 0.0165055 -0.01014877 0.03369068 0.01682322 -0.01014877 0.0324656 0.01624244 -0.01014877 0.04394395 0.0153596 -0.01014878 0.04398308 0.01416798 -0.01014878 0.04477733 0.0130768 -0.01014879 0.04628035 0.01280028 -0.01014879 0.04732684 0.01337184 -0.01014879 0.04789665 0.01440674 -0.0101488 0.04775656 0.01559089 -0.01014879 0.0470087 0.01650549 -0.01014879 0.04569068 0.01682322 -0.01014879 0.04459924 0.01634241 -0.01014879 0.05190007 0.001360724 -0.003843244 0.05190009 0.0006772149 -0.003843982 0.05190007 0.0002879836 -0.004305016 0.05190007 0.0002796035 -0.004924055 0.05190007 0.0008551739 -0.005392384 0.05190007 0.001519784 -0.005260755 0.05190007 0.001841433 -0.004743546 0.05190009 0.001759505 -0.004207455 0.05190007 0.0002118628 0.004044458 0.05190007 0.0005879235 0.003181316 0.05190007 0.001467163 0.003177907 0.05190007 0.001884645 0.003952563 0.05190004 0.001535404 0.004532724 0.0519001 0.0008765645 0.004722334 0.05190007 -0.007258667 -0.003800113 0.05190007 -0.007925223 -0.003911004 0.05190007 -0.008253027 -0.004507713 0.05190004 -0.008091826 -0.005097363 0.05190005 -0.007348986 -0.005430974 0.05190007 -0.006629218 -0.004816834 0.05190004 -0.006800987 -0.004091695 0.05190009 -0.007466316 0.004738357 0.05190007 -0.008060787 0.004414037 0.05190007 -0.008278206 0.003763866 0.05190008 -0.007699866 0.003101576 0.0519001 -0.006903205 0.003260106 0.05190007 -0.006622927 0.003949888 0.05190012 -0.006848937 0.004440036 0.05442234 -0.0003899764 -0.000253737 0.05441761 -0.0006210562 -0.001445279 0.05439923 -0.001211647 -0.002344355 0.05441777 -0.002506556 -0.003092658 0.05439989 -0.003716016 0.00242224 0.05441723 -0.004784927 0.001978871 0.05440034 -0.005483726 0.001288172 0.05439973 -0.005988207 0.0001221225 0.05439991 -0.005883267 -0.00121332 0.05439991 -0.005110877 -0.00242006 0.05440023 -0.003893236 -0.003077157 0.05442485 -0.000705516 0.0009635314 0.05440047 -0.001487855 0.001891002 0.05440089 -0.002567436 0.002387751 0.05410006 0.004094394 -0.002537455 0.05410006 0.005075734 -0.001435999 0.05410006 0.005313525 3.545359e-05 0.05410007 0.004656773 0.001358252 0.05410007 0.003376573 0.002124041 0.05410007 0.001695534 0.001942754 0.05410019 0.0007605627 0.001112342 0.05410006 0.0003222246 0.0001297332 0.05410006 0.0004628636 -0.001354199 0.05410003 0.001253184 -0.002323817 0.05410007 0.002430363 -0.002865408 0.05410005 -0.005532257 -0.007355075 0.05410005 -0.004386958 -0.008598767 0.05410006 -0.002933037 -0.008857358 0.05410006 -0.001743646 -0.008408226 0.05410008 -0.0009291861 -0.007440217 0.05410005 -0.000683127 -0.006187707 0.0541001 -0.001193127 -0.004787147 0.05410007 -0.002202088 -0.004048057 0.05410006 -0.003254825 -0.003826577 0.05410004 -0.004866235 -0.004391458 0.05410005 -0.005677797 -0.005870297 0.0541001 -0.01043393 0.001858752 0.05410013 -0.01123956 0.001112211 0.05410007 -0.01173078 -8.706748e-05 0.05410006 -0.01142859 -0.001532625 0.05410012 -0.01056847 -0.002468739 0.05410007 -0.009415239 -0.002868287 0.05410006 -0.00832953 -0.002700675 0.05410009 -0.007251248 -0.001982328 0.05410007 -0.006692115 -0.0006155186 0.05410002 -0.006880596 0.0006418042 0.05410007 -0.00782809 0.001792502 0.05410007 -0.00925488 0.002173424 0.05410007 -0.005677486 0.006122001 0.05410007 -0.005644346 0.005085822 0.05410013 -0.005196467 0.004107903 0.0541001 -0.004190456 0.003330633 0.05410007 -0.002710216 0.00315544 0.05409996 -0.001416497 0.003867771 0.05410007 -0.0007732865 0.004964292 0.05410008 -0.0007923748 0.006456144 0.0541001 -0.001658315 0.007647522 0.05410007 -0.002827765 0.008146282 0.05410004 -0.004091976 0.008011322 0.05410008 -0.005129935 0.007276952 0.04390402 -0.002902336 0.009451218 0.04406681 -0.004083706 0.009451207 0.04487891 -0.004941626 0.009451214 0.04603579 -0.005231056 0.009451203 0.04713466 -0.004797356 0.00945121 0.04790247 -0.003667455 0.0094512 0.04772094 -0.002330316 0.00945121 0.04677812 -0.001341667 0.00945121 0.04525713 -0.001270216 0.009451214 0.04430306 -0.001966916 0.009451214 0.04394452 0.01543404 0.009451218 0.04406682 0.01391633 0.009451218 0.04487906 0.0130583 0.009451214 0.04603579 0.01276896 0.009451214 0.04728112 0.01330482 0.00945121 0.04795252 0.01467764 0.00945121 0.04754757 0.01596503 0.00945121 0.04676982 0.01662044 0.0094512 0.0455927 0.01681067 0.009451214 0.04468258 0.01639423 0.009451214 0.0318774 0.01457747 0.009451233 0.03235735 0.01349794 0.009451233 0.03335165 0.01283972 0.009451229 0.0347044 0.01293013 0.009451229 0.03570009 0.01385026 0.009451229 0.03589668 0.01519172 0.009451229 0.03507969 0.01648319 0.009451229 0.03359269 0.01681067 0.009451229 0.03226769 0.01604925 0.009451233 0.05475691 -0.003716856 -0.001918547 0.05478791 -0.002739737 0.001093052 0.05468086 -0.005091606 -0.0007723086 0.05479387 -0.004531678 0.0002696216 0.05489887 -0.002708856 -0.0008430518 0.05410006 0.0007537845 -0.0005573593 0.05410006 0.001371773 -0.001775566 0.05410005 0.002248904 -0.002290588 0.05410006 0.003430335 -0.002283279 0.05410006 0.004610674 -0.001321398 0.05410006 0.004758714 0.0001996122 0.05410002 0.004100535 0.001193851 0.05410007 0.002852146 0.001706563 0.05410007 0.001291294 0.001048863 0.05410005 -0.001835685 -0.007835359 0.05410005 -0.001222655 -0.006825667 0.05410005 -0.001422845 -0.00531622 0.05410009 -0.002640406 -0.004392676 0.05410005 -0.003993705 -0.004474871 0.05409997 -0.004795956 -0.005131557 0.05410006 -0.005212227 -0.006041426 0.0541001 -0.005022017 -0.007218558 0.05410005 -0.004235977 -0.00810061 0.05410007 -0.002905726 -0.008362107 0.05410007 -0.01120771 -0.0005622059 0.05410009 -0.01084883 -0.001513816 0.05410007 -0.009925 -0.002250347 0.05410007 -0.008734279 -0.002312377 0.05410004 -0.007706449 -0.001729827 0.05410008 -0.007204857 -0.0006480664 0.05410009 -0.007362146 0.000522893 0.05410006 -0.008466228 0.001571532 0.05410006 -0.00999368 0.00152513 0.05410006 -0.01099492 0.0006111115 0.05410007 -0.001961326 0.004037451 0.05410007 -0.001168797 0.005337633 0.05410011 -0.001622936 0.006969415 0.05410007 -0.002979027 0.007673893 0.05410011 -0.004450897 0.007283606 0.05410007 -0.005164176 0.006118562 0.05410007 -0.005142806 0.005101774 0.05410009 -0.004517127 0.004099552 0.05410007 -0.003250178 0.003617 0.05190007 0.002922505 0.001682267 0.05190005 0.001777414 0.001391575 0.05190007 0.0009605736 0.0005229264 0.05190009 0.000888804 -0.001176093 0.05190007 0.002168124 -0.002283264 0.05190007 0.003523504 -0.002250314 0.05190007 0.004325144 -0.001651574 0.05190007 0.004798174 -0.000729084 0.05190007 0.004708664 0.000267677 0.05190006 0.004171114 0.001153987 0.05190008 -0.002569357 -0.004431855 0.05190007 -0.003935406 -0.004428476 0.05190007 -0.005039427 -0.005477075 0.05190006 -0.005196726 -0.006648015 0.05190006 -0.004695177 -0.007729814 0.05190006 -0.003495846 -0.008362096 0.05190006 -0.002330257 -0.008169703 0.05190006 -0.001552817 -0.007513885 0.05190005 -0.001193846 -0.006562214 0.05190004 -0.001478337 -0.005226094 0.05190006 -0.009244055 0.001668986 0.05190008 -0.01053319 0.001217104 0.05190007 -0.01122478 -0.0001394227 0.05190007 -0.01090701 -0.001457475 0.05190012 -0.009992484 -0.002205271 0.05190007 -0.008808236 -0.002345376 0.05190007 -0.007641103 -0.001655664 0.05190007 -0.007193858 -0.0005622134 0.05190006 -0.007344607 0.0004436262 0.05190004 -0.008102596 0.001364227 0.05190008 -0.002902336 0.007647268 0.05190008 -0.004249357 0.007419746 0.05190008 -0.005160276 0.006199609 0.05190008 -0.005069906 0.004846945 0.05190007 -0.004149746 0.003851216 0.05190007 -0.002631696 0.003675487 0.0519001 -0.001442686 0.004626718 0.05190007 -0.001189336 0.005958606 0.05190008 -0.001828866 0.007153958 0.04193904 -0.003414894 -0.01004878 0.04190239 -0.003641384 0.00935122 0.04173972 -0.002375293 0.00935122 0.03436637 -0.0006989837 0.01085121 0.03552852 -0.001293166 0.01085123 0.03617607 -0.002112545 0.01085123 0.03640791 -0.003162855 0.01085122 0.0362207 -0.004190365 0.01085122 0.03528585 -0.005333645 0.01085123 0.03342353 -0.005726265 0.01085123 0.03197165 -0.004827374 0.01085123 0.03142328 -0.003680384 0.01085123 0.03150395 -0.002411496 0.01085122 0.03206319 -0.001492854 0.01085123 0.03290944 -0.0008806027 0.01085123 0.03374269 -0.005717255 -0.01154877 0.03479998 -0.005541894 -0.01154877 0.03568346 -0.004985034 -0.01154877 0.03632727 -0.003888724 -0.01154878 0.03631812 -0.002411883 -0.01154878 0.03544333 -0.001205074 -0.01154877 0.03406967 -0.0006629545 -0.01154877 0.03243767 -0.001119684 -0.01154877 0.03145491 -0.002500294 -0.01154877 0.0315039 -0.003990075 -0.01154877 0.03233838 -0.005208425 -0.01154877 0.03090005 -0.0002007838 -0.01154877 0.03090005 -0.0002007838 -0.01234877 0.03090005 -0.006700784 -0.01154877 0.03090005 -0.006041324 -0.01234877 0.03090005 -0.006700784 -0.01192051 0.03040005 -0.0002007838 -0.01234876 0.03040006 -0.0002007838 -0.01154877 0.03040005 -0.006041324 -0.01234876 0.03090009 -0.0002007838 0.01165123 0.03090009 -0.0002007838 0.01085123 0.03090009 -0.006041324 0.01165123 0.03040009 -0.0002007838 0.01085124 0.03040009 -0.0002007838 0.01165124 0.03040009 -0.006700784 0.01085124 0.03040009 -0.006041324 0.01165124 0.03040009 -0.006700784 0.01122298</float_array> + <technique_common> + <accessor count="2281" source="#cubeverts-array0-array" stride="3"> + <param type="float" name="X"/> + <param type="float" name="Y"/> + <param type="float" name="Z"/> + </accessor> + </technique_common> + </source> + <vertices id="cubeverts-array0-vertices"> + <input source="#cubeverts-array0" semantic="POSITION"/> + </vertices> + <triangles count="4545" material="ref_Mesh001"> + <input source="#cubenormals-array0" semantic="NORMAL" offset="1"/> + <input source="#cubeverts-array0-vertices" semantic="VERTEX" offset="0"/> + <p>3 0 4 0 5 0 5 1 4 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 11 6 12 6 13 6 13 7 12 7 14 7 13 8 14 8 15 8 15 9 14 9 16 9 15 10 16 10 17 10 17 11 16 11 18 11 17 12 18 12 19 12 19 13 18 13 20 13 19 14 20 14 21 14 21 15 20 15 22 15 21 16 22 16 23 16 23 17 22 17 24 17 23 18 24 18 25 18 25 19 24 19 26 19 25 20 26 20 7 20 7 21 26 21 8 21 5 22 6 22 27 22 27 23 6 23 28 23 29 24 30 24 31 24 29 25 31 25 32 25 32 26 31 26 33 26 32 27 33 27 34 27 34 28 33 28 35 28 34 29 35 29 36 29 36 30 35 30 37 30 37 31 35 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 43 36 43 37 42 37 44 37 43 38 44 38 45 38 45 39 44 39 46 39 45 40 46 40 47 40 47 41 46 41 48 41 48 42 46 42 30 42 48 43 30 43 29 43 49 44 50 44 51 44 6 45 4 45 55 45 6 46 55 46 28 46 28 47 55 47 49 47 28 48 49 48 1 48 1 49 49 49 51 49 1 50 51 50 53 50 1 51 53 51 4 51 4 52 53 52 54 52 4 53 54 53 56 53 27 54 28 54 0 54 0 55 28 55 1 55 50 56 49 56 57 56 50 57 57 57 58 57 58 58 57 58 59 58 58 59 59 59 60 59 58 60 60 60 61 60 62 61 4 61 56 61 62 62 56 62 63 62 65 63 64 63 66 63 67 64 68 64 69 64 70 65 71 65 72 65 72 66 71 66 73 66 76 67 72 67 73 67 75 68 77 68 78 68 79 69 78 69 77 69 1 70 4 70 2 70 2 71 4 71 3 71 80 72 68 72 81 72 81 73 68 73 82 73 61 74 60 74 86 74 61 75 86 75 87 75 88 76 89 76 90 76 90 77 89 77 91 77 87 78 86 78 92 78 93 79 94 79 95 79 89 80 88 80 95 80 95 81 96 81 97 81 98 82 95 82 99 82 100 83 101 83 92 83 94 84 96 84 95 84 97 85 99 85 95 85 87 86 92 86 101 86 93 87 88 87 102 87 93 88 95 88 88 88 103 89 87 89 101 89 104 90 105 90 92 90 92 91 105 91 100 91 93 92 102 92 101 92 101 93 102 93 103 93 106 94 107 94 108 94 109 95 110 95 111 95 111 96 110 96 112 96 111 97 113 97 114 97 114 98 115 98 111 98 111 99 115 99 109 99 116 100 117 100 118 100 119 101 120 101 121 101 121 102 120 102 116 102 122 103 123 103 124 103 122 104 124 104 108 104 106 105 125 105 126 105 106 106 127 106 128 106 106 107 129 107 107 107 116 108 118 108 121 108 111 109 130 109 117 109 108 110 124 110 131 110 106 111 128 111 129 111 108 112 131 112 132 112 108 113 132 113 106 113 117 114 116 114 111 114 111 115 116 115 113 115 106 116 126 116 127 116 130 117 111 117 133 117 130 118 133 118 134 118 135 119 106 119 136 119 136 120 106 120 132 120 136 121 132 121 134 121 137 122 138 122 139 122 137 123 139 123 140 123 140 124 139 124 141 124 142 125 143 125 137 125 143 126 144 126 137 126 137 127 144 127 138 127 144 128 145 128 138 128 145 129 144 129 146 129 145 130 146 130 147 130 147 131 148 131 145 131 147 132 149 132 148 132 148 133 149 133 150 133 148 134 150 134 151 134 148 135 151 135 152 135 152 136 151 136 153 136 152 137 153 137 154 137 154 138 153 138 155 138 154 139 155 139 156 139 156 140 155 140 157 140 142 141 158 141 143 141 159 142 158 142 142 142 159 143 142 143 160 143 161 144 162 144 23 144 23 145 162 145 163 145 23 146 163 146 21 146 21 147 163 147 164 147 21 148 164 148 19 148 19 149 164 149 165 149 19 150 165 150 17 150 17 151 165 151 166 151 17 152 166 152 15 152 15 153 166 153 167 153 15 154 167 154 13 154 13 155 167 155 11 155 11 156 167 156 168 156 11 157 168 157 9 157 9 158 168 158 169 158 9 159 169 159 7 159 7 160 169 160 161 160 7 161 161 161 25 161 25 162 161 162 23 162 170 163 171 163 172 163 170 164 172 164 173 164 172 165 174 165 173 165 175 166 176 166 177 166 175 167 178 167 176 167 175 168 174 168 178 168 174 169 172 169 178 169 177 170 179 170 180 170 180 171 175 171 177 171 181 172 182 172 180 172 179 173 181 173 180 173 181 174 179 174 183 174 183 175 179 175 184 175 183 176 184 176 185 176 185 177 184 177 186 177 186 178 184 178 187 178 186 179 187 179 188 179 189 180 190 180 191 180 189 181 191 181 178 181 178 182 191 182 176 182 192 183 193 183 194 183 194 184 193 184 195 184 194 185 195 185 196 185 195 186 197 186 196 186 196 187 197 187 198 187 31 188 30 188 200 188 200 189 30 189 201 189 201 190 30 190 46 190 201 191 46 191 202 191 202 192 46 192 44 192 202 193 44 193 203 193 203 194 44 194 42 194 203 195 42 195 204 195 204 196 42 196 40 196 204 197 40 197 205 197 205 198 40 198 38 198 205 199 38 199 206 199 206 200 38 200 207 200 207 201 38 201 35 201 207 202 35 202 208 202 208 203 35 203 33 203 208 204 33 204 209 204 209 205 33 205 31 205 209 206 31 206 200 206 210 207 80 207 211 207 211 208 80 208 81 208 148 209 152 209 115 209 109 210 154 210 110 210 110 211 154 211 156 211 110 212 156 212 112 212 109 213 115 213 152 213 109 214 152 214 154 214 125 215 188 215 187 215 126 216 184 216 127 216 179 217 127 217 184 217 126 218 125 218 187 218 126 219 187 219 184 219 212 220 213 220 214 220 212 221 214 221 215 221 215 222 214 222 216 222 215 223 216 223 217 223 217 224 216 224 218 224 217 225 218 225 219 225 219 226 218 226 220 226 219 227 220 227 221 227 221 228 220 228 222 228 221 229 222 229 223 229 223 230 222 230 224 230 223 231 224 231 225 231 225 232 224 232 226 232 226 233 224 233 227 233 226 234 227 234 228 234 226 235 228 235 229 235 229 236 228 236 230 236 230 237 228 237 231 237 230 238 231 238 212 238 212 239 231 239 213 239 232 240 233 240 234 240 232 241 234 241 235 241 235 242 234 242 236 242 235 243 236 243 237 243 237 244 236 244 238 244 237 245 238 245 239 245 239 246 238 246 240 246 239 247 240 247 241 247 241 248 240 248 242 248 241 249 242 249 243 249 243 250 242 250 244 250 243 251 244 251 245 251 245 252 244 252 246 252 245 253 246 253 247 253 247 254 246 254 248 254 247 255 248 255 249 255 249 256 248 256 233 256 249 257 233 257 232 257 250 258 251 258 252 258 252 259 251 259 253 259 252 260 253 260 254 260 254 261 253 261 255 261 254 262 255 262 256 262 256 263 255 263 257 263 256 264 257 264 258 264 258 265 257 265 259 265 258 266 259 266 260 266 260 267 259 267 261 267 260 268 261 268 262 268 262 269 261 269 263 269 263 270 261 270 264 270 263 271 264 271 265 271 265 272 264 272 266 272 265 273 266 273 267 273 265 274 267 274 268 274 268 275 267 275 250 275 268 276 250 276 269 276 269 277 250 277 252 277 270 278 271 278 272 278 272 279 271 279 273 279 274 280 275 280 276 280 277 281 278 281 279 281 277 282 276 282 280 282 281 283 282 283 283 283 277 284 284 284 276 284 276 285 284 285 274 285 274 286 284 286 285 286 274 287 286 287 287 287 288 288 279 288 278 288 274 289 285 289 289 289 272 290 290 290 270 290 274 291 291 291 275 291 292 292 293 292 294 292 294 293 293 293 295 293 294 294 295 294 296 294 296 295 295 295 297 295 141 296 298 296 299 296 274 297 289 297 300 297 274 298 287 298 301 298 274 299 301 299 302 299 140 300 303 300 304 300 140 301 304 301 305 301 306 302 307 302 308 302 293 303 309 303 306 303 306 304 309 304 307 304 286 305 310 305 290 305 290 306 310 306 270 306 311 307 312 307 303 307 311 308 303 308 140 308 311 309 140 309 141 309 311 310 141 310 299 310 305 311 313 311 140 311 140 312 313 312 272 312 140 313 272 313 273 313 273 314 314 314 140 314 314 315 288 315 140 315 140 316 288 316 278 316 280 317 315 317 277 317 277 318 315 318 278 318 278 319 315 319 316 319 278 320 316 320 317 320 317 321 316 321 282 321 282 322 316 322 318 322 282 323 318 323 283 323 281 324 283 324 319 324 281 325 320 325 309 325 306 326 308 326 291 326 291 327 308 327 275 327 274 328 300 328 310 328 274 329 310 329 286 329 292 330 281 330 293 330 293 331 281 331 309 331 297 332 321 332 296 332 296 333 321 333 141 333 141 334 321 334 298 334 302 335 301 335 322 335 302 336 322 336 311 336 311 337 322 337 312 337 281 338 319 338 320 338 323 339 324 339 325 339 323 340 325 340 326 340 326 341 325 341 327 341 326 342 327 342 328 342 328 343 327 343 329 343 328 344 329 344 330 344 330 345 329 345 331 345 330 346 331 346 332 346 332 347 331 347 333 347 332 348 333 348 334 348 334 349 333 349 335 349 334 350 335 350 336 350 336 351 335 351 337 351 336 352 337 352 338 352 336 353 338 353 339 353 339 354 338 354 340 354 339 355 340 355 341 355 341 356 340 356 342 356 342 357 340 357 343 357 342 358 343 358 324 358 342 359 324 359 323 359 344 360 345 360 346 360 346 361 345 361 347 361 346 362 347 362 348 362 346 363 348 363 349 363 349 364 348 364 350 364 350 365 348 365 351 365 350 366 351 366 352 366 352 367 351 367 353 367 352 368 353 368 354 368 354 369 353 369 355 369 354 370 355 370 356 370 356 371 355 371 357 371 356 372 357 372 358 372 358 373 357 373 359 373 358 374 359 374 360 374 360 375 359 375 361 375 360 376 361 376 344 376 344 377 361 377 345 377 362 378 363 378 364 378 362 379 364 379 365 379 365 380 364 380 366 380 365 381 366 381 367 381 367 382 366 382 368 382 367 383 368 383 369 383 369 384 368 384 370 384 369 385 370 385 371 385 371 386 370 386 372 386 371 387 372 387 373 387 373 388 372 388 374 388 373 389 374 389 375 389 375 390 374 390 376 390 375 391 376 391 377 391 377 392 376 392 378 392 377 393 378 393 379 393 379 394 378 394 363 394 379 395 363 395 362 395 380 396 381 396 382 396 380 397 382 397 383 397 383 398 382 398 384 398 383 399 384 399 385 399 385 400 384 400 386 400 385 401 386 401 387 401 387 402 386 402 388 402 387 403 388 403 389 403 389 404 388 404 390 404 389 405 390 405 391 405 391 406 390 406 392 406 391 407 392 407 393 407 393 408 392 408 394 408 393 409 394 409 395 409 395 410 394 410 396 410 395 411 396 411 397 411 397 412 396 412 398 412 397 413 398 413 399 413 399 414 398 414 381 414 399 415 381 415 380 415 400 416 401 416 402 416 402 417 401 417 403 417 403 418 401 418 404 418 403 419 404 419 405 419 405 420 404 420 406 420 405 421 406 421 407 421 407 422 406 422 408 422 407 423 408 423 409 423 409 424 408 424 410 424 409 425 410 425 411 425 411 426 410 426 412 426 411 427 412 427 413 427 413 428 412 428 414 428 413 429 414 429 415 429 415 430 414 430 416 430 415 431 416 431 417 431 417 432 416 432 418 432 417 433 418 433 419 433 419 434 418 434 402 434 402 435 418 435 400 435 420 436 421 436 422 436 420 437 422 437 423 437 423 438 422 438 424 438 423 439 424 439 425 439 425 440 424 440 426 440 425 441 426 441 427 441 427 442 426 442 428 442 428 443 426 443 429 443 428 444 429 444 430 444 428 445 430 445 431 445 431 446 430 446 432 446 431 447 432 447 433 447 433 448 432 448 434 448 434 449 432 449 435 449 434 450 435 450 436 450 436 451 435 451 437 451 436 452 437 452 438 452 438 453 437 453 421 453 438 454 421 454 420 454 439 455 440 455 441 455 439 456 441 456 442 456 442 457 441 457 443 457 442 458 443 458 444 458 444 459 443 459 445 459 444 460 445 460 446 460 446 461 445 461 447 461 446 462 447 462 448 462 448 463 447 463 449 463 448 464 449 464 450 464 450 465 449 465 451 465 450 466 451 466 452 466 452 467 451 467 453 467 452 468 453 468 454 468 454 469 453 469 455 469 454 470 455 470 456 470 454 471 456 471 457 471 457 472 456 472 440 472 457 473 440 473 439 473 458 474 459 474 460 474 458 475 460 475 461 475 461 476 460 476 462 476 461 477 462 477 463 477 463 478 462 478 464 478 463 479 464 479 465 479 465 480 464 480 466 480 465 481 466 481 467 481 467 482 466 482 468 482 467 483 468 483 469 483 469 484 468 484 470 484 469 485 470 485 471 485 471 486 470 486 472 486 471 487 472 487 473 487 473 488 472 488 474 488 473 489 474 489 475 489 475 490 474 490 476 490 475 491 476 491 477 491 477 492 476 492 459 492 477 493 459 493 458 493 80 494 210 494 478 494 478 495 210 495 84 495 483 496 478 496 484 496 484 497 478 497 84 497 484 498 84 498 482 498 482 499 84 499 68 499 482 500 68 500 481 500 481 501 68 501 67 501 485 502 486 502 430 502 485 503 430 503 487 503 487 504 430 504 429 504 406 505 470 505 408 505 472 506 401 506 474 506 408 507 470 507 468 507 408 508 468 508 453 508 488 509 489 509 447 509 418 510 416 510 490 510 447 511 491 511 449 511 449 512 491 512 487 512 447 513 489 513 491 513 470 514 406 514 472 514 406 515 404 515 472 515 472 516 404 516 401 516 474 517 400 517 418 517 474 518 418 518 490 518 490 519 416 519 492 519 492 520 416 520 414 520 492 521 414 521 493 521 493 522 414 522 412 522 412 523 410 523 493 523 493 524 410 524 432 524 493 525 432 525 486 525 486 526 432 526 430 526 494 527 459 527 476 527 494 528 476 528 474 528 494 529 474 529 490 529 401 530 400 530 474 530 495 531 462 531 460 531 410 532 435 532 432 532 466 533 455 533 468 533 468 534 455 534 453 534 464 535 456 535 466 535 466 536 456 536 455 536 408 537 437 537 410 537 410 538 437 538 435 538 453 539 451 539 421 539 421 540 451 540 422 540 488 541 447 541 445 541 488 542 445 542 443 542 441 543 440 543 495 543 495 544 460 544 459 544 495 545 459 545 494 545 487 546 429 546 426 546 487 547 426 547 449 547 426 548 424 548 449 548 488 549 443 549 441 549 488 550 441 550 495 550 464 551 462 551 456 551 456 552 462 552 495 552 456 553 495 553 440 553 449 554 424 554 422 554 453 555 421 555 408 555 408 556 421 556 437 556 422 557 451 557 449 557 496 558 497 558 498 558 496 559 498 559 98 559 123 560 122 560 499 560 499 561 122 561 500 561 499 562 500 562 501 562 501 563 500 563 502 563 501 564 502 564 503 564 501 565 503 565 504 565 504 566 503 566 505 566 504 567 505 567 506 567 506 568 505 568 507 568 506 569 507 569 508 569 506 570 508 570 509 570 509 571 508 571 510 571 510 572 508 572 511 572 510 573 511 573 512 573 512 574 511 574 513 574 512 575 513 575 514 575 514 576 513 576 515 576 514 577 515 577 516 577 516 578 515 578 517 578 516 579 517 579 518 579 518 580 517 580 519 580 518 581 519 581 520 581 520 582 519 582 521 582 520 583 521 583 522 583 522 584 521 584 523 584 522 585 523 585 524 585 524 586 523 586 525 586 524 587 525 587 526 587 524 588 526 588 527 588 527 589 526 589 528 589 527 590 528 590 529 590 527 591 529 591 530 591 530 592 529 592 531 592 530 593 531 593 532 593 530 594 532 594 533 594 533 595 532 595 534 595 533 596 534 596 535 596 535 597 534 597 497 597 535 598 497 598 496 598 536 599 537 599 538 599 539 600 540 600 541 600 541 601 540 601 542 601 541 602 542 602 543 602 543 603 542 603 544 603 543 604 544 604 545 604 545 605 544 605 546 605 544 606 547 606 546 606 546 607 547 607 548 607 546 608 548 608 549 608 550 609 538 609 551 609 552 610 553 610 554 610 549 611 553 611 546 611 546 612 553 612 552 612 546 613 552 613 555 613 555 614 552 614 556 614 555 615 556 615 557 615 557 616 556 616 558 616 190 617 559 617 560 617 561 618 562 618 539 618 563 619 540 619 564 619 564 620 540 620 539 620 565 621 566 621 567 621 190 622 568 622 539 622 539 623 568 623 561 623 539 624 562 624 564 624 569 625 570 625 571 625 552 626 554 626 572 626 572 627 554 627 550 627 572 628 550 628 551 628 190 629 560 629 573 629 569 630 574 630 570 630 570 631 574 631 575 631 538 632 576 632 536 632 565 633 567 633 540 633 576 634 538 634 565 634 565 635 538 635 566 635 537 636 577 636 578 636 537 637 578 637 538 637 538 638 578 638 551 638 579 639 559 639 189 639 189 640 559 640 190 640 190 641 580 641 568 641 563 642 581 642 540 642 582 643 583 643 565 643 565 644 583 644 575 644 584 645 585 645 537 645 557 646 558 646 586 646 571 647 580 647 569 647 569 648 580 648 190 648 569 649 190 649 573 649 540 650 581 650 582 650 540 651 582 651 565 651 575 652 574 652 565 652 537 653 585 653 587 653 588 654 589 654 537 654 537 655 589 655 584 655 189 656 590 656 589 656 557 657 586 657 590 657 557 658 590 658 189 658 589 659 588 659 189 659 189 660 588 660 579 660 537 661 587 661 577 661 591 662 559 662 579 662 591 663 579 663 592 663 592 664 579 664 593 664 593 665 579 665 588 665 593 666 588 666 594 666 594 667 588 667 537 667 594 668 537 668 595 668 595 669 537 669 596 669 596 670 537 670 536 670 596 671 536 671 576 671 596 672 576 672 597 672 597 673 576 673 565 673 597 674 565 674 598 674 598 675 565 675 599 675 599 676 565 676 574 676 599 677 574 677 600 677 600 678 574 678 569 678 600 679 569 679 601 679 601 680 569 680 573 680 601 681 573 681 602 681 602 682 573 682 560 682 602 683 560 683 559 683 602 684 559 684 591 684 477 685 592 685 593 685 477 686 593 686 475 686 475 687 593 687 594 687 475 688 594 688 473 688 465 689 599 689 600 689 465 690 600 690 601 690 465 691 601 691 463 691 463 692 601 692 602 692 463 693 602 693 461 693 461 694 602 694 591 694 465 695 467 695 599 695 599 696 467 696 598 696 598 697 467 697 469 697 598 698 469 698 597 698 597 699 469 699 471 699 597 700 471 700 596 700 596 701 471 701 595 701 595 702 471 702 473 702 595 703 473 703 594 703 592 704 477 704 458 704 592 705 458 705 591 705 591 706 458 706 461 706 603 707 570 707 604 707 604 708 570 708 575 708 604 709 575 709 605 709 605 710 575 710 606 710 606 711 575 711 583 711 606 712 583 712 582 712 606 713 582 713 607 713 607 714 582 714 581 714 607 715 581 715 608 715 608 716 581 716 609 716 609 717 581 717 563 717 609 718 563 718 610 718 610 719 563 719 564 719 610 720 564 720 611 720 611 721 564 721 562 721 611 722 562 722 612 722 612 723 562 723 561 723 612 724 561 724 568 724 612 725 568 725 613 725 613 726 568 726 580 726 613 727 580 727 614 727 614 728 580 728 571 728 614 729 571 729 603 729 603 730 571 730 570 730 606 731 454 731 605 731 605 732 454 732 457 732 605 733 457 733 604 733 603 734 442 734 614 734 614 735 442 735 613 735 613 736 442 736 444 736 613 737 444 737 612 737 612 738 444 738 446 738 612 739 446 739 611 739 607 740 452 740 606 740 452 741 454 741 606 741 611 742 446 742 448 742 611 743 448 743 610 743 610 744 448 744 450 744 610 745 450 745 609 745 609 746 450 746 608 746 608 747 450 747 452 747 608 748 452 748 607 748 604 749 457 749 439 749 604 750 439 750 603 750 603 751 439 751 442 751 615 752 538 752 616 752 616 753 538 753 550 753 616 754 550 754 617 754 617 755 550 755 554 755 617 756 554 756 618 756 618 757 554 757 553 757 618 758 553 758 619 758 619 759 553 759 549 759 619 760 549 760 620 760 620 761 549 761 548 761 620 762 548 762 621 762 621 763 548 763 547 763 621 764 547 764 622 764 622 765 547 765 544 765 622 766 544 766 623 766 623 767 544 767 542 767 623 768 542 768 624 768 624 769 542 769 540 769 624 770 540 770 625 770 625 771 540 771 626 771 626 772 540 772 567 772 626 773 567 773 566 773 626 774 566 774 615 774 615 775 566 775 538 775 619 776 620 776 433 776 617 777 436 777 616 777 621 778 431 778 620 778 433 779 620 779 431 779 619 780 433 780 434 780 619 781 434 781 618 781 618 782 434 782 436 782 618 783 436 783 617 783 615 784 420 784 423 784 615 785 423 785 626 785 626 786 423 786 425 786 626 787 425 787 625 787 625 788 425 788 624 788 624 789 425 789 427 789 624 790 427 790 623 790 623 791 427 791 428 791 623 792 428 792 622 792 622 793 428 793 621 793 621 794 428 794 431 794 436 795 438 795 616 795 616 796 438 796 420 796 616 797 420 797 615 797 627 798 585 798 584 798 627 799 584 799 628 799 628 800 584 800 589 800 628 801 589 801 629 801 629 802 589 802 590 802 629 803 590 803 630 803 630 804 590 804 586 804 630 805 586 805 631 805 631 806 586 806 558 806 631 807 558 807 632 807 632 808 558 808 556 808 632 809 556 809 633 809 633 810 556 810 552 810 633 811 552 811 634 811 634 812 552 812 572 812 634 813 572 813 551 813 634 814 551 814 635 814 635 815 551 815 578 815 635 816 578 816 636 816 636 817 578 817 577 817 636 818 577 818 637 818 637 819 577 819 587 819 637 820 587 820 638 820 638 821 587 821 585 821 638 822 585 822 627 822 419 823 628 823 629 823 638 824 403 824 637 824 637 825 403 825 405 825 637 826 405 826 636 826 636 827 405 827 407 827 636 828 407 828 635 828 635 829 407 829 634 829 419 830 629 830 417 830 417 831 629 831 630 831 417 832 630 832 415 832 407 833 409 833 634 833 634 834 409 834 633 834 633 835 409 835 411 835 633 836 411 836 632 836 632 837 411 837 413 837 632 838 413 838 631 838 631 839 413 839 415 839 631 840 415 840 630 840 419 841 402 841 628 841 628 842 402 842 627 842 627 843 402 843 403 843 627 844 403 844 638 844 639 845 640 845 641 845 641 846 104 846 639 846 120 847 119 847 642 847 120 848 642 848 643 848 643 849 642 849 644 849 643 850 644 850 645 850 645 851 644 851 646 851 645 852 646 852 647 852 647 853 646 853 648 853 647 854 648 854 649 854 649 855 648 855 650 855 649 856 650 856 651 856 651 857 650 857 652 857 651 858 652 858 653 858 653 859 652 859 654 859 653 860 654 860 655 860 655 861 654 861 656 861 655 862 656 862 657 862 655 863 657 863 658 863 658 864 657 864 659 864 659 865 657 865 660 865 659 866 660 866 661 866 661 867 660 867 662 867 661 868 662 868 663 868 661 869 663 869 664 869 664 870 663 870 665 870 664 871 665 871 666 871 666 872 665 872 667 872 666 873 667 873 668 873 668 874 667 874 669 874 668 875 669 875 670 875 671 876 672 876 673 876 670 877 669 877 674 877 670 878 674 878 673 878 673 879 674 879 675 879 673 880 675 880 671 880 639 881 676 881 640 881 640 882 676 882 677 882 677 883 676 883 678 883 678 884 676 884 679 884 678 885 679 885 680 885 678 886 680 886 681 886 681 887 680 887 682 887 682 888 680 888 683 888 682 889 683 889 671 889 671 890 683 890 672 890 336 891 399 891 334 891 334 892 399 892 380 892 367 893 395 893 397 893 395 894 367 894 369 894 336 895 339 895 399 895 399 896 339 896 397 896 397 897 339 897 367 897 334 898 380 898 332 898 684 899 371 899 373 899 684 900 375 900 377 900 684 901 377 901 685 901 395 902 369 902 393 902 393 903 369 903 371 903 686 904 389 904 391 904 686 905 391 905 684 905 684 906 373 906 375 906 685 907 377 907 687 907 687 908 377 908 379 908 379 909 362 909 687 909 687 910 362 910 358 910 687 911 358 911 688 911 688 912 358 912 689 912 689 913 358 913 360 913 689 914 360 914 344 914 362 915 356 915 358 915 391 916 393 916 684 916 354 917 365 917 367 917 323 918 350 918 342 918 342 919 350 919 352 919 686 920 387 920 389 920 371 921 684 921 393 921 689 922 344 922 690 922 362 923 365 923 356 923 356 924 365 924 354 924 323 925 349 925 350 925 380 926 383 926 332 926 385 927 332 927 383 927 349 928 323 928 346 928 346 929 323 929 690 929 354 930 367 930 352 930 352 931 367 931 339 931 352 932 339 932 341 932 326 933 691 933 692 933 326 934 692 934 323 934 323 935 692 935 693 935 323 936 693 936 690 936 686 937 330 937 332 937 344 938 346 938 690 938 352 939 341 939 342 939 332 940 385 940 387 940 332 941 387 941 686 941 691 942 326 942 328 942 328 943 330 943 691 943 691 944 330 944 686 944 694 945 384 945 382 945 694 946 382 946 695 946 390 947 696 947 697 947 390 948 697 948 392 948 392 949 697 949 394 949 386 950 698 950 388 950 388 951 698 951 699 951 388 952 699 952 696 952 388 953 696 953 390 953 384 954 694 954 700 954 384 955 700 955 386 955 386 956 700 956 698 956 697 957 701 957 394 957 394 958 701 958 702 958 394 959 702 959 396 959 396 960 702 960 703 960 396 961 703 961 704 961 396 962 704 962 398 962 398 963 704 963 705 963 695 964 382 964 381 964 695 965 381 965 705 965 705 966 381 966 398 966 696 967 305 967 304 967 696 968 304 968 697 968 697 969 304 969 303 969 697 970 303 970 701 970 701 971 303 971 702 971 702 972 303 972 312 972 702 973 312 973 703 973 703 974 312 974 322 974 703 975 322 975 704 975 704 976 322 976 301 976 704 977 301 977 705 977 705 978 301 978 287 978 705 979 287 979 695 979 695 980 287 980 286 980 695 981 286 981 694 981 694 982 286 982 290 982 694 983 290 983 700 983 700 984 290 984 272 984 700 985 272 985 698 985 698 986 272 986 313 986 698 987 313 987 699 987 699 988 313 988 305 988 699 989 305 989 696 989 368 990 366 990 706 990 706 991 366 991 707 991 370 992 708 992 709 992 370 993 709 993 372 993 707 994 366 994 364 994 707 995 364 995 710 995 710 996 364 996 711 996 708 997 370 997 368 997 708 998 368 998 706 998 372 999 709 999 712 999 372 1000 712 1000 374 1000 374 1001 712 1001 713 1001 374 1002 713 1002 714 1002 374 1003 714 1003 376 1003 376 1004 714 1004 715 1004 376 1005 715 1005 716 1005 376 1006 716 1006 378 1006 378 1007 716 1007 717 1007 711 1008 364 1008 363 1008 711 1009 363 1009 717 1009 717 1010 363 1010 378 1010 311 1011 299 1011 709 1011 709 1012 299 1012 712 1012 712 1013 299 1013 298 1013 712 1014 298 1014 713 1014 713 1015 298 1015 714 1015 714 1016 298 1016 321 1016 714 1017 321 1017 297 1017 714 1018 297 1018 715 1018 715 1019 297 1019 716 1019 716 1020 297 1020 295 1020 716 1021 295 1021 717 1021 717 1022 295 1022 293 1022 717 1023 293 1023 711 1023 711 1024 293 1024 306 1024 711 1025 306 1025 710 1025 710 1026 306 1026 291 1026 710 1027 291 1027 707 1027 707 1028 291 1028 274 1028 707 1029 274 1029 706 1029 706 1030 274 1030 302 1030 706 1031 302 1031 708 1031 708 1032 302 1032 311 1032 708 1033 311 1033 709 1033 718 1034 361 1034 719 1034 720 1035 347 1035 345 1035 720 1036 345 1036 718 1036 718 1037 345 1037 361 1037 719 1038 361 1038 359 1038 719 1039 359 1039 721 1039 721 1040 359 1040 357 1040 721 1041 357 1041 722 1041 353 1042 723 1042 355 1042 355 1043 723 1043 724 1043 355 1044 724 1044 357 1044 724 1045 722 1045 357 1045 720 1046 725 1046 347 1046 347 1047 725 1047 348 1047 348 1048 725 1048 726 1048 348 1049 726 1049 727 1049 348 1050 727 1050 351 1050 351 1051 727 1051 353 1051 353 1052 727 1052 728 1052 353 1053 728 1053 723 1053 723 1054 276 1054 275 1054 723 1055 275 1055 724 1055 724 1056 275 1056 308 1056 724 1057 308 1057 722 1057 722 1058 308 1058 307 1058 722 1059 307 1059 721 1059 721 1060 307 1060 309 1060 721 1061 309 1061 320 1061 721 1062 320 1062 719 1062 719 1063 320 1063 319 1063 719 1064 319 1064 718 1064 718 1065 319 1065 283 1065 718 1066 283 1066 720 1066 720 1067 283 1067 318 1067 720 1068 318 1068 725 1068 725 1069 318 1069 316 1069 725 1070 316 1070 726 1070 726 1071 316 1071 315 1071 726 1072 315 1072 727 1072 727 1073 315 1073 280 1073 727 1074 280 1074 728 1074 728 1075 280 1075 276 1075 728 1076 276 1076 723 1076 729 1077 730 1077 327 1077 333 1078 331 1078 731 1078 731 1079 331 1079 732 1079 327 1080 730 1080 329 1080 329 1081 730 1081 733 1081 329 1082 733 1082 331 1082 331 1083 733 1083 732 1083 734 1084 735 1084 338 1084 338 1085 735 1085 736 1085 338 1086 736 1086 340 1086 340 1087 736 1087 737 1087 340 1088 737 1088 343 1088 343 1089 737 1089 738 1089 343 1090 738 1090 324 1090 333 1091 731 1091 739 1091 333 1092 739 1092 335 1092 338 1093 337 1093 734 1093 734 1094 337 1094 335 1094 734 1095 335 1095 740 1095 740 1096 335 1096 739 1096 327 1097 325 1097 729 1097 729 1098 325 1098 324 1098 729 1099 324 1099 741 1099 741 1100 324 1100 738 1100 740 1101 271 1101 270 1101 740 1102 270 1102 734 1102 734 1103 270 1103 310 1103 734 1104 310 1104 735 1104 735 1105 310 1105 300 1105 735 1106 300 1106 736 1106 736 1107 300 1107 289 1107 736 1108 289 1108 737 1108 737 1109 289 1109 285 1109 737 1110 285 1110 738 1110 738 1111 285 1111 284 1111 738 1112 284 1112 741 1112 741 1113 284 1113 277 1113 741 1114 277 1114 729 1114 729 1115 277 1115 279 1115 729 1116 279 1116 730 1116 730 1117 279 1117 288 1117 730 1118 288 1118 733 1118 733 1119 288 1119 314 1119 733 1120 314 1120 732 1120 732 1121 314 1121 731 1121 731 1122 314 1122 273 1122 731 1123 273 1123 739 1123 739 1124 273 1124 271 1124 739 1125 271 1125 740 1125 120 1126 643 1126 742 1126 743 1127 744 1127 278 1127 661 1128 664 1128 281 1128 281 1129 664 1129 745 1129 281 1130 745 1130 282 1130 659 1131 661 1131 281 1131 658 1132 659 1132 281 1132 658 1133 281 1133 746 1133 655 1134 658 1134 746 1134 746 1135 281 1135 292 1135 668 1136 745 1136 666 1136 666 1137 745 1137 664 1137 747 1138 742 1138 645 1138 645 1139 742 1139 643 1139 744 1140 679 1140 676 1140 744 1141 743 1141 679 1141 679 1142 743 1142 680 1142 743 1143 748 1143 683 1143 743 1144 683 1144 680 1144 748 1145 672 1145 683 1145 748 1146 673 1146 672 1146 668 1147 670 1147 749 1147 749 1148 670 1148 673 1148 317 1149 748 1149 743 1149 278 1150 317 1150 743 1150 748 1151 317 1151 673 1151 673 1152 317 1152 749 1152 745 1153 668 1153 282 1153 282 1154 668 1154 749 1154 317 1155 282 1155 749 1155 746 1156 292 1156 653 1156 746 1157 653 1157 655 1157 292 1158 651 1158 653 1158 292 1159 294 1159 651 1159 651 1160 294 1160 649 1160 294 1161 750 1161 647 1161 294 1162 647 1162 649 1162 294 1163 296 1163 750 1163 647 1164 750 1164 645 1164 296 1165 747 1165 750 1165 750 1166 747 1166 645 1166 691 1167 686 1167 751 1167 751 1168 686 1168 752 1168 751 1169 752 1169 104 1169 752 1170 105 1170 104 1170 104 1171 641 1171 751 1171 642 1172 119 1172 753 1172 642 1173 753 1173 754 1173 642 1174 754 1174 644 1174 644 1175 754 1175 755 1175 644 1176 755 1176 646 1176 646 1177 755 1177 648 1177 657 1178 656 1178 756 1178 657 1179 756 1179 660 1179 665 1180 663 1180 757 1180 665 1181 757 1181 667 1181 669 1182 667 1182 758 1182 669 1183 758 1183 674 1183 675 1184 674 1184 759 1184 675 1185 759 1185 671 1185 681 1186 682 1186 760 1186 681 1187 760 1187 678 1187 650 1188 648 1188 688 1188 650 1189 688 1189 652 1189 652 1190 688 1190 654 1190 662 1191 660 1191 689 1191 662 1192 689 1192 663 1192 667 1193 757 1193 758 1193 678 1194 760 1194 692 1194 678 1195 692 1195 677 1195 677 1196 692 1196 761 1196 677 1197 761 1197 640 1197 640 1198 761 1198 641 1198 641 1199 761 1199 751 1199 648 1200 755 1200 687 1200 648 1201 687 1201 688 1201 654 1202 688 1202 762 1202 654 1203 762 1203 656 1203 656 1204 762 1204 756 1204 660 1205 756 1205 689 1205 663 1206 689 1206 757 1206 674 1207 758 1207 759 1207 671 1208 759 1208 693 1208 671 1209 693 1209 682 1209 682 1210 693 1210 760 1210 755 1211 754 1211 687 1211 758 1212 757 1212 690 1212 761 1213 691 1213 751 1213 753 1214 685 1214 754 1214 758 1215 690 1215 759 1215 759 1216 690 1216 693 1216 760 1217 693 1217 692 1217 754 1218 685 1218 687 1218 756 1219 762 1219 689 1219 757 1220 689 1220 690 1220 761 1221 692 1221 691 1221 762 1222 688 1222 689 1222 684 1223 685 1223 763 1223 763 1224 685 1224 753 1224 119 1225 763 1225 753 1225 119 1226 764 1226 763 1226 119 1227 121 1227 764 1227 545 1228 546 1228 765 1228 502 1229 766 1229 539 1229 122 1230 766 1230 500 1230 557 1231 767 1231 534 1231 768 1232 769 1232 546 1232 528 1233 769 1233 768 1233 768 1234 546 1234 555 1234 529 1235 528 1235 770 1235 770 1236 528 1236 768 1236 531 1237 529 1237 770 1237 770 1238 768 1238 555 1238 532 1239 531 1239 771 1239 771 1240 531 1240 770 1240 771 1241 770 1241 555 1241 503 1242 502 1242 539 1242 517 1243 772 1243 519 1243 772 1244 765 1244 519 1244 519 1245 765 1245 521 1245 521 1246 546 1246 523 1246 523 1247 546 1247 769 1247 523 1248 769 1248 525 1248 525 1249 769 1249 526 1249 766 1250 502 1250 500 1250 505 1251 503 1251 773 1251 773 1252 503 1252 539 1252 511 1253 508 1253 774 1253 774 1254 508 1254 507 1254 774 1255 507 1255 505 1255 774 1256 505 1256 773 1256 775 1257 515 1257 513 1257 513 1258 511 1258 541 1258 541 1259 511 1259 774 1259 541 1260 774 1260 773 1260 541 1261 773 1261 539 1261 541 1262 543 1262 513 1262 513 1263 543 1263 775 1263 775 1264 772 1264 515 1264 515 1265 772 1265 517 1265 775 1266 543 1266 545 1266 775 1267 545 1267 772 1267 772 1268 545 1268 765 1268 546 1269 521 1269 765 1269 526 1270 769 1270 528 1270 555 1271 557 1271 771 1271 771 1272 557 1272 534 1272 771 1273 534 1273 532 1273 534 1274 767 1274 497 1274 776 1275 494 1275 490 1275 776 1276 490 1276 777 1276 776 1277 777 1277 99 1277 99 1278 777 1278 98 1278 98 1279 777 1279 778 1279 98 1280 778 1280 496 1280 530 1281 533 1281 779 1281 530 1282 779 1282 527 1282 524 1283 527 1283 780 1283 514 1284 781 1284 512 1284 533 1285 535 1285 782 1285 533 1286 782 1286 779 1286 527 1287 779 1287 783 1287 527 1288 783 1288 780 1288 524 1289 780 1289 784 1289 524 1290 784 1290 522 1290 520 1291 522 1291 785 1291 520 1292 785 1292 518 1292 518 1293 785 1293 786 1293 518 1294 786 1294 516 1294 514 1295 516 1295 781 1295 509 1296 510 1296 787 1296 509 1297 787 1297 506 1297 501 1298 504 1298 788 1298 501 1299 788 1299 789 1299 501 1300 789 1300 499 1300 499 1301 789 1301 123 1301 123 1302 789 1302 790 1302 496 1303 778 1303 492 1303 496 1304 492 1304 535 1304 535 1305 492 1305 791 1305 535 1306 791 1306 782 1306 522 1307 784 1307 785 1307 512 1308 781 1308 792 1308 512 1309 792 1309 510 1309 506 1310 787 1310 504 1310 504 1311 787 1311 788 1311 777 1312 490 1312 778 1312 516 1313 786 1313 781 1313 789 1314 788 1314 489 1314 783 1315 493 1315 780 1315 784 1316 780 1316 486 1316 781 1317 487 1317 792 1317 510 1318 792 1318 787 1318 789 1319 489 1319 790 1319 778 1320 490 1320 492 1320 782 1321 791 1321 493 1321 782 1322 493 1322 779 1322 779 1323 493 1323 783 1323 780 1324 493 1324 486 1324 786 1325 785 1325 485 1325 786 1326 485 1326 487 1326 786 1327 487 1327 781 1327 787 1328 792 1328 491 1328 787 1329 491 1329 788 1329 791 1330 492 1330 493 1330 784 1331 486 1331 785 1331 785 1332 486 1332 485 1332 788 1333 491 1333 489 1333 489 1334 488 1334 790 1334 792 1335 487 1335 491 1335 488 1336 495 1336 790 1336 790 1337 495 1337 793 1337 790 1338 793 1338 123 1338 793 1339 794 1339 123 1339 123 1340 794 1340 124 1340 795 1341 113 1341 116 1341 795 1342 116 1342 120 1342 795 1343 120 1343 742 1343 795 1344 742 1344 141 1344 141 1345 742 1345 747 1345 296 1346 141 1346 747 1346 108 1347 107 1347 122 1347 766 1348 122 1348 796 1348 796 1349 122 1349 107 1349 766 1350 796 1350 539 1350 539 1351 796 1351 190 1351 128 1352 179 1352 177 1352 128 1353 177 1353 797 1353 177 1354 176 1354 798 1354 139 1355 138 1355 799 1355 141 1356 139 1356 799 1356 141 1357 799 1357 795 1357 799 1358 138 1358 145 1358 795 1359 799 1359 113 1359 115 1360 145 1360 148 1360 799 1361 145 1361 114 1361 799 1362 114 1362 113 1362 145 1363 115 1363 114 1363 127 1364 179 1364 128 1364 798 1365 129 1365 797 1365 129 1366 128 1366 797 1366 796 1367 107 1367 798 1367 107 1368 129 1368 798 1368 190 1369 796 1369 191 1369 191 1370 796 1370 176 1370 176 1371 796 1371 798 1371 797 1372 177 1372 798 1372 800 1373 801 1373 802 1373 803 1374 804 1374 805 1374 800 1375 806 1375 807 1375 807 1376 806 1376 808 1376 800 1377 802 1377 806 1377 809 1378 810 1378 807 1378 808 1379 811 1379 812 1379 812 1380 811 1380 813 1380 814 1381 815 1381 807 1381 807 1382 815 1382 809 1382 810 1383 816 1383 807 1383 817 1384 818 1384 819 1384 820 1385 800 1385 821 1385 820 1386 821 1386 822 1386 820 1387 801 1387 800 1387 803 1388 805 1388 823 1388 803 1389 823 1389 824 1389 808 1390 812 1390 807 1390 807 1391 812 1391 814 1391 824 1392 823 1392 814 1392 814 1393 823 1393 815 1393 816 1394 825 1394 807 1394 807 1395 825 1395 819 1395 819 1396 825 1396 826 1396 819 1397 818 1397 827 1397 821 1398 828 1398 829 1398 829 1399 830 1399 831 1399 832 1400 822 1400 821 1400 803 1401 817 1401 804 1401 804 1402 817 1402 833 1402 819 1403 826 1403 834 1403 819 1404 834 1404 835 1404 819 1405 835 1405 833 1405 819 1406 833 1406 817 1406 819 1407 827 1407 821 1407 821 1408 827 1408 828 1408 836 1409 832 1409 821 1409 829 1410 831 1410 821 1410 821 1411 831 1411 837 1411 821 1412 837 1412 836 1412 829 1413 838 1413 830 1413 830 1414 838 1414 813 1414 830 1415 813 1415 811 1415 84 1416 210 1416 85 1416 85 1417 210 1417 211 1417 839 1418 830 1418 811 1418 839 1419 811 1419 840 1419 840 1420 811 1420 841 1420 841 1421 811 1421 808 1421 841 1422 808 1422 842 1422 842 1423 808 1423 806 1423 842 1424 806 1424 802 1424 842 1425 802 1425 843 1425 843 1426 802 1426 801 1426 843 1427 801 1427 844 1427 844 1428 801 1428 820 1428 844 1429 820 1429 845 1429 845 1430 820 1430 846 1430 846 1431 820 1431 822 1431 846 1432 822 1432 847 1432 847 1433 822 1433 832 1433 847 1434 832 1434 848 1434 848 1435 832 1435 836 1435 848 1436 836 1436 849 1436 849 1437 836 1437 837 1437 849 1438 837 1438 850 1438 850 1439 837 1439 831 1439 850 1440 831 1440 830 1440 850 1441 830 1441 839 1441 842 1442 255 1442 253 1442 842 1443 253 1443 841 1443 841 1444 253 1444 840 1444 840 1445 253 1445 251 1445 839 1446 250 1446 850 1446 850 1447 250 1447 267 1447 255 1448 842 1448 843 1448 255 1449 843 1449 257 1449 257 1450 843 1450 259 1450 259 1451 843 1451 844 1451 259 1452 844 1452 845 1452 259 1453 845 1453 261 1453 261 1454 845 1454 846 1454 261 1455 846 1455 847 1455 261 1456 847 1456 264 1456 264 1457 847 1457 848 1457 264 1458 848 1458 849 1458 264 1459 849 1459 266 1459 266 1460 849 1460 267 1460 267 1461 849 1461 850 1461 840 1462 251 1462 839 1462 839 1463 251 1463 250 1463 851 1464 803 1464 852 1464 852 1465 803 1465 853 1465 853 1466 803 1466 824 1466 853 1467 824 1467 854 1467 854 1468 824 1468 855 1468 855 1469 824 1469 814 1469 855 1470 814 1470 856 1470 856 1471 814 1471 812 1471 856 1472 812 1472 857 1472 857 1473 812 1473 813 1473 857 1474 813 1474 858 1474 858 1475 813 1475 838 1475 858 1476 838 1476 829 1476 858 1477 829 1477 859 1477 859 1478 829 1478 860 1478 860 1479 829 1479 828 1479 860 1480 828 1480 827 1480 860 1481 827 1481 861 1481 861 1482 827 1482 862 1482 862 1483 827 1483 818 1483 862 1484 818 1484 851 1484 851 1485 818 1485 817 1485 851 1486 817 1486 803 1486 854 1487 234 1487 853 1487 856 1488 238 1488 855 1488 855 1489 238 1489 236 1489 855 1490 236 1490 854 1490 854 1491 236 1491 234 1491 853 1492 234 1492 852 1492 238 1493 856 1493 857 1493 238 1494 857 1494 240 1494 240 1495 857 1495 858 1495 240 1496 858 1496 242 1496 242 1497 858 1497 859 1497 242 1498 859 1498 244 1498 244 1499 859 1499 860 1499 244 1500 860 1500 246 1500 246 1501 860 1501 861 1501 246 1502 861 1502 862 1502 246 1503 862 1503 248 1503 248 1504 862 1504 851 1504 248 1505 851 1505 233 1505 234 1506 233 1506 852 1506 852 1507 233 1507 851 1507 863 1508 825 1508 864 1508 864 1509 825 1509 816 1509 864 1510 816 1510 865 1510 865 1511 816 1511 810 1511 865 1512 810 1512 866 1512 866 1513 810 1513 809 1513 866 1514 809 1514 815 1514 866 1515 815 1515 867 1515 867 1516 815 1516 823 1516 867 1517 823 1517 868 1517 868 1518 823 1518 869 1518 869 1519 823 1519 805 1519 869 1520 805 1520 870 1520 870 1521 805 1521 804 1521 870 1522 804 1522 871 1522 871 1523 804 1523 833 1523 871 1524 833 1524 872 1524 872 1525 833 1525 835 1525 872 1526 835 1526 834 1526 872 1527 834 1527 873 1527 873 1528 834 1528 826 1528 873 1529 826 1529 874 1529 874 1530 826 1530 863 1530 863 1531 826 1531 825 1531 865 1532 214 1532 864 1532 231 1533 873 1533 874 1533 865 1534 216 1534 214 1534 216 1535 865 1535 866 1535 216 1536 866 1536 218 1536 218 1537 866 1537 867 1537 218 1538 867 1538 220 1538 220 1539 867 1539 868 1539 220 1540 868 1540 222 1540 222 1541 868 1541 869 1541 222 1542 869 1542 870 1542 222 1543 870 1543 224 1543 224 1544 870 1544 871 1544 224 1545 871 1545 227 1545 227 1546 871 1546 872 1546 227 1547 872 1547 228 1547 228 1548 872 1548 873 1548 228 1549 873 1549 231 1549 864 1550 214 1550 213 1550 864 1551 213 1551 863 1551 863 1552 213 1552 874 1552 874 1553 213 1553 231 1553 875 1554 876 1554 877 1554 821 1555 800 1555 875 1555 875 1556 800 1556 876 1556 878 1557 879 1557 877 1557 878 1558 877 1558 876 1558 879 1559 878 1559 880 1559 880 1560 878 1560 881 1560 882 1561 883 1561 881 1561 881 1562 883 1562 880 1562 882 1563 881 1563 884 1563 686 1564 885 1564 882 1564 882 1565 884 1565 686 1565 885 1566 686 1566 684 1566 886 1567 807 1567 819 1567 807 1568 886 1568 887 1568 887 1569 886 1569 888 1569 887 1570 888 1570 889 1570 889 1571 888 1571 890 1571 890 1572 891 1572 889 1572 892 1573 891 1573 890 1573 891 1574 892 1574 893 1574 893 1575 894 1575 891 1575 894 1576 893 1576 895 1576 894 1577 895 1577 896 1577 896 1578 895 1578 494 1578 895 1579 495 1579 494 1579 170 1580 897 1580 898 1580 170 1581 898 1581 899 1581 170 1582 899 1582 900 1582 901 1583 193 1583 900 1583 901 1584 900 1584 899 1584 193 1585 901 1585 195 1585 195 1586 901 1586 902 1586 195 1587 902 1587 903 1587 195 1588 903 1588 197 1588 197 1589 903 1589 198 1589 904 1590 198 1590 903 1590 904 1591 905 1591 198 1591 906 1592 182 1592 905 1592 906 1593 905 1593 904 1593 906 1594 180 1594 182 1594 907 1595 180 1595 906 1595 908 1596 180 1596 907 1596 908 1597 175 1597 180 1597 909 1598 175 1598 908 1598 175 1599 909 1599 174 1599 897 1600 174 1600 909 1600 174 1601 897 1601 173 1601 897 1602 170 1602 173 1602 200 1603 898 1603 209 1603 209 1604 898 1604 897 1604 209 1605 897 1605 909 1605 209 1606 909 1606 208 1606 208 1607 909 1607 207 1607 207 1608 909 1608 908 1608 207 1609 908 1609 206 1609 206 1610 908 1610 907 1610 206 1611 907 1611 906 1611 206 1612 906 1612 205 1612 205 1613 906 1613 904 1613 205 1614 904 1614 204 1614 204 1615 904 1615 903 1615 204 1616 903 1616 203 1616 203 1617 903 1617 902 1617 203 1618 902 1618 202 1618 202 1619 902 1619 901 1619 202 1620 901 1620 201 1620 201 1621 901 1621 899 1621 201 1622 899 1622 200 1622 200 1623 899 1623 898 1623 910 1624 911 1624 912 1624 910 1625 912 1625 913 1625 914 1626 915 1626 911 1626 914 1627 911 1627 910 1627 913 1628 912 1628 916 1628 913 1629 916 1629 917 1629 918 1630 161 1630 919 1630 919 1631 161 1631 169 1631 919 1632 169 1632 920 1632 920 1633 169 1633 168 1633 920 1634 168 1634 921 1634 921 1635 168 1635 922 1635 922 1636 168 1636 167 1636 922 1637 167 1637 923 1637 923 1638 167 1638 924 1638 924 1639 167 1639 166 1639 924 1640 166 1640 925 1640 925 1641 166 1641 165 1641 925 1642 165 1642 926 1642 926 1643 165 1643 164 1643 926 1644 164 1644 927 1644 927 1645 164 1645 163 1645 927 1646 163 1646 928 1646 928 1647 163 1647 929 1647 929 1648 163 1648 162 1648 929 1649 162 1649 918 1649 918 1650 162 1650 161 1650 930 1651 914 1651 923 1651 923 1652 914 1652 922 1652 924 1653 159 1653 923 1653 923 1654 159 1654 930 1654 159 1655 924 1655 925 1655 159 1656 925 1656 158 1656 158 1657 925 1657 143 1657 143 1658 925 1658 926 1658 144 1659 143 1659 926 1659 144 1660 926 1660 927 1660 144 1661 927 1661 146 1661 928 1662 146 1662 927 1662 929 1663 147 1663 928 1663 928 1664 147 1664 146 1664 929 1665 149 1665 147 1665 918 1666 931 1666 929 1666 929 1667 931 1667 149 1667 918 1668 917 1668 931 1668 917 1669 918 1669 919 1669 922 1670 914 1670 910 1670 922 1671 910 1671 921 1671 921 1672 910 1672 920 1672 920 1673 910 1673 913 1673 920 1674 913 1674 919 1674 919 1675 913 1675 917 1675 932 1676 933 1676 183 1676 933 1677 934 1677 935 1677 936 1678 935 1678 934 1678 74 1679 937 1679 938 1679 74 1680 938 1680 75 1680 75 1681 938 1681 939 1681 75 1682 939 1682 77 1682 77 1683 939 1683 940 1683 77 1684 940 1684 79 1684 936 1685 934 1685 940 1685 940 1686 934 1686 79 1686 79 1687 934 1687 941 1687 933 1688 932 1688 934 1688 934 1689 932 1689 941 1689 941 1690 932 1690 188 1690 183 1691 185 1691 932 1691 932 1692 185 1692 186 1692 932 1693 186 1693 188 1693 942 1694 943 1694 944 1694 945 1695 66 1695 946 1695 947 1696 948 1696 949 1696 950 1697 153 1697 151 1697 943 1698 942 1698 951 1698 943 1699 951 1699 950 1699 950 1700 951 1700 153 1700 153 1701 951 1701 155 1701 948 1702 947 1702 944 1702 944 1703 947 1703 942 1703 945 1704 946 1704 949 1704 949 1705 946 1705 952 1705 949 1706 952 1706 947 1706 947 1707 953 1707 942 1707 942 1708 953 1708 951 1708 951 1709 953 1709 157 1709 951 1710 157 1710 155 1710 954 1711 159 1711 160 1711 915 1712 930 1712 159 1712 915 1713 159 1713 954 1713 915 1714 914 1714 930 1714 955 1715 931 1715 917 1715 916 1716 955 1716 917 1716 150 1717 931 1717 955 1717 150 1718 149 1718 931 1718 192 1719 900 1719 193 1719 170 1720 900 1720 192 1720 171 1721 170 1721 192 1721 956 1722 957 1722 182 1722 182 1723 181 1723 956 1723 957 1724 905 1724 182 1724 957 1725 958 1725 905 1725 199 1726 198 1726 958 1726 958 1727 198 1727 905 1727 959 1728 960 1728 961 1728 100 1729 959 1729 961 1729 961 1730 962 1730 101 1730 961 1731 101 1731 100 1731 963 1732 686 1732 884 1732 881 1733 878 1733 964 1733 752 1734 686 1734 965 1734 876 1735 966 1735 878 1735 963 1736 967 1736 965 1736 968 1737 959 1737 967 1737 965 1738 967 1738 100 1738 876 1739 969 1739 966 1739 878 1740 966 1740 964 1740 964 1741 960 1741 881 1741 881 1742 960 1742 968 1742 105 1743 965 1743 100 1743 800 1744 969 1744 876 1744 881 1745 968 1745 884 1745 884 1746 968 1746 967 1746 884 1747 967 1747 963 1747 963 1748 965 1748 686 1748 752 1749 965 1749 105 1749 960 1750 970 1750 962 1750 960 1751 962 1751 961 1751 969 1752 970 1752 966 1752 966 1753 970 1753 960 1753 968 1754 960 1754 959 1754 966 1755 960 1755 964 1755 967 1756 959 1756 100 1756 93 1757 101 1757 962 1757 93 1758 962 1758 971 1758 971 1759 962 1759 970 1759 969 1760 972 1760 970 1760 970 1761 972 1761 971 1761 800 1762 807 1762 969 1762 969 1763 807 1763 972 1763 973 1764 891 1764 894 1764 973 1765 896 1765 974 1765 973 1766 974 1766 975 1766 97 1767 976 1767 974 1767 974 1768 976 1768 975 1768 976 1769 97 1769 96 1769 776 1770 97 1770 974 1770 97 1771 776 1771 99 1771 977 1772 972 1772 807 1772 977 1773 807 1773 887 1773 972 1774 977 1774 971 1774 894 1775 896 1775 973 1775 889 1776 891 1776 978 1776 979 1777 977 1777 980 1777 979 1778 980 1778 94 1778 978 1779 980 1779 977 1779 980 1780 96 1780 94 1780 889 1781 978 1781 887 1781 887 1782 978 1782 977 1782 977 1783 979 1783 971 1783 971 1784 979 1784 94 1784 971 1785 94 1785 93 1785 891 1786 973 1786 975 1786 896 1787 776 1787 974 1787 980 1788 975 1788 976 1788 494 1789 776 1789 896 1789 891 1790 975 1790 978 1790 978 1791 975 1791 980 1791 980 1792 976 1792 96 1792 883 1793 981 1793 982 1793 882 1794 983 1794 883 1794 883 1795 983 1795 981 1795 984 1796 118 1796 985 1796 121 1797 118 1797 984 1797 981 1798 764 1798 984 1798 984 1799 764 1799 121 1799 986 1800 982 1800 985 1800 986 1801 118 1801 987 1801 987 1802 118 1802 117 1802 885 1803 684 1803 763 1803 885 1804 763 1804 983 1804 885 1805 983 1805 882 1805 880 1806 988 1806 879 1806 989 1807 990 1807 991 1807 986 1808 989 1808 988 1808 989 1809 986 1809 987 1809 989 1810 987 1810 990 1810 990 1811 987 1811 117 1811 990 1812 117 1812 130 1812 883 1813 982 1813 988 1813 880 1814 883 1814 988 1814 981 1815 984 1815 982 1815 986 1816 985 1816 118 1816 763 1817 764 1817 983 1817 983 1818 764 1818 981 1818 984 1819 985 1819 982 1819 982 1820 986 1820 988 1820 879 1821 988 1821 989 1821 879 1822 989 1822 877 1822 877 1823 989 1823 991 1823 877 1824 991 1824 875 1824 875 1825 991 1825 992 1825 130 1826 134 1826 132 1826 130 1827 132 1827 993 1827 130 1828 993 1828 990 1828 990 1829 993 1829 994 1829 990 1830 994 1830 991 1830 991 1831 994 1831 992 1831 875 1832 992 1832 995 1832 875 1833 995 1833 821 1833 821 1834 995 1834 819 1834 996 1835 997 1835 998 1835 998 1836 997 1836 999 1836 998 1837 999 1837 994 1837 994 1838 993 1838 998 1838 998 1839 993 1839 996 1839 996 1840 993 1840 132 1840 495 1841 895 1841 793 1841 1000 1842 793 1842 895 1842 895 1843 893 1843 1000 1843 1000 1844 893 1844 1001 1844 888 1845 1002 1845 890 1845 793 1846 1000 1846 794 1846 819 1847 995 1847 886 1847 890 1848 1002 1848 1003 1848 892 1849 1003 1849 1001 1849 1000 1850 1001 1850 794 1850 794 1851 1004 1851 124 1851 1002 1852 999 1852 1003 1852 1004 1853 131 1853 124 1853 995 1854 992 1854 886 1854 886 1855 992 1855 1005 1855 886 1856 1005 1856 888 1856 888 1857 1005 1857 1002 1857 794 1858 1001 1858 1004 1858 890 1859 1003 1859 892 1859 893 1860 892 1860 1001 1860 996 1861 132 1861 131 1861 1005 1862 992 1862 994 1862 1005 1863 994 1863 999 1863 1003 1864 997 1864 1001 1864 997 1865 996 1865 1004 1865 1004 1866 996 1866 131 1866 1002 1867 1005 1867 999 1867 1003 1868 999 1868 997 1868 1001 1869 997 1869 1004 1869 91 1870 89 1870 1006 1870 91 1871 1006 1871 1007 1871 1007 1872 1006 1872 1008 1872 1007 1873 1008 1873 1009 1873 1009 1874 1008 1874 1010 1874 1010 1875 1008 1875 192 1875 1010 1876 192 1876 194 1876 1006 1877 1011 1877 1008 1877 1008 1878 1011 1878 1012 1878 1008 1879 1012 1879 192 1879 89 1880 1013 1880 1006 1880 1006 1881 1013 1881 1011 1881 192 1882 1012 1882 171 1882 89 1883 95 1883 1013 1883 1011 1884 1014 1884 1012 1884 1012 1885 1014 1885 171 1885 95 1886 1015 1886 1013 1886 1013 1887 1015 1887 1016 1887 1013 1888 1016 1888 1011 1888 1011 1889 1016 1889 1017 1889 1011 1890 1017 1890 1014 1890 1014 1891 1017 1891 172 1891 1014 1892 172 1892 171 1892 189 1893 178 1893 1018 1893 1018 1894 178 1894 1019 1894 1018 1895 1019 1895 1020 1895 1019 1896 1017 1896 1016 1896 1019 1897 1016 1897 1020 1897 1020 1898 1016 1898 1015 1898 1020 1899 1015 1899 1021 1899 1021 1900 1015 1900 95 1900 178 1901 172 1901 1019 1901 1019 1902 172 1902 1017 1902 98 1903 498 1903 95 1903 498 1904 497 1904 1021 1904 1021 1905 497 1905 1020 1905 95 1906 498 1906 1021 1906 1018 1907 557 1907 189 1907 1018 1908 767 1908 557 1908 497 1909 767 1909 1020 1909 1020 1910 767 1910 1018 1910 911 1911 915 1911 1022 1911 1022 1912 915 1912 1023 1912 1022 1913 1023 1913 1024 1913 1024 1914 1023 1914 1025 1914 1024 1915 1025 1915 1026 1915 1026 1916 1025 1916 60 1916 60 1917 1025 1917 86 1917 86 1918 1027 1918 1028 1918 1029 1919 954 1919 1030 1919 1030 1920 954 1920 160 1920 1027 1921 1031 1921 1029 1921 1029 1922 1031 1922 954 1922 86 1923 1025 1923 1027 1923 954 1924 1031 1924 915 1924 1027 1925 1025 1925 1023 1925 1027 1926 1023 1926 1031 1926 1031 1927 1023 1927 915 1927 1029 1928 1030 1928 1032 1928 1029 1929 1032 1929 1027 1929 1027 1930 1032 1930 1028 1930 86 1931 1028 1931 92 1931 160 1932 142 1932 1030 1932 142 1933 137 1933 1030 1933 1030 1934 137 1934 1033 1934 1030 1935 1033 1935 1034 1935 1030 1936 1034 1936 1032 1936 1032 1937 1034 1937 1028 1937 1028 1938 1034 1938 1035 1938 1028 1939 1035 1939 92 1939 137 1940 140 1940 1033 1940 1033 1941 140 1941 1036 1941 1033 1942 1036 1942 1037 1942 1033 1943 1037 1943 1034 1943 1034 1944 1037 1944 1035 1944 104 1945 92 1945 1035 1945 1035 1946 639 1946 104 1946 1037 1947 639 1947 1035 1947 639 1948 1037 1948 676 1948 1037 1949 744 1949 676 1949 1036 1950 744 1950 1037 1950 140 1951 278 1951 1036 1951 1036 1952 278 1952 744 1952 1038 1953 1039 1953 1040 1953 1041 1954 916 1954 1040 1954 1040 1955 916 1955 1042 1955 1042 1956 916 1956 912 1956 1038 1957 1040 1957 1042 1957 1043 1958 1042 1958 1044 1958 944 1959 1038 1959 1042 1959 944 1960 1042 1960 948 1960 948 1961 1042 1961 1043 1961 1045 1962 1042 1962 912 1962 1045 1963 1044 1963 1042 1963 1044 1964 945 1964 1043 1964 945 1965 949 1965 1043 1965 1043 1966 949 1966 948 1966 151 1967 1047 1967 950 1967 950 1968 1047 1968 943 1968 943 1969 1047 1969 1039 1969 943 1970 1039 1970 944 1970 944 1971 1039 1971 1038 1971 151 1972 150 1972 955 1972 151 1973 955 1973 1047 1973 1041 1974 955 1974 916 1974 1041 1975 1040 1975 1039 1975 1041 1976 1039 1976 955 1976 955 1977 1039 1977 1047 1977 1048 1978 1049 1978 199 1978 1050 1979 1048 1979 1051 1979 1052 1980 1050 1980 1053 1980 1053 1981 1050 1981 1051 1981 937 1982 1052 1982 938 1982 938 1983 1052 1983 1053 1983 938 1984 1053 1984 939 1984 939 1985 1053 1985 936 1985 199 1986 1051 1986 1048 1986 1048 1987 1050 1987 1052 1987 1048 1988 1052 1988 1054 1988 1051 1989 936 1989 1053 1989 936 1990 940 1990 939 1990 181 1991 183 1991 933 1991 181 1992 933 1992 957 1992 957 1993 933 1993 935 1993 935 1994 936 1994 1051 1994 957 1995 935 1995 1055 1995 1055 1996 935 1996 1051 1996 1051 1997 958 1997 1055 1997 957 1998 956 1998 181 1998 958 1999 1051 1999 199 1999 1055 2000 958 2000 957 2000 90 2001 91 2001 1056 2001 1056 2002 91 2002 1057 2002 1056 2003 1057 2003 483 2003 483 2004 1057 2004 1058 2004 1058 2005 478 2005 483 2005 1058 2006 1059 2006 478 2006 1060 2007 1059 2007 1058 2007 1060 2008 1058 2008 1057 2008 1009 2009 1061 2009 1060 2009 1009 2010 1060 2010 1007 2010 1007 2011 1060 2011 1057 2011 1007 2012 1057 2012 91 2012 194 2013 1062 2013 1010 2013 1059 2014 1060 2014 1061 2014 1061 2015 1009 2015 1062 2015 1062 2016 1009 2016 1010 2016 1063 2017 80 2017 478 2017 1063 2018 478 2018 1064 2018 1064 2019 478 2019 1059 2019 1064 2020 1059 2020 1065 2020 1065 2021 1059 2021 1061 2021 1065 2022 1061 2022 1066 2022 1066 2023 1061 2023 1062 2023 1066 2024 1062 2024 1067 2024 1067 2025 1062 2025 196 2025 196 2026 1062 2026 194 2026 1063 2027 1064 2027 1065 2027 1068 2028 1069 2028 1063 2028 1068 2029 1063 2029 1070 2029 1070 2030 1063 2030 1065 2030 1049 2031 1048 2031 1067 2031 937 2032 1071 2032 1068 2032 1072 2033 1070 2033 1066 2033 1071 2034 1069 2034 1068 2034 1070 2035 1065 2035 1066 2035 1048 2036 1054 2036 1067 2036 1054 2037 1072 2037 1067 2037 1052 2038 937 2038 1054 2038 1054 2039 1070 2039 1072 2039 1072 2040 1066 2040 1067 2040 937 2041 1068 2041 1054 2041 1054 2042 1068 2042 1070 2042 937 2043 74 2043 1071 2043 1024 2044 1073 2044 1022 2044 1074 2045 1073 2045 1075 2045 1075 2046 1073 2046 1024 2046 1076 2047 1074 2047 1075 2047 1077 2048 1075 2048 1024 2048 1076 2049 1075 2049 57 2049 57 2050 1075 2050 1077 2050 1026 2051 1077 2051 1024 2051 1022 2052 1073 2052 911 2052 1026 2053 60 2053 1077 2053 1077 2054 60 2054 59 2054 1077 2055 59 2055 57 2055 1076 2056 57 2056 49 2056 912 2057 911 2057 1078 2057 1078 2058 911 2058 1073 2058 1078 2059 1073 2059 1074 2059 1078 2060 1074 2060 1079 2060 1079 2061 1074 2061 1076 2061 1079 2062 1076 2062 55 2062 55 2063 1076 2063 49 2063 1046 2064 945 2064 1044 2064 1045 2065 912 2065 1078 2065 1045 2066 1078 2066 1080 2066 1080 2067 1078 2067 1079 2067 1081 2068 1046 2068 1044 2068 1080 2069 1044 2069 1045 2069 1080 2070 1081 2070 1044 2070 55 2071 1081 2071 1079 2071 1079 2072 1081 2072 1080 2072 66 2073 64 2073 946 2073 946 2074 1082 2074 952 2074 952 2075 1082 2075 947 2075 82 2076 68 2076 83 2076 83 2077 68 2077 84 2077 269 2078 260 2078 262 2078 260 2079 269 2079 252 2079 260 2080 252 2080 254 2080 254 2081 256 2081 260 2081 260 2082 256 2082 258 2082 262 2083 263 2083 269 2083 263 2084 265 2084 269 2084 269 2085 265 2085 268 2085 225 2086 212 2086 223 2086 221 2087 223 2087 215 2087 215 2088 223 2088 212 2088 229 2089 225 2089 226 2089 229 2090 230 2090 225 2090 221 2091 215 2091 219 2091 225 2092 230 2092 212 2092 219 2093 215 2093 217 2093 243 2094 232 2094 241 2094 241 2095 232 2095 239 2095 239 2096 232 2096 235 2096 232 2097 243 2097 249 2097 249 2098 243 2098 245 2098 235 2099 237 2099 239 2099 249 2100 245 2100 247 2100 1083 2101 1084 2101 1085 2101 1086 2102 1087 2102 1088 2102 1089 2103 1090 2103 1086 2103 1086 2104 1090 2104 1087 2104 1091 2105 1092 2105 1093 2105 1094 2106 1093 2106 1095 2106 1094 2107 1096 2107 1093 2107 1088 2108 1083 2108 1085 2108 1095 2109 1093 2109 1092 2109 1085 2110 1096 2110 1088 2110 1088 2111 1096 2111 1086 2111 1084 2112 1097 2112 1098 2112 1099 2113 1085 2113 1100 2113 1101 2114 1102 2114 1103 2114 1084 2115 1098 2115 1104 2115 1104 2116 1105 2116 1084 2116 1084 2117 1105 2117 1085 2117 1085 2118 1105 2118 1100 2118 1101 2119 1106 2119 1099 2119 1107 2120 134 2120 1103 2120 1107 2121 1103 2121 1102 2121 134 2122 1107 2122 1108 2122 136 2123 1109 2123 1110 2123 1111 2124 1097 2124 1112 2124 1112 2125 1097 2125 1113 2125 1113 2126 1097 2126 1084 2126 134 2127 1108 2127 1114 2127 1115 2128 134 2128 1116 2128 134 2129 1117 2129 136 2129 136 2130 1117 2130 1109 2130 1118 2131 1092 2131 1091 2131 134 2132 1114 2132 1111 2132 1119 2133 1089 2133 1120 2133 1120 2134 1089 2134 1086 2134 1121 2135 1119 2135 1120 2135 134 2136 1115 2136 1122 2136 134 2137 1122 2137 1123 2137 134 2138 1123 2138 1117 2138 136 2139 1110 2139 1118 2139 136 2140 1118 2140 1091 2140 1112 2141 1116 2141 1111 2141 1111 2142 1116 2142 134 2142 1119 2143 1121 2143 1123 2143 1119 2144 1123 2144 1122 2144 1124 2145 1097 2145 1125 2145 1125 2146 1097 2146 1111 2146 1125 2147 1111 2147 1126 2147 1126 2148 1111 2148 1114 2148 1126 2149 1114 2149 1127 2149 1127 2150 1114 2150 1128 2150 1128 2151 1114 2151 1108 2151 1128 2152 1108 2152 1107 2152 1128 2153 1107 2153 1129 2153 1129 2154 1107 2154 1102 2154 1129 2155 1102 2155 1130 2155 1130 2156 1102 2156 1131 2156 1131 2157 1102 2157 1101 2157 1131 2158 1101 2158 1099 2158 1131 2159 1099 2159 1132 2159 1132 2160 1099 2160 1100 2160 1132 2161 1100 2161 1133 2161 1133 2162 1100 2162 1105 2162 1133 2163 1105 2163 1104 2163 1133 2164 1104 2164 1134 2164 1134 2165 1104 2165 1124 2165 1124 2166 1104 2166 1098 2166 1124 2167 1098 2167 1097 2167 1135 2168 1089 2168 1136 2168 1136 2169 1089 2169 1119 2169 1136 2170 1119 2170 1122 2170 1136 2171 1122 2171 1137 2171 1137 2172 1122 2172 1115 2172 1137 2173 1115 2173 1138 2173 1138 2174 1115 2174 1116 2174 1138 2175 1116 2175 1139 2175 1139 2176 1116 2176 1112 2176 1139 2177 1112 2177 1140 2177 1140 2178 1112 2178 1141 2178 1141 2179 1112 2179 1113 2179 1141 2180 1113 2180 1084 2180 1141 2181 1084 2181 1142 2181 1142 2182 1084 2182 1083 2182 1142 2183 1083 2183 1143 2183 1143 2184 1083 2184 1088 2184 1143 2185 1088 2185 1144 2185 1144 2186 1088 2186 1087 2186 1144 2187 1087 2187 1145 2187 1145 2188 1087 2188 1090 2188 1145 2189 1090 2189 1135 2189 1135 2190 1090 2190 1089 2190 1146 2191 1092 2191 1118 2191 1146 2192 1118 2192 1147 2192 1147 2193 1118 2193 1110 2193 1147 2194 1110 2194 1109 2194 1147 2195 1109 2195 1148 2195 1148 2196 1109 2196 1149 2196 1149 2197 1109 2197 1117 2197 1149 2198 1117 2198 1150 2198 1150 2199 1117 2199 1123 2199 1150 2200 1123 2200 1121 2200 1150 2201 1121 2201 1151 2201 1151 2202 1121 2202 1120 2202 1151 2203 1120 2203 1152 2203 1152 2204 1120 2204 1086 2204 1152 2205 1086 2205 1153 2205 1153 2206 1086 2206 1154 2206 1154 2207 1086 2207 1096 2207 1154 2208 1096 2208 1155 2208 1155 2209 1096 2209 1094 2209 1155 2210 1094 2210 1156 2210 1156 2211 1094 2211 1095 2211 1156 2212 1095 2212 1092 2212 1156 2213 1092 2213 1146 2213 1157 2214 136 2214 1091 2214 1158 2215 1159 2215 1160 2215 1158 2216 1160 2216 1161 2216 103 2217 1161 2217 1160 2217 1103 2218 134 2218 1162 2218 1162 2219 1163 2219 1106 2219 1162 2220 1106 2220 1103 2220 1101 2221 1103 2221 1106 2221 1096 2222 1085 2222 1093 2222 1093 2223 1085 2223 1164 2223 1164 2224 1085 2224 1165 2224 1165 2225 1085 2225 1166 2225 1093 2226 1167 2226 1091 2226 1091 2227 1167 2227 1157 2227 1157 2228 1167 2228 1168 2228 1132 2229 1169 2229 1131 2229 1125 2230 1126 2230 1170 2230 1170 2231 1126 2231 1171 2231 1132 2232 1172 2232 1169 2232 1126 2233 1127 2233 1171 2233 1171 2234 1127 2234 1128 2234 1171 2235 1128 2235 1173 2235 1173 2236 1128 2236 1174 2236 1174 2237 1128 2237 1129 2237 1174 2238 1129 2238 1175 2238 1176 2239 1125 2239 1170 2239 1172 2240 1132 2240 1133 2240 1172 2241 1133 2241 1177 2241 1177 2242 1133 2242 1178 2242 1178 2243 1133 2243 1134 2243 1178 2244 1134 2244 1124 2244 1178 2245 1124 2245 1179 2245 1179 2246 1124 2246 1125 2246 1179 2247 1125 2247 1176 2247 1175 2248 1129 2248 1130 2248 1175 2249 1130 2249 1131 2249 1175 2250 1131 2250 1169 2250 1142 2251 1180 2251 1141 2251 1181 2252 1136 2252 1137 2252 1181 2253 1137 2253 1182 2253 1143 2254 1183 2254 1142 2254 1142 2255 1183 2255 1180 2255 1182 2256 1137 2256 1138 2256 1182 2257 1138 2257 1184 2257 1184 2258 1138 2258 1139 2258 1184 2259 1139 2259 1185 2259 1186 2260 1135 2260 1136 2260 1186 2261 1136 2261 1181 2261 1183 2262 1143 2262 1144 2262 1183 2263 1144 2263 1187 2263 1187 2264 1144 2264 1145 2264 1187 2265 1145 2265 1188 2265 1188 2266 1145 2266 1135 2266 1188 2267 1135 2267 1186 2267 1139 2268 1140 2268 1185 2268 1185 2269 1140 2269 1141 2269 1185 2270 1141 2270 1180 2270 1153 2271 1189 2271 1152 2271 1190 2272 1147 2272 1191 2272 1191 2273 1147 2273 1148 2273 1154 2274 1192 2274 1189 2274 1154 2275 1189 2275 1153 2275 1191 2276 1148 2276 1149 2276 1191 2277 1149 2277 1193 2277 1193 2278 1149 2278 1150 2278 1193 2279 1150 2279 1194 2279 1195 2280 1146 2280 1190 2280 1190 2281 1146 2281 1147 2281 1154 2282 1155 2282 1192 2282 1192 2283 1155 2283 1156 2283 1192 2284 1156 2284 1196 2284 1196 2285 1156 2285 1197 2285 1197 2286 1156 2286 1146 2286 1197 2287 1146 2287 1195 2287 1150 2288 1151 2288 1194 2288 1194 2289 1151 2289 1198 2289 1198 2290 1151 2290 1152 2290 1198 2291 1152 2291 1189 2291 1199 2292 136 2292 1200 2292 1200 2293 136 2293 1157 2293 1200 2294 1157 2294 1201 2294 1202 2295 1203 2295 1204 2295 1205 2296 1206 2296 1207 2296 1207 2297 1206 2297 484 2297 135 2298 136 2298 1199 2298 1205 2299 1202 2299 1206 2299 1206 2300 1202 2300 1204 2300 1206 2301 1204 2301 1208 2301 1208 2302 1204 2302 1209 2302 1208 2303 1209 2303 1210 2303 1211 2304 70 2304 72 2304 1212 2305 1213 2305 1203 2305 1203 2306 1214 2306 1215 2306 67 2307 1216 2307 481 2307 1216 2308 67 2308 70 2308 1211 2309 72 2309 75 2309 1213 2310 1212 2310 1217 2310 1218 2311 1219 2311 1220 2311 1220 2312 1219 2312 1211 2312 1211 2313 1219 2313 1221 2313 1203 2314 1215 2314 1212 2314 1216 2315 1222 2315 481 2315 484 2316 482 2316 1207 2316 1207 2317 482 2317 1223 2317 1224 2318 1225 2318 1202 2318 1207 2319 1223 2319 1222 2319 1207 2320 1222 2320 1216 2320 1211 2321 75 2321 78 2321 1213 2322 1217 2322 1226 2322 1221 2323 1224 2323 1211 2323 1220 2324 1227 2324 1218 2324 70 2325 1211 2325 1216 2325 1216 2326 1211 2326 1202 2326 1202 2327 1211 2327 1224 2327 1225 2328 1214 2328 1202 2328 1202 2329 1214 2329 1203 2329 1213 2330 1226 2330 1220 2330 1220 2331 1226 2331 1227 2331 1228 2332 1159 2332 1229 2332 1229 2333 1159 2333 1158 2333 1162 2334 134 2334 1230 2334 1230 2335 134 2335 133 2335 1232 2336 54 2336 1233 2336 1234 2337 1231 2337 51 2337 1234 2338 51 2338 1235 2338 1235 2339 51 2339 1236 2339 1235 2340 1236 2340 1237 2340 1237 2341 1236 2341 1238 2341 1239 2342 1240 2342 1238 2342 1238 2343 1240 2343 1241 2343 1238 2344 1241 2344 1237 2344 1237 2345 1241 2345 1242 2345 1237 2346 1242 2346 1232 2346 1232 2347 1242 2347 1243 2347 1232 2348 1243 2348 56 2348 56 2349 1243 2349 64 2349 1162 2350 1230 2350 1244 2350 1162 2351 1244 2351 1245 2351 56 2352 54 2352 1232 2352 1232 2353 1233 2353 1234 2353 1234 2354 1233 2354 1231 2354 1082 2355 946 2355 1243 2355 1243 2356 946 2356 64 2356 1246 2357 1247 2357 1248 2357 1249 2358 1250 2358 1246 2358 1250 2359 1249 2359 1251 2359 1250 2360 1251 2360 1252 2360 1246 2361 1248 2361 1249 2361 1253 2362 1242 2362 1254 2362 1255 2363 1256 2363 1243 2363 1243 2364 1256 2364 1257 2364 1243 2365 1257 2365 1247 2365 1243 2366 1247 2366 1246 2366 1250 2367 1252 2367 1242 2367 1242 2368 1252 2368 1254 2368 1253 2369 1255 2369 1242 2369 1242 2370 1255 2370 1243 2370 1162 2371 1245 2371 1163 2371 1163 2372 1245 2372 1258 2372 1166 2373 1259 2373 1165 2373 1165 2374 1259 2374 1260 2374 1168 2375 1261 2375 1157 2375 1157 2376 1261 2376 1201 2376 1175 2377 1262 2377 1263 2377 1175 2378 1263 2378 1174 2378 1174 2379 1263 2379 1264 2379 1174 2380 1264 2380 1173 2380 1173 2381 1264 2381 1265 2381 1173 2382 1265 2382 1171 2382 1171 2383 1265 2383 1266 2383 1171 2384 1266 2384 1170 2384 1170 2385 1266 2385 1176 2385 1176 2386 1266 2386 1267 2386 1176 2387 1267 2387 1268 2387 1176 2388 1268 2388 1179 2388 1179 2389 1268 2389 1178 2389 1178 2390 1268 2390 1269 2390 1178 2391 1269 2391 1270 2391 1178 2392 1270 2392 1177 2392 1177 2393 1270 2393 1172 2393 1172 2394 1270 2394 1271 2394 1172 2395 1271 2395 1272 2395 1172 2396 1272 2396 1169 2396 1169 2397 1272 2397 1175 2397 1175 2398 1272 2398 1262 2398 1185 2399 1273 2399 1274 2399 1185 2400 1274 2400 1275 2400 1185 2401 1275 2401 1184 2401 1184 2402 1275 2402 1182 2402 1182 2403 1275 2403 1276 2403 1182 2404 1276 2404 1181 2404 1181 2405 1276 2405 1277 2405 1181 2406 1277 2406 1278 2406 1181 2407 1278 2407 1186 2407 1186 2408 1278 2408 1279 2408 1186 2409 1279 2409 1188 2409 1188 2410 1279 2410 1280 2410 1188 2411 1280 2411 1187 2411 1187 2412 1280 2412 1281 2412 1187 2413 1281 2413 1183 2413 1183 2414 1281 2414 1282 2414 1183 2415 1282 2415 1180 2415 1180 2416 1282 2416 1273 2416 1180 2417 1273 2417 1185 2417 1198 2418 1283 2418 1194 2418 1194 2419 1283 2419 1284 2419 1194 2420 1284 2420 1193 2420 1193 2421 1284 2421 1285 2421 1193 2422 1285 2422 1191 2422 1191 2423 1285 2423 1286 2423 1191 2424 1286 2424 1190 2424 1190 2425 1286 2425 1287 2425 1190 2426 1287 2426 1195 2426 1195 2427 1287 2427 1197 2427 1197 2428 1287 2428 1288 2428 1197 2429 1288 2429 1196 2429 1196 2430 1288 2430 1192 2430 1192 2431 1288 2431 1289 2431 1192 2432 1289 2432 1290 2432 1192 2433 1290 2433 1189 2433 1189 2434 1290 2434 1291 2434 1189 2435 1291 2435 1198 2435 1198 2436 1291 2436 1283 2436 1199 2437 1292 2437 1293 2437 1199 2438 1293 2438 135 2438 135 2439 1293 2439 106 2439 1292 2440 1211 2440 79 2440 79 2441 1211 2441 78 2441 1219 2442 1294 2442 1221 2442 1221 2443 1294 2443 1295 2443 1221 2444 1295 2444 1224 2444 1224 2445 1295 2445 1296 2445 1224 2446 1296 2446 1225 2446 1225 2447 1296 2447 1297 2447 1225 2448 1297 2448 1214 2448 1214 2449 1297 2449 1215 2449 1215 2450 1297 2450 1298 2450 1215 2451 1298 2451 1212 2451 1212 2452 1298 2452 1299 2452 1212 2453 1299 2453 1217 2453 1217 2454 1299 2454 1300 2454 1217 2455 1300 2455 1226 2455 1226 2456 1300 2456 1301 2456 1226 2457 1301 2457 1227 2457 1227 2458 1301 2458 1302 2458 1227 2459 1302 2459 1218 2459 1218 2460 1302 2460 1219 2460 1219 2461 1302 2461 1294 2461 1303 2462 1216 2462 1304 2462 1304 2463 1216 2463 1202 2463 1305 2464 1207 2464 1306 2464 1306 2465 1207 2465 1216 2465 1306 2466 1216 2466 1303 2466 1305 2467 1307 2467 1207 2467 1207 2468 1307 2468 1205 2468 1304 2469 1202 2469 1308 2469 1308 2470 1202 2470 1205 2470 1308 2471 1205 2471 1307 2471 1309 2472 1310 2472 1245 2472 1311 2473 1312 2473 1313 2473 1313 2474 1314 2474 1315 2474 1316 2475 1317 2475 1318 2475 1315 2476 1319 2476 1313 2476 1313 2477 1312 2477 1314 2477 1314 2478 1320 2478 1315 2478 1321 2479 1322 2479 1244 2479 1259 2480 1323 2480 1260 2480 1316 2481 1324 2481 1325 2481 1200 2482 1326 2482 1327 2482 1316 2483 1318 2483 1328 2483 1328 2484 1318 2484 1329 2484 1328 2485 1329 2485 1321 2485 1321 2486 1329 2486 1330 2486 1321 2487 1330 2487 1322 2487 1244 2488 1322 2488 1309 2488 1244 2489 1309 2489 1245 2489 1258 2490 1331 2490 1323 2490 1258 2491 1323 2491 1259 2491 1316 2492 1325 2492 1317 2492 1332 2493 1333 2493 1334 2493 1332 2494 1334 2494 1260 2494 1260 2495 1334 2495 1335 2495 1335 2496 1261 2496 1260 2496 1261 2497 1335 2497 1336 2497 1261 2498 1336 2498 1201 2498 1200 2499 1337 2499 1326 2499 1245 2500 1310 2500 1258 2500 1323 2501 1338 2501 1260 2501 1260 2502 1338 2502 1332 2502 1332 2503 1338 2503 1339 2503 1339 2504 1338 2504 1317 2504 1320 2505 1314 2505 1340 2505 1320 2506 1340 2506 1332 2506 1332 2507 1340 2507 1333 2507 1201 2508 1336 2508 1200 2508 1200 2509 1336 2509 1337 2509 1327 2510 1326 2510 1311 2510 1311 2511 1341 2511 1327 2511 1258 2512 1310 2512 1331 2512 1325 2513 1342 2513 1317 2513 1317 2514 1342 2514 1339 2514 1311 2515 1313 2515 1341 2515 1343 2516 1199 2516 1344 2516 1344 2517 1199 2517 1200 2517 1345 2518 1211 2518 1343 2518 1346 2519 1220 2519 1347 2519 1347 2520 1220 2520 1211 2520 1347 2521 1211 2521 1345 2521 1346 2522 1348 2522 1220 2522 1220 2523 1348 2523 1349 2523 1220 2524 1349 2524 1213 2524 1213 2525 1349 2525 1350 2525 1213 2526 1350 2526 1351 2526 1351 2527 1350 2527 1352 2527 1353 2528 1203 2528 1354 2528 1354 2529 1203 2529 1213 2529 1354 2530 1213 2530 1351 2530 1203 2531 1353 2531 1204 2531 1204 2532 1353 2532 1355 2532 1356 2533 1209 2533 1204 2533 1356 2534 1204 2534 1355 2534 1209 2535 1357 2535 1358 2535 1209 2536 1358 2536 1210 2536 1359 2537 1360 2537 1361 2537 1210 2538 1358 2538 1362 2538 1210 2539 1362 2539 1363 2539 1364 2540 1365 2540 1366 2540 1367 2541 1368 2541 1360 2541 1360 2542 1368 2542 1361 2542 1361 2543 1368 2543 1369 2543 1370 2544 1371 2544 1372 2544 1370 2545 1372 2545 1373 2545 1373 2546 1372 2546 1374 2546 1374 2547 1372 2547 1375 2547 1374 2548 1375 2548 1376 2548 1371 2549 1370 2549 1209 2549 1209 2550 1370 2550 1357 2550 1363 2551 1362 2551 1377 2551 1378 2552 1379 2552 1380 2552 1381 2553 1382 2553 1367 2553 1381 2554 1367 2554 1360 2554 1383 2555 1384 2555 1366 2555 1379 2556 1378 2556 1376 2556 1379 2557 1376 2557 1385 2557 1385 2558 1376 2558 1375 2558 1363 2559 1377 2559 1366 2559 1366 2560 1377 2560 1386 2560 1366 2561 1386 2561 1380 2561 1366 2562 1380 2562 1383 2562 1383 2563 1380 2563 1379 2563 1381 2564 1387 2564 1382 2564 1382 2565 1387 2565 1384 2565 1384 2566 1387 2566 1364 2566 1384 2567 1364 2567 1366 2567 1365 2568 1364 2568 1388 2568 1389 2569 1239 2569 1390 2569 1391 2570 1392 2570 1240 2570 1240 2571 1392 2571 1393 2571 1359 2572 1361 2572 1394 2572 1390 2573 1239 2573 1395 2573 1390 2574 1395 2574 1388 2574 1388 2575 1395 2575 1365 2575 1239 2576 1389 2576 1240 2576 1240 2577 1389 2577 1391 2577 1359 2578 1394 2578 1396 2578 1396 2579 1394 2579 1393 2579 1396 2580 1393 2580 1392 2580 1208 2581 1210 2581 1397 2581 1397 2582 1210 2582 1363 2582 1206 2583 1208 2583 1398 2583 1206 2584 1398 2584 1399 2584 1399 2585 1400 2585 1206 2585 1229 2586 1158 2586 1401 2586 1401 2587 1158 2587 1402 2587 1401 2588 1402 2588 1403 2588 1228 2589 1229 2589 1404 2589 1228 2590 1404 2590 1405 2590 1404 2591 1229 2591 1406 2591 1229 2592 1407 2592 1406 2592 1406 2593 1407 2593 1408 2593 1409 2594 87 2594 1410 2594 1409 2595 1410 2595 1411 2595 1411 2596 1410 2596 1412 2596 1411 2597 1412 2597 1228 2597 1228 2598 1412 2598 1159 2598 1236 2599 1409 2599 1413 2599 1236 2600 1413 2600 1414 2600 111 2601 1415 2601 133 2601 133 2602 1415 2602 1230 2602 1243 2603 1415 2603 1416 2603 1082 2604 1243 2604 947 2604 947 2605 1243 2605 1416 2605 1417 2606 1247 2606 1418 2606 1418 2607 1247 2607 1257 2607 1418 2608 1257 2608 1256 2608 1418 2609 1256 2609 1419 2609 1419 2610 1256 2610 1255 2610 1419 2611 1255 2611 1420 2611 1420 2612 1255 2612 1253 2612 1420 2613 1253 2613 1421 2613 1421 2614 1253 2614 1254 2614 1421 2615 1254 2615 1252 2615 1421 2616 1252 2616 1422 2616 1422 2617 1252 2617 1251 2617 1422 2618 1251 2618 1423 2618 1423 2619 1251 2619 1249 2619 1423 2620 1249 2620 1424 2620 1424 2621 1249 2621 1248 2621 1424 2622 1248 2622 1425 2622 1425 2623 1248 2623 1247 2623 1425 2624 1247 2624 1417 2624 1232 2625 1426 2625 1237 2625 1237 2626 1426 2626 1427 2626 1428 2627 1235 2627 1429 2627 1429 2628 1235 2628 1237 2628 1429 2629 1237 2629 1427 2629 1428 2630 1430 2630 1235 2630 1235 2631 1430 2631 1234 2631 1426 2632 1232 2632 1431 2632 1431 2633 1232 2633 1234 2633 1431 2634 1234 2634 1430 2634 1432 2635 1395 2635 1238 2635 1238 2636 1395 2636 1239 2636 1433 2637 1241 2637 1434 2637 1434 2638 1241 2638 1240 2638 1435 2639 1242 2639 1433 2639 1433 2640 1242 2640 1241 2640 1436 2641 1250 2641 1437 2641 1437 2642 1250 2642 1242 2642 1437 2643 1242 2643 1435 2643 1436 2644 1438 2644 1250 2644 1250 2645 1438 2645 1439 2645 1250 2646 1439 2646 1246 2646 1246 2647 1439 2647 1440 2647 1246 2648 1440 2648 1441 2648 1441 2649 1440 2649 1442 2649 1443 2650 1243 2650 1444 2650 1444 2651 1243 2651 1246 2651 1444 2652 1246 2652 1441 2652 1230 2653 1443 2653 1445 2653 1446 2654 1244 2654 1230 2654 1446 2655 1230 2655 1445 2655 1414 2656 1447 2656 1236 2656 1236 2657 1447 2657 1238 2657 1163 2658 1258 2658 1448 2658 1448 2659 1258 2659 1166 2659 1166 2660 1258 2660 1259 2660 1165 2661 1260 2661 1449 2661 1449 2662 1260 2662 1261 2662 1449 2663 1261 2663 1168 2663 1268 2664 1450 2664 1269 2664 1269 2665 1450 2665 1451 2665 1269 2666 1451 2666 1270 2666 1270 2667 1451 2667 1452 2667 1270 2668 1452 2668 1271 2668 1271 2669 1452 2669 1272 2669 1272 2670 1452 2670 1453 2670 1272 2671 1453 2671 1262 2671 1262 2672 1453 2672 1454 2672 1262 2673 1454 2673 1263 2673 1263 2674 1454 2674 1264 2674 1264 2675 1454 2675 1455 2675 1264 2676 1455 2676 1265 2676 1265 2677 1455 2677 1456 2677 1265 2678 1456 2678 1266 2678 1266 2679 1456 2679 1457 2679 1266 2680 1457 2680 1267 2680 1267 2681 1457 2681 1458 2681 1267 2682 1458 2682 1268 2682 1268 2683 1458 2683 1450 2683 1279 2684 1459 2684 1280 2684 1280 2685 1459 2685 1460 2685 1280 2686 1460 2686 1461 2686 1280 2687 1461 2687 1281 2687 1281 2688 1461 2688 1462 2688 1281 2689 1462 2689 1282 2689 1282 2690 1462 2690 1463 2690 1282 2691 1463 2691 1273 2691 1273 2692 1463 2692 1464 2692 1273 2693 1464 2693 1465 2693 1273 2694 1465 2694 1274 2694 1274 2695 1465 2695 1275 2695 1275 2696 1465 2696 1466 2696 1275 2697 1466 2697 1467 2697 1275 2698 1467 2698 1276 2698 1276 2699 1467 2699 1468 2699 1276 2700 1468 2700 1277 2700 1277 2701 1468 2701 1469 2701 1277 2702 1469 2702 1278 2702 1278 2703 1469 2703 1470 2703 1278 2704 1470 2704 1279 2704 1279 2705 1470 2705 1459 2705 1288 2706 1471 2706 1289 2706 1289 2707 1471 2707 1472 2707 1289 2708 1472 2708 1290 2708 1290 2709 1472 2709 1473 2709 1290 2710 1473 2710 1291 2710 1291 2711 1473 2711 1474 2711 1291 2712 1474 2712 1475 2712 1291 2713 1475 2713 1283 2713 1283 2714 1475 2714 1476 2714 1283 2715 1476 2715 1477 2715 1283 2716 1477 2716 1284 2716 1284 2717 1477 2717 1478 2717 1284 2718 1478 2718 1285 2718 1285 2719 1478 2719 1479 2719 1285 2720 1479 2720 1286 2720 1286 2721 1479 2721 1480 2721 1286 2722 1480 2722 1287 2722 1287 2723 1480 2723 1481 2723 1287 2724 1481 2724 1482 2724 1287 2725 1482 2725 1288 2725 1288 2726 1482 2726 1471 2726 106 2727 1293 2727 125 2727 125 2728 1293 2728 1292 2728 79 2729 941 2729 1292 2729 188 2730 125 2730 1292 2730 941 2731 188 2731 1292 2731 1302 2732 1301 2732 1297 2732 1301 2733 1300 2733 1297 2733 1300 2734 1299 2734 1297 2734 1297 2735 1299 2735 1298 2735 1297 2736 1295 2736 1294 2736 1297 2737 1294 2737 1302 2737 1295 2738 1297 2738 1296 2738 1308 2739 1483 2739 1304 2739 1483 2740 1484 2740 1304 2740 1304 2741 1484 2741 1485 2741 1304 2742 1485 2742 1303 2742 1303 2743 1485 2743 1486 2743 1486 2744 1487 2744 1303 2744 1488 2745 1483 2745 1308 2745 1306 2746 1489 2746 1490 2746 1487 2747 1491 2747 1303 2747 1303 2748 1491 2748 1306 2748 1306 2749 1491 2749 1492 2749 1306 2750 1492 2750 1489 2750 1306 2751 1490 2751 1308 2751 1308 2752 1490 2752 1493 2752 1308 2753 1493 2753 1488 2753 1305 2754 1306 2754 1307 2754 1307 2755 1306 2755 1308 2755 1453 2756 1310 2756 1454 2756 1454 2757 1310 2757 1309 2757 1454 2758 1309 2758 1322 2758 1454 2759 1322 2759 1455 2759 1455 2760 1322 2760 1456 2760 1456 2761 1322 2761 1330 2761 1456 2762 1330 2762 1329 2762 1456 2763 1329 2763 1457 2763 1457 2764 1329 2764 1318 2764 1457 2765 1318 2765 1458 2765 1458 2766 1318 2766 1317 2766 1458 2767 1317 2767 1450 2767 1450 2768 1317 2768 1451 2768 1451 2769 1317 2769 1338 2769 1451 2770 1338 2770 1323 2770 1451 2771 1323 2771 1452 2771 1452 2772 1323 2772 1331 2772 1452 2773 1331 2773 1453 2773 1453 2774 1331 2774 1310 2774 1475 2775 1314 2775 1476 2775 1476 2776 1314 2776 1312 2776 1476 2777 1312 2777 1477 2777 1477 2778 1312 2778 1311 2778 1477 2779 1311 2779 1478 2779 1478 2780 1311 2780 1326 2780 1478 2781 1326 2781 1479 2781 1479 2782 1326 2782 1337 2782 1479 2783 1337 2783 1480 2783 1480 2784 1337 2784 1336 2784 1480 2785 1336 2785 1481 2785 1481 2786 1336 2786 1482 2786 1482 2787 1336 2787 1335 2787 1482 2788 1335 2788 1471 2788 1471 2789 1335 2789 1334 2789 1471 2790 1334 2790 1472 2790 1472 2791 1334 2791 1333 2791 1472 2792 1333 2792 1473 2792 1473 2793 1333 2793 1474 2793 1474 2794 1333 2794 1340 2794 1474 2795 1340 2795 1314 2795 1474 2796 1314 2796 1475 2796 1321 2797 1494 2797 1495 2797 1321 2798 1495 2798 1328 2798 1328 2799 1495 2799 1496 2799 1328 2800 1496 2800 1316 2800 1494 2801 1321 2801 1497 2801 1497 2802 1321 2802 1244 2802 1497 2803 1244 2803 1446 2803 1327 2804 1498 2804 1200 2804 1200 2805 1498 2805 1499 2805 1200 2806 1499 2806 1344 2806 1313 2807 1500 2807 1501 2807 1313 2808 1501 2808 1341 2808 1341 2809 1501 2809 1498 2809 1341 2810 1498 2810 1327 2810 1466 2811 1324 2811 1502 2811 1466 2812 1502 2812 1467 2812 1467 2813 1502 2813 1503 2813 1467 2814 1503 2814 1468 2814 1468 2815 1503 2815 1469 2815 1469 2816 1503 2816 1319 2816 1469 2817 1319 2817 1315 2817 1469 2818 1315 2818 1470 2818 1470 2819 1315 2819 1320 2819 1470 2820 1320 2820 1459 2820 1459 2821 1320 2821 1460 2821 1460 2822 1320 2822 1332 2822 1460 2823 1332 2823 1461 2823 1461 2824 1332 2824 1462 2824 1462 2825 1332 2825 1339 2825 1462 2826 1339 2826 1463 2826 1463 2827 1339 2827 1342 2827 1463 2828 1342 2828 1464 2828 1464 2829 1342 2829 1325 2829 1464 2830 1325 2830 1465 2830 1465 2831 1325 2831 1324 2831 1465 2832 1324 2832 1466 2832 1504 2833 1505 2833 1345 2833 1345 2834 1505 2834 1347 2834 1347 2835 1505 2835 1506 2835 1507 2836 1344 2836 1508 2836 1344 2837 1507 2837 1509 2837 1510 2838 1343 2838 1509 2838 1509 2839 1343 2839 1344 2839 1510 2840 1511 2840 1343 2840 1506 2841 1508 2841 1347 2841 1347 2842 1508 2842 1344 2842 1343 2843 1511 2843 1512 2843 1343 2844 1512 2844 1345 2844 1512 2845 1513 2845 1345 2845 1345 2846 1513 2846 1504 2846 1514 2847 1356 2847 1354 2847 1514 2848 1354 2848 1352 2848 1352 2849 1354 2849 1351 2849 1514 2850 1352 2850 1515 2850 1515 2851 1352 2851 1350 2851 1515 2852 1350 2852 1516 2852 1515 2853 1516 2853 1517 2853 1517 2854 1516 2854 1518 2854 1518 2855 1516 2855 1519 2855 1520 2856 1519 2856 1516 2856 1520 2857 1516 2857 1349 2857 1349 2858 1516 2858 1350 2858 1500 2859 1520 2859 1501 2859 1348 2860 1499 2860 1349 2860 1349 2861 1499 2861 1498 2861 1349 2862 1498 2862 1520 2862 1520 2863 1498 2863 1501 2863 1348 2864 1346 2864 1499 2864 1499 2865 1346 2865 1347 2865 1499 2866 1347 2866 1344 2866 1521 2867 1522 2867 1355 2867 1355 2868 1522 2868 1356 2868 1522 2869 1523 2869 1356 2869 1356 2870 1523 2870 1524 2870 1356 2871 1524 2871 1525 2871 1353 2872 1526 2872 1527 2872 1528 2873 1526 2873 1353 2873 1353 2874 1527 2874 1355 2874 1355 2875 1527 2875 1529 2875 1356 2876 1525 2876 1354 2876 1354 2877 1525 2877 1530 2877 1354 2878 1530 2878 1531 2878 1531 2879 1528 2879 1354 2879 1354 2880 1528 2880 1353 2880 1355 2881 1529 2881 1521 2881 1389 2882 1532 2882 1533 2882 1389 2883 1533 2883 1391 2883 1391 2884 1533 2884 1534 2884 1391 2885 1534 2885 1392 2885 1392 2886 1534 2886 1535 2886 1392 2887 1535 2887 1396 2887 1396 2888 1535 2888 1359 2888 1359 2889 1535 2889 1536 2889 1359 2890 1536 2890 1360 2890 1360 2891 1536 2891 1537 2891 1360 2892 1537 2892 1381 2892 1381 2893 1537 2893 1387 2893 1387 2894 1537 2894 1538 2894 1387 2895 1538 2895 1364 2895 1364 2896 1538 2896 1539 2896 1364 2897 1539 2897 1388 2897 1388 2898 1539 2898 1540 2898 1388 2899 1540 2899 1541 2899 1388 2900 1541 2900 1390 2900 1390 2901 1541 2901 1532 2901 1390 2902 1532 2902 1389 2902 1376 2903 1542 2903 1543 2903 1376 2904 1543 2904 1374 2904 1374 2905 1543 2905 1544 2905 1374 2906 1544 2906 1373 2906 1373 2907 1544 2907 1545 2907 1373 2908 1545 2908 1370 2908 1370 2909 1545 2909 1357 2909 1357 2910 1545 2910 1546 2910 1357 2911 1546 2911 1547 2911 1357 2912 1547 2912 1358 2912 1358 2913 1547 2913 1548 2913 1358 2914 1548 2914 1362 2914 1362 2915 1548 2915 1549 2915 1362 2916 1549 2916 1377 2916 1377 2917 1549 2917 1550 2917 1377 2918 1550 2918 1551 2918 1377 2919 1551 2919 1386 2919 1386 2920 1551 2920 1552 2920 1386 2921 1552 2921 1380 2921 1380 2922 1552 2922 1378 2922 1378 2923 1552 2923 1542 2923 1378 2924 1542 2924 1376 2924 1553 2925 1393 2925 1394 2925 1553 2926 1394 2926 1554 2926 1554 2927 1394 2927 1555 2927 1555 2928 1394 2928 1361 2928 1393 2929 1553 2929 1240 2929 1240 2930 1553 2930 1556 2930 1240 2931 1556 2931 1434 2931 1432 2932 1557 2932 1395 2932 1557 2933 1558 2933 1395 2933 1395 2934 1558 2934 1365 2934 1558 2935 1559 2935 1365 2935 1560 2936 1366 2936 1559 2936 1559 2937 1366 2937 1365 2937 1366 2938 1561 2938 1363 2938 1363 2939 1561 2939 1397 2939 1515 2940 1371 2940 1514 2940 1514 2941 1371 2941 1209 2941 1514 2942 1209 2942 1356 2942 1518 2943 1375 2943 1372 2943 1518 2944 1372 2944 1517 2944 1517 2945 1372 2945 1515 2945 1515 2946 1372 2946 1371 2946 1562 2947 1563 2947 1564 2947 1564 2948 1563 2948 1565 2948 1564 2949 1565 2949 1566 2949 1566 2950 1565 2950 1567 2950 1567 2951 1565 2951 1369 2951 1567 2952 1369 2952 1368 2952 1567 2953 1368 2953 1568 2953 1568 2954 1368 2954 1569 2954 1569 2955 1368 2955 1367 2955 1569 2956 1367 2956 1570 2956 1570 2957 1367 2957 1382 2957 1570 2958 1382 2958 1571 2958 1571 2959 1382 2959 1384 2959 1571 2960 1384 2960 1572 2960 1572 2961 1384 2961 1383 2961 1572 2962 1383 2962 1573 2962 1573 2963 1383 2963 1379 2963 1573 2964 1379 2964 1574 2964 1574 2965 1379 2965 1385 2965 1574 2966 1385 2966 1575 2966 1575 2967 1385 2967 1562 2967 1562 2968 1385 2968 1563 2968 1208 2969 1397 2969 1398 2969 1398 2970 1397 2970 1576 2970 1577 2971 1578 2971 1579 2971 1580 2972 1581 2972 1582 2972 1585 2973 1586 2973 1587 2973 1588 2974 1589 2974 1447 2974 1414 2975 1590 2975 1591 2975 1585 2976 1587 2976 1580 2976 1580 2977 1587 2977 1581 2977 1447 2978 1589 2978 1592 2978 1592 2979 1589 2979 1593 2979 1593 2980 1594 2980 1595 2980 1582 2981 1594 2981 1580 2981 1593 2982 1595 2982 1592 2982 1597 2983 1598 2983 1398 2983 1414 2984 1591 2984 1599 2984 1414 2985 1599 2985 1447 2985 1447 2986 1599 2986 1600 2986 1597 2987 1398 2987 1576 2987 1597 2988 1576 2988 1584 2988 1398 2989 1598 2989 1601 2989 1398 2990 1601 2990 1399 2990 1399 2991 1601 2991 1602 2991 1404 2992 1603 2992 1405 2992 1405 2993 1603 2993 1604 2993 1590 2994 1414 2994 1604 2994 1604 2995 1414 2995 1405 2995 1605 2996 1606 2996 1578 2996 1607 2997 1608 2997 1596 2997 1606 2998 1608 2998 1609 2998 1609 2999 1608 2999 1607 2999 1610 3000 1611 3000 1399 3000 1612 3001 1613 3001 1586 3001 1612 3002 1586 3002 1585 3002 1614 3003 1615 3003 1613 3003 1614 3004 1613 3004 1612 3004 1578 3005 1616 3005 1617 3005 1578 3006 1617 3006 1615 3006 1618 3007 1619 3007 1579 3007 1579 3008 1619 3008 1577 3008 1620 3009 1600 3009 1621 3009 1399 3010 1602 3010 1610 3010 1610 3011 1602 3011 1605 3011 1610 3012 1605 3012 1578 3012 1606 3013 1609 3013 1578 3013 1578 3014 1609 3014 1616 3014 1615 3015 1614 3015 1578 3015 1578 3016 1614 3016 1579 3016 1620 3017 1621 3017 1622 3017 1620 3018 1622 3018 1623 3018 1447 3019 1624 3019 1588 3019 1611 3020 1625 3020 1399 3020 1399 3021 1625 3021 1626 3021 1600 3022 1620 3022 1447 3022 1447 3023 1620 3023 1624 3023 1626 3024 1408 3024 1407 3024 1618 3025 1579 3025 1627 3025 1627 3026 1579 3026 1623 3026 1627 3027 1623 3027 1622 3027 1626 3028 1407 3028 1400 3028 1626 3029 1400 3029 1399 3029 1400 3030 1403 3030 1206 3030 1407 3031 1229 3031 1400 3031 1400 3032 1229 3032 1401 3032 1403 3033 1400 3033 1401 3033 88 3034 1402 3034 102 3034 102 3035 1402 3035 1628 3035 1628 3036 1161 3036 102 3036 1402 3037 1158 3037 1161 3037 1402 3038 1161 3038 1628 3038 1404 3039 1629 3039 1630 3039 1404 3040 1406 3040 1629 3040 1631 3041 1404 3041 1630 3041 1404 3042 1631 3042 1603 3042 1603 3043 1631 3043 1632 3043 1603 3044 1632 3044 1604 3044 1632 3045 1633 3045 1604 3045 1604 3046 1633 3046 1590 3046 1590 3047 1633 3047 1634 3047 1590 3048 1634 3048 1591 3048 1634 3049 1635 3049 1591 3049 1591 3050 1635 3050 1599 3050 1635 3051 1636 3051 1599 3051 1599 3052 1636 3052 1600 3052 1600 3053 1636 3053 1637 3053 1600 3054 1637 3054 1621 3054 1637 3055 1638 3055 1621 3055 1621 3056 1638 3056 1622 3056 1622 3057 1638 3057 1639 3057 1622 3058 1639 3058 1627 3058 1639 3059 1640 3059 1627 3059 1627 3060 1640 3060 1618 3060 1618 3061 1640 3061 1641 3061 1618 3062 1641 3062 1619 3062 1619 3063 1641 3063 1642 3063 1619 3064 1642 3064 1577 3064 1642 3065 1643 3065 1577 3065 1577 3066 1643 3066 1578 3066 1578 3067 1643 3067 1644 3067 1578 3068 1644 3068 1610 3068 1644 3069 1645 3069 1610 3069 1610 3070 1645 3070 1646 3070 1610 3071 1646 3071 1611 3071 1611 3072 1646 3072 1647 3072 1611 3073 1647 3073 1625 3073 1647 3074 1648 3074 1625 3074 1625 3075 1648 3075 1626 3075 1648 3076 1649 3076 1626 3076 1626 3077 1649 3077 1408 3077 1629 3078 1406 3078 1649 3078 1649 3079 1406 3079 1408 3079 1414 3080 1413 3080 1405 3080 1413 3081 1409 3081 1650 3081 1650 3082 1409 3082 1411 3082 1405 3083 1413 3083 1650 3083 1405 3084 1650 3084 1228 3084 1228 3085 1650 3085 1411 3085 1651 3086 1410 3086 1652 3086 1651 3087 1652 3087 103 3087 1412 3088 1410 3088 1651 3088 1651 3089 103 3089 1160 3089 1159 3090 1412 3090 1651 3090 1651 3091 1160 3091 1159 3091 157 3092 953 3092 1416 3092 1416 3093 953 3093 947 3093 1415 3094 111 3094 1416 3094 1416 3095 111 3095 112 3095 1416 3096 112 3096 156 3096 1416 3097 156 3097 157 3097 1421 3098 1423 3098 1424 3098 1424 3099 1425 3099 1421 3099 1421 3100 1425 3100 1417 3100 1421 3101 1417 3101 1418 3101 1418 3102 1419 3102 1421 3102 1423 3103 1421 3103 1422 3103 1421 3104 1419 3104 1420 3104 1426 3105 1653 3105 1654 3105 1427 3106 1655 3106 1656 3106 1427 3107 1656 3107 1657 3107 1654 3108 1658 3108 1426 3108 1426 3109 1658 3109 1427 3109 1427 3110 1658 3110 1655 3110 1431 3111 1659 3111 1660 3111 1431 3112 1660 3112 1653 3112 1431 3113 1653 3113 1426 3113 1427 3114 1657 3114 1429 3114 1429 3115 1657 3115 1661 3115 1661 3116 1662 3116 1429 3116 1429 3117 1662 3117 1663 3117 1429 3118 1663 3118 1431 3118 1431 3119 1663 3119 1659 3119 1428 3120 1429 3120 1430 3120 1430 3121 1429 3121 1431 3121 1447 3122 1557 3122 1238 3122 1238 3123 1557 3123 1432 3123 1664 3124 1665 3124 1435 3124 1435 3125 1665 3125 1666 3125 1667 3126 1668 3126 1434 3126 1669 3127 1670 3127 1433 3127 1435 3128 1666 3128 1437 3128 1437 3129 1666 3129 1671 3129 1670 3130 1664 3130 1433 3130 1433 3131 1664 3131 1435 3131 1668 3132 1669 3132 1434 3132 1434 3133 1669 3133 1433 3133 1671 3134 1672 3134 1437 3134 1437 3135 1672 3135 1673 3135 1437 3136 1673 3136 1434 3136 1434 3137 1673 3137 1667 3137 1497 3138 1446 3138 1444 3138 1497 3139 1444 3139 1442 3139 1442 3140 1444 3140 1441 3140 1497 3141 1442 3141 1494 3141 1494 3142 1442 3142 1440 3142 1494 3143 1440 3143 1495 3143 1495 3144 1440 3144 1674 3144 1495 3145 1674 3145 1496 3145 1440 3146 1439 3146 1675 3146 1440 3147 1675 3147 1674 3147 1438 3148 1556 3148 1439 3148 1439 3149 1556 3149 1553 3149 1439 3150 1553 3150 1554 3150 1439 3151 1554 3151 1675 3151 1675 3152 1554 3152 1555 3152 1438 3153 1436 3153 1556 3153 1556 3154 1436 3154 1437 3154 1556 3155 1437 3155 1434 3155 1676 3156 1446 3156 1445 3156 1446 3157 1676 3157 1677 3157 1444 3158 1678 3158 1679 3158 1444 3159 1679 3159 1680 3159 1681 3160 1443 3160 1682 3160 1443 3161 1681 3161 1683 3161 1446 3162 1677 3162 1684 3162 1684 3163 1678 3163 1446 3163 1446 3164 1678 3164 1444 3164 1444 3165 1680 3165 1443 3165 1443 3166 1680 3166 1682 3166 1445 3167 1685 3167 1676 3167 1443 3168 1683 3168 1445 3168 1445 3169 1683 3169 1685 3169 1085 3170 1099 3170 1106 3170 1085 3171 1106 3171 1163 3171 1085 3172 1163 3172 1448 3172 1085 3173 1448 3173 1166 3173 1164 3174 1165 3174 1449 3174 1093 3175 1164 3175 1449 3175 1093 3176 1449 3176 1167 3176 1168 3177 1167 3177 1449 3177 1491 3178 1686 3178 1687 3178 1491 3179 1687 3179 1492 3179 1492 3180 1687 3180 1688 3180 1492 3181 1688 3181 1489 3181 1489 3182 1688 3182 1689 3182 1489 3183 1689 3183 1490 3183 1490 3184 1689 3184 1690 3184 1490 3185 1690 3185 1493 3185 1493 3186 1690 3186 1691 3186 1493 3187 1691 3187 1488 3187 1488 3188 1691 3188 1692 3188 1488 3189 1692 3189 1483 3189 1483 3190 1692 3190 1693 3190 1483 3191 1693 3191 1484 3191 1484 3192 1693 3192 1694 3192 1484 3193 1694 3193 1485 3193 1485 3194 1694 3194 1695 3194 1485 3195 1695 3195 1486 3195 1486 3196 1695 3196 1696 3196 1486 3197 1696 3197 1697 3197 1486 3198 1697 3198 1487 3198 1487 3199 1697 3199 1686 3199 1487 3200 1686 3200 1491 3200 1518 3201 1519 3201 1520 3201 1496 3202 1674 3202 1675 3202 1385 3203 1375 3203 1518 3203 1324 3204 1316 3204 1496 3204 1555 3205 1361 3205 1369 3205 1500 3206 1313 3206 1319 3206 1385 3207 1518 3207 1369 3207 1369 3208 1518 3208 1555 3208 1555 3209 1518 3209 1520 3209 1555 3210 1520 3210 1675 3210 1675 3211 1520 3211 1500 3211 1675 3212 1500 3212 1496 3212 1496 3213 1500 3213 1319 3213 1496 3214 1319 3214 1324 3214 1509 3215 1698 3215 1510 3215 1510 3216 1698 3216 1699 3216 1510 3217 1699 3217 1511 3217 1511 3218 1699 3218 1700 3218 1511 3219 1700 3219 1512 3219 1512 3220 1700 3220 1701 3220 1512 3221 1701 3221 1513 3221 1513 3222 1701 3222 1504 3222 1504 3223 1701 3223 1702 3223 1504 3224 1702 3224 1703 3224 1504 3225 1703 3225 1505 3225 1505 3226 1703 3226 1704 3226 1505 3227 1704 3227 1705 3227 1505 3228 1705 3228 1506 3228 1506 3229 1705 3229 1706 3229 1506 3230 1706 3230 1508 3230 1508 3231 1706 3231 1707 3231 1508 3232 1707 3232 1507 3232 1507 3233 1707 3233 1708 3233 1507 3234 1708 3234 1509 3234 1509 3235 1708 3235 1698 3235 1528 3236 1709 3236 1710 3236 1528 3237 1710 3237 1711 3237 1528 3238 1711 3238 1526 3238 1526 3239 1711 3239 1712 3239 1526 3240 1712 3240 1527 3240 1527 3241 1712 3241 1713 3241 1527 3242 1713 3242 1529 3242 1529 3243 1713 3243 1714 3243 1529 3244 1714 3244 1521 3244 1521 3245 1714 3245 1715 3245 1521 3246 1715 3246 1522 3246 1522 3247 1715 3247 1523 3247 1523 3248 1715 3248 1716 3248 1523 3249 1716 3249 1524 3249 1524 3250 1716 3250 1717 3250 1524 3251 1717 3251 1525 3251 1525 3252 1717 3252 1718 3252 1525 3253 1718 3253 1530 3253 1530 3254 1718 3254 1719 3254 1530 3255 1719 3255 1531 3255 1531 3256 1719 3256 1709 3256 1531 3257 1709 3257 1528 3257 1720 3258 1541 3258 1721 3258 1721 3259 1541 3259 1722 3259 1722 3260 1541 3260 1540 3260 1722 3261 1540 3261 1539 3261 1722 3262 1539 3262 1723 3262 1723 3263 1539 3263 1538 3263 1723 3264 1538 3264 1724 3264 1724 3265 1538 3265 1537 3265 1724 3266 1537 3266 1725 3266 1725 3267 1537 3267 1536 3267 1725 3268 1536 3268 1726 3268 1726 3269 1536 3269 1535 3269 1726 3270 1535 3270 1727 3270 1727 3271 1535 3271 1534 3271 1727 3272 1534 3272 1728 3272 1728 3273 1534 3273 1729 3273 1729 3274 1534 3274 1533 3274 1729 3275 1533 3275 1720 3275 1720 3276 1533 3276 1532 3276 1720 3277 1532 3277 1541 3277 1730 3278 1542 3278 1552 3278 1730 3279 1552 3279 1731 3279 1731 3280 1552 3280 1551 3280 1731 3281 1551 3281 1732 3281 1732 3282 1551 3282 1550 3282 1732 3283 1550 3283 1549 3283 1732 3284 1549 3284 1733 3284 1733 3285 1549 3285 1548 3285 1733 3286 1548 3286 1734 3286 1734 3287 1548 3287 1547 3287 1734 3288 1547 3288 1735 3288 1735 3289 1547 3289 1546 3289 1735 3290 1546 3290 1736 3290 1736 3291 1546 3291 1545 3291 1736 3292 1545 3292 1737 3292 1737 3293 1545 3293 1544 3293 1737 3294 1544 3294 1738 3294 1738 3295 1544 3295 1543 3295 1738 3296 1543 3296 1739 3296 1739 3297 1543 3297 1542 3297 1739 3298 1542 3298 1730 3298 1557 3299 1447 3299 1592 3299 1558 3300 1557 3300 1595 3300 1595 3301 1557 3301 1592 3301 1558 3302 1595 3302 1740 3302 1559 3303 1558 3303 1740 3303 1741 3304 1569 3304 1742 3304 1742 3305 1569 3305 1570 3305 1742 3306 1570 3306 1743 3306 1743 3307 1570 3307 1571 3307 1743 3308 1571 3308 1744 3308 1744 3309 1571 3309 1572 3309 1744 3310 1572 3310 1745 3310 1745 3311 1572 3311 1573 3311 1745 3312 1573 3312 1574 3312 1745 3313 1574 3313 1746 3313 1746 3314 1574 3314 1575 3314 1746 3315 1575 3315 1747 3315 1747 3316 1575 3316 1562 3316 1747 3317 1562 3317 1748 3317 1748 3318 1562 3318 1564 3318 1748 3319 1564 3319 1749 3319 1749 3320 1564 3320 1566 3320 1749 3321 1566 3321 1750 3321 1750 3322 1566 3322 1567 3322 1750 3323 1567 3323 1751 3323 1751 3324 1567 3324 1568 3324 1751 3325 1568 3325 1741 3325 1741 3326 1568 3326 1569 3326 1752 3327 1588 3327 1624 3327 1752 3328 1624 3328 1753 3328 1753 3329 1624 3329 1620 3329 1753 3330 1620 3330 1754 3330 1754 3331 1620 3331 1623 3331 1754 3332 1623 3332 1755 3332 1755 3333 1623 3333 1579 3333 1755 3334 1579 3334 1756 3334 1756 3335 1579 3335 1614 3335 1756 3336 1614 3336 1757 3336 1757 3337 1614 3337 1758 3337 1758 3338 1614 3338 1612 3338 1758 3339 1612 3339 1759 3339 1759 3340 1612 3340 1585 3340 1759 3341 1585 3341 1760 3341 1760 3342 1585 3342 1580 3342 1760 3343 1580 3343 1761 3343 1761 3344 1580 3344 1594 3344 1761 3345 1594 3345 1762 3345 1762 3346 1594 3346 1593 3346 1762 3347 1593 3347 1763 3347 1763 3348 1593 3348 1589 3348 1763 3349 1589 3349 1764 3349 1764 3350 1589 3350 1752 3350 1752 3351 1589 3351 1588 3351 1765 3352 1586 3352 1766 3352 1766 3353 1586 3353 1613 3353 1766 3354 1613 3354 1767 3354 1767 3355 1613 3355 1615 3355 1767 3356 1615 3356 1768 3356 1768 3357 1615 3357 1617 3357 1768 3358 1617 3358 1769 3358 1769 3359 1617 3359 1616 3359 1769 3360 1616 3360 1770 3360 1770 3361 1616 3361 1609 3361 1770 3362 1609 3362 1771 3362 1771 3363 1609 3363 1607 3363 1771 3364 1607 3364 1772 3364 1772 3365 1607 3365 1773 3365 1774 3366 1582 3366 1775 3366 1775 3367 1582 3367 1776 3367 1776 3368 1582 3368 1581 3368 1776 3369 1581 3369 1765 3369 1765 3370 1581 3370 1587 3370 1765 3371 1587 3371 1586 3371 1777 3372 1596 3372 1778 3372 1778 3373 1596 3373 1608 3373 1778 3374 1608 3374 1779 3374 1779 3375 1608 3375 1780 3375 1780 3376 1608 3376 1606 3376 1780 3377 1606 3377 1605 3377 1780 3378 1605 3378 1781 3378 1781 3379 1605 3379 1602 3379 1781 3380 1602 3380 1782 3380 1782 3381 1602 3381 1601 3381 1782 3382 1601 3382 1783 3382 1783 3383 1601 3383 1598 3383 1783 3384 1598 3384 1784 3384 1784 3385 1598 3385 1597 3385 1784 3386 1597 3386 1785 3386 1785 3387 1597 3387 1584 3387 1785 3388 1584 3388 1786 3388 1788 3389 1583 3389 1596 3389 1788 3390 1596 3390 1777 3390 1789 3391 1645 3391 1790 3391 1790 3392 1645 3392 1644 3392 1644 3393 1643 3393 1790 3393 1790 3394 1643 3394 1791 3394 1791 3395 1643 3395 1642 3395 1791 3396 1642 3396 1792 3396 1792 3397 1642 3397 1641 3397 1792 3398 1641 3398 1793 3398 1793 3399 1641 3399 1640 3399 1793 3400 1640 3400 1794 3400 1794 3401 1640 3401 1639 3401 1794 3402 1639 3402 1638 3402 1794 3403 1638 3403 1795 3403 1795 3404 1638 3404 1637 3404 1795 3405 1637 3405 1796 3405 1796 3406 1637 3406 1636 3406 1796 3407 1636 3407 1797 3407 1797 3408 1636 3408 1798 3408 1798 3409 1636 3409 1635 3409 1798 3410 1635 3410 1799 3410 1799 3411 1635 3411 1634 3411 1799 3412 1634 3412 1800 3412 1634 3413 1633 3413 1800 3413 1800 3414 1633 3414 1632 3414 1800 3415 1632 3415 1801 3415 1632 3416 1631 3416 1801 3416 1801 3417 1631 3417 1630 3417 1630 3418 1629 3418 1802 3418 1802 3419 1629 3419 1803 3419 1803 3420 1629 3420 1649 3420 1803 3421 1649 3421 1804 3421 1649 3422 1648 3422 1804 3422 1804 3423 1648 3423 1647 3423 1804 3424 1647 3424 1805 3424 1805 3425 1647 3425 1646 3425 1805 3426 1646 3426 1789 3426 1789 3427 1646 3427 1645 3427 1806 3428 1653 3428 1807 3428 1807 3429 1653 3429 1660 3429 1807 3430 1660 3430 1659 3430 1807 3431 1659 3431 1808 3431 1808 3432 1659 3432 1809 3432 1809 3433 1659 3433 1663 3433 1809 3434 1663 3434 1662 3434 1809 3435 1662 3435 1810 3435 1810 3436 1662 3436 1811 3436 1811 3437 1662 3437 1661 3437 1811 3438 1661 3438 1812 3438 1812 3439 1661 3439 1657 3439 1812 3440 1657 3440 1813 3440 1813 3441 1657 3441 1656 3441 1813 3442 1656 3442 1814 3442 1814 3443 1656 3443 1655 3443 1814 3444 1655 3444 1815 3444 1815 3445 1655 3445 1658 3445 1815 3446 1658 3446 1816 3446 1816 3447 1658 3447 1654 3447 1816 3448 1654 3448 1806 3448 1806 3449 1654 3449 1653 3449 1817 3450 1666 3450 1818 3450 1818 3451 1666 3451 1665 3451 1818 3452 1665 3452 1819 3452 1819 3453 1665 3453 1820 3453 1820 3454 1665 3454 1664 3454 1820 3455 1664 3455 1821 3455 1821 3456 1664 3456 1670 3456 1821 3457 1670 3457 1822 3457 1822 3458 1670 3458 1669 3458 1822 3459 1669 3459 1823 3459 1823 3460 1669 3460 1668 3460 1823 3461 1668 3461 1824 3461 1824 3462 1668 3462 1667 3462 1824 3463 1667 3463 1825 3463 1825 3464 1667 3464 1673 3464 1825 3465 1673 3465 1672 3465 1825 3466 1672 3466 1826 3466 1826 3467 1672 3467 1671 3467 1826 3468 1671 3468 1817 3468 1817 3469 1671 3469 1666 3469 1827 3470 1676 3470 1828 3470 1828 3471 1676 3471 1685 3471 1828 3472 1685 3472 1829 3472 1829 3473 1685 3473 1683 3473 1829 3474 1683 3474 1830 3474 1830 3475 1683 3475 1681 3475 1830 3476 1681 3476 1831 3476 1831 3477 1681 3477 1682 3477 1831 3478 1682 3478 1680 3478 1831 3479 1680 3479 1832 3479 1832 3480 1680 3480 1679 3480 1832 3481 1679 3481 1833 3481 1833 3482 1679 3482 1678 3482 1833 3483 1678 3483 1834 3483 1834 3484 1678 3484 1835 3484 1835 3485 1678 3485 1684 3485 1835 3486 1684 3486 1836 3486 1836 3487 1684 3487 1677 3487 1836 3488 1677 3488 1827 3488 1827 3489 1677 3489 1676 3489 1324 3490 1319 3490 1503 3490 1324 3491 1503 3491 1502 3491 1837 3492 1696 3492 1695 3492 1837 3493 1695 3493 1838 3493 1838 3494 1695 3494 1694 3494 1838 3495 1694 3495 1839 3495 1839 3496 1694 3496 1693 3496 1839 3497 1693 3497 1840 3497 1840 3498 1693 3498 1692 3498 1840 3499 1692 3499 1841 3499 1841 3500 1692 3500 1691 3500 1841 3501 1691 3501 1690 3501 1841 3502 1690 3502 1842 3502 1842 3503 1690 3503 1689 3503 1842 3504 1689 3504 1688 3504 1842 3505 1688 3505 1843 3505 1843 3506 1688 3506 1687 3506 1843 3507 1687 3507 1844 3507 1844 3508 1687 3508 1686 3508 1844 3509 1686 3509 1845 3509 1845 3510 1686 3510 1697 3510 1845 3511 1697 3511 1837 3511 1837 3512 1697 3512 1696 3512 1563 3513 1385 3513 1369 3513 1369 3514 1565 3514 1563 3514 1846 3515 1700 3515 1699 3515 1846 3516 1699 3516 1847 3516 1847 3517 1699 3517 1698 3517 1847 3518 1698 3518 1848 3518 1848 3519 1698 3519 1708 3519 1848 3520 1708 3520 1849 3520 1849 3521 1708 3521 1707 3521 1849 3522 1707 3522 1850 3522 1850 3523 1707 3523 1706 3523 1850 3524 1706 3524 1851 3524 1851 3525 1706 3525 1705 3525 1851 3526 1705 3526 1704 3526 1851 3527 1704 3527 1852 3527 1852 3528 1704 3528 1703 3528 1852 3529 1703 3529 1853 3529 1853 3530 1703 3530 1702 3530 1853 3531 1702 3531 1701 3531 1853 3532 1701 3532 1854 3532 1854 3533 1701 3533 1700 3533 1854 3534 1700 3534 1846 3534 1855 3535 1719 3535 1856 3535 1856 3536 1719 3536 1718 3536 1856 3537 1718 3537 1717 3537 1856 3538 1717 3538 1857 3538 1857 3539 1717 3539 1716 3539 1857 3540 1716 3540 1858 3540 1858 3541 1716 3541 1715 3541 1858 3542 1715 3542 1859 3542 1859 3543 1715 3543 1860 3543 1860 3544 1715 3544 1714 3544 1860 3545 1714 3545 1861 3545 1861 3546 1714 3546 1713 3546 1861 3547 1713 3547 1862 3547 1862 3548 1713 3548 1712 3548 1862 3549 1712 3549 1863 3549 1863 3550 1712 3550 1711 3550 1863 3551 1711 3551 1864 3551 1864 3552 1711 3552 1710 3552 1864 3553 1710 3553 1709 3553 1864 3554 1709 3554 1855 3554 1855 3555 1709 3555 1719 3555 1720 3556 1865 3556 1729 3556 1729 3557 1865 3557 1866 3557 1729 3558 1866 3558 1867 3558 1729 3559 1867 3559 1728 3559 1728 3560 1867 3560 1868 3560 1728 3561 1868 3561 1727 3561 1727 3562 1868 3562 1726 3562 1726 3563 1868 3563 1869 3563 1726 3564 1869 3564 1725 3564 1725 3565 1869 3565 1870 3565 1725 3566 1870 3566 1724 3566 1724 3567 1870 3567 1871 3567 1724 3568 1871 3568 1723 3568 1723 3569 1871 3569 1872 3569 1723 3570 1872 3570 1722 3570 1722 3571 1872 3571 1873 3571 1722 3572 1873 3572 1721 3572 1721 3573 1873 3573 1874 3573 1721 3574 1874 3574 1720 3574 1720 3575 1874 3575 1865 3575 1739 3576 1875 3576 1738 3576 1738 3577 1875 3577 1876 3577 1738 3578 1876 3578 1737 3578 1737 3579 1876 3579 1877 3579 1737 3580 1877 3580 1736 3580 1736 3581 1877 3581 1878 3581 1736 3582 1878 3582 1735 3582 1735 3583 1878 3583 1879 3583 1735 3584 1879 3584 1734 3584 1734 3585 1879 3585 1880 3585 1734 3586 1880 3586 1733 3586 1733 3587 1880 3587 1881 3587 1733 3588 1881 3588 1732 3588 1732 3589 1881 3589 1882 3589 1732 3590 1882 3590 1731 3590 1731 3591 1882 3591 1883 3591 1731 3592 1883 3592 1730 3592 1730 3593 1883 3593 1875 3593 1730 3594 1875 3594 1739 3594 1741 3595 1884 3595 1885 3595 1741 3596 1885 3596 1751 3596 1751 3597 1885 3597 1750 3597 1750 3598 1885 3598 1886 3598 1750 3599 1886 3599 1749 3599 1749 3600 1886 3600 1887 3600 1749 3601 1887 3601 1748 3601 1748 3602 1887 3602 1888 3602 1748 3603 1888 3603 1747 3603 1747 3604 1888 3604 1889 3604 1747 3605 1889 3605 1746 3605 1746 3606 1889 3606 1890 3606 1746 3607 1890 3607 1745 3607 1745 3608 1890 3608 1891 3608 1745 3609 1891 3609 1744 3609 1744 3610 1891 3610 1892 3610 1744 3611 1892 3611 1893 3611 1744 3612 1893 3612 1743 3612 1743 3613 1893 3613 1894 3613 1743 3614 1894 3614 1742 3614 1742 3615 1894 3615 1884 3615 1742 3616 1884 3616 1741 3616 1871 3617 1760 3617 1761 3617 1871 3618 1761 3618 1872 3618 1872 3619 1761 3619 1762 3619 1872 3620 1762 3620 1873 3620 1873 3621 1762 3621 1763 3621 1873 3622 1763 3622 1874 3622 1874 3623 1763 3623 1764 3623 1874 3624 1764 3624 1752 3624 1874 3625 1752 3625 1865 3625 1865 3626 1752 3626 1753 3626 1865 3627 1753 3627 1866 3627 1866 3628 1753 3628 1867 3628 1867 3629 1753 3629 1754 3629 1867 3630 1754 3630 1755 3630 1867 3631 1755 3631 1868 3631 1868 3632 1755 3632 1756 3632 1868 3633 1756 3633 1869 3633 1869 3634 1756 3634 1757 3634 1869 3635 1757 3635 1870 3635 1870 3636 1757 3636 1758 3636 1870 3637 1758 3637 1759 3637 1870 3638 1759 3638 1871 3638 1871 3639 1759 3639 1760 3639 1891 3640 1773 3640 1774 3640 1891 3641 1774 3641 1892 3641 1892 3642 1774 3642 1893 3642 1893 3643 1774 3643 1775 3643 1893 3644 1775 3644 1776 3644 1893 3645 1776 3645 1894 3645 1894 3646 1776 3646 1765 3646 1894 3647 1765 3647 1884 3647 1884 3648 1765 3648 1766 3648 1884 3649 1766 3649 1885 3649 1885 3650 1766 3650 1767 3650 1885 3651 1767 3651 1886 3651 1886 3652 1767 3652 1768 3652 1886 3653 1768 3653 1769 3653 1886 3654 1769 3654 1887 3654 1887 3655 1769 3655 1888 3655 1888 3656 1769 3656 1770 3656 1888 3657 1770 3657 1889 3657 1889 3658 1770 3658 1771 3658 1889 3659 1771 3659 1890 3659 1890 3660 1771 3660 1772 3660 1890 3661 1772 3661 1891 3661 1891 3662 1772 3662 1773 3662 1880 3663 1785 3663 1881 3663 1881 3664 1785 3664 1786 3664 1881 3665 1786 3665 1882 3665 1882 3666 1786 3666 1787 3666 1882 3667 1787 3667 1883 3667 1883 3668 1787 3668 1788 3668 1883 3669 1788 3669 1777 3669 1883 3670 1777 3670 1875 3670 1875 3671 1777 3671 1778 3671 1875 3672 1778 3672 1779 3672 1875 3673 1779 3673 1876 3673 1876 3674 1779 3674 1780 3674 1876 3675 1780 3675 1877 3675 1877 3676 1780 3676 1781 3676 1877 3677 1781 3677 1878 3677 1878 3678 1781 3678 1782 3678 1878 3679 1782 3679 1783 3679 1878 3680 1783 3680 1879 3680 1879 3681 1783 3681 1784 3681 1879 3682 1784 3682 1880 3682 1880 3683 1784 3683 1785 3683 1895 3684 1805 3684 1789 3684 1895 3685 1789 3685 1896 3685 1805 3686 1895 3686 1897 3686 1898 3687 1899 3687 1790 3687 1790 3688 1899 3688 1789 3688 1789 3689 1899 3689 1896 3689 1900 3690 1901 3690 1902 3690 1903 3691 1904 3691 1804 3691 1805 3692 1905 3692 1903 3692 1902 3693 1901 3693 1906 3693 1902 3694 1906 3694 1805 3694 1805 3695 1906 3695 1905 3695 1805 3696 1903 3696 1804 3696 1904 3697 1907 3697 1804 3697 1804 3698 1907 3698 1803 3698 1908 3699 1801 3699 1909 3699 1910 3700 1802 3700 1911 3700 1911 3701 1802 3701 1803 3701 1802 3702 1910 3702 1912 3702 1630 3703 1909 3703 1801 3703 1802 3704 1912 3704 1630 3704 1630 3705 1912 3705 1909 3705 1913 3706 1799 3706 1800 3706 1799 3707 1913 3707 1914 3707 1915 3708 1916 3708 1917 3708 1799 3709 1914 3709 1915 3709 1916 3710 1918 3710 1801 3710 1801 3711 1918 3711 1800 3711 1800 3712 1918 3712 1919 3712 1800 3713 1919 3713 1913 3713 1917 3714 1916 3714 1801 3714 1920 3715 1797 3715 1921 3715 1797 3716 1798 3716 1922 3716 1923 3717 1798 3717 1799 3717 1923 3718 1799 3718 1924 3718 1798 3719 1923 3719 1922 3719 1797 3720 1922 3720 1921 3720 1925 3721 1796 3721 1797 3721 1794 3722 1926 3722 1927 3722 1927 3723 1926 3723 1928 3723 1797 3724 1929 3724 1925 3724 1927 3725 1928 3725 1930 3725 1925 3726 1931 3726 1796 3726 1796 3727 1931 3727 1795 3727 1794 3728 1932 3728 1926 3728 1795 3729 1931 3729 1932 3729 1795 3730 1932 3730 1794 3730 1933 3731 1792 3731 1934 3731 1935 3732 1793 3732 1794 3732 1794 3733 1936 3733 1935 3733 1793 3734 1935 3734 1934 3734 1793 3735 1934 3735 1792 3735 1792 3736 1937 3736 1938 3736 1938 3737 1791 3737 1792 3737 1790 3738 1939 3738 1940 3738 1790 3739 1940 3739 1941 3739 1938 3740 1942 3740 1791 3740 1791 3741 1942 3741 1790 3741 1790 3742 1942 3742 1939 3742 1799 3743 1943 3743 1924 3743 1944 3744 1945 3744 1917 3744 1917 3745 1945 3745 1943 3745 1797 3746 1920 3746 1946 3746 1947 3747 1927 3747 1946 3747 1947 3748 1948 3748 1927 3748 1927 3749 1948 3749 1917 3749 1917 3750 1948 3750 1944 3750 1949 3751 1950 3751 1917 3751 1902 3752 1951 3752 1952 3752 1801 3753 1908 3753 1917 3753 1917 3754 1908 3754 1949 3754 1950 3755 1953 3755 1917 3755 1954 3756 1951 3756 1902 3756 1902 3757 1952 3757 1803 3757 1803 3758 1952 3758 1911 3758 1955 3759 1956 3759 1902 3759 1897 3760 1955 3760 1805 3760 1805 3761 1955 3761 1902 3761 1902 3762 1956 3762 1957 3762 1957 3763 1958 3763 1959 3763 1959 3764 1958 3764 1960 3764 1959 3765 1960 3765 1898 3765 1959 3766 1898 3766 1790 3766 1792 3767 1933 3767 1961 3767 1962 3768 1963 3768 1927 3768 1792 3769 1961 3769 1964 3769 1792 3770 1964 3770 1959 3770 1959 3771 1964 3771 1965 3771 1927 3772 1963 3772 1794 3772 1794 3773 1963 3773 1936 3773 1959 3774 1965 3774 1966 3774 1959 3775 1966 3775 1927 3775 1927 3776 1966 3776 1962 3776 1967 3777 1968 3777 1917 3777 1917 3778 1968 3778 1927 3778 1917 3779 1969 3779 1967 3779 1953 3780 1954 3780 1917 3780 1917 3781 1954 3781 1902 3781 1917 3782 1902 3782 1970 3782 1970 3783 1971 3783 1917 3783 1917 3784 1971 3784 1969 3784 1972 3785 1902 3785 1973 3785 1902 3786 1972 3786 1970 3786 1973 3787 1902 3787 1974 3787 1957 3788 1959 3788 1902 3788 1902 3789 1959 3789 1974 3789 1975 3790 1976 3790 1959 3790 1976 3791 1974 3791 1959 3791 1975 3792 1959 3792 1927 3792 1975 3793 1927 3793 1977 3793 1978 3794 1977 3794 1927 3794 1907 3795 1900 3795 1803 3795 1803 3796 1900 3796 1902 3796 1930 3797 1797 3797 1927 3797 1927 3798 1797 3798 1946 3798 1797 3799 1930 3799 1929 3799 1959 3800 1979 3800 1937 3800 1937 3801 1792 3801 1959 3801 1941 3802 1979 3802 1959 3802 1959 3803 1790 3803 1941 3803 1943 3804 1799 3804 1917 3804 1917 3805 1799 3805 1915 3805 1927 3806 1968 3806 1978 3806 1980 3807 1815 3807 1981 3807 1981 3808 1815 3808 1816 3808 1981 3809 1816 3809 1982 3809 1982 3810 1816 3810 1806 3810 1982 3811 1806 3811 1983 3811 1983 3812 1806 3812 1984 3812 1984 3813 1806 3813 1807 3813 1984 3814 1807 3814 1985 3814 1985 3815 1807 3815 1808 3815 1985 3816 1808 3816 1809 3816 1985 3817 1809 3817 1986 3817 1986 3818 1809 3818 1810 3818 1986 3819 1810 3819 1987 3819 1987 3820 1810 3820 1811 3820 1987 3821 1811 3821 1988 3821 1988 3822 1811 3822 1812 3822 1988 3823 1812 3823 1813 3823 1988 3824 1813 3824 1989 3824 1989 3825 1813 3825 1814 3825 1989 3826 1814 3826 1980 3826 1980 3827 1814 3827 1815 3827 1990 3828 1822 3828 1991 3828 1991 3829 1822 3829 1823 3829 1991 3830 1823 3830 1992 3830 1992 3831 1823 3831 1824 3831 1992 3832 1824 3832 1993 3832 1993 3833 1824 3833 1825 3833 1993 3834 1825 3834 1994 3834 1994 3835 1825 3835 1826 3835 1994 3836 1826 3836 1995 3836 1995 3837 1826 3837 1817 3837 1995 3838 1817 3838 1996 3838 1996 3839 1817 3839 1818 3839 1996 3840 1818 3840 1997 3840 1997 3841 1818 3841 1819 3841 1997 3842 1819 3842 1998 3842 1998 3843 1819 3843 1820 3843 1998 3844 1820 3844 1999 3844 1999 3845 1820 3845 1821 3845 1999 3846 1821 3846 1990 3846 1990 3847 1821 3847 1822 3847 2000 3848 1829 3848 2001 3848 2001 3849 1829 3849 1830 3849 2001 3850 1830 3850 1831 3850 2001 3851 1831 3851 2002 3851 2002 3852 1831 3852 2003 3852 2003 3853 1831 3853 1832 3853 2003 3854 1832 3854 2004 3854 2004 3855 1832 3855 1833 3855 2004 3856 1833 3856 2005 3856 2005 3857 1833 3857 1834 3857 2005 3858 1834 3858 2006 3858 2006 3859 1834 3859 1835 3859 2006 3860 1835 3860 2007 3860 2007 3861 1835 3861 1836 3861 2007 3862 1836 3862 2008 3862 2008 3863 1836 3863 1827 3863 2008 3864 1827 3864 2009 3864 2009 3865 1827 3865 1828 3865 2009 3866 1828 3866 2000 3866 2000 3867 1828 3867 1829 3867 1844 3868 2010 3868 2011 3868 1844 3869 2011 3869 1843 3869 1843 3870 2011 3870 2012 3870 1843 3871 2012 3871 1842 3871 1842 3872 2012 3872 2013 3872 1842 3873 2013 3873 1841 3873 1841 3874 2013 3874 2014 3874 1841 3875 2014 3875 2015 3875 1841 3876 2015 3876 1840 3876 1840 3877 2015 3877 2016 3877 1840 3878 2016 3878 1839 3878 1839 3879 2016 3879 1838 3879 1838 3880 2016 3880 2017 3880 1838 3881 2017 3881 1837 3881 1837 3882 2017 3882 2018 3882 1837 3883 2018 3883 2019 3883 1837 3884 2019 3884 1845 3884 1845 3885 2019 3885 2010 3885 1845 3886 2010 3886 1844 3886 1848 3887 2020 3887 2021 3887 1848 3888 2021 3888 1847 3888 1847 3889 2021 3889 2022 3889 1847 3890 2022 3890 1846 3890 1846 3891 2022 3891 2023 3891 1846 3892 2023 3892 1854 3892 1854 3893 2023 3893 2024 3893 1854 3894 2024 3894 1853 3894 1853 3895 2024 3895 2025 3895 1853 3896 2025 3896 1852 3896 1852 3897 2025 3897 2026 3897 1852 3898 2026 3898 1851 3898 1851 3899 2026 3899 2027 3899 1851 3900 2027 3900 1850 3900 1850 3901 2027 3901 2028 3901 1850 3902 2028 3902 1849 3902 1849 3903 2028 3903 2029 3903 1849 3904 2029 3904 1848 3904 1848 3905 2029 3905 2020 3905 1864 3906 2030 3906 2031 3906 1864 3907 2031 3907 2032 3907 1864 3908 2032 3908 1863 3908 1863 3909 2032 3909 1862 3909 1862 3910 2032 3910 2033 3910 1862 3911 2033 3911 1861 3911 1861 3912 2033 3912 2034 3912 1861 3913 2034 3913 1860 3913 1860 3914 2034 3914 2035 3914 1860 3915 2035 3915 1859 3915 1859 3916 2035 3916 2036 3916 1859 3917 2036 3917 1858 3917 1858 3918 2036 3918 2037 3918 1858 3919 2037 3919 1857 3919 1857 3920 2037 3920 2038 3920 1857 3921 2038 3921 1856 3921 1856 3922 2038 3922 2039 3922 1856 3923 2039 3923 1855 3923 1855 3924 2039 3924 2030 3924 1855 3925 2030 3925 1864 3925 2040 3926 1937 3926 2041 3926 2041 3927 1937 3927 1979 3927 2041 3928 1979 3928 2042 3928 2042 3929 1979 3929 1941 3929 2042 3930 1941 3930 2043 3930 2043 3931 1941 3931 1940 3931 2043 3932 1940 3932 2044 3932 2044 3933 1940 3933 1939 3933 2044 3934 1939 3934 2045 3934 2045 3935 1939 3935 1942 3935 2045 3936 1942 3936 1938 3936 2045 3937 1938 3937 2046 3937 2046 3938 1938 3938 2047 3938 2047 3939 1938 3939 1937 3939 2047 3940 1937 3940 2040 3940 2048 3941 1930 3941 2049 3941 2049 3942 1930 3942 1928 3942 2049 3943 1928 3943 1926 3943 2049 3944 1926 3944 2050 3944 2050 3945 1926 3945 2051 3945 2051 3946 1926 3946 1932 3946 2051 3947 1932 3947 1931 3947 2051 3948 1931 3948 2052 3948 2052 3949 1931 3949 2053 3949 2053 3950 1931 3950 1925 3950 2053 3951 1925 3951 1929 3951 2053 3952 1929 3952 2048 3952 2048 3953 1929 3953 1930 3953 2054 3954 1900 3954 2055 3954 2055 3955 1900 3955 1907 3955 2055 3956 1907 3956 2056 3956 2056 3957 1907 3957 1904 3957 2056 3958 1904 3958 2057 3958 2057 3959 1904 3959 2058 3959 2058 3960 1904 3960 1903 3960 2058 3961 1903 3961 1905 3961 2058 3962 1905 3962 2059 3962 2059 3963 1905 3963 1906 3963 2059 3964 1906 3964 1901 3964 2059 3965 1901 3965 2060 3965 2060 3966 1901 3966 2054 3966 2054 3967 1901 3967 1900 3967 2061 3968 1913 3968 1919 3968 2061 3969 1919 3969 2062 3969 2062 3970 1919 3970 2063 3970 2063 3971 1919 3971 1918 3971 2063 3972 1918 3972 2064 3972 2064 3973 1918 3973 1916 3973 2064 3974 1916 3974 2065 3974 2065 3975 1916 3975 1915 3975 2065 3976 1915 3976 2066 3976 2066 3977 1915 3977 1914 3977 2066 3978 1914 3978 2067 3978 2067 3979 1914 3979 2061 3979 2061 3980 1914 3980 1913 3980 1975 3981 2068 3981 2069 3981 1976 3982 2070 3982 2071 3982 2072 3983 1967 3983 1969 3983 2072 3984 1969 3984 2073 3984 2073 3985 1969 3985 2074 3985 2074 3986 1969 3986 1971 3986 2074 3987 1971 3987 2075 3987 2075 3988 1971 3988 1970 3988 2075 3989 1970 3989 2076 3989 2076 3990 1970 3990 1972 3990 2076 3991 1972 3991 2077 3991 2077 3992 1972 3992 1973 3992 2077 3993 1973 3993 2078 3993 2078 3994 1973 3994 1974 3994 2078 3995 1974 3995 2071 3995 2071 3996 1974 3996 1976 3996 2070 3997 1976 3997 1975 3997 2070 3998 1975 3998 2069 3998 2068 3999 1975 3999 1977 3999 2068 4000 1977 4000 2079 4000 2079 4001 1977 4001 1978 4001 1978 4002 2080 4002 2079 4002 1967 4003 2072 4003 1968 4003 1968 4004 2072 4004 2081 4004 1968 4005 2081 4005 1978 4005 1978 4006 2081 4006 2080 4006 2082 4007 1933 4007 1934 4007 2082 4008 1934 4008 2083 4008 2083 4009 1934 4009 2084 4009 2084 4010 1934 4010 1935 4010 2084 4011 1935 4011 2085 4011 2085 4012 1935 4012 1936 4012 2085 4013 1936 4013 2086 4013 1936 4014 1963 4014 2086 4014 2086 4015 1963 4015 2087 4015 2087 4016 1963 4016 1962 4016 2087 4017 1962 4017 2088 4017 2088 4018 1962 4018 2089 4018 2089 4019 1962 4019 1966 4019 2089 4020 1966 4020 2090 4020 2090 4021 1966 4021 1965 4021 2090 4022 1965 4022 2091 4022 2091 4023 1965 4023 1964 4023 2091 4024 1964 4024 2092 4024 2092 4025 1964 4025 1961 4025 2092 4026 1961 4026 2082 4026 2082 4027 1961 4027 1933 4027 2093 4028 1897 4028 2094 4028 2094 4029 1897 4029 1895 4029 2094 4030 1895 4030 2095 4030 2095 4031 1895 4031 1896 4031 2095 4032 1896 4032 2096 4032 2096 4033 1896 4033 1899 4033 2096 4034 1899 4034 2097 4034 2097 4035 1899 4035 1898 4035 2097 4036 1898 4036 2098 4036 2098 4037 1898 4037 1960 4037 2098 4038 1960 4038 2099 4038 2099 4039 1960 4039 1958 4039 2099 4040 1958 4040 2100 4040 2100 4041 1958 4041 1957 4041 2100 4042 1957 4042 2101 4042 2101 4043 1957 4043 1956 4043 2101 4044 1956 4044 2102 4044 2102 4045 1956 4045 1955 4045 2102 4046 1955 4046 2103 4046 2103 4047 1955 4047 2093 4047 2093 4048 1955 4048 1897 4048 2104 4049 1909 4049 2105 4049 2105 4050 1909 4050 2106 4050 2106 4051 1909 4051 1912 4051 2106 4052 1912 4052 2107 4052 2107 4053 1912 4053 1910 4053 2107 4054 1910 4054 1911 4054 2107 4055 1911 4055 2108 4055 2108 4056 1911 4056 2109 4056 2109 4057 1911 4057 1952 4057 2109 4058 1952 4058 2110 4058 2110 4059 1952 4059 1951 4059 2110 4060 1951 4060 2111 4060 2111 4061 1951 4061 1954 4061 2111 4062 1954 4062 2112 4062 2112 4063 1954 4063 1953 4063 2112 4064 1953 4064 2113 4064 2113 4065 1953 4065 1950 4065 2113 4066 1950 4066 2114 4066 2114 4067 1950 4067 1949 4067 2114 4068 1949 4068 2115 4068 2115 4069 1949 4069 1908 4069 2115 4070 1908 4070 2104 4070 2104 4071 1908 4071 1909 4071 2116 4072 1943 4072 2117 4072 2117 4073 1943 4073 2118 4073 2118 4074 1943 4074 1945 4074 2118 4075 1945 4075 1944 4075 2118 4076 1944 4076 2119 4076 2119 4077 1944 4077 1948 4077 2119 4078 1948 4078 2120 4078 2120 4079 1948 4079 1947 4079 2120 4080 1947 4080 2121 4080 2121 4081 1947 4081 2122 4081 2122 4082 1947 4082 1946 4082 2122 4083 1946 4083 2123 4083 2123 4084 1946 4084 1920 4084 2123 4085 1920 4085 1921 4085 2123 4086 1921 4086 2124 4086 2124 4087 1921 4087 1922 4087 2124 4088 1922 4088 2125 4088 2125 4089 1922 4089 1923 4089 2125 4090 1923 4090 2126 4090 2126 4091 1923 4091 1924 4091 2126 4092 1924 4092 2127 4092 2127 4093 1924 4093 2116 4093 2116 4094 1924 4094 1943 4094 2128 4095 1984 4095 2129 4095 2129 4096 1984 4096 1985 4096 2129 4097 1985 4097 2130 4097 2130 4098 1985 4098 1986 4098 2130 4099 1986 4099 2131 4099 2131 4100 1986 4100 1987 4100 2131 4101 1987 4101 2132 4101 2132 4102 1987 4102 2133 4102 2133 4103 1987 4103 1988 4103 2133 4104 1988 4104 1989 4104 2133 4105 1989 4105 2134 4105 2134 4106 1989 4106 2135 4106 2135 4107 1989 4107 1980 4107 2135 4108 1980 4108 1981 4108 2135 4109 1981 4109 2136 4109 2136 4110 1981 4110 1982 4110 2136 4111 1982 4111 2137 4111 2137 4112 1982 4112 1983 4112 2137 4113 1983 4113 2128 4113 2128 4114 1983 4114 1984 4114 2138 4115 1996 4115 2139 4115 2139 4116 1996 4116 1997 4116 2139 4117 1997 4117 2140 4117 2140 4118 1997 4118 1998 4118 2140 4119 1998 4119 2141 4119 2141 4120 1998 4120 1999 4120 2141 4121 1999 4121 1990 4121 2141 4122 1990 4122 2142 4122 2142 4123 1990 4123 1991 4123 2142 4124 1991 4124 2143 4124 2143 4125 1991 4125 1992 4125 2143 4126 1992 4126 2144 4126 2144 4127 1992 4127 1993 4127 2144 4128 1993 4128 2145 4128 2145 4129 1993 4129 2146 4129 2146 4130 1993 4130 1994 4130 2146 4131 1994 4131 2147 4131 2147 4132 1994 4132 1995 4132 2147 4133 1995 4133 2138 4133 2138 4134 1995 4134 1996 4134 2148 4135 2008 4135 2009 4135 2148 4136 2009 4136 2149 4136 2149 4137 2009 4137 2000 4137 2149 4138 2000 4138 2150 4138 2150 4139 2000 4139 2001 4139 2150 4140 2001 4140 2151 4140 2151 4141 2001 4141 2002 4141 2151 4142 2002 4142 2152 4142 2152 4143 2002 4143 2003 4143 2152 4144 2003 4144 2153 4144 2153 4145 2003 4145 2004 4145 2153 4146 2004 4146 2154 4146 2154 4147 2004 4147 2005 4147 2154 4148 2005 4148 2155 4148 2155 4149 2005 4149 2006 4149 2155 4150 2006 4150 2156 4150 2156 4151 2006 4151 2007 4151 2156 4152 2007 4152 2008 4152 2156 4153 2008 4153 2148 4153 2012 4154 2016 4154 2015 4154 2016 4155 2012 4155 2017 4155 2012 4156 2011 4156 2017 4156 2017 4157 2011 4157 2010 4157 2010 4158 2019 4158 2017 4158 2017 4159 2019 4159 2018 4159 2013 4160 2015 4160 2014 4160 2012 4161 2015 4161 2013 4161 2020 4162 2029 4162 2024 4162 2024 4163 2029 4163 2028 4163 2024 4164 2028 4164 2027 4164 2024 4165 2022 4165 2021 4165 2021 4166 2020 4166 2024 4166 2022 4167 2024 4167 2023 4167 2024 4168 2027 4168 2026 4168 2024 4169 2026 4169 2025 4169 2034 4170 2038 4170 2037 4170 2039 4171 2033 4171 2032 4171 2033 4172 2039 4172 2034 4172 2034 4173 2039 4173 2038 4173 2031 4174 2030 4174 2032 4174 2032 4175 2030 4175 2039 4175 2034 4176 2036 4176 2035 4176 2037 4177 2036 4177 2034 4177 2045 4178 2040 4178 2041 4178 2044 4179 2041 4179 2043 4179 2045 4180 2041 4180 2044 4180 2046 4181 2047 4181 2045 4181 2045 4182 2047 4182 2040 4182 2041 4183 2042 4183 2043 4183 2052 4184 2053 4184 2050 4184 2053 4185 2049 4185 2050 4185 2051 4186 2052 4186 2050 4186 2053 4187 2048 4187 2049 4187 2054 4188 2055 4188 2059 4188 2059 4189 2055 4189 2058 4189 2055 4190 2056 4190 2057 4190 2060 4191 2054 4191 2059 4191 2057 4192 2058 4192 2055 4192 2065 4193 2066 4193 2067 4193 2064 4194 2065 4194 2061 4194 2067 4195 2061 4195 2065 4195 2061 4196 2062 4196 2063 4196 2061 4197 2063 4197 2064 4197 2078 4198 2071 4198 2157 4198 2081 4199 2158 4199 2080 4199 2079 4200 2080 4200 2158 4200 2157 4201 2077 4201 2078 4201 2159 4202 2075 4202 2076 4202 2073 4203 2074 4203 2160 4203 2160 4204 2074 4204 2075 4204 2081 4205 2072 4205 2158 4205 2158 4206 2072 4206 2073 4206 2076 4207 2077 4207 2159 4207 2159 4208 2077 4208 2157 4208 2161 4209 2157 4209 2071 4209 2161 4210 2071 4210 2069 4210 2069 4211 2071 4211 2070 4211 2160 4212 2159 4212 2157 4212 2160 4213 2157 4213 2161 4213 2068 4214 2161 4214 2069 4214 2160 4215 2075 4215 2159 4215 2158 4216 2160 4216 2161 4216 2158 4217 2161 4217 2079 4217 2079 4218 2161 4218 2068 4218 2073 4219 2160 4219 2158 4219 2162 4220 2089 4220 2090 4220 2162 4221 2090 4221 2163 4221 2163 4222 2090 4222 2091 4222 2163 4223 2091 4223 2164 4223 2164 4224 2091 4224 2092 4224 2164 4225 2092 4225 2165 4225 2165 4226 2092 4226 2082 4226 2165 4227 2082 4227 2166 4227 2166 4228 2082 4228 2083 4228 2166 4229 2083 4229 2084 4229 2166 4230 2084 4230 2167 4230 2167 4231 2084 4231 2085 4231 2167 4232 2085 4232 2168 4232 2168 4233 2085 4233 2086 4233 2168 4234 2086 4234 2169 4234 2169 4235 2086 4235 2087 4235 2169 4236 2087 4236 2170 4236 2170 4237 2087 4237 2088 4237 2170 4238 2088 4238 2089 4238 2170 4239 2089 4239 2162 4239 2171 4240 2096 4240 2097 4240 2171 4241 2097 4241 2172 4241 2172 4242 2097 4242 2098 4242 2172 4243 2098 4243 2173 4243 2173 4244 2098 4244 2099 4244 2173 4245 2099 4245 2174 4245 2174 4246 2099 4246 2100 4246 2174 4247 2100 4247 2101 4247 2174 4248 2101 4248 2175 4248 2175 4249 2101 4249 2102 4249 2175 4250 2102 4250 2176 4250 2176 4251 2102 4251 2177 4251 2177 4252 2102 4252 2103 4252 2177 4253 2103 4253 2093 4253 2177 4254 2093 4254 2178 4254 2178 4255 2093 4255 2179 4255 2179 4256 2093 4256 2094 4256 2179 4257 2094 4257 2180 4257 2180 4258 2094 4258 2095 4258 2180 4259 2095 4259 2096 4259 2180 4260 2096 4260 2171 4260 2181 4261 2106 4261 2107 4261 2181 4262 2107 4262 2182 4262 2182 4263 2107 4263 2108 4263 2182 4264 2108 4264 2183 4264 2183 4265 2108 4265 2109 4265 2183 4266 2109 4266 2184 4266 2184 4267 2109 4267 2110 4267 2184 4268 2110 4268 2185 4268 2185 4269 2110 4269 2111 4269 2185 4270 2111 4270 2186 4270 2186 4271 2111 4271 2112 4271 2186 4272 2112 4272 2187 4272 2187 4273 2112 4273 2113 4273 2187 4274 2113 4274 2114 4274 2187 4275 2114 4275 2188 4275 2188 4276 2114 4276 2115 4276 2188 4277 2115 4277 2189 4277 2189 4278 2115 4278 2104 4278 2189 4279 2104 4279 2190 4279 2190 4280 2104 4280 2105 4280 2190 4281 2105 4281 2106 4281 2190 4282 2106 4282 2181 4282 2191 4283 2121 4283 2192 4283 2192 4284 2121 4284 2122 4284 2192 4285 2122 4285 2123 4285 2192 4286 2123 4286 2193 4286 2193 4287 2123 4287 2124 4287 2193 4288 2124 4288 2194 4288 2194 4289 2124 4289 2125 4289 2194 4290 2125 4290 2126 4290 2194 4291 2126 4291 2195 4291 2195 4292 2126 4292 2127 4292 2195 4293 2127 4293 2196 4293 2196 4294 2127 4294 2116 4294 2196 4295 2116 4295 2197 4295 2197 4296 2116 4296 2117 4296 2197 4297 2117 4297 2118 4297 2197 4298 2118 4298 2198 4298 2198 4299 2118 4299 2119 4299 2198 4300 2119 4300 2199 4300 2199 4301 2119 4301 2120 4301 2199 4302 2120 4302 2191 4302 2191 4303 2120 4303 2121 4303 2135 4304 2137 4304 2128 4304 2133 4305 2134 4305 2130 4305 2135 4306 2136 4306 2137 4306 2135 4307 2128 4307 2129 4307 2129 4308 2130 4308 2135 4308 2135 4309 2130 4309 2134 4309 2133 4310 2130 4310 2131 4310 2131 4311 2132 4311 2133 4311 2145 4312 2146 4312 2140 4312 2145 4313 2140 4313 2141 4313 2140 4314 2146 4314 2147 4314 2140 4315 2147 4315 2139 4315 2139 4316 2147 4316 2138 4316 2141 4317 2142 4317 2145 4317 2145 4318 2142 4318 2143 4318 2145 4319 2143 4319 2144 4319 2154 4320 2155 4320 2152 4320 2152 4321 2155 4321 2156 4321 2156 4322 2148 4322 2152 4322 2152 4323 2148 4323 2149 4323 2152 4324 2149 4324 2150 4324 2154 4325 2152 4325 2153 4325 2152 4326 2150 4326 2151 4326 2200 4327 2169 4327 2201 4327 2201 4328 2169 4328 2170 4328 2201 4329 2170 4329 2202 4329 2202 4330 2170 4330 2162 4330 2202 4331 2162 4331 2203 4331 2203 4332 2162 4332 2163 4332 2203 4333 2163 4333 2204 4333 2204 4334 2163 4334 2164 4334 2204 4335 2164 4335 2165 4335 2204 4336 2165 4336 2205 4336 2205 4337 2165 4337 2166 4337 2205 4338 2166 4338 2206 4338 2206 4339 2166 4339 2207 4339 2207 4340 2166 4340 2167 4340 2207 4341 2167 4341 2208 4341 2208 4342 2167 4342 2209 4342 2209 4343 2167 4343 2168 4343 2209 4344 2168 4344 2169 4344 2209 4345 2169 4345 2200 4345 2210 4346 2174 4346 2211 4346 2211 4347 2174 4347 2175 4347 2211 4348 2175 4348 2176 4348 2211 4349 2176 4349 2212 4349 2212 4350 2176 4350 2177 4350 2212 4351 2177 4351 2213 4351 2213 4352 2177 4352 2178 4352 2213 4353 2178 4353 2214 4353 2214 4354 2178 4354 2179 4354 2214 4355 2179 4355 2215 4355 2215 4356 2179 4356 2180 4356 2215 4357 2180 4357 2216 4357 2216 4358 2180 4358 2171 4358 2216 4359 2171 4359 2217 4359 2217 4360 2171 4360 2172 4360 2217 4361 2172 4361 2218 4361 2218 4362 2172 4362 2173 4362 2218 4363 2173 4363 2219 4363 2219 4364 2173 4364 2174 4364 2219 4365 2174 4365 2210 4365 2220 4366 2188 4366 2189 4366 2220 4367 2189 4367 2221 4367 2221 4368 2189 4368 2190 4368 2221 4369 2190 4369 2222 4369 2222 4370 2190 4370 2181 4370 2222 4371 2181 4371 2223 4371 2223 4372 2181 4372 2182 4372 2223 4373 2182 4373 2183 4373 2223 4374 2183 4374 2224 4374 2224 4375 2183 4375 2225 4375 2225 4376 2183 4376 2184 4376 2225 4377 2184 4377 2185 4377 2225 4378 2185 4378 2226 4378 2226 4379 2185 4379 2186 4379 2226 4380 2186 4380 2227 4380 2227 4381 2186 4381 2187 4381 2227 4382 2187 4382 2228 4382 2228 4383 2187 4383 2229 4383 2229 4384 2187 4384 2188 4384 2229 4385 2188 4385 2220 4385 2230 4386 2194 4386 2231 4386 2231 4387 2194 4387 2195 4387 2231 4388 2195 4388 2232 4388 2232 4389 2195 4389 2196 4389 2232 4390 2196 4390 2197 4390 2232 4391 2197 4391 2233 4391 2233 4392 2197 4392 2198 4392 2233 4393 2198 4393 2234 4393 2234 4394 2198 4394 2199 4394 2234 4395 2199 4395 2235 4395 2235 4396 2199 4396 2191 4396 2235 4397 2191 4397 2236 4397 2236 4398 2191 4398 2192 4398 2236 4399 2192 4399 2237 4399 2237 4400 2192 4400 2193 4400 2237 4401 2193 4401 2238 4401 2238 4402 2193 4402 2194 4402 2238 4403 2194 4403 2230 4403 2203 4404 2204 4404 2209 4404 2206 4405 2209 4405 2205 4405 2209 4406 2204 4406 2205 4406 2209 4407 2200 4407 2203 4407 2203 4408 2200 4408 2201 4408 2203 4409 2201 4409 2202 4409 2207 4410 2208 4410 2206 4410 2206 4411 2208 4411 2209 4411 2216 4412 2210 4412 2211 4412 2214 4413 2215 4413 2211 4413 2216 4414 2211 4414 2215 4414 2211 4415 2212 4415 2214 4415 2217 4416 2218 4416 2219 4416 2217 4417 2219 4417 2216 4417 2216 4418 2219 4418 2210 4418 2212 4419 2213 4419 2214 4419 2223 4420 2224 4420 2221 4420 2226 4421 2229 4421 2225 4421 2225 4422 2229 4422 2220 4422 2221 4423 2224 4423 2225 4423 2225 4424 2220 4424 2221 4424 2226 4425 2228 4425 2229 4425 2223 4426 2221 4426 2222 4426 2226 4427 2227 4427 2228 4427 2234 4428 2231 4428 2233 4428 2231 4429 2234 4429 2235 4429 2230 4430 2231 4430 2235 4430 2236 4431 2237 4431 2235 4431 2235 4432 2237 4432 2238 4432 2235 4433 2238 4433 2230 4433 2231 4434 2232 4434 2233 4434 1402 4435 88 4435 90 4435 1402 4436 90 4436 1403 4436 1403 4437 90 4437 1056 4437 1403 4438 1056 4438 483 4438 1403 4439 483 4439 1206 4439 1206 4440 483 4440 484 4440 1409 4441 61 4441 87 4441 1409 4442 58 4442 61 4442 1409 4443 50 4443 58 4443 51 4444 50 4444 1236 4444 1236 4445 50 4445 1409 4445 1223 4446 480 4446 2239 4446 1223 4447 2239 4447 1222 4447 1222 4448 2239 4448 479 4448 52 4449 1231 4449 2240 4449 2240 4450 1231 4450 1233 4450 2240 4451 1233 4451 2241 4451 2241 4452 1233 4452 54 4452 1161 4453 103 4453 102 4453 103 4454 1652 4454 1410 4454 1410 4455 87 4455 103 4455 3 4456 5 4456 2 4456 2 4457 5 4457 27 4457 2 4458 27 4458 0 4458 24 4459 2242 4459 26 4459 26 4460 2242 4460 2243 4460 26 4461 2243 4461 2244 4461 26 4462 2244 4462 8 4462 8 4463 2244 4463 2245 4463 8 4464 2245 4464 10 4464 10 4465 2245 4465 2246 4465 10 4466 2246 4466 2247 4466 10 4467 2247 4467 12 4467 12 4468 2247 4468 14 4468 14 4469 2247 4469 2248 4469 14 4470 2248 4470 16 4470 16 4471 2248 4471 2249 4471 16 4472 2249 4472 18 4472 18 4473 2249 4473 2250 4473 18 4474 2250 4474 20 4474 20 4475 2250 4475 2251 4475 20 4476 2251 4476 22 4476 22 4477 2251 4477 2252 4477 22 4478 2252 4478 2253 4478 22 4479 2253 4479 24 4479 24 4480 2253 4480 2242 4480 2248 4481 2247 4481 2242 4481 2243 4482 2242 4482 2246 4482 2248 4483 2251 4483 2250 4483 2242 4484 2247 4484 2246 4484 2248 4485 2242 4485 2253 4485 2248 4486 2252 4486 2251 4486 2249 4487 2248 4487 2250 4487 2246 4488 2244 4488 2243 4488 2248 4489 2253 4489 2252 4489 2246 4490 2245 4490 2244 4490 81 4491 82 4491 211 4491 211 4492 82 4492 83 4492 211 4493 83 4493 85 4493 29 4494 2254 4494 2255 4494 29 4495 2255 4495 48 4495 48 4496 2255 4496 2256 4496 48 4497 2256 4497 47 4497 47 4498 2256 4498 2257 4498 47 4499 2257 4499 45 4499 45 4500 2257 4500 2258 4500 45 4501 2258 4501 43 4501 43 4502 2258 4502 2259 4502 43 4503 2259 4503 41 4503 41 4504 2259 4504 2260 4504 41 4505 2260 4505 39 4505 39 4506 2260 4506 2261 4506 39 4507 2261 4507 37 4507 37 4508 2261 4508 2262 4508 37 4509 2262 4509 36 4509 36 4510 2262 4510 2263 4510 36 4511 2263 4511 34 4511 34 4512 2263 4512 2264 4512 34 4513 2264 4513 32 4513 32 4514 2264 4514 2254 4514 32 4515 2254 4515 29 4515 2260 4516 2255 4516 2254 4516 2260 4517 2256 4517 2255 4517 2262 4518 2254 4518 2264 4518 2264 4519 2263 4519 2262 4519 2256 4520 2260 4520 2259 4520 2262 4521 2261 4521 2254 4521 2256 4522 2259 4522 2258 4522 2256 4523 2258 4523 2257 4523 2254 4524 2261 4524 2260 4524 2265 4525 2266 4525 2267 4525 2267 4526 2266 4526 2268 4526 2267 4527 2268 4527 2269 4527 2270 4528 2271 4528 2272 4528 2268 4529 2272 4529 2269 4529 2266 4530 2270 4530 2268 4530 2268 4531 2270 4531 2272 4531 2267 4532 2271 4532 2265 4532 2265 4533 2271 4533 2266 4533 2266 4534 2271 4534 2270 4534 2273 4535 2274 4535 2275 4535 2276 4536 2277 4536 2278 4536 2278 4537 2277 4537 2279 4537 2278 4538 2279 4538 2280 4538 2275 4539 2280 4539 2279 4539 2275 4540 2279 4540 2273 4540 2273 4541 2279 4541 2277 4541 2276 4542 2278 4542 2274 4542 2273 4543 2277 4543 2274 4543 2274 4544 2277 4544 2276 4544</p> + </triangles> + </mesh> + </geometry> + </library_geometries> + <library_materials> + <material name="Mesh001" id="mat_Mesh001"> + <instance_effect url="#effect_Mesh001"/> + </material> + </library_materials> + <library_visual_scenes> + <visual_scene id="myscene"> + <node name="node0" id="node0"> + <instance_geometry url="#geometry0"> + <bind_material> + <technique_common> + <instance_material symbol="ref_Mesh001" target="#mat_Mesh001"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#myscene"/> + </scene> +</COLLADA> diff --git a/kinton_description/meshes/arm/link5.stl b/kinton_description/meshes/arm/link5.stl new file mode 100644 index 0000000000000000000000000000000000000000..6c51fb5f1d4966aea8e18f28ed42cb872cca3903 Binary files /dev/null and b/kinton_description/meshes/arm/link5.stl differ diff --git a/kinton_description/meshes/arm/link6.dae b/kinton_description/meshes/arm/link6.dae new file mode 100644 index 0000000000000000000000000000000000000000..3fa3992b5dabc5c837c447988fa9ff6f7c51dd1e --- /dev/null +++ b/kinton_description/meshes/arm/link6.dae @@ -0,0 +1,199 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2015-07-29T19:31:24</created> + <modified>2015-07-29T19:31:24</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera_003-camera" name="Camera.007"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp_003-light" name="Lamp.007"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>9.99987e-4</adapt_thresh> + <area_shape>1</area_shape> + <area_size>0.1</area_size> + <area_sizey>0.1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <shadspotsize>45</shadspotsize> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_images/> + <library_effects> + <effect id="Material_003_001-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.05576943 0.05576943 0.05576943 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="Material_003_001-material" name="Material_003_001"> + <instance_effect url="#Material_003_001-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Link5_001-mesh" name="Link5.001"> + <mesh> + <source id="Link5_001-mesh-positions"> + <float_array id="Link5_001-mesh-positions-array" count="1320">-1.534331 8.71291 -1.490304 -0.2745829 8.825143 0.9926505 1.149036 8.745455 1.002068 -1.748669 8.642651 0.9930477 1.164547 8.787592 -1.490267 2.58745 8.445889 0.9931064 -3.230638 8.203927 0.9993715 3.36767 8.185907 -1.490269 -3.411164 8.166715 -1.490106 4.112689 7.818077 1.001413 5.328929 7.121345 -1.490255 5.278046 7.078439 1.0058 -4.604884 7.525935 0.9942179 -5.879422 6.644312 -1.490285 -5.879181 6.575895 0.9972539 6.402625 6.112786 1.001501 6.963662 5.50654 -1.490246 -6.84957 5.557624 1.005162 7.344791 4.946287 1.005962 -7.329813 4.957341 -1.490277 7.788552 4.280242 -1.490257 -7.717708 4.289441 1.000986 8.053492 3.711599 1.005784 -8.440762 2.817183 -1.490301 8.662293 2.190901 -1.490257 -8.352818 2.897231 0.9962068 8.603909 2.209496 0.9960404 -8.732886 1.414143 1.00096 8.898423 0.4816096 0.9998977 -8.848876 0.6850774 -1.490283 8.925349 -0.7507785 -1.490237 -8.87224 -0.05927187 0.9842253 8.860688 -0.9047642 0.9942885 -8.845542 -0.8138629 -1.49028 -8.724147 -1.569769 1.001331 8.588255 -2.377389 1.001128 -8.599314 -2.268263 -1.490272 8.400237 -3.053534 -1.490246 8.415999 -2.767111 1.009773 -8.355655 -2.997134 1.000067 8.102991 -3.712913 1.003127 -8.071802 -3.76159 -1.490261 7.419076 -5.059848 -1.490253 7.376217 -5.037698 0.9944463 -7.693055 -4.464787 1.001088 -7.334657 -5.068413 -1.490276 -6.887362 -5.631072 1.002627 6.40921 -6.218988 1.002715 -6.425722 -6.194052 -1.490301 5.923102 -6.718259 -1.490243 -5.83711 -6.739298 0.9931541 5.31843 -7.180039 0.9993734 4.038931 -8.033802 -1.490245 4.092494 -7.942055 1.002794 -4.582229 -7.647683 1.000454 -4.662265 -7.655974 -1.490215 2.621704 -8.564402 0.9751043 -3.308228 -8.285986 1.001413 -2.618122 -8.557287 -1.490257 1.925963 -8.7516 -1.490265 -1.829311 -8.747416 0.994513 1.07873 -8.868077 1.002441 -0.3586082 -8.981272 -1.490268 -0.325295 -8.930293 0.9997745 -3.438563 -4.505965 -1.490245 -3.405199 -4.256117 1.009758 -3.447234 -4.095602 -1.490249 -3.572902 -4.791133 1.009757 -3.745192 -4.972912 -1.490233 -3.648972 -3.72961 -1.49025 -3.626131 -3.75346 1.009758 -3.957211 -5.06349 1.009758 -4.149096 -3.479074 1.009758 -3.965888 -3.541877 -1.49025 -4.256387 -5.105496 -1.490242 -4.392615 -5.092278 1.009758 -4.321627 -3.500073 -1.49025 -4.745275 -4.935457 -1.490243 -4.751128 -4.907456 1.009758 -4.788176 -3.711 1.009758 -4.684501 -3.644075 -1.49025 -4.980374 -4.587219 1.009758 -5.01131 -4.468116 -1.49025 -4.971442 -3.990574 -1.49025 -5.014644 -4.160714 1.009758 4.569353 -3.547653 -1.490234 4.224931 -3.498085 1.009766 4.664105 -3.594252 1.009765 3.962022 -3.542947 -1.490234 3.813818 -3.622169 1.009764 4.987082 -3.931256 -1.490234 4.989112 -3.949069 1.009766 3.575876 -3.875181 -1.490234 3.515135 -4.003789 1.009766 5.068991 -4.34799 1.009766 5.058088 -4.463549 -1.490234 3.449818 -4.448662 -1.490235 3.463679 -4.408132 1.009766 4.947664 -4.727949 1.009768 4.779351 -4.929937 -1.490234 3.655774 -4.84309 1.009769 4.591347 -5.045686 1.009773 3.777346 -4.949863 -1.490234 4.254582 -5.116638 -1.490234 4.092707 -5.092292 1.009773 -3.416581 4.252016 1.009742 -3.428612 4.019149 -1.490257 -3.508929 3.795943 1.00975 -3.456235 4.417148 -1.490257 -3.647351 4.770237 1.009743 -3.705193 3.558159 -1.490256 -3.664897 4.775264 -1.490257 -3.944973 3.410027 1.00975 -4.120122 3.385569 -1.490257 -4.119654 4.98535 -1.490257 -4.165767 4.989231 1.009743 -4.610054 3.458511 1.00975 -4.494513 3.424344 -1.490256 -4.656419 4.875945 1.009743 -4.674894 4.868959 -1.490257 -4.851216 3.675296 -1.490257 -4.962667 3.864665 1.00975 -5.017284 4.373977 1.009748 -4.979279 4.454093 -1.490257 -5.02495 4.083594 -1.490257 5.045176 3.915042 -1.490242 5.021954 3.868767 1.009758 5.000559 4.545266 1.009758 5.009842 4.487547 -1.490249 4.714349 4.858278 -1.49025 4.712134 3.520243 1.00976 4.640275 3.467046 -1.490242 4.596751 4.916079 1.009758 4.228054 3.359277 1.009758 4.160129 3.379502 -1.490242 4.297056 4.985872 -1.49025 4.160118 4.987237 1.009758 3.870692 4.8959 -1.490251 3.639377 3.65097 -1.490241 3.694837 4.76248 1.009758 3.607079 3.689888 1.009759 3.577877 4.599696 -1.490249 3.455724 4.2795 1.009758 3.451092 4.225031 -1.490241 -0.6201682 -2.799894 0.6589152 -0.9225581 -2.697502 1.009758 0.3112623 -2.871284 1.009745 0.2931833 -2.855598 0.6611491 0.1145281 -1.667844 1.003113 -0.8678436 -1.459163 1.002223 -2.455836 -1.391035 0.6755414 -1.452562 -2.452228 0.6596959 0.8145714 -1.4598 1.004608 -1.572698 0.007159948 1.004422 -1.998491 -1.99925 0.6619634 1.064372 -2.657366 0.659758 -2.759996 -0.4922185 0.6595326 -2.459912 1.254983 0.690724 -1.753318 -2.229951 1.009758 1.730174 -2.278753 0.6686032 -2.744933 0.4642146 0.6576078 -2.368387 -1.531051 1.009758 1.648533 -0.5243499 0.9969196 1.361837 -2.524882 1.009766 -1.997351 1.881875 0.6645842 -2.776736 0.3506691 1.00975 -2.689261 -0.7648018 1.009753 2.332576 -1.67013 0.6575992 2.044762 -1.9995 1.009764 -0.8793335 1.284797 1.007407 -2.375364 1.407101 1.009754 -1.491609 2.313881 0.6600882 2.721283 -0.8138077 0.6612795 0.9217262 1.286593 1.008963 4.00186e-4 1.560335 0.9999499 -1.640995 2.207892 1.009751 2.548746 -1.265867 1.009759 2.82706 0.08681392 0.6613168 2.621615 0.9864035 0.6865368 -0.4858726 2.721832 0.6602292 -0.799506 2.617999 1.00975 2.81421 -0.3417811 1.009758 2.158726 1.769546 0.6609992 0.9776741 2.591913 0.6593025 2.74428 0.5849194 1.00976 -0.03432077 2.7386 1.009808 0.829383 2.630516 1.009757 2.383496 1.459653 1.009757 1.779238 2.130794 1.009759 -2.180891 -7.266608 0.359756 -2.007797 -7.555995 1.009763 -1.731827 -7.038178 0.3597565 -1.637161 -7.942672 0.3597562 -1.305664 -7.565979 0.359757 -2.479437 -6.413686 1.009766 -1.430297 -7.449665 -1.490242 -1.875258 -6.729032 -1.490242 -2.450738 -6.502892 0.3597602 -1.226198 -8.233396 1.009765 -1.957861 -6.398478 0.3597564 -0.7186342 -8.472378 0.3597565 -0.4529949 -8.033594 0.3597565 -0.553034 -8.004858 -1.490234 -1.970236 -5.717958 -1.490242 -2.452419 -5.63523 0.3597649 -0.5065307 -8.504307 1.009766 -1.930867 -5.546421 0.3597656 -2.346353 -5.223077 1.009767 0.3265487 -8.552341 1.009766 -2.180907 -4.851969 0.3597607 0.3587042 -8.547017 0.3597565 0.5529032 -7.993644 0.3597565 0.6548037 -7.984958 -1.490234 -1.491986 -4.725433 -1.490243 -1.437238 -4.66227 0.3597585 -1.925628 -4.488011 1.009758 -1.637199 -4.175917 0.3597559 1.203493 -8.269652 0.3597565 1.169343 -8.289324 1.009767 -1.297246 -3.919282 1.009758 1.298211 -7.619209 0.3597567 -0.9150837 -3.731299 0.3597573 2.032299 -7.574542 0.3597566 -0.7850351 -4.223242 -1.49024 -0.5747814 -4.131458 0.3597565 1.790203 -7.826904 1.00977 1.477921 -7.439047 -1.49023 -0.1959963 -3.54791 1.009758 2.266044 -7.174146 1.009767 0.07230204 -3.541106 0.3597564 1.827248 -6.92987 0.3597565 -0.136634 -4.059727 -1.490242 2.464262 -6.614562 0.3597565 1.944375 -6.65455 -1.490234 0.2926957 -4.070929 0.3597565 2.505382 -6.373835 1.009766 2.013825 -6.286391 0.3597565 0.5377978 -4.121418 -1.490242 0.7979466 -3.679235 1.009768 1.093974 -3.793706 0.3597564 0.9668804 -4.291003 0.3597563 2.48811 -5.545578 0.3597566 2.008945 -5.819311 -1.490234 1.94969 -5.464528 0.3597565 2.459385 -5.452778 1.009765 1.161555 -4.410794 -1.490239 1.913944 -4.392475 0.3597511 1.507912 -4.712922 0.3597513 1.524646 -4.051503 1.009766 1.738378 -5.008279 -1.490231 2.121213 -4.701591 1.009765 -7.47454 1.971803 0.3597567 -7.291004 2.070541 1.009741 -7.996021 1.457564 1.009744 -7.305649 1.447403 0.3597564 -6.570808 1.871216 0.3597567 -6.596283 2.370875 1.009743 -7.301575 1.442749 -1.490257 -6.729207 1.806247 -1.490257 -6.383279 2.429829 0.3597565 -7.731827 0.9196322 0.3597559 -8.16993 1.164306 0.3597568 -7.734787 0.9212489 -1.490258 -8.480189 0.2582871 1.009749 -5.826176 1.949826 -1.490257 -5.499151 2.420265 1.00975 -7.957859 0.2799147 0.3597565 -8.452421 0.3647461 0.3597564 -5.514107 1.909955 0.3597565 -5.304331 2.355135 0.3597567 -7.98921 0.04896074 -1.490257 -7.960537 -0.3811343 0.3597565 -8.421905 -0.6952068 0.3597565 -8.317531 -1.001572 1.00975 -5.115735 1.745728 -1.490259 -4.54649 1.998831 0.3597565 -4.596949 1.409662 0.3597566 -4.521664 1.984485 1.00975 -7.89 -0.6676467 -1.490257 -7.73185 -1.038132 0.359756 -4.464114 1.268302 -1.492467 -3.828239 1.259902 0.3597565 -4.034527 1.51128 1.009752 -7.931622 -1.635448 0.35976 -7.578141 -1.269377 -1.490256 -7.555508 -2.02248 1.00975 -7.305662 -1.565975 0.3597559 -4.139164 0.735009 0.3597564 -3.56104 0.659946 1.00975 -7.312581 -2.186826 0.3597649 -4.040518 0.4584629 -1.49025 -6.884941 -1.868492 -1.488724 -3.462355 0.02571719 0.3597565 -6.570781 -1.989773 0.3597655 -3.97511 0.1021757 0.3597565 -6.432746 -2.540225 1.010131 -6.301046 -2.569458 0.3597581 -3.982659 -0.1878064 -1.49025 -4.05161 -0.6119694 0.3597568 -3.493918 -0.3592034 1.00975 -3.6705 -1.035714 0.3597531 -5.810674 -2.068717 -1.49025 -5.598221 -2.037813 0.3597642 -4.179942 -0.9690167 -1.490251 -3.717599 -1.132829 1.00975 -5.2437 -2.462227 1.009758 -4.345867 -1.222709 0.3597569 -4.965891 -2.365876 0.3597573 -4.125186 -1.743789 0.3597525 -4.318686 -1.959531 1.009754 -4.833127 -1.705772 0.3597607 -4.848682 -1.727775 -1.490249 2.057273 7.403826 0.3597558 2.447845 6.586174 0.3597565 1.821199 7.69184 1.009739 1.950129 6.531445 0.3597565 2.343208 6.87808 1.00975 1.405419 7.406317 0.3597605 1.815419 6.829444 -1.490252 1.455761 7.994068 0.359755 1.41721 7.38013 -1.490247 2.008927 6.180792 -1.49025 2.520288 5.770985 0.3597564 2.534208 5.879206 1.00975 1.088032 8.207132 1.009744 1.995112 5.536706 0.3597565 0.6544196 7.843533 0.3597567 0.4971365 8.413899 0.3597565 0.8665625 7.758332 -1.490258 1.975304 5.504534 -1.49025 2.334238 4.973386 0.3597568 0.3047254 8.434301 1.009743 2.377586 5.107869 1.00975 0.2126881 7.936409 -1.490257 -0.04919803 7.948033 0.3597565 1.715802 4.87053 -1.490249 1.649898 4.770225 0.3597563 2.044138 4.466536 1.009754 1.879909 4.257901 0.3597567 -0.5082006 8.39332 0.3597564 -0.8394818 8.312923 1.009743 -0.5680248 7.862037 -1.490257 -0.7279517 7.803124 0.3597567 1.233711 4.33747 -1.490251 1.173216 4.299487 0.3597564 1.471569 3.900304 1.009757 1.203492 3.730379 0.3597562 -1.483896 7.964862 0.3597556 0.756868 3.543999 1.009305 -1.30564 7.447453 0.35976 -1.693477 7.769268 1.009743 0.4017707 3.962185 0.3597565 -1.16891 7.548691 -1.490253 0.642447 4.036695 -1.49025 0.3699537 3.453471 0.3597565 -0.001785039 3.434201 1.00947 -1.64443 7.065935 -1.490257 -1.73185 6.919606 0.3597647 -2.276167 6.978813 0.3597649 -2.31381 6.881647 1.00975 -0.1527016 3.931634 -1.49025 -0.5276364 3.490633 0.3597563 -0.4024537 3.978644 0.3597565 -0.7116636 3.550311 1.009751 -1.98947 6.116456 0.3597649 -1.994688 6.118765 -1.490257 -1.480275 3.91164 0.3597564 -1.03372 4.22873 -1.490252 -1.031935 4.231585 0.3597565 -1.561081 3.977899 1.009749 -2.488509 5.940732 0.3597648 -2.482313 5.727824 1.00975 -1.87208 5.272083 0.3597564 -1.541228 4.679805 0.3597563 -2.275253 4.89665 0.3597579 -1.53639 4.683673 -1.490257 -1.848175 5.213975 -1.490255 -2.211319 4.798183 1.009749 5.871209 2.441933 0.3597565 6.884592 2.307407 0.3597565 6.254812 2.453055 1.009758 5.950793 1.948027 0.3597565 6.6624 1.841568 0.3597564 5.083336 2.272608 1.009758 6.363268 1.927899 -1.490242 5.084923 2.268709 0.3597573 5.272015 1.803114 0.3597568 5.266125 1.817792 -1.490242 7.218202 2.142119 1.009765 7.322614 1.489916 -1.49024 7.258974 1.519118 0.359756 7.832904 1.677898 0.3597567 4.36416 1.822584 0.359756 4.126814 1.602829 1.009758 4.567037 1.340084 0.3597564 7.898251 1.598361 1.009763 7.813431 0.8651106 0.3597564 4.458031 1.202258 -1.490241 8.285607 1.011765 0.3597565 3.830085 1.164298 0.3597568 8.429805 0.6813499 1.009766 7.830005 0.7995959 -1.490236 4.127924 0.6094061 0.3597564 3.632409 0.7012171 1.009765 8.538516 0.03382003 0.3597564 4.026546 0.2825897 -1.490242 3.547573 0.3647173 0.3597565 8.024945 0.1044324 -1.490234 8.035953 -0.1394365 0.3597565 4.011946 -0.07493931 0.3597565 3.519222 -0.05925214 1.009766 8.5037 -0.3655077 1.009766 3.549251 -0.5028564 0.3597564 3.719554 -1.108239 1.009767 8.329482 -1.035738 0.3597533 4.127928 -0.7279514 0.3597566 7.96687 -0.5235334 -1.490233 7.747668 -1.101402 0.3597556 8.282401 -1.132808 1.009766 4.119637 -0.7183153 -1.490241 3.929476 -1.472518 0.359758 7.640403 -1.260105 -1.490234 7.872265 -1.749244 0.3597535 7.820337 -1.806314 1.012102 4.458765 -1.320181 0.3597559 4.632492 -1.524276 -1.491511 4.526844 -2.078736 1.00982 7.173224 -1.7005 0.3597524 7.037831 -2.363317 0.3597573 4.968029 -1.768392 0.3597603 4.704942 -2.195677 0.3597649 6.934339 -1.848842 -1.490233 7.145117 -2.289939 1.010629 6.401784 -2.037812 0.3597584 5.415974 -2.491453 1.009766 6.354477 -2.551686 1.009766 5.246744 -1.906339 -1.491017 5.597547 -2.021355 0.3597645 6.064001 -2.079329 -1.490234 5.729873 -2.569577 0.3597589</float_array> + <technique_common> + <accessor source="#Link5_001-mesh-positions-array" count="440" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Link5_001-mesh-normals"> + <float_array id="Link5_001-mesh-normals-array" count="2724">-0.02764713 0.9991328 -0.0311352 -0.1228389 0.9922729 0.01747119 0.2039608 0.9788169 0.01781791 0.05576634 0.9982953 0.0172249 0.2634136 0.964511 -0.01821517 0.3804273 0.9245314 0.02273321 0.4770098 0.8788033 -0.01289564 0.5356268 0.8440719 0.02542835 0.7026797 0.7113512 -0.01485872 0.777709 0.6282303 0.02225816 0.8297446 0.5581415 -0.001417636 0.8670876 0.4976981 0.02134853 0.9225309 0.3857928 -0.0100305 0.9388107 0.3438829 0.01947349 0.9855386 0.1680313 0.02188599 0.9954735 0.08901864 -0.03329187 0.9993315 -0.02729862 0.02431619 0.9832261 -0.1818282 0.01431959 0.9748862 -0.2223095 -0.01323902 0.9396677 -0.3413973 0.02173852 0.8765163 -0.4809809 0.01940691 0.7737233 -0.6332389 0.01899111 0.7424936 -0.6697686 -0.01064449 0.6608911 -0.7501775 0.021371 0.5724269 -0.8198521 -0.01303839 0.3891526 -0.9208195 0.02552598 0.3216001 -0.9466874 -0.01887446 0.193408 -0.9809165 0.01990103 0.1000199 -0.994907 -0.01249384 0.04422265 -0.9988244 0.01985764 -0.1844003 -0.9827101 -0.0166555 -0.2976847 -0.9544227 0.02147203 -0.4034176 -0.9149359 -0.01211172 -0.6381166 -0.769735 -0.01775437 -0.8226224 -0.568259 0.01934254 -0.8709722 -0.4912924 -0.006260871 -0.9428871 -0.3330716 -0.005229532 -0.9950704 -0.09734416 0.01894903 -0.9821265 0.1879925 -0.009289085 -0.9683429 0.2482393 0.02625721 -0.909666 0.4149141 0.01881611 -0.8874493 0.4606718 -0.01467293 -0.8249938 0.5646762 0.02293473 -0.75823 0.6518962 -0.01089471 -0.5975295 0.8015422 0.02210348 -0.5246837 0.850669 -0.03269863 -0.2794218 0.9601503 0.005910575 -0.9154245 -0.4023543 -0.01044183 -0.4646033 -0.885509 -0.004202842 0.341095 -0.9398986 -0.01564496 0.8930403 -0.4497207 -0.01517361 0.9967512 0.08009028 -0.008518636 0.8131178 0.5820811 -0.004615604 0.4581993 0.888805 -0.008882045 -0.06597024 0.9977822 -0.008870422 -0.5781027 0.8157317 -0.01947259 -0.9540802 0.2990598 -0.01715487 0.7874201 -0.6162886 -0.0125724 0.9766043 -0.2146699 0.01268458 0.9919938 -0.1262394 -0.003453552 0.9146995 0.4039676 -0.01162075 0.4953874 0.8685747 -0.01300615 -0.09305024 0.9955374 -0.01571983 -0.6654656 0.7462678 -0.01549243 -0.9525668 0.3041684 -0.009905695 -0.9805359 -0.1963385 -6.02793e-4 -0.7373975 -0.6754459 -0.004213929 -0.2138932 -0.9768049 -0.01010036 -0.9134474 -0.4067685 -0.01237952 -0.389127 -0.9211662 -0.005747616 0.224969 -0.9743654 0.001060247 0.8119499 -0.5837109 -0.004369318 0.994181 0.1066118 -0.01543164 0.9201033 0.391511 0.01136267 0.7550281 0.6554973 -0.0159927 0.07269722 0.9972436 -0.01484966 -0.6626283 0.7487025 -0.01919144 -0.9994516 -0.03160834 -0.009868741 -0.6763011 -0.736477 -0.01478475 -0.1608412 -0.9869456 -0.008271276 0.4349 -0.9003096 -0.01745569 0.8961084 -0.4436439 -0.01303607 0.9685707 0.2486339 -0.007211565 0.4699364 0.882667 -0.00766921 -0.315513 0.9488561 -0.01112174 -0.7473677 0.66437 0.007344722 -0.08718597 -0.9832942 0.1597846 -0.917565 -0.3784494 -0.1218634 -0.8575771 -0.5034503 0.1053532 -0.7382524 -0.6646812 -0.1148139 -0.5573559 -0.7999943 0.2221792 -0.4633098 -0.8806447 -0.09904021 0.1538926 -0.9763339 -0.1519511 0.3751515 -0.9248964 0.06187069 0.6490225 -0.7593086 0.04711991 0.8041375 -0.5904899 0.06844472 0.9408054 -0.3380929 -0.02404814 0.9962625 -0.01551854 0.0849719 0.9872421 0.07741916 -0.1391377 0.945272 0.3209289 0.05886715 0.9194873 0.3850433 -0.0792768 0.7989921 0.5998557 0.04224389 0.6375452 0.7680692 0.06004995 0.3846933 0.9209054 0.06280267 0.06072086 0.9972823 0.04172635 -0.3117854 0.9455958 -0.09294384 -0.4931607 0.8650943 0.0916748 -0.954539 0.2742126 -0.1168881 -0.907452 0.4115529 0.08458769 0.7772631 0.6251199 0.07132595 0.4982956 0.8640608 0.07141679 0.05753606 0.9978853 0.03024244 0.06910997 0.9975417 0.01158988 -0.3119175 0.9500288 0.0123648 -0.6415193 0.7649083 0.05803686 -0.8059815 0.5875357 -0.07208007 -0.909366 0.4091884 0.07495611 -0.9570844 0.2862217 -0.04545563 -0.9982433 0.02226966 0.054901 -0.9980718 -0.04984277 -0.03699076 -0.8927605 -0.4445332 0.07327377 -0.7340391 -0.6736048 -0.08627349 -0.588276 -0.8056018 0.07026511 -0.2395597 -0.9689297 0.06153512 -0.1307147 -0.9893321 -0.06431019 0.1887121 -0.9797003 0.06763911 0.318367 -0.9440724 -0.08584827 0.5232974 -0.8499009 0.06187361 0.7784713 -0.6260774 0.04482817 0.8661919 -0.4957771 -0.06258314 0.943494 -0.3270554 0.05342054 0.9990366 0.001935362 0.04384285 0.9428658 0.3331477 -0.004092574 0.9216396 0.380529 -0.07601392 0.7545838 -0.6498225 0.09129017 0.9243891 -0.3731908 -0.07895171 0.9427857 -0.3330935 -0.01427912 0.9984641 0.02874541 0.0473631 0.9869531 0.1274233 -0.09842258 0.8841731 0.461046 0.07532954 0.7967818 0.5947315 -0.1069269 0.4176631 0.905673 -0.07289713 0.3536478 0.9349105 0.02959173 -0.06536489 0.9961737 -0.05801117 -0.1502299 0.9852581 0.08183825 -0.4761958 0.8762506 -0.07363742 -0.5924408 0.800641 0.08937549 -0.8412877 0.5402265 0.01975572 -0.9602723 0.2776464 -0.0280978 -0.97916 0.1920117 0.06616103 -0.9940512 -0.06546896 -0.08703994 -0.9505385 -0.2817947 0.1306453 -0.8704591 -0.4841231 -0.08902662 -0.7170174 -0.6969519 0.01200318 -0.4251888 -0.9043552 -0.03682315 -0.06884723 -0.9944933 0.07901358 0.3866539 -0.9212146 0.0431537 0.3966665 -0.9175544 0.02737742 -0.9012888 -0.4305231 0.04825299 -0.8398532 -0.5387482 -0.0663101 -0.6990509 -0.7123985 0.06177526 -0.5740786 -0.8168112 -0.05703681 -0.4000917 -0.9135546 0.07310783 0.02045142 -0.9990905 0.03741383 0.4003919 -0.9117853 0.09129083 0.7780077 -0.6251131 0.06275045 0.9793624 -0.2003313 0.02677065 0.9782271 0.1998046 0.05612248 0.9587448 0.2794778 -0.05196541 0.7835386 0.62111 0.01702147 0.7777591 0.6277112 0.03270226 0.4493563 0.8926615 -0.03513258 0.04130846 0.9977276 0.05322706 -0.3147811 0.9475436 0.05544513 -0.6142794 0.7876619 0.04743105 -0.7022638 0.7101234 -0.05049967 -0.8434684 0.5355969 0.04119658 -0.8866598 0.4609996 -0.03624892 -0.9737161 0.2271325 -0.01696389 -0.9954273 -0.08846044 0.03604561 -0.979543 -0.1873036 -0.07357215 -0.1310093 -0.9868953 0.09420281 0.1518355 -0.9857257 -0.07273983 0.215143 -0.9765619 0.006383061 0.5262909 -0.8502807 0.006385445 0.7746395 -0.6284745 0.07038009 0.9417284 -0.3327359 0.04934281 0.9989927 0.001931846 0.04483252 0.9789109 0.1869492 -0.08236181 0.9267171 0.3633856 0.09563577 0.6809708 0.7302268 0.05520439 0.42055 0.9060111 -0.04776644 0.3422395 0.9381439 0.0525186 0.0637952 0.9940167 -0.0886619 -0.1546157 0.9804645 0.1215863 -0.3137496 0.9479029 -0.05514705 -0.5822945 0.8129664 0.004330635 -0.5925543 0.8051942 0.02327382 -0.8418032 0.5394294 0.01958346 -0.960454 0.2770071 -0.02819949 -0.9793482 0.1914032 0.06513106 -0.992888 -0.07008492 -0.09623706 -0.9644636 -0.2494222 0.08716982 -0.8634473 -0.5005055 -0.06287127 -0.8269956 -0.5620247 0.01436889 -0.6241626 -0.7806069 -0.03276872 -0.55163 -0.8309921 0.07180815 -0.3060629 -0.9482933 -0.08405458 -0.2814134 0.006362915 0.9595655 0.2900368 -0.03410422 0.9564076 0.2654925 -0.1246228 0.9560245 0.1913626 -0.171935 0.9663429 0.06925785 -0.2626833 0.9623932 0.1290956 -0.2494397 0.9597469 -0.01938265 -0.2793089 0.9600057 -0.1814519 -0.2234795 0.9576702 -0.1100253 -0.2655771 0.9577909 -0.2518171 -0.06802064 0.9653815 -0.2636125 0.05468302 0.9630776 -0.105932 0.2608265 0.9595561 0.02641987 0.2907995 0.9564192 0.1713576 0.2480642 0.9534677 0.258381 0.03193986 0.9655149 -0.1777703 0.2180993 0.9595991 -0.2055939 -0.1760864 0.9626654 -0.07092064 0.252551 0.964981 -0.05552905 -0.2572889 0.9647377 0.06648313 0.2555187 0.9645156 0.07675433 -0.2651753 0.9611404 0.2105854 0.1559398 0.9650579 0.1982972 0.07308459 0.9774134 0.2008776 -0.1711564 0.9645485 0 0 1 9.83748e-7 -8.76355e-7 1 2.16643e-6 1.2942e-7 1 -4.10138e-6 3.64485e-6 1 1.45322e-6 5.9286e-6 1 1.07178e-6 7.42394e-6 1 -2.36752e-6 6.1856e-6 1 5.16955e-7 -1.07543e-5 1 8.71164e-6 -5.44442e-6 1 7.0227e-6 2.52803e-6 1 1.49499e-6 -4.89594e-6 1 -1.0925e-6 1.90722e-7 1 -1.47228e-6 -9.19603e-7 1 -3.95067e-7 -1.86757e-6 1 -2.35511e-7 2.10498e-7 1 0 0 1 0 0 1 0 0 1 0 -2.22046e-7 1 1.36946e-7 -2.49035e-7 1 0 1.28705e-7 1 0 0 1 0 1.23988e-7 1 -2.15301e-7 0 1 -1.23066e-7 0 1 6.54207e-7 5.08129e-6 1 -3.46153e-6 4.94405e-6 1 4.90131e-6 -5.65235e-6 1 5.34765e-6 -1.48655e-6 1 1.67893e-7 -1.62765e-7 1 0 0 1 5.94827e-6 4.74625e-6 1 4.87212e-6 1.44424e-5 1 -4.66827e-6 1.45487e-5 1 2.33568e-6 -1.18174e-5 1 8.21705e-7 -1.25219e-5 1 2.96667e-6 -1.53575e-5 1 7.44082e-6 -6.7337e-6 1 1.11332e-5 -7.47633e-6 1 1.13442e-5 -3.54588e-6 1 7.08539e-6 -5.34952e-6 1 6.42014e-6 -2.94686e-6 1 5.03905e-6 -4.18899e-6 1 0 4.10754e-7 1 0 0 1 -1.64473e-7 0 1 0 -2.14478e-7 1 1.53171e-7 1.89216e-7 1 0 2.0128e-7 1 0 -3.65034e-7 1 -1.82935e-7 -2.4852e-7 1 0 2.31733e-7 1 1.23988e-7 2.25129e-7 1 0 -7.33228e-7 1 0 -7.37461e-7 1 1.43369e-6 -1.08702e-6 1 2.09558e-6 0 1 -1.98028e-7 -4.51863e-7 1 0 0 1 -1.4548e-7 0 1 3.44911e-7 -6.96449e-7 1 3.46278e-6 5.57752e-6 1 -1.82239e-7 2.13718e-7 1 0 4.77522e-7 1 -1.17796e-6 9.43554e-7 1 4.79396e-7 8.68982e-6 1 2.94787e-7 8.62622e-6 1 1.29573e-6 8.38878e-6 1 3.97642e-7 1.32199e-7 1 0 0 1 3.27474e-6 -9.63915e-6 1 8.41068e-6 -4.90431e-6 1 2.59018e-6 1.34626e-6 1 2.29204e-6 3.37058e-7 1 -1.6772e-7 1.41879e-7 1 0 0 1 0 -3.03086e-7 1 0 -2.94294e-7 1 -1.98701e-7 0 1 3.65126e-7 0 1 2.8527e-7 -2.99024e-7 1 -4.41587e-7 -3.37693e-7 1 -3.87451e-7 5.82272e-7 1 -8.51362e-7 3.73996e-7 1 -7.74652e-7 0 1 -1.59913e-7 4.85682e-7 1 0 0 1 0 0 1 -2.12784e-7 8.46023e-7 1 7.26909e-6 0 1 7.30262e-6 8.70435e-6 1 2.97621e-7 9.30435e-6 1 1.90741e-6 7.34989e-7 1 -1.44292e-7 1.69215e-7 1 8.07798e-7 1.06921e-5 1 6.99143e-7 1.03107e-5 1 -1.89106e-6 1.19056e-5 1 2.32058e-6 -9.65989e-6 1 7.34966e-6 -8.44601e-6 1 1.37103e-6 -8.91701e-7 1 5.07097e-6 6.33811e-6 1 -1.04831e-6 7.5881e-6 1 -1.82972e-6 -3.61808e-6 1 4.32146e-6 -2.43505e-6 1 4.29324e-6 -2.18505e-6 1 1.27226e-6 -3.17439e-6 1 1.46276e-7 0 1 0 0 1 0 -2.9401e-7 1 -1.12059e-6 -2.66488e-7 1 -9.07703e-7 -1.036e-6 1 5.0105e-7 -3.66938e-7 1 1.38497e-7 -1.9401e-7 1 0 0 1 4.24457e-7 0 1 1.01705e-6 -4.87444e-7 1 0 -9.10605e-7 1 -1.77236e-6 0 1 4.13987e-7 9.77033e-7 1 7.32598e-7 -3.58693e-7 1 3.84146e-7 -5.45725e-7 1 1.26364e-7 0 1 0 0 1 -2.55658e-7 1.37145e-7 1 3.68943e-7 1.74288e-6 1 3.63398e-6 8.72635e-7 1 -0.9967819 0.07705914 0.02208471 -0.9968248 -0.07778781 -0.01701039 -0.9481697 -0.3163174 0.03029215 -0.8618033 -0.5065504 -0.02648854 -0.7192745 -0.6944007 0.02125841 -0.6148968 -0.7884896 -0.0136491 -0.4207973 -0.9070397 0.01445227 -0.3102804 -0.9505242 -0.01516675 -0.0910815 -0.9957289 0.0151081 0.06959033 -0.9973288 -0.02218872 0.244476 -0.9694426 0.02031183 0.5240682 -0.8515003 -0.01731544 0.5790848 -0.8151972 0.01069533 0.873098 -0.4874581 -0.009195387 0.9006714 -0.4339896 0.02107381 0.9993305 -0.03166007 -0.01833063 0.9427275 0.3331082 -0.01742559 0.8506675 0.5252509 0.02182006 0.7779759 0.6281613 -0.01291769 0.4808129 0.8767358 -0.01238214 -0.01647108 0.9997295 0.01641905 -0.03968328 0.9992091 0.00250566 -0.4488271 0.8933828 -0.02052754 -0.7931783 0.6087302 -0.01776891 -0.8593366 0.5109525 0.02163517 -0.9602622 0.2784271 -0.01935964 -0.9679055 -0.2509182 -0.01410245 -0.8859136 -0.4633272 0.02202117 -0.8273727 -0.5614114 -0.0164895 -0.5908671 -0.8065408 0.01917988 -0.4787182 -0.8776075 -0.02517884 0.03662157 -0.9989451 -0.02770692 0.4995661 -0.8661877 -0.01235455 0.5361008 -0.8441475 0.003304243 0.7780108 -0.6282483 -0.001793861 0.9428732 -0.3331467 -0.001799821 0.9598307 -0.2799569 0.01868385 0.9998568 -0.004050374 -0.0164383 0.9443177 0.3286975 -0.01490068 0.7779724 0.6281453 -0.01387798 0.4993738 0.8659322 -0.0280568 0.1831717 0.9825156 0.03333246 0.04932308 0.9985328 -0.0223447 -0.3339681 0.9423131 0.02261102 -0.3981005 0.9173107 -0.007562458 -0.7040397 0.7101563 -0.002526283 -0.7500016 0.6610227 0.0233795 -0.9006844 0.4339532 -0.02127313 -0.9693678 0.2447987 0.01999765 -0.9942321 0.1065034 -0.01263689 -0.9987181 0.04965448 0.009829699 -0.9987106 -0.04516273 -0.02318114 -0.9579978 -0.2857928 0.02372223 -0.8486753 -0.5284002 -0.02331733 -0.8103321 -0.5859626 0.003129422 -0.5030462 -0.8640743 -0.01789057 -0.2627435 -0.9647597 0.01430207 -0.1468909 -0.9890453 -0.01457941 0.0948143 -0.9953005 0.01967537 0.2087696 -0.9778773 -0.01309263 0.5242636 -0.8515198 -0.007850527 0.7123535 -0.7016761 0.01425063 0.7779683 -0.6281706 -0.01292383 0.9522088 -0.3054322 -0.003066897 0.9904703 0.1377015 -0.002621769 0.9871121 0.1598437 0.007734358 0.873016 0.4876748 -0.004036784 0.8620414 0.5068271 0.003314018 0.6606613 0.7506819 -0.001796305 0.37285 0.9278899 -0.001792132 0.3194814 0.9474009 0.01905596 0.02045553 0.9995344 -0.02263748 -0.1309557 0.9911242 0.02288144 -0.4005675 0.916141 -0.0152136 -0.7026323 0.7115039 -0.008367955 -0.7416388 0.6707257 0.009945929 -0.9117412 0.4106379 -0.01021534 -0.9254716 0.3788024 0.003321349 -0.9760819 -0.2162158 -0.02269381 -0.962858 -0.2700065 9.3573e-4 -0.7626746 -0.6465837 -0.01602965 -0.4754896 -0.8797178 -0.002470552 -0.1479218 -0.9887493 -0.02222299 0.09980207 -0.9944576 0.03307151 0.2087789 -0.9779266 -0.008423566 0.548959 -0.8358073 -0.008378922 0.8570641 -0.5150669 -0.01212733 0.9050189 -0.4246113 0.02541697 0.9856455 -0.1670405 -0.02450305 0.9845847 0.1748729 -0.003501296 0.9953727 0.09257644 0.025747 0.8730151 0.4876913 -0.00137192 0.8435211 0.5367241 0.01998662 0.6605342 0.750509 -0.02075409 0.5280855 0.8490357 0.01624387 0.3728274 0.9278095 -0.01300829 0.02045148 0.9994484 -0.02616322 -0.4005324 0.9160249 -0.02173179 -0.6402663 0.7678631 0.02110505 -0.7216916 0.6919929 -0.01751834 -0.9140728 0.4051397 0.01824414 -0.957638 0.2869874 -0.02382427 -0.00232613 0.009638071 0.9999509 0.04880332 -0.1592077 0.9860382 -0.00336039 -0.02571845 0.9996636 0.003403186 -9.86548e-4 0.9999938 0.002923905 -0.002126455 0.9999935 -0.003563344 -0.001474022 0.9999926 0.001827836 -5.4515e-4 0.9999983 -0.001588225 1.76632e-4 0.9999988 0.001802623 9.09289e-5 0.9999984 4.90131e-4 -0.005256652 0.9999861 0.006062686 -0.001930236 0.9999798 -2.62876e-6 -7.07343e-7 1 1.93997e-6 1.18636e-5 1 0 -2.54547e-7 1 -2.06645e-6 5.39101e-6 1 0.004021346 -0.008758425 0.9999536 -0.003433108 0.001728296 0.9999927 -1.81158e-6 4.38739e-7 1 -1.69676e-6 -9.7498e-6 1 0 -2.50654e-7 1 -1.21071e-7 7.53343e-5 1 0 -4.70033e-6 1 0 -4.4319e-7 1 0.002733528 -0.007931113 0.9999648 -6.33403e-7 -1.95266e-6 1 -2.64361e-4 -0.002498805 0.9999969 2.93134e-4 3.1508e-4 0.9999999 -0.003867387 -0.005751252 0.999976 -0.003569602 -0.007004201 0.9999691 7.70015e-5 -2.10638e-4 1 0 -4.71897e-7 1 -7.40263e-7 1.06106e-5 1 -2.16408e-5 3.22142e-5 1 -0.002833306 -5.83225e-4 0.9999958 -2.14789e-5 3.72853e-5 1 0.02688491 -3.31053e-4 0.9996386 0.03574961 -0.005016386 0.9993483 -0.006227374 0.01376992 0.9998858 -7.22951e-6 1.01593e-5 1 -3.88541e-6 8.15216e-7 1 -2.84666e-6 2.87597e-6 1 -6.90498e-6 2.88663e-6 1 -1.04632e-5 -1.31638e-6 1 0.00131905 -0.006120979 0.9999804 -1.19551e-5 2.4064e-6 1 0.02795529 0.01620727 0.9994778 -8.93454e-4 0.02990484 0.9995523 -0.06043094 -0.005621254 0.9981565 -0.06864947 0.004567384 0.9976304 -1.83076e-6 -2.83856e-6 1 -4.26821e-7 2.83556e-6 1 -4.87355e-7 3.6161e-6 1 9.85548e-5 0.003017067 0.9999955 1.11447e-6 4.50386e-6 1 6.93013e-4 0.002167463 0.9999974 -5.93252e-5 4.88455e-4 1 2.78339e-5 -6.60942e-4 0.9999998 -3.61052e-7 0 1 -0.05013632 0.09683489 0.9940369 -3.65134e-4 0.004024386 0.9999918 -7.03828e-5 -1.35803e-4 1 0 8.01881e-7 1 -0.004262864 0.004297256 0.9999817 -0.003331542 -0.001913011 0.9999927 -3.81841e-7 3.70218e-6 1 -3.04057e-6 6.34759e-7 1 -1.44767e-7 6.46231e-6 1 -1.05003e-4 -0.001057684 0.9999994 0.001327455 0.004896581 0.9999871 -8.90593e-4 0.003854095 0.9999923 -0.003210186 -0.001095414 0.9999942 -3.92929e-6 -2.67877e-6 1 4.33583e-4 0.006472051 0.999979 -4.16563e-6 7.92803e-6 1 0.00215888 -4.38216e-4 0.9999976 -0.001056492 1.54191e-4 0.9999995 0.001328647 2.53585e-4 0.9999991 0.003508925 0.002264082 0.9999914 -0.005655169 0.003861546 0.9999765 -0.006306111 0.01165384 0.9999123 -0.003672063 0.03461706 0.9993939 -0.006503283 0.04762369 0.9988442 0.003369927 0.004786491 0.9999829 -0.004467964 0.03826546 0.9992576 -5.75744e-7 3.00939e-5 -1 -6.71305e-6 -2.54228e-5 -1 -7.59284e-7 4.47019e-5 -1 -2.4739e-6 -2.93577e-6 -1 6.98707e-6 -5.02011e-5 -1 -7.1435e-6 3.50252e-6 -1 3.54008e-7 -1.13136e-6 -1 -1.7879e-6 3.22514e-6 -1 -1.61752e-6 -2.72196e-6 -1 -3.10295e-6 -3.16715e-6 -1 -6.38421e-6 6.50888e-6 -1 1.13691e-5 3.07847e-5 -1 1.55907e-6 -6.52626e-6 -1 2.48797e-6 1.73968e-6 -1 1.13841e-5 3.20298e-5 -1 1.34604e-5 -8.40767e-6 -1 1.16028e-5 -1.2183e-6 -1 2.37308e-6 -1.96168e-5 -1 4.61712e-6 1.40982e-5 -1 2.09446e-6 1.77344e-7 -1 2.14514e-6 1.41742e-6 -1 3.41765e-6 -2.14213e-6 -1 3.44163e-6 -6.0486e-6 -1 1.34934e-6 1.58395e-5 -1 -1.70319e-4 -0.005330622 -0.9999858 -1.01787e-4 -0.001455962 -0.9999989 -1.28743e-6 9.5163e-6 -1 -1.64596e-4 0.001470327 -0.9999989 -4.10435e-6 0 -1 1.25863e-6 -3.15175e-6 -1 2.43464e-5 -2.57031e-6 -1 -7.03362e-6 -1.13865e-5 -1 -1.15097e-5 -7.79679e-6 -1 1.04911e-6 6.74383e-7 -1 2.30096e-4 -0.002616345 -0.9999965 2.71333e-5 -2.04825e-5 -1 4.60461e-5 -4.60982e-4 -0.9999999 7.83526e-7 -4.80785e-5 -1 5.3322e-6 -3.43668e-5 -1 2.3253e-5 -1.25581e-5 -1 -4.92543e-6 -1.54155e-5 -1 3.60601e-6 5.01898e-5 -1 3.49529e-6 2.59767e-5 -1 9.95497e-6 8.92463e-6 -1 -4.23568e-6 -1.48604e-6 -1 -3.31115e-6 -5.8547e-6 -1 -6.02639e-6 5.44666e-6 -1 -6.68029e-7 8.20239e-6 -1 4.50201e-6 -2.09322e-5 -1 1.63642e-6 -5.99127e-6 -1 2.12311e-6 -2.32043e-6 -1 2.09272e-6 -2.03135e-6 -1 1.0719e-5 5.72886e-6 -1 -8.02191e-7 1.17512e-5 -1 8.73042e-7 2.85525e-6 -1 -7.08245e-7 3.77137e-6 -1 6.66317e-6 -3.58833e-5 -1 6.86314e-6 -5.88024e-5 -1 4.09985e-6 1.05769e-5 -1 1.98693e-6 -1.65923e-6 -1 0 -5.66036e-6 -1 8.1246e-7 1.35884e-7 -1 4.18945e-6 -1.69316e-6 -1 6.95865e-6 -2.32155e-6 -1 5.94974e-6 -9.77922e-6 -1 6.55951e-6 1.68766e-6 -1 -3.21756e-6 -1.86935e-5 -1 -2.37303e-5 -8.4315e-5 -1 0.6512956 0.7583678 0.02631306 0.8982952 -0.4392986 -0.009083807 -4.09105e-6 7.03738e-6 -1 0.5278436 -0.8491083 0.01990717 -0.1207497 -0.9924407 0.02193409 -0.4478877 -0.8939211 0.01736843 -0.5863193 -0.8097937 0.02153682 -0.7255885 -0.6878095 0.02096444 -0.7780188 -0.6282371 -0.002197861 -0.9111967 -0.4113614 0.02241522 -0.9680246 -0.2499268 0.02156472 -0.9859665 -0.1669229 -0.002603352 -0.9999464 -0.002224147 -0.01011002 -0.9954003 0.09392952 0.01885652 -0.7237173 0.6898339 0.01904332 -0.2838523 0.9588643 0.002628922 -0.442419 0.896614 0.01868009 0.2533282 -0.09060531 0.963128 -0.9996576 -0.02112102 0.01545184 -0.8757627 -0.4827299 0.003396213 -0.5096007 -0.8602672 -0.01573407 -0.1166951 -0.9930325 0.01639437 0.3688386 -0.929444 -0.00958544 0.7701088 -0.6377394 0.01486402 0.9964666 -0.08319056 0.01155805 0.8689845 0.4946733 0.0128135 0.3284782 0.9444234 0.01290571 -0.2510303 0.9678812 0.01377815 -0.835757 0.5488143 0.01769202 -0.00774765 -0.999794 0.01875585 0.2889238 -0.957261 -0.01320636 0.6521372 -0.7579596 0.0146411 0.8369815 0.5469564 0.01734119 0.3298721 0.9439473 0.01216667 -0.3351383 0.9419891 0.01841044 -0.8582668 0.5129435 0.01633942 -0.9911658 -0.1322175 0.01043403 -0.6763314 -0.7365013 0.01190555 -0.9975371 -0.069233 0.01124936 -0.8640187 -0.5034343 0.005051732 -0.4193844 -0.9078081 0.001118004 0.205161 -0.9787139 0.005303323 0.8062474 -0.5915405 -0.006700515 0.9924263 -0.1223325 0.01116621 0.5753329 0.8177741 0.01541316 0.1030129 0.9946408 -0.008832693 -0.3839912 0.9231638 0.0178703 -0.8573589 0.5143905 0.01838213 -0.9800169 0.198437 -0.01376748 -0.9980984 -0.06159943 -0.002284169 -0.7819387 -0.6232495 0.01148557 -0.2923933 -0.9562618 0.008355438 0.2064614 -0.9783831 0.01184296 0.7111081 -0.7029716 0.01250469 0.9472218 -0.3205365 0.005228698 0.9501699 0.3116442 0.007424294 0.4622539 0.8867313 -0.005385994 -0.1793556 0.9837006 0.01283109 -0.741879 0.6705111 0.005519926 0.1375253 0.9764157 -0.1664308 -0.1239696 -0.9906668 0.05666685 0.4365138 -0.8956729 -0.08500427 0.7315411 -0.6708638 -0.1216117 0.9319456 -0.3540759 -0.07815253 0.7476068 0.6579341 -0.09059143 0.4862432 0.8639731 -0.1308366 -0.2484619 0.9669983 0.05639857 -0.7078538 0.7020303 0.07808041 -0.6074831 0.7896431 -0.086187 -0.9704055 -0.2241371 0.08986532 -0.9889283 -0.07462614 -0.1282638 -0.9875527 0.1159831 0.106243 -0.8158249 0.5604468 -0.1425802 0.6530507 0.7535039 -0.07587367 0.351469 0.9336662 -0.06882482 -0.2979 0.954572 -0.006917774 -0.5973147 0.8019754 -0.007110238 -0.9117059 -0.4104355 0.01830679 -0.4553406 -0.8888648 -0.05083543 0.6699043 -0.7401686 -0.05812698 0.9896557 -0.1106218 -0.09134805 0.6544982 -0.7527733 -0.07045787 0.6639319 0.7454088 0.05966609 -0.807967 0.5874654 -0.04554015 -0.6956746 -0.7161568 0.05618077 -0.4071806 -0.913336 -0.004606723 0.04484361 -0.9961252 -0.07565402 -0.2781557 -0.9591146 -0.05223566 0.1052365 -0.9920457 -0.06906944 0.5352786 -0.8408375 -0.08043074 0.8190698 -0.572425 -0.03813618 0.9879134 -0.1442739 -0.05667597 0.4040352 0.9142365 0.03045254 0.1612388 0.9858949 -0.04486727 -0.1430485 0.9883205 -0.0525332 -0.4455853 0.8938476 -0.04990208 -0.9797146 0.1989343 0.02417814 0.5722827 -0.8172867 -0.06734395 0.8743093 -0.4794342 -0.07567137 0.9877242 -0.1470111 -0.05280721 0.7641736 0.6356575 -0.1094451 -0.8245161 0.5656082 -0.01615053 -0.1964158 0.1850784 0.962895 -0.197273 0.1047812 0.9747329 -0.2046005 -0.09981083 0.9737435 0 -1.04639e-6 -1 0.9952339 0.09349042 0.0277332 0.5346938 0.8448728 0.01709711 -0.552504 0.8330579 0.02745664 -0.9958542 -0.08915674 0.01803874 -0.2760238 -0.9608031 0.02585357 0.1569888 -0.9873721 0.02123278 0.7692106 -0.6389868 0.003301441 0.990417 0.1371176 0.01652699 0.8877273 0.4600827 0.01624828 0.6536606 0.7563751 0.02498924 -0.5661363 -0.8242722 0.008059024 0.4623492 -0.8866204 0.01173436 0.9377908 -0.3467898 0.01688438 0.6710287 0.741424 0.003305017 -0.4534017 0.8912996 0.003473222 -0.8056845 -0.5921853 0.01375329 -0.4151826 -0.9094029 0.0246939 0.6057775 -0.7952853 0.02355557 0.2070155 0.9781004 0.02154546 -0.2559195 0.9663738 0.02504062 -0.9955886 0.0920723 0.01806128 -0.007746875 -0.02057445 0.9997583 -0.004091143 -0.03293317 0.9994492 0.003962516 -0.01327723 0.999904 -0.002750396 -0.04770433 0.9988577 0.004151582 -0.01330679 0.9999029 0.002839148 -0.003819704 0.9999887 -0.003425776 -0.00533539 0.9999799 -0.003897726 -0.004494667 0.9999823 0.003390848 -0.007325053 0.9999674 -0.003771603 -0.01212131 0.9999195 -0.005050122 0.001059472 0.9999868 9.47826e-4 -0.004315614 0.9999902 0.002258718 -0.002516448 0.9999943 -5.95596e-6 5.8216e-6 1 0.006520748 0.0016613 0.9999774 -0.002014756 -0.003906309 0.9999904 0.001261711 -0.01907527 0.9998172 -8.27298e-4 -0.008292376 0.9999653 -0.00268656 -0.001923203 0.9999946 -4.87411e-6 9.06609e-6 1 -0.003581464 -2.88335e-4 0.9999935 -7.54755e-6 1.47455e-6 1 -0.003140389 -8.50104e-4 0.9999946 -8.47105e-7 -1.87021e-7 1 0 -1.84805e-6 1 0.002100288 4.19662e-4 0.9999977 -6.04761e-7 -6.48063e-6 1 3.65903e-6 -5.99006e-5 1 1.21002e-6 4.98811e-6 1 -2.18483e-6 6.86523e-7 1 -1.10967e-6 -1.68051e-6 1 6.76786e-6 -2.80921e-5 1 -1.2642e-5 1.1435e-4 1 -1.9198e-6 1.2617e-5 1 1.46879e-7 -7.58882e-7 1 4.86547e-6 -1.2094e-4 1 -1.47864e-5 -1.64117e-5 1 0.007719874 0.01876646 0.999794 -0.0083853 -0.003050684 0.9999601 -2.04881e-6 -1.80306e-6 1 -8.1688e-6 1.22739e-5 1 0.01117014 -0.004194915 0.9999289 0.03018379 -0.008705496 0.9995065 0.005899846 -0.0112816 0.999919 1.90162e-4 0.005161225 0.9999867 0.002260923 -4.12956e-4 0.9999974 -0.0101335 -0.007564306 0.99992 -0.01753908 -0.002263545 0.9998437 -3.58486e-6 5.18853e-6 1 -8.62159e-4 -0.001868426 0.9999979 0 0 1 -6.16293e-6 -2.13737e-6 1 -8.0231e-6 1.20682e-5 1 -1.33972e-6 2.99073e-6 1 0.02170628 0.001532018 0.9997631 -0.01221024 0.004934191 0.9999133 -1.29968e-6 -3.68134e-6 1 0.01525914 0.004832983 0.9998719 -1.28857e-6 5.79649e-6 1 -1.26566e-7 1.61045e-7 1 0 6.55312e-7 1 0.001423716 0.001778602 0.9999974 -7.74259e-7 -3.89429e-6 1 0.01902335 4.85393e-4 0.9998189 -3.90651e-5 4.87507e-4 1 7.17388e-5 -1.1325e-4 1 -6.08652e-6 4.86771e-6 1 8.27707e-5 -0.001912772 0.9999982 -4.2876e-6 1.58255e-6 1 0.001438498 -0.004340112 0.9999896 0.00280559 -0.01918607 0.999812 2.82297e-4 0.001789271 0.9999983 -0.01278501 0.01470959 0.9998101 -0.003672599 -0.003188431 0.9999882 6.84224e-7 -7.73103e-7 1 -9.93878e-7 1.71911e-5 1 -2.96301e-6 1.2201e-6 1 0.002775967 -0.002461552 0.9999932 0.001610398 5.11075e-5 0.9999987 0.001364946 0.001486063 0.9999979 0.001160085 5.21638e-4 0.9999992 -3.75916e-6 -3.05421e-6 1 0.001457571 0.01494073 0.9998873 -0.001704573 0.001235187 0.9999977 -3.66055e-6 -8.12114e-6 1 -0.00323373 -3.42095e-4 0.9999947 9.02501e-4 0.005537867 0.9999843 -3.77701e-6 9.41017e-6 1 -0.00103861 -3.04312e-4 0.9999994 0.002243459 -0.001839518 0.9999959 -0.004541754 0.01209396 0.9999166 8.49632e-4 0.007269918 0.9999732 -0.004671871 0.007338762 0.9999622 -0.003729045 0.002614021 0.9999897 0.004002511 0.01380443 0.9998968 0.008986353 0.01323932 0.999872 0.006478786 0.02896505 0.9995594 -0.004115879 0.02831131 0.9995907 -9.95337e-7 2.02815e-5 -1 -2.43075e-6 5.36836e-5 -1 -1.05052e-6 4.57906e-5 -1 -3.03859e-6 1.15693e-5 -1 -8.00962e-6 -5.11102e-6 -1 -2.43074e-6 -2.40259e-7 -1 1.30329e-5 1.22429e-6 -1 -6.39926e-6 1.86252e-5 -1 -6.43402e-6 2.05622e-5 -1 9.46981e-6 3.45696e-5 -1 -3.71269e-6 1.76606e-7 -1 1.46597e-6 -1.2152e-5 -1 -2.07148e-5 1.49101e-4 -1 2.829e-6 -1.01076e-5 -1 -1.6838e-6 -2.41685e-5 -1 1.40663e-6 3.24217e-6 -1 3.52114e-6 -5.79939e-5 -1 -2.98984e-6 -2.63431e-6 -1 -1.88706e-7 -2.43514e-5 -1 2.24915e-6 -1.8965e-6 -1 4.39292e-7 -3.06839e-6 -1 1.55997e-6 1.31894e-5 -1 3.66362e-6 -9.23203e-6 -1 8.13737e-7 -1.51744e-5 -1 0 8.42925e-6 -1 1.33307e-6 -2.36276e-6 -1 4.03974e-6 5.4662e-5 -1 -5.50893e-6 4.37947e-6 -1 -6.25069e-6 4.06521e-6 -1 -3.88318e-4 0.005537807 -0.9999846 -3.00885e-6 4.6205e-6 -1 1.12592e-6 1.24162e-6 -1 -0.001541614 -0.004340946 -0.9999893 2.23335e-5 1.05842e-5 -1 8.69896e-4 1.42191e-4 -0.9999996 3.38868e-5 4.19237e-6 -1 -1.46254e-5 -6.84503e-6 -1 1.02032e-6 -6.46484e-7 -1 1.01179e-6 -5.01404e-7 -1 2.86592e-4 0.005016088 -0.9999875 1.65364e-6 -3.33297e-6 -1 2.45713e-5 -8.39677e-6 -1 8.01336e-7 -4.91489e-5 -1 1.54058e-6 1.29556e-5 -1 1.33804e-5 -2.07409e-5 -1 1.80323e-6 6.38938e-5 -1 1.75433e-6 -2.83623e-6 -1 -1.37368e-6 7.53412e-6 -1 1.99548e-6 7.78003e-6 -1 -3.74601e-6 -1.16835e-5 -1 3.05896e-6 5.87983e-7 -1 1.36325e-6 -1.2587e-5 -1 2.0756e-6 -2.67242e-6 -1 1.94685e-6 -8.76633e-6 -1 -7.8387e-7 1.13411e-5 -1 8.13254e-7 -1.83708e-6 -1 5.28731e-7 4.13237e-6 -1 -1.2821e-6 -1.13738e-5 -1 7.73574e-6 -3.66427e-6 -1 8.03272e-6 -2.27717e-6 -1 2.24355e-6 1.64012e-6 -1 1.08914e-5 5.26374e-6 -1 -6.40638e-7 -3.31538e-6 -1 -1.50885e-6 7.13495e-6 -1 -4.49413e-5 7.40074e-5 -1 -2.50436e-5 2.59686e-4 -1 -2.47187e-5 2.64797e-4 -0.9999999 -2.27694e-5 1.54449e-4 -1 -3.33844e-6 -5.56405e-6 -1 4.05239e-7 -2.74628e-5 -1 2.62104e-5 -4.52366e-4 -1</float_array> + <technique_common> + <accessor source="#Link5_001-mesh-normals-array" count="908" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Link5_001-mesh-vertices"> + <input semantic="POSITION" source="#Link5_001-mesh-positions"/> + </vertices> + <polylist material="Material_003_001-material" count="908"> + <input semantic="VERTEX" source="#Link5_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Link5_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>0 0 1 0 4 0 3 1 1 1 0 1 4 2 2 2 5 2 4 3 1 3 2 3 4 4 5 4 7 4 5 5 9 5 7 5 9 6 10 6 7 6 9 7 11 7 10 7 10 8 15 8 16 8 15 9 18 9 16 9 18 10 20 10 16 10 20 11 18 11 22 11 20 12 22 12 24 12 24 13 22 13 26 13 24 14 26 14 28 14 24 15 28 15 30 15 28 16 32 16 30 16 32 17 35 17 30 17 30 18 35 18 37 18 35 19 40 19 37 19 42 20 40 20 43 20 42 21 43 21 47 21 49 22 42 22 47 22 47 23 51 23 49 23 49 24 51 24 52 24 52 25 53 25 56 25 59 26 52 26 56 26 56 27 61 27 59 27 59 28 61 28 62 28 61 29 63 29 62 29 62 30 60 30 58 30 60 31 57 31 58 31 57 32 55 32 58 32 55 33 50 33 48 33 46 34 44 34 45 34 41 35 45 35 44 35 41 36 39 36 36 36 34 37 31 37 33 37 27 38 23 38 29 38 27 39 25 39 23 39 25 40 21 40 23 40 23 41 21 41 19 41 21 42 17 42 19 42 17 43 13 43 19 43 14 44 12 44 13 44 13 45 12 45 8 45 8 46 6 46 0 46 65 47 70 47 66 47 69 48 70 48 72 48 72 49 79 49 76 49 83 50 79 50 84 50 84 51 81 51 82 51 81 52 78 52 77 52 78 53 75 53 77 53 75 54 71 54 74 54 71 55 67 55 68 55 67 56 65 56 64 56 89 57 93 57 92 57 93 58 96 58 92 58 93 59 97 59 96 59 97 60 100 60 96 60 100 61 104 61 102 61 104 62 101 62 103 62 101 63 98 63 99 63 95 64 98 64 94 64 90 65 94 65 91 65 91 66 87 66 90 66 87 67 86 67 85 67 105 68 109 68 108 68 109 69 115 69 114 69 115 70 118 70 119 70 118 71 122 71 119 71 122 72 121 72 124 72 121 73 120 73 124 73 121 74 116 74 120 74 116 75 112 75 113 75 112 76 107 76 110 76 126 77 127 77 125 77 127 78 132 78 129 78 132 79 136 79 135 79 136 80 139 80 137 80 139 81 142 81 141 81 142 82 140 82 143 82 140 83 133 83 138 83 133 84 130 84 131 84 130 85 126 85 131 85 179 86 183 86 185 86 184 87 187 87 178 87 182 88 178 88 187 88 188 89 182 89 187 89 183 90 182 90 188 90 186 91 183 91 188 91 180 92 179 92 185 92 171 93 179 93 180 93 164 94 171 94 175 94 157 95 164 95 170 95 165 96 160 96 157 96 165 97 156 97 160 97 166 98 156 98 165 98 166 99 150 99 156 99 161 100 150 100 166 100 161 101 154 101 150 101 151 102 154 102 158 102 145 103 144 103 151 103 146 104 147 104 144 104 163 105 155 105 146 105 159 106 155 106 163 106 181 107 172 107 176 107 172 108 167 108 176 108 192 109 189 109 190 109 200 110 192 110 198 110 208 111 200 111 205 111 210 112 200 112 208 112 217 113 210 113 218 113 222 114 217 114 225 114 228 115 222 115 225 115 232 116 222 116 228 116 235 117 232 117 228 117 241 118 232 118 235 118 235 119 244 119 241 119 246 120 241 120 250 120 248 121 246 121 250 121 239 122 246 122 248 122 229 123 239 123 238 123 227 124 229 124 238 124 221 125 229 125 227 125 219 126 221 126 227 126 216 127 221 127 219 127 209 128 216 128 215 128 207 129 209 129 215 129 204 130 209 130 207 130 197 131 204 131 194 131 194 132 189 132 197 132 194 133 190 133 189 133 261 134 251 134 253 134 263 135 261 135 253 135 267 136 261 136 263 136 272 137 267 137 263 137 273 138 272 138 263 138 283 139 272 139 273 139 285 140 283 140 273 140 295 141 289 141 285 141 296 142 289 142 295 142 305 143 296 143 295 143 307 144 296 144 305 144 305 145 309 145 307 145 308 146 307 146 309 146 300 147 308 147 304 147 299 148 300 148 304 148 292 149 300 149 299 149 288 150 292 150 299 150 281 151 292 151 288 151 282 152 281 152 288 152 275 153 281 153 277 153 269 154 275 154 265 154 259 155 269 155 265 155 256 156 251 156 259 156 252 157 251 157 256 157 312 158 313 158 316 158 314 159 312 159 316 159 319 160 312 160 314 160 314 161 324 161 319 161 327 162 319 162 324 162 339 163 327 163 331 163 347 164 339 164 340 164 358 165 347 165 350 165 370 166 358 166 359 166 374 167 370 167 371 167 374 168 371 168 377 168 369 169 374 169 377 169 366 170 374 170 369 170 363 171 366 171 369 171 354 172 361 172 355 172 346 173 354 173 348 173 338 174 346 174 345 174 337 175 338 175 345 175 330 176 338 176 337 176 332 177 330 177 337 177 322 178 330 178 323 178 313 179 322 179 323 179 316 180 313 180 323 180 378 181 379 181 380 181 383 182 378 182 380 182 385 183 378 183 383 183 392 184 385 184 383 184 399 185 392 185 393 185 406 186 399 186 403 186 412 187 406 187 410 187 413 188 412 188 410 188 420 189 412 189 413 189 430 190 420 190 426 190 434 191 430 191 426 191 439 192 430 192 434 192 435 193 439 193 434 193 428 194 439 194 435 194 432 195 428 195 435 195 423 196 428 196 432 196 422 197 428 197 423 197 414 198 422 198 418 198 411 199 414 199 418 199 404 200 414 200 411 200 400 201 404 201 411 201 398 202 404 202 400 202 395 203 398 203 400 203 391 204 398 204 395 204 388 205 391 205 395 205 379 206 391 206 388 206 380 207 379 207 388 207 160 208 156 208 153 208 177 209 162 209 172 209 172 210 162 210 167 210 159 211 167 211 162 211 147 212 155 212 152 212 152 213 155 213 159 213 148 214 144 214 147 214 154 215 151 215 149 215 149 216 151 216 144 216 153 217 156 217 150 217 157 218 160 218 153 218 169 219 179 219 171 219 183 220 179 220 174 220 173 221 182 221 183 221 162 222 177 222 178 222 169 223 171 223 164 223 149 224 150 224 154 224 174 225 179 225 169 225 148 226 149 226 144 226 173 227 183 227 174 227 152 228 148 228 147 228 182 229 173 229 178 229 173 230 162 230 178 230 152 231 159 231 162 231 234 232 229 232 224 232 224 233 229 233 221 233 224 234 221 234 214 234 214 235 221 235 216 235 214 236 216 236 209 236 214 237 209 237 206 237 206 238 209 238 204 238 206 239 204 239 199 239 199 240 204 240 197 240 199 241 197 241 191 241 191 242 197 242 189 242 191 243 189 243 193 243 193 244 189 244 192 244 193 245 192 245 201 245 201 246 192 246 200 246 201 247 200 247 210 247 201 248 210 248 211 248 211 249 210 249 217 249 211 250 217 250 220 250 220 251 217 251 222 251 220 252 222 252 230 252 230 253 222 253 232 253 230 254 232 254 236 254 236 255 232 255 241 255 236 256 241 256 243 256 243 257 241 257 246 257 243 258 246 258 247 258 247 259 246 259 240 259 240 260 246 260 239 260 240 261 239 261 234 261 234 262 239 262 229 262 279 263 283 263 286 263 286 264 283 264 289 264 286 265 289 265 293 265 293 266 289 266 296 266 293 267 296 267 302 267 302 268 296 268 307 268 302 269 307 269 310 269 310 270 307 270 308 270 310 271 308 271 306 271 306 272 308 272 300 272 306 273 300 273 298 273 298 274 300 274 292 274 298 275 292 275 294 275 294 276 292 276 287 276 287 277 292 277 281 277 287 278 281 278 276 278 276 279 281 279 275 279 276 280 275 280 268 280 268 281 275 281 269 281 268 282 269 282 259 282 268 283 259 283 255 283 255 284 259 284 251 284 255 285 251 285 254 285 254 286 251 286 260 286 260 287 251 287 261 287 260 288 261 288 266 288 266 289 261 289 267 289 266 290 267 290 271 290 271 291 267 291 272 291 271 292 272 292 279 292 279 293 272 293 283 293 334 294 327 294 339 294 334 295 339 295 342 295 342 296 339 296 347 296 342 297 347 297 349 297 349 298 347 298 357 298 357 299 347 299 358 299 357 300 358 300 364 300 364 301 358 301 370 301 364 302 370 302 372 302 372 303 370 303 374 303 372 304 374 304 373 304 373 305 374 305 366 305 373 306 366 306 368 306 368 307 366 307 362 307 362 308 366 308 361 308 362 309 361 309 351 309 351 310 361 310 354 310 351 311 354 311 346 311 351 312 346 312 344 312 344 313 346 313 338 313 344 314 338 314 336 314 336 315 338 315 330 315 336 316 330 316 325 316 325 317 330 317 322 317 325 318 322 318 315 318 315 319 322 319 313 319 315 320 313 320 312 320 315 321 312 321 317 321 317 322 312 322 319 322 317 323 319 323 326 323 326 324 319 324 327 324 326 325 327 325 334 325 424 326 420 326 429 326 429 327 420 327 430 327 429 328 430 328 437 328 437 329 430 329 439 329 437 330 439 330 433 330 433 331 439 331 428 331 433 332 428 332 427 332 427 333 428 333 422 333 427 334 422 334 417 334 417 335 422 335 414 335 417 336 414 336 408 336 408 337 414 337 404 337 408 338 404 338 396 338 396 339 404 339 398 339 396 340 398 340 391 340 396 341 391 341 390 341 390 342 391 342 379 342 390 343 379 343 382 343 382 344 379 344 381 344 381 345 379 345 378 345 381 346 378 346 386 346 386 347 378 347 385 347 386 348 385 348 394 348 394 349 385 349 392 349 394 350 392 350 399 350 394 351 399 351 402 351 402 352 399 352 406 352 402 353 406 353 409 353 409 354 406 354 412 354 409 355 412 355 415 355 415 356 412 356 420 356 415 357 420 357 424 357 233 358 236 358 242 358 236 359 243 359 242 359 242 360 243 360 249 360 243 361 247 361 249 361 249 362 247 362 245 362 247 363 240 363 245 363 245 364 240 364 237 364 240 365 234 365 237 365 234 366 231 366 237 366 234 367 224 367 231 367 231 368 224 368 223 368 224 369 214 369 223 369 223 370 214 370 213 370 214 371 206 371 213 371 213 372 206 372 203 372 206 373 199 373 203 373 199 374 191 374 196 374 196 375 191 375 195 375 191 376 193 376 195 376 193 377 201 377 202 377 201 378 212 378 202 378 201 379 211 379 212 379 211 380 220 380 212 380 220 381 230 381 226 381 226 382 230 382 233 382 230 383 236 383 233 383 294 384 287 384 290 384 290 385 287 385 280 385 287 386 276 386 280 386 280 387 276 387 274 387 276 388 268 388 274 388 268 389 255 389 264 389 255 390 254 390 258 390 258 391 254 391 257 391 254 392 260 392 262 392 260 393 266 393 262 393 262 394 266 394 270 394 266 395 271 395 270 395 271 396 279 396 278 396 279 397 286 397 284 397 286 398 293 398 291 398 291 399 293 399 301 399 293 400 302 400 301 400 301 401 302 401 311 401 302 402 310 402 311 402 310 403 306 403 311 403 311 404 306 404 303 404 306 405 298 405 303 405 303 406 298 406 297 406 298 407 294 407 297 407 329 408 325 408 321 408 325 409 315 409 321 409 321 410 315 410 318 410 315 411 317 411 318 411 318 412 317 412 320 412 317 413 326 413 328 413 328 414 326 414 333 414 326 415 334 415 333 415 333 416 334 416 341 416 334 417 342 417 341 417 342 418 349 418 352 418 352 419 349 419 356 419 349 420 357 420 356 420 357 421 364 421 365 421 364 422 372 422 365 422 365 423 372 423 376 423 372 424 373 424 376 424 376 425 373 425 375 425 373 426 368 426 367 426 368 427 362 427 367 427 367 428 362 428 360 428 362 429 351 429 360 429 360 430 351 430 353 430 351 431 344 431 353 431 344 432 336 432 343 432 336 433 335 433 343 433 336 434 325 434 335 434 335 435 325 435 329 435 408 436 396 436 407 436 407 437 396 437 401 437 396 438 390 438 389 438 390 439 382 439 389 439 382 440 381 440 384 440 384 441 381 441 387 441 381 442 386 442 387 442 386 443 394 443 387 443 394 444 402 444 397 444 397 445 402 445 405 445 402 446 409 446 405 446 409 447 415 447 419 447 419 448 405 448 409 448 415 449 424 449 419 449 419 450 424 450 425 450 424 451 429 451 425 451 425 452 429 452 436 452 429 453 437 453 436 453 437 454 433 454 438 454 433 455 427 455 431 455 431 456 427 456 421 456 427 457 417 457 421 457 421 458 417 458 416 458 417 459 408 459 416 459 61 460 60 460 63 460 61 461 56 461 53 461 198 462 57 462 60 462 53 463 51 463 228 463 53 464 228 464 225 464 190 465 194 465 54 465 47 466 235 466 228 466 207 467 46 467 194 467 47 468 244 468 235 468 47 469 101 469 104 469 43 470 94 470 98 470 100 471 250 471 244 471 207 472 215 472 65 472 215 473 219 473 65 473 250 474 100 474 97 474 94 475 43 475 40 475 44 476 84 476 79 476 38 477 227 477 86 477 89 478 86 478 227 478 70 479 219 479 227 479 227 480 238 480 89 480 238 481 248 481 93 481 70 482 65 482 219 482 91 483 40 483 38 483 435 484 434 484 72 484 38 485 432 485 435 485 305 486 295 486 72 486 295 487 39 487 79 487 285 488 39 488 295 488 295 489 79 489 72 489 158 490 305 490 72 490 158 491 309 491 305 491 426 492 168 492 163 492 39 493 44 493 79 493 426 494 413 494 168 494 35 495 32 495 418 495 32 496 28 496 411 496 152 497 162 497 148 497 304 498 309 498 166 498 166 499 299 499 304 499 166 500 165 500 299 500 181 501 176 501 413 501 413 502 410 502 181 502 153 503 162 503 173 503 181 504 410 504 403 504 28 505 395 505 400 505 169 506 173 506 174 506 31 507 263 507 27 507 31 508 34 508 263 508 170 509 282 509 288 509 277 510 282 510 175 510 175 511 180 511 277 511 186 512 380 512 22 512 186 513 188 513 393 513 380 514 388 514 22 514 133 515 355 515 185 515 265 516 180 516 185 516 112 517 116 517 265 517 116 518 27 518 252 518 140 519 348 519 355 519 133 520 140 520 355 520 265 521 277 521 180 521 116 522 25 522 27 522 21 523 25 523 116 523 112 524 363 524 369 524 337 525 140 525 142 525 337 526 345 526 140 526 345 527 348 527 140 527 18 528 15 528 132 528 17 529 118 529 115 529 17 530 21 530 122 530 105 531 369 531 377 531 15 532 332 532 136 532 332 533 337 533 139 533 332 534 15 534 323 534 17 535 371 535 359 535 316 536 323 536 11 536 314 537 316 537 9 537 6 538 12 538 350 538 12 539 14 539 350 539 2 540 340 540 331 540 2 541 6 541 340 541 314 542 9 542 324 542 2 543 1 543 3 543 52 544 59 544 58 544 195 545 202 545 55 545 202 546 58 546 55 546 49 547 226 547 233 547 196 548 55 548 48 548 99 549 95 549 42 549 242 550 102 550 103 550 242 551 249 551 102 551 249 552 96 552 102 552 42 553 49 553 242 553 95 554 37 554 42 554 48 555 45 555 74 555 245 556 237 556 96 556 237 557 92 557 96 557 45 558 77 558 74 558 82 559 77 559 45 559 45 560 83 560 82 560 66 561 231 561 223 561 45 562 41 562 83 562 66 563 69 563 88 563 92 564 231 564 66 564 41 565 80 565 83 565 41 566 36 566 76 566 438 567 37 567 301 567 311 568 436 568 438 568 311 569 425 569 436 569 438 570 431 570 37 570 311 571 419 571 425 571 30 572 416 572 407 572 419 573 311 573 303 573 33 574 29 574 278 574 24 575 401 575 389 575 24 576 30 576 407 576 290 577 397 577 405 577 397 578 290 578 280 578 29 579 257 579 262 579 24 580 384 580 387 580 23 581 24 581 264 581 264 582 258 582 23 582 257 583 29 583 23 583 24 584 389 584 384 584 117 585 113 585 23 585 24 586 23 586 134 586 23 587 120 587 117 587 131 588 20 588 24 588 20 589 128 589 129 589 20 590 131 590 125 590 129 591 16 591 20 591 141 592 143 592 353 592 353 593 343 593 141 593 138 594 110 594 360 594 110 595 106 595 360 595 23 596 124 596 120 596 135 597 137 597 335 597 16 598 129 598 135 598 137 599 343 599 335 599 19 600 114 600 119 600 19 601 376 601 114 601 367 602 111 602 114 602 367 603 106 603 108 603 321 604 10 604 16 604 329 605 321 605 16 605 19 606 365 606 376 606 13 607 356 607 365 607 365 608 19 608 13 608 13 609 352 609 356 609 7 610 10 610 320 610 7 611 8 611 4 611 11 612 15 612 10 612 40 613 42 613 37 613 226 614 49 614 52 614 51 615 53 615 52 615 63 616 60 616 62 616 57 617 54 617 55 617 54 618 50 618 55 618 50 619 46 619 48 619 48 620 46 620 45 620 44 621 39 621 41 621 39 622 34 622 36 622 34 623 33 623 36 623 33 624 31 624 29 624 31 625 27 625 29 625 17 626 14 626 13 626 6 627 3 627 0 627 12 628 6 628 8 628 38 629 40 629 35 629 65 630 66 630 64 630 70 631 69 631 66 631 73 632 69 632 72 632 72 633 76 633 73 633 76 634 79 634 80 634 80 635 79 635 83 635 83 636 84 636 82 636 82 637 81 637 77 637 77 638 75 638 74 638 71 639 68 639 74 639 67 640 64 640 68 640 85 641 86 641 88 641 86 642 89 642 88 642 88 643 89 643 92 643 96 644 100 644 102 644 102 645 104 645 103 645 101 646 99 646 103 646 98 647 95 647 99 647 94 648 90 648 95 648 87 649 85 649 90 649 105 650 108 650 106 650 109 651 111 651 108 651 109 652 114 652 111 652 114 653 115 653 119 653 119 654 122 654 123 654 123 655 122 655 124 655 120 656 116 656 117 656 117 657 116 657 113 657 112 658 110 658 113 658 107 659 106 659 110 659 107 660 105 660 106 660 127 661 128 661 125 661 127 662 129 662 128 662 132 663 135 663 129 663 135 664 136 664 137 664 137 665 139 665 141 665 141 666 142 666 143 666 143 667 140 667 138 667 138 668 133 668 134 668 133 669 131 669 134 669 126 670 125 670 131 670 146 671 144 671 145 671 183 672 186 672 185 672 175 673 171 673 180 673 175 674 170 674 164 674 170 675 165 675 157 675 158 676 154 676 161 676 145 677 151 677 158 677 155 678 147 678 146 678 167 679 159 679 168 679 159 680 163 680 168 680 178 681 177 681 184 681 177 682 181 682 184 682 177 683 172 683 181 683 167 684 168 684 176 684 198 685 192 685 190 685 205 686 200 686 198 686 210 687 208 687 218 687 217 688 218 688 225 688 241 689 244 689 250 689 239 690 248 690 238 690 215 691 216 691 219 691 204 692 207 692 194 692 251 693 252 693 253 693 283 694 285 694 289 694 308 695 309 695 304 695 281 696 282 696 277 696 275 697 277 697 265 697 256 698 259 698 265 698 327 699 324 699 331 699 340 700 339 700 331 700 350 701 347 701 340 701 359 702 358 702 350 702 371 703 370 703 359 703 366 704 363 704 361 704 355 705 361 705 363 705 354 706 355 706 348 706 346 707 348 707 345 707 330 708 332 708 323 708 393 709 392 709 383 709 403 710 399 710 393 710 410 711 406 711 403 711 426 712 420 712 413 712 422 713 423 713 418 713 164 714 157 714 169 714 157 715 153 715 169 715 153 716 150 716 149 716 74 717 213 717 203 717 203 718 199 718 196 718 195 719 193 719 202 719 220 720 226 720 212 720 294 721 290 721 297 721 268 722 264 722 274 722 264 723 255 723 258 723 257 724 254 724 262 724 270 725 271 725 278 725 278 726 279 726 284 726 284 727 286 727 291 727 317 728 328 728 320 728 341 729 342 729 352 729 356 730 357 730 365 730 375 731 373 731 367 731 344 732 343 732 353 732 396 733 389 733 401 733 382 734 384 734 389 734 387 735 394 735 397 735 436 736 437 736 438 736 433 737 431 737 438 737 408 738 407 738 416 738 198 739 60 739 205 739 208 740 60 740 61 740 218 741 61 741 53 741 60 742 208 742 205 742 61 743 218 743 208 743 218 744 53 744 225 744 57 745 190 745 54 745 57 746 198 746 190 746 47 747 228 747 51 747 46 748 50 748 194 748 50 749 54 749 194 749 244 750 47 750 104 750 47 751 98 751 101 751 104 752 100 752 244 752 47 753 43 753 98 753 78 754 46 754 75 754 75 755 46 755 71 755 71 756 46 756 207 756 81 757 46 757 78 757 67 758 71 758 207 758 84 759 46 759 81 759 67 760 207 760 65 760 44 761 46 761 84 761 93 762 250 762 97 762 93 763 248 763 250 763 40 764 91 764 94 764 87 765 38 765 86 765 227 766 38 766 70 766 89 767 238 767 93 767 87 768 91 768 38 768 70 769 38 769 72 769 72 770 146 770 145 770 434 771 146 771 72 771 72 772 38 772 435 772 158 773 72 773 145 773 434 774 426 774 146 774 426 775 163 775 146 775 35 776 432 776 38 776 34 777 39 777 285 777 309 778 158 778 161 778 413 779 176 779 168 779 35 780 418 780 423 780 32 781 411 781 418 781 432 782 35 782 423 782 162 783 149 783 148 783 149 784 162 784 153 784 273 785 34 785 285 785 263 786 34 786 273 786 309 787 161 787 166 787 153 788 173 788 169 788 288 789 299 789 165 789 403 790 184 790 181 790 403 791 393 791 184 791 187 792 184 792 393 792 411 793 28 793 400 793 253 794 27 794 263 794 288 795 165 795 170 795 395 796 28 796 26 796 282 797 170 797 175 797 186 798 383 798 380 798 383 799 186 799 393 799 22 800 388 800 395 800 187 801 393 801 188 801 22 802 395 802 26 802 355 803 265 803 185 803 265 804 355 804 112 804 116 805 256 805 265 805 355 806 363 806 112 806 256 807 116 807 252 807 133 808 22 808 130 808 185 809 22 809 133 809 185 810 186 810 22 810 252 811 27 811 253 811 121 812 21 812 116 812 369 813 107 813 112 813 369 814 105 814 107 814 337 815 142 815 139 815 126 816 130 816 18 816 127 817 126 817 18 817 18 818 132 818 127 818 18 819 130 819 22 819 109 820 105 820 377 820 115 821 377 821 17 821 17 822 122 822 118 822 115 823 109 823 377 823 21 824 121 824 122 824 15 825 136 825 132 825 136 826 332 826 139 826 17 827 377 827 371 827 15 828 11 828 323 828 359 829 14 829 17 829 316 830 11 830 9 830 350 831 340 831 6 831 14 832 359 832 350 832 324 833 2 833 331 833 5 834 2 834 324 834 324 835 9 835 5 835 6 836 2 836 3 836 62 837 58 837 59 837 58 838 212 838 52 838 212 839 58 839 202 839 52 840 212 840 226 840 195 841 55 841 196 841 49 842 233 842 242 842 48 843 203 843 196 843 99 844 42 844 103 844 103 845 42 845 242 845 203 846 48 846 74 846 90 847 37 847 95 847 245 848 96 848 249 848 68 849 213 849 74 849 223 850 64 850 66 850 213 851 68 851 64 851 64 852 223 852 213 852 69 853 37 853 88 853 90 854 85 854 37 854 37 855 85 855 88 855 66 856 88 856 92 856 73 857 37 857 69 857 231 858 92 858 237 858 80 859 41 859 76 859 36 860 37 860 76 860 37 861 73 861 76 861 311 862 438 862 301 862 37 863 36 863 301 863 37 864 431 864 421 864 416 865 37 865 421 865 301 866 36 866 291 866 37 867 416 867 30 867 297 868 419 868 303 868 291 869 33 869 284 869 33 870 278 870 284 870 291 871 36 871 33 871 29 872 270 872 278 872 407 873 401 873 24 873 297 874 290 874 405 874 405 875 419 875 297 875 274 876 397 876 280 876 397 877 274 877 387 877 29 878 262 878 270 878 24 879 387 879 264 879 264 880 387 880 274 880 257 881 23 881 258 881 134 882 23 882 113 882 134 883 113 883 110 883 134 884 131 884 24 884 110 885 138 885 134 885 125 886 128 886 20 886 138 887 353 887 143 887 360 888 353 888 138 888 106 889 367 889 360 889 343 890 137 890 141 890 335 891 16 891 135 891 329 892 16 892 335 892 376 893 375 893 114 893 375 894 367 894 114 894 123 895 19 895 119 895 124 896 19 896 123 896 367 897 108 897 111 897 23 898 19 898 124 898 10 899 321 899 318 899 320 900 10 900 318 900 352 901 8 901 341 901 8 902 333 902 341 902 8 903 7 903 333 903 352 904 13 904 8 904 7 905 328 905 333 905 328 906 7 906 320 906 8 907 0 907 4 907</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Camera_003" name="Camera_003" type="NODE"> + <matrix sid="transform">0.6858804 -0.3173701 0.6548619 7.481132 0.7276337 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953431 0.4452454 5.343665 0 0 0 1</matrix> + <instance_camera url="#Camera_003-camera"/> + </node> + <node id="Lamp_003" name="Lamp_003" type="NODE"> + <matrix sid="transform">-0.2908648 -0.7711007 0.5663931 4.076245 0.9551712 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1</matrix> + <instance_light url="#Lamp_003-light"/> + </node> + <node id="Link5_001" name="Link5_001" type="NODE"> + <matrix sid="transform">0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1</matrix> + <instance_geometry url="#Link5_001-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="Material_003_001-material" target="#Material_003_001-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/arm/link6.stl b/kinton_description/meshes/arm/link6.stl new file mode 100644 index 0000000000000000000000000000000000000000..e49ba9579346d5ef1b8337d11518e0804cb05b76 Binary files /dev/null and b/kinton_description/meshes/arm/link6.stl differ diff --git a/kinton_description/meshes/kinton/kinton.blend b/kinton_description/meshes/kinton/kinton.blend new file mode 100644 index 0000000000000000000000000000000000000000..41bd14ba1b70f394d385f6b831421b7d6771162e Binary files /dev/null and b/kinton_description/meshes/kinton/kinton.blend differ diff --git a/kinton_description/meshes/kinton/kinton.dae b/kinton_description/meshes/kinton/kinton.dae new file mode 100755 index 0000000000000000000000000000000000000000..9038a2cdfcb997008e76c634f1881989d3ade69b --- /dev/null +++ b/kinton_description/meshes/kinton/kinton.dae @@ -0,0 +1,454 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2014-12-15T09:46:10</created> + <modified>2014-12-15T09:46:10</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera_001-camera" name="Camera.001"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp_001-light" name="Lamp.001"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>9.99987e-4</adapt_thresh> + <area_shape>1</area_shape> + <area_size>0.1</area_size> + <area_sizey>0.1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <shadspotsize>45</shadspotsize> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_images/> + <library_effects> + <effect id="mat_kinton_struct-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0 0 0 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_helix_front-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.64 0.6037959 0.6309487 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_helix_back-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.1402223 0.1402223 0.1402223 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_pc_embed-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.01503302 0.05598268 0.01891075 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_battery-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0 0 0 1</color> + </diffuse> + <specular> + <color sid="specular">0.06643155 0.06643155 0.06643155 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_marker-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.8 0.16 0.01876392 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_potes-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.01892042 0.01892042 0.01892042 1</color> + </diffuse> + <specular> + <color sid="specular">0.25 0.25 0.25 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="mat_kinton_struct-material" name="mat_kinton_struct"> + <instance_effect url="#mat_kinton_struct-effect"/> + </material> + <material id="mat_helix_front-material" name="mat_helix_front"> + <instance_effect url="#mat_helix_front-effect"/> + </material> + <material id="mat_helix_back-material" name="mat_helix_back"> + <instance_effect url="#mat_helix_back-effect"/> + </material> + <material id="mat_pc_embed-material" name="mat_pc_embed"> + <instance_effect url="#mat_pc_embed-effect"/> + </material> + <material id="mat_battery-material" name="mat_battery"> + <instance_effect url="#mat_battery-effect"/> + </material> + <material id="mat_marker-material" name="mat_marker"> + <instance_effect url="#mat_marker-effect"/> + </material> + <material id="mat_potes-material" name="mat_potes"> + <instance_effect url="#mat_potes-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Kinton-mesh" name="Kinton"> + <mesh> + <source id="Kinton-mesh-positions"> + <float_array id="Kinton-mesh-positions-array" count="46008">44.48469 14.13331 -40.4057 38.68642 8.133311 -34.60743 44.48469 8.133312 -40.4057 40.5956 8.133312 -44.29479 48.65662 7.597413 -44.57764 44.48469 6.633311 -40.4057 48.65662 92.13331 -44.57762 34.51448 -1.86669 -30.43551 38.68642 6.63331 -34.60743 34.79733 6.63331 -38.49652 38.68642 14.13331 -34.60743 34.79733 8.133311 -38.49652 47.2424 4.133311 -43.16342 40.5956 6.633311 -44.29479 44.48469 21.63331 -40.4057 38.68642 15.63331 -34.60743 44.48469 15.63331 -40.4057 40.5956 15.63331 -44.29479 34.79733 14.13331 -38.49652 38.68642 21.63331 -34.60743 34.79733 15.63331 -38.49652 40.5956 14.13331 -44.29479 44.48469 29.13331 -40.4057 38.68642 23.13331 -34.60743 44.48469 23.13331 -40.4057 40.5956 23.13331 -44.29479 34.79733 21.63331 -38.49652 38.68642 29.13331 -34.60743 34.79733 23.13331 -38.49651 40.5956 21.63331 -44.29479 44.48469 36.63331 -40.4057 38.68642 30.63331 -34.60743 44.48469 30.63331 -40.4057 40.5956 30.63331 -44.29479 34.79733 29.13331 -38.49651 38.68642 36.63331 -34.60742 34.79733 30.63331 -38.49651 40.5956 29.13331 -44.29479 44.48469 44.13331 -40.4057 38.68642 38.13331 -34.60742 44.48469 38.13331 -40.4057 40.5956 38.13331 -44.29479 34.79733 36.63331 -38.49651 38.68642 44.13331 -34.60742 34.79733 38.13331 -38.49651 40.5956 36.63331 -44.29479 44.48469 51.63331 -40.4057 38.68642 45.63331 -34.60742 44.48469 45.63331 -40.4057 40.5956 45.63331 -44.29479 34.79733 44.13331 -38.49651 38.68642 51.63331 -34.60742 34.79733 45.63331 -38.49651 40.5956 44.13331 -44.29479 44.48469 59.13331 -40.4057 38.68642 53.13331 -34.60742 44.48469 53.13331 -40.4057 40.5956 53.13331 -44.29478 34.79733 51.63331 -38.49651 38.68642 59.13331 -34.60742 34.79733 53.13331 -38.49651 40.5956 51.63331 -44.29478 44.48469 66.6333 -40.4057 38.68642 60.63331 -34.60742 44.48469 60.63331 -40.4057 40.5956 60.63331 -44.29478 34.79733 59.13331 -38.49651 38.68642 66.6333 -34.60742 34.79733 60.63331 -38.49651 40.5956 59.13331 -44.29478 44.48469 74.1333 -40.4057 38.68642 68.1333 -34.60742 44.48469 68.1333 -40.4057 40.5956 68.1333 -44.29478 34.79733 66.6333 -38.49651 38.68642 74.1333 -34.60742 34.79733 68.1333 -38.49651 40.5956 66.6333 -44.29478 44.48469 81.6333 -40.4057 38.68642 75.6333 -34.60742 44.48469 75.6333 -40.4057 40.5956 75.6333 -44.29478 34.79733 74.1333 -38.49651 38.68642 81.6333 -34.60742 34.79733 75.6333 -38.49651 40.5956 74.1333 -44.29478 38.68642 83.1333 -34.60742 44.48469 83.1333 -40.4057 40.5956 83.1333 -44.29478 34.79733 81.6333 -38.4965 44.48469 89.1333 -40.4057 38.68642 89.1333 -34.60742 34.79733 83.1333 -38.4965 40.5956 81.6333 -44.29478 38.68642 90.6333 -34.60742 44.48469 90.6333 -40.40569 40.5956 90.6333 -44.29478 34.79733 89.1333 -38.4965 34.51448 92.1333 -30.4355 34.79733 90.6333 -38.4965 40.5956 89.1333 -44.29478 55.72768 -1.866688 -51.64871 45.75748 -9.366689 -41.6785 51.55575 -9.366688 -47.47677 47.66666 -9.366687 -51.36586 51.55575 -10.86669 -47.47677 41.58555 -73.86669 -37.50658 45.75748 -10.86669 -41.6785 41.86839 -10.86669 -45.56759 51.48504 -1.866688 -47.40607 47.2424 -1.866689 -43.16342 41.58555 -1.866689 -37.50657 41.86839 -9.366688 -45.56759 45.75748 -16.86669 -41.6785 51.55575 -16.86669 -47.47677 47.66666 -10.86669 -51.36586 47.66666 -16.86669 -51.36586 51.55575 -18.36669 -47.47677 45.75748 -18.36669 -41.6785 41.86839 -18.36669 -45.56759 41.86839 -16.86669 -45.56759 45.75748 -24.36669 -41.6785 51.55575 -24.36669 -47.47677 47.66666 -18.36669 -51.36586 47.66666 -24.36669 -51.36586 51.55575 -25.86669 -47.47677 45.75748 -25.86669 -41.6785 41.86839 -25.86669 -45.56759 41.86839 -24.36669 -45.56759 45.75748 -31.86669 -41.6785 51.55575 -31.86669 -47.47678 47.66666 -25.86669 -51.36586 47.66666 -31.86669 -51.36586 51.55575 -33.36669 -47.47678 45.75748 -33.36669 -41.6785 41.86839 -33.36669 -45.56759 41.86839 -31.86669 -45.56759 45.75748 -39.36668 -41.6785 51.55575 -39.36668 -47.47678 47.66666 -33.36669 -51.36586 47.66666 -39.36668 -51.36587 51.55575 -40.86668 -47.47678 45.75748 -40.86668 -41.6785 41.86839 -40.86668 -45.56759 41.86839 -39.36668 -45.56759 45.75748 -46.86668 -41.6785 51.55575 -46.86668 -47.47678 47.66666 -40.86668 -51.36587 47.66666 -46.86668 -51.36587 51.55575 -48.36668 -47.47678 45.75748 -48.36668 -41.6785 41.86839 -48.36668 -45.56759 41.86839 -46.86668 -45.56759 45.75748 -54.36668 -41.6785 51.55575 -54.36668 -47.47678 47.66666 -48.36668 -51.36587 47.66666 -54.36668 -51.36587 51.55575 -55.86668 -47.47678 45.75748 -55.86668 -41.6785 41.86839 -55.86668 -45.56759 41.86839 -54.36668 -45.56759 45.75748 -61.86668 -41.67851 51.55575 -61.86668 -47.47678 47.66666 -55.86668 -51.36587 47.66666 -61.86668 -51.36587 51.55575 -63.36668 -47.47678 45.75748 -63.36668 -41.67851 41.86839 -63.36668 -45.56759 41.86839 -61.86668 -45.56759 45.75748 -69.36668 -41.67851 51.55575 -69.36668 -47.47678 47.66666 -63.36668 -51.36587 47.66666 -69.36668 -51.36587 51.55575 -70.86668 -47.47678 45.75748 -70.86668 -41.67851 41.86839 -70.86668 -45.5676 41.86839 -69.36668 -45.5676 55.72768 -75.86668 -51.64871 47.66666 -70.86668 -51.36587 58.55611 4.475049 -54.47713 51.48504 0.1333116 -47.40607 47.59596 0.1333123 -51.29515 43.35332 -1.866688 -47.05251 47.59596 -1.866688 -51.29515 51.55358 1.112151 -47.4746 51.75453 2.046519 -47.67555 47.66449 1.112151 -51.36368 52.08052 2.909821 -48.00153 47.86544 2.04652 -51.56464 52.52057 3.668845 -48.44159 48.19143 2.909822 -51.89062 53.05728 4.291186 -48.9783 48.63149 3.668846 -52.33068 53.66773 4.752203 -49.58875 49.1682 4.291187 -52.86739 55.02058 5.133312 -50.9416 54.32844 5.03639 -50.24945 49.77865 4.752204 -53.47784 50.43935 5.036391 -54.13854 54.66702 4.47505 -58.36622 51.13149 5.133313 -54.83068 58.55611 -1.866688 -54.47713 51.8386 -1.866687 -55.53779 54.66702 -1.866687 -58.36622 50.07082 -85.86668 -45.99186 80.47642 -75.86668 -76.39746 51.83859 -75.86668 -55.5378 80.47642 -85.86668 -76.39746 76.58734 -75.86668 -80.28654 76.58734 -85.86668 -80.28656 46.18174 -85.86668 -49.88095 37.69646 -73.86669 -41.39567 37.69646 -1.866688 -41.39566 30.6254 -1.866689 -34.32459 43.70687 99.1333 -39.62788 39.46424 99.1333 -35.38523 30.6254 92.1333 -34.32458 35.57515 99.1333 -39.27432 39.81779 99.1333 -43.51696 44.76753 92.13331 -48.46671 43.35332 4.133312 -47.05251 44.76753 7.597413 -48.46672 -40.50954 14.13331 -44.29478 -34.71126 8.133315 -38.49651 -40.50954 8.133316 -44.29478 -44.39862 8.133316 -40.4057 -44.68147 7.597417 -48.46672 -40.50954 6.633315 -44.29478 -44.68147 92.13331 -48.4667 -30.53934 -1.866686 -34.32458 -34.71126 6.633314 -38.49651 -38.60035 6.633314 -34.60743 -34.71126 14.13331 -38.49651 -38.60035 8.133315 -34.60743 -43.26726 4.133316 -47.0525 -44.39862 6.633315 -40.4057 -40.50954 21.63331 -44.29478 -34.71126 15.63331 -38.49651 -40.50954 15.63331 -44.29478 -44.39862 15.63331 -40.4057 -38.60035 14.13331 -34.60742 -34.71126 21.63331 -38.49651 -38.60035 15.63331 -34.60742 -44.39862 14.13331 -40.4057 -40.50954 29.13331 -44.29478 -34.71126 23.13331 -38.49651 -40.50954 23.13331 -44.29478 -44.39862 23.13331 -40.4057 -38.60035 21.63331 -34.60742 -34.71126 29.13331 -38.49651 -38.60035 23.13331 -34.60742 -44.39862 21.63331 -40.4057 -40.50954 36.63331 -44.29478 -34.71126 30.63331 -38.49651 -40.50954 30.63331 -44.29478 -44.39862 30.63331 -40.4057 -38.60035 29.13331 -34.60742 -34.71126 36.63331 -38.49651 -38.60035 30.63331 -34.60742 -44.39862 29.13331 -40.4057 -40.50954 44.13331 -44.29478 -34.71126 38.13331 -38.49651 -40.50954 38.13331 -44.29478 -44.39862 38.13331 -40.4057 -38.60035 36.63331 -34.60742 -34.71126 44.13331 -38.4965 -38.60035 38.13331 -34.60742 -44.39862 36.63331 -40.4057 -40.50954 51.63331 -44.29478 -34.71126 45.63331 -38.4965 -40.50954 45.63331 -44.29478 -44.39862 45.63331 -40.40569 -38.60034 44.13331 -34.60742 -34.71126 51.63331 -38.4965 -38.60034 45.63331 -34.60742 -44.39862 44.13331 -40.40569 -40.50954 59.13331 -44.29478 -34.71126 53.13331 -38.4965 -40.50954 53.13331 -44.29478 -44.39862 53.13331 -40.40569 -38.60034 51.63331 -34.60742 -34.71126 59.13331 -38.4965 -38.60034 53.13331 -34.60742 -44.39862 51.63331 -40.40569 -40.50954 66.63331 -44.29478 -34.71126 60.63331 -38.4965 -40.50954 60.63331 -44.29478 -44.39862 60.63331 -40.40569 -38.60034 59.13331 -34.60742 -34.71126 66.63331 -38.4965 -38.60034 60.63331 -34.60742 -44.39862 59.13331 -40.40569 -40.50954 74.13331 -44.29477 -34.71126 68.13331 -38.4965 -40.50954 68.13331 -44.29478 -44.39862 68.13331 -40.40569 -38.60034 66.63331 -34.60742 -34.71126 74.13331 -38.4965 -38.60034 68.13331 -34.60742 -44.39862 66.63331 -40.40569 -40.50954 81.63331 -44.29477 -34.71126 75.63331 -38.4965 -40.50954 75.63331 -44.29477 -44.39862 75.63331 -40.40569 -38.60034 74.13331 -34.60742 -34.71126 81.63331 -38.4965 -38.60034 75.63331 -34.60742 -44.39862 74.13331 -40.40569 -34.71126 83.13331 -38.4965 -40.50954 83.13331 -44.29477 -44.39862 83.13331 -40.40569 -38.60034 81.63331 -34.60742 -40.50954 89.13331 -44.29477 -34.71126 89.13331 -38.4965 -38.60034 83.13331 -34.60742 -44.39862 81.63331 -40.40569 -34.71126 90.63331 -38.4965 -40.50954 90.63331 -44.29477 -44.39862 90.63331 -40.40569 -38.60034 89.13331 -34.60742 -30.53933 92.13331 -34.32457 -38.60034 90.63331 -34.60742 -44.39862 89.13331 -40.40569 -51.75254 -1.866683 -55.53778 -41.78233 -9.366684 -45.56758 -47.58061 -9.366683 -51.36585 -51.46969 -9.366683 -47.47677 -47.58061 -10.86668 -51.36585 -37.61041 -73.86668 -41.39566 -41.78233 -10.86668 -45.56758 -45.67142 -10.86668 -41.67849 -47.5099 -1.866683 -51.29514 -43.26726 -1.866684 -47.0525 -37.6104 -1.866685 -41.39565 -45.67142 -9.366684 -41.67849 -41.78233 -16.86668 -45.56758 -47.58061 -16.86668 -51.36585 -51.46969 -10.86668 -47.47677 -51.46969 -16.86668 -47.47677 -47.58061 -18.36668 -51.36585 -41.78233 -18.36668 -45.56758 -45.67142 -18.36668 -41.6785 -45.67142 -16.86668 -41.6785 -41.78233 -24.36668 -45.56758 -47.58061 -24.36668 -51.36585 -51.46969 -18.36668 -47.47677 -51.46969 -24.36668 -47.47677 -47.58061 -25.86668 -51.36585 -41.78233 -25.86668 -45.56758 -45.67142 -25.86668 -41.6785 -45.67142 -24.36668 -41.6785 -41.78233 -31.86668 -45.56758 -47.58061 -31.86668 -51.36585 -51.46969 -25.86668 -47.47677 -51.46969 -31.86668 -47.47677 -47.58061 -33.36668 -51.36585 -41.78233 -33.36668 -45.56758 -45.67142 -33.36668 -41.6785 -45.67142 -31.86668 -41.6785 -41.78233 -39.36668 -45.56758 -47.58061 -39.36668 -51.36585 -51.46969 -33.36668 -47.47677 -51.46969 -39.36668 -47.47677 -47.58061 -40.86668 -51.36585 -41.78233 -40.86668 -45.56758 -45.67142 -40.86668 -41.6785 -45.67142 -39.36668 -41.6785 -41.78234 -46.86668 -45.56758 -47.58061 -46.86668 -51.36586 -51.46969 -40.86668 -47.47677 -51.46969 -46.86668 -47.47677 -47.58061 -48.36668 -51.36586 -41.78234 -48.36668 -45.56758 -45.67142 -48.36668 -41.6785 -45.67142 -46.86668 -41.6785 -41.78234 -54.36668 -45.56758 -47.58061 -54.36668 -51.36586 -51.46969 -48.36668 -47.47677 -51.46969 -54.36668 -47.47677 -47.58061 -55.86668 -51.36586 -41.78234 -55.86668 -45.56758 -45.67142 -55.86668 -41.6785 -45.67142 -54.36668 -41.6785 -41.78234 -61.86668 -45.56758 -47.58061 -61.86668 -51.36586 -51.46969 -55.86668 -47.47677 -51.46969 -61.86668 -47.47677 -47.58061 -63.36668 -51.36586 -41.78234 -63.36668 -45.56758 -45.67142 -63.36668 -41.6785 -45.67142 -61.86668 -41.6785 -41.78234 -69.36668 -45.56758 -47.58061 -69.36668 -51.36586 -51.46969 -63.36668 -47.47677 -51.46969 -69.36668 -47.47677 -47.58061 -70.86668 -51.36586 -41.78234 -70.86668 -45.56758 -45.67142 -70.86668 -41.6785 -45.67142 -69.36668 -41.6785 -51.75254 -75.86668 -55.53779 -51.46969 -70.86668 -47.47677 -54.58097 4.475055 -58.36621 -47.5099 0.1333166 -51.29514 -51.39898 0.133316 -47.40606 -47.15634 -1.866684 -43.16342 -51.39898 -1.866684 -47.40606 -47.57843 1.112156 -51.36368 -47.77938 2.046524 -51.56463 -51.46752 1.112155 -47.47459 -48.10537 2.909826 -51.89061 -51.66847 2.046524 -47.67554 -48.54543 3.66885 -52.33067 -51.99445 2.909826 -48.00153 -49.08214 4.291191 -52.86738 -52.43451 3.66885 -48.44159 -49.69259 4.752209 -53.47783 -52.97122 4.291191 -48.9783 -51.04543 5.133316 -54.83067 -50.35329 5.036395 -54.13853 -53.58167 4.752209 -49.58875 -54.24237 5.036395 -50.24945 -58.47005 4.475055 -54.47712 -54.93452 5.133316 -50.94159 -54.58097 -1.866682 -58.36621 -55.64162 -1.866683 -51.6487 -58.47005 -1.866682 -54.47712 -46.09569 -85.86668 -49.88094 -76.50128 -75.86667 -80.28652 -55.64163 -75.86668 -51.64871 -76.50128 -85.86667 -80.28652 -80.39036 -75.86667 -76.39744 -80.39036 -85.86667 -76.39744 -49.98477 -85.86668 -45.99185 -41.49949 -73.86668 -37.50657 -41.49949 -1.866685 -37.50656 -34.42842 -1.866687 -30.4355 -39.73172 99.13331 -43.51696 -35.48908 99.13331 -39.27432 -34.42842 92.13331 -30.43549 -39.37816 99.13331 -35.38523 -43.6208 99.13331 -39.62787 -48.57055 92.13331 -44.57762 -47.15634 4.133316 -43.16342 -48.57056 7.597417 -44.57763 -44.39862 14.1333 40.69944 -38.60034 8.133304 34.90116 -44.39862 8.133303 40.69944 -40.50953 8.133303 44.58853 -48.57055 7.597405 44.87137 -44.39862 6.633303 40.69944 -48.57054 92.1333 44.87138 -34.42841 -1.866695 30.72923 -38.60034 6.633304 34.90116 -34.71126 6.633304 38.79025 -38.60034 14.1333 34.90116 -34.71126 8.133304 38.79025 -47.15633 4.133304 43.45716 -40.50953 6.633303 44.58853 -44.39862 21.6333 40.69944 -38.60034 15.6333 34.90116 -44.39862 15.6333 40.69944 -40.50953 15.6333 44.58853 -34.71126 14.1333 38.79025 -38.60034 21.6333 34.90116 -34.71126 15.6333 38.79025 -40.50953 14.1333 44.58853 -44.39862 29.1333 40.69944 -38.60034 23.1333 34.90117 -44.39862 23.1333 40.69944 -40.50953 23.1333 44.58853 -34.71126 21.6333 38.79025 -38.60034 29.1333 34.90117 -34.71126 23.1333 38.79025 -40.50953 21.6333 44.58853 -44.39862 36.6333 40.69944 -38.60034 30.6333 34.90117 -44.39862 30.6333 40.69944 -40.50953 30.6333 44.58853 -34.71126 29.1333 38.79025 -38.60034 36.6333 34.90117 -34.71126 30.6333 38.79025 -40.50953 29.1333 44.58853 -44.39862 44.1333 40.69944 -38.60034 38.1333 34.90117 -44.39862 38.1333 40.69944 -40.50953 38.1333 44.58853 -34.71126 36.6333 38.79026 -38.60034 44.1333 34.90117 -34.71126 38.1333 38.79026 -40.50953 36.6333 44.58853 -44.39862 51.6333 40.69945 -38.60034 45.6333 34.90117 -44.39862 45.6333 40.69944 -40.50953 45.6333 44.58853 -34.71126 44.1333 38.79026 -38.60034 51.6333 34.90117 -34.71126 45.6333 38.79026 -40.50953 44.1333 44.58853 -44.39862 59.1333 40.69945 -38.60034 53.1333 34.90117 -44.39862 53.1333 40.69945 -40.50953 53.1333 44.58853 -34.71126 51.6333 38.79026 -38.60034 59.1333 34.90117 -34.71126 53.1333 38.79026 -40.50953 51.6333 44.58853 -44.39862 66.6333 40.69945 -38.60034 60.6333 34.90117 -44.39862 60.6333 40.69945 -40.50953 60.6333 44.58853 -34.71126 59.1333 38.79026 -38.60034 66.6333 34.90117 -34.71126 60.6333 38.79026 -40.50953 59.1333 44.58853 -44.39862 74.1333 40.69945 -38.60034 68.1333 34.90117 -44.39862 68.1333 40.69945 -40.50953 68.1333 44.58853 -34.71126 66.6333 38.79026 -38.60034 74.1333 34.90117 -34.71126 68.1333 38.79026 -40.50953 66.6333 44.58853 -44.39861 81.6333 40.69945 -38.60034 75.6333 34.90117 -44.39862 75.6333 40.69945 -40.50953 75.6333 44.58853 -34.71126 74.1333 38.79026 -38.60034 81.6333 34.90118 -34.71126 75.6333 38.79026 -40.50953 74.1333 44.58853 -38.60034 83.1333 34.90118 -44.39861 83.1333 40.69945 -40.50953 83.1333 44.58853 -34.71126 81.6333 38.79026 -44.39861 89.1333 40.69945 -38.60034 89.1333 34.90118 -34.71126 83.1333 38.79026 -40.50953 81.6333 44.58853 -38.60034 90.6333 34.90118 -44.39861 90.6333 40.69945 -40.50952 90.6333 44.58854 -34.71126 89.1333 38.79026 -34.42841 92.1333 30.72924 -34.71125 90.6333 38.79026 -40.50953 89.1333 44.58853 -55.64161 -1.866697 51.94244 -45.67141 -9.366697 41.97223 -51.46969 -9.366697 47.7705 -47.5806 -9.366698 51.65959 -51.46969 -10.8667 47.7705 -41.49948 -73.86669 37.80029 -45.67141 -10.8667 41.97223 -41.78232 -10.8667 45.86132 -51.39897 -1.866696 47.6998 -47.15633 -1.866696 43.45716 -41.49948 -1.866695 37.8003 -41.78232 -9.366698 45.86132 -45.67141 -16.8667 41.97223 -51.46969 -16.8667 47.7705 -47.5806 -10.8667 51.65959 -47.5806 -16.8667 51.65959 -51.46969 -18.36669 47.7705 -45.67141 -18.36669 41.97223 -41.78232 -18.36669 45.86132 -41.78232 -16.8667 45.86132 -45.67141 -24.36669 41.97223 -51.46969 -24.36669 47.7705 -47.5806 -18.36669 51.65959 -47.5806 -24.36669 51.65959 -51.46969 -25.86669 47.7705 -45.67141 -25.86669 41.97223 -41.78232 -25.86669 45.86132 -41.78232 -24.36669 45.86132 -45.67141 -31.86669 41.97223 -51.46969 -31.86669 47.7705 -47.5806 -25.86669 51.65959 -47.5806 -31.86669 51.65959 -51.46969 -33.36669 47.7705 -45.67141 -33.36669 41.97223 -41.78232 -33.36669 45.86131 -41.78232 -31.86669 45.86131 -45.67141 -39.36669 41.97222 -51.46969 -39.36669 47.7705 -47.5806 -33.36669 51.65959 -47.5806 -39.36669 51.65959 -51.46969 -40.86669 47.7705 -45.67141 -40.86669 41.97222 -41.78232 -40.86669 45.86131 -41.78232 -39.36669 45.86131 -45.67141 -46.86669 41.97222 -51.46969 -46.86669 47.7705 -47.5806 -40.86669 51.65959 -47.5806 -46.86669 51.65959 -51.46969 -48.36669 47.7705 -45.67141 -48.36669 41.97222 -41.78232 -48.36669 45.86131 -41.78232 -46.86669 45.86131 -45.67141 -54.36669 41.97222 -51.46969 -54.36669 47.7705 -47.5806 -48.36669 51.65959 -47.5806 -54.36669 51.65959 -51.46969 -55.86669 47.7705 -45.67141 -55.86669 41.97222 -41.78232 -55.86669 45.86131 -41.78232 -54.36669 45.86131 -45.67141 -61.86669 41.97222 -51.46969 -61.86669 47.7705 -47.5806 -55.86669 51.65958 -47.5806 -61.86669 51.65958 -51.46969 -63.36669 47.7705 -45.67141 -63.36669 41.97222 -41.78232 -63.36669 45.86131 -41.78232 -61.86669 45.86131 -45.67141 -69.36669 41.97222 -51.46969 -69.36669 47.7705 -47.5806 -63.36669 51.65958 -47.5806 -69.36669 51.65958 -51.46969 -70.86669 47.7705 -45.67141 -70.86669 41.97222 -41.78232 -70.86669 45.86131 -41.78232 -69.36669 45.86131 -55.64162 -75.86669 51.94243 -47.5806 -70.86669 51.65958 -58.47004 4.475041 54.77087 -51.39897 0.1333037 47.6998 -47.50989 0.133303 51.58888 -43.26725 -1.866696 47.34624 -47.50989 -1.866697 51.58888 -51.46751 1.112143 47.76833 -51.66846 2.046511 47.96928 -47.57843 1.112142 51.65742 -51.99444 2.909813 48.29527 -47.77938 2.046511 51.85837 -52.4345 3.668838 48.73533 -48.10536 2.909812 52.18436 -52.97122 4.291178 49.27204 -48.54542 3.668837 52.62442 -53.58166 4.752196 49.88249 -49.08213 4.291177 53.16113 -54.9345 5.133303 51.23533 -54.24237 5.036381 50.54319 -49.69258 4.752195 53.77157 -50.35328 5.03638 54.43228 -54.58095 4.47504 58.65995 -51.04542 5.133302 55.12442 -58.47004 -1.866697 54.77087 -51.75253 -1.866697 55.83152 -54.58095 -1.866697 58.65995 -49.98476 -85.86669 46.28557 -80.39035 -75.86669 76.69117 -51.75253 -75.86669 55.83152 -80.39035 -85.86669 76.69116 -76.50126 -75.86669 80.58026 -76.50126 -85.86669 80.58026 -46.09568 -85.86669 50.17465 -37.6104 -73.86669 41.68938 -37.6104 -1.866696 41.68939 -30.53933 -1.866695 34.61832 -43.6208 99.1333 39.92163 -39.37816 99.1333 35.67899 -30.53932 92.1333 34.61833 -35.48907 99.1333 39.56808 -39.73171 99.1333 43.81072 -44.68146 92.1333 48.76047 -43.26725 4.133303 47.34624 -44.68146 7.597405 48.76046 40.59561 14.1333 44.58852 34.79733 8.1333 38.79024 40.59561 8.133299 44.58852 44.48469 8.133299 40.69943 44.76754 7.5974 48.76045 40.59561 6.633299 44.58852 44.76754 92.1333 48.76046 30.6254 -1.866698 34.61831 34.79733 6.6333 38.79024 38.68642 6.6333 34.90116 34.79733 14.1333 38.79025 38.68642 8.1333 34.90116 43.35332 4.133299 47.34623 44.48469 6.633299 40.69943 40.59561 21.6333 44.58852 34.79733 15.6333 38.79025 40.59561 15.6333 44.58852 44.48469 15.6333 40.69944 38.68642 14.1333 34.90116 34.79733 21.6333 38.79025 38.68642 15.6333 34.90116 44.48469 14.1333 40.69944 40.59561 29.1333 44.58852 34.79733 23.1333 38.79025 40.59561 23.1333 44.58852 44.48469 23.1333 40.69944 38.68642 21.6333 34.90116 34.79733 29.1333 38.79025 38.68642 23.1333 34.90116 44.48469 21.6333 40.69944 40.59561 36.6333 44.58852 34.79733 30.6333 38.79025 40.59561 30.6333 44.58852 44.48469 30.6333 40.69944 38.68642 29.1333 34.90116 34.79733 36.6333 38.79025 38.68642 30.6333 34.90116 44.48469 29.1333 40.69944 40.59561 44.1333 44.58852 34.79733 38.1333 38.79025 40.59561 38.1333 44.58852 44.48469 38.1333 40.69944 38.68642 36.6333 34.90116 34.79734 44.1333 38.79025 38.68642 38.1333 34.90116 44.48469 36.6333 40.69944 40.59561 51.6333 44.58852 34.79734 45.6333 38.79025 40.59561 45.6333 44.58852 44.48469 45.6333 40.69944 38.68642 44.1333 34.90117 34.79734 51.6333 38.79025 38.68642 45.6333 34.90117 44.48469 44.1333 40.69944 40.59561 59.1333 44.58852 34.79734 53.1333 38.79025 40.59561 53.1333 44.58852 44.48469 53.1333 40.69944 38.68642 51.6333 34.90117 34.79734 59.1333 38.79025 38.68642 53.1333 34.90117 44.48469 51.6333 40.69944 40.59561 66.6333 44.58852 34.79734 60.6333 38.79025 40.59561 60.6333 44.58852 44.48469 60.6333 40.69944 38.68642 59.1333 34.90117 34.79734 66.6333 38.79025 38.68642 60.6333 34.90117 44.48469 59.1333 40.69944 40.59561 74.1333 44.58853 34.79734 68.1333 38.79025 40.59561 68.1333 44.58852 44.48469 68.1333 40.69944 38.68642 66.6333 34.90117 34.79734 74.1333 38.79026 38.68642 68.1333 34.90117 44.48469 66.6333 40.69944 40.59561 81.6333 44.58853 34.79734 75.6333 38.79026 40.59561 75.6333 44.58853 44.48469 75.6333 40.69944 38.68642 74.1333 34.90117 34.79734 81.6333 38.79026 38.68642 75.6333 34.90117 44.48469 74.1333 40.69944 34.79734 83.1333 38.79026 40.59561 83.1333 44.58853 44.48469 83.1333 40.69944 38.68642 81.6333 34.90117 40.59561 89.1333 44.58853 34.79734 89.1333 38.79026 38.68642 83.1333 34.90117 44.48469 81.6333 40.69944 34.79734 90.6333 38.79026 40.59561 90.6333 44.58853 44.48469 90.6333 40.69944 38.68642 89.1333 34.90117 30.62541 92.1333 34.61832 38.68642 90.6333 34.90117 44.48469 89.1333 40.69944 51.83861 -1.866702 55.83151 41.8684 -9.366701 45.86131 47.66667 -9.366702 51.65958 51.55576 -9.366702 47.7705 47.66667 -10.8667 51.65958 37.69647 -73.86669 41.68937 41.8684 -10.8667 45.86131 45.75748 -10.8667 41.97222 47.59597 -1.866701 51.58887 43.35332 -1.8667 47.34623 37.69647 -1.866699 41.68938 45.75748 -9.366701 41.97222 41.8684 -16.8667 45.8613 47.66667 -16.8667 51.65958 51.55576 -10.8667 47.7705 51.55576 -16.8667 47.7705 47.66667 -18.3667 51.65958 41.8684 -18.3667 45.8613 45.75748 -18.3667 41.97222 45.75748 -16.8667 41.97222 41.8684 -24.3667 45.8613 47.66667 -24.3667 51.65958 51.55576 -18.3667 47.7705 51.55576 -24.3667 47.7705 47.66667 -25.8667 51.65958 41.8684 -25.8667 45.8613 45.75748 -25.8667 41.97222 45.75748 -24.3667 41.97222 41.8684 -31.8667 45.8613 47.66667 -31.8667 51.65958 51.55576 -25.8667 47.7705 51.55576 -31.8667 47.7705 47.66667 -33.3667 51.65958 41.8684 -33.3667 45.8613 45.75748 -33.3667 41.97222 45.75748 -31.8667 41.97222 41.8684 -39.36669 45.8613 47.66667 -39.36669 51.65958 51.55576 -33.3667 47.7705 51.55576 -39.36669 47.7705 47.66667 -40.86669 51.65958 41.8684 -40.86669 45.8613 45.75748 -40.86669 41.97222 45.75748 -39.36669 41.97222 41.8684 -46.86669 45.8613 47.66667 -46.86669 51.65958 51.55576 -40.86669 47.7705 51.55575 -46.86669 47.77049 47.66667 -48.36669 51.65958 41.8684 -48.36669 45.8613 45.75748 -48.36669 41.97222 45.75748 -46.86669 41.97222 41.8684 -54.36669 45.8613 47.66667 -54.36669 51.65958 51.55575 -48.36669 47.77049 51.55575 -54.36669 47.77049 47.66667 -55.86669 51.65958 41.8684 -55.86669 45.8613 45.75748 -55.86669 41.97222 45.75748 -54.36669 41.97222 41.8684 -61.86669 45.8613 47.66667 -61.86669 51.65958 51.55575 -55.86669 47.77049 51.55575 -61.86669 47.77049 47.66667 -63.36669 51.65958 41.8684 -63.36669 45.8613 45.75748 -63.36669 41.97222 45.75748 -61.86669 41.97222 41.8684 -69.36669 45.8613 47.66667 -69.36669 51.65958 51.55575 -63.36669 47.77049 51.55575 -69.36669 47.77049 47.66667 -70.86669 51.65958 41.8684 -70.86669 45.8613 45.75748 -70.86669 41.97222 45.75748 -69.36669 41.97222 51.8386 -75.86669 55.8315 51.55575 -70.86669 47.77049 54.66703 4.475035 58.65994 47.59597 0.1332988 51.58887 51.48505 0.1332991 47.69979 47.24241 -1.8667 43.45715 51.48505 -1.866701 47.69979 47.6645 1.112138 51.65741 47.86545 2.046506 51.85836 51.55358 1.112138 47.76832 48.19144 2.909809 52.18434 51.75453 2.046507 47.96928 48.6315 3.668832 52.6244 52.08052 2.909809 48.29526 49.16821 4.291173 53.16112 52.52058 3.668832 48.73532 49.77865 4.752191 53.77156 53.05729 4.291173 49.27203 51.1315 5.133298 55.1244 50.43936 5.036376 54.43227 53.66774 4.752191 49.88248 54.32844 5.036376 50.54318 58.55612 4.475035 54.77085 55.02058 5.133298 51.23532 54.66703 -1.866702 58.65994 55.72769 -1.866701 51.94243 58.55612 -1.866702 54.77085 46.18175 -85.86669 50.17465 76.58735 -75.8667 80.58024 55.72769 -75.86669 51.94242 76.58735 -85.8667 80.58024 80.47644 -75.8667 76.69116 80.47644 -85.8667 76.69116 50.07083 -85.86669 46.28556 41.58555 -73.86669 37.80029 41.58555 -1.866699 37.8003 34.51449 -1.866698 30.72922 39.81779 99.1333 43.81071 35.57515 99.1333 39.56807 34.51449 92.1333 30.72924 39.46424 99.1333 35.67899 43.70688 99.1333 39.92163 48.65663 92.1333 44.87137 47.24241 4.133299 43.45715 48.65662 7.5974 44.87136 122.1993 -1.86668 -134.4545 69.0979 -1.866685 -76.33673 68.24347 -1.866685 -75.90248 68.24347 3.533314 -75.90248 62.58662 -1.866686 -66.35652 67.80923 -1.866685 -75.04805 67.80923 3.533314 -75.04805 55.7479 -1.866686 -68.00309 70.04167 -1.866685 -76.18788 69.0979 3.533314 -76.33673 70.72093 -1.866685 -75.50863 70.04167 3.533314 -76.18788 74.75476 -1.866686 -70.67987 70.86975 -1.866685 -74.56486 70.72093 3.533314 -75.50863 75.69853 -1.866686 -70.53103 73.66677 -1.866685 -76.01999 74.18318 -1.866685 -77.95308 73.66677 -1.866685 -77.05775 73.90033 -1.866686 -70.24562 70.4355 -1.866686 -73.71044 70.86975 3.533314 -74.56486 73.46608 -1.866686 -69.3912 69.5811 -1.866686 -73.27619 70.4355 3.533314 -73.71044 73.61492 -1.866686 -68.44742 68.63732 -1.866685 -73.42502 69.5811 3.533314 -73.27619 70.03268 -1.866686 -67.29966 67.95806 -1.866685 -74.10427 68.63732 3.533314 -73.42502 68.38489 -1.866686 -69.32638 67.95806 3.533314 -74.10427 69.51628 -1.866686 -68.195 65.55648 -1.866686 -69.32637 66.45182 -1.866686 -69.84279 67.48957 -1.866686 -69.84278 113.6456 -1.866681 -120.8844 112.7912 -1.866681 -120.4502 112.7912 3.533318 -120.4502 95.74993 -1.866683 -99.51983 112.357 -1.866681 -119.5958 112.357 3.533318 -119.5958 114.5894 -1.866681 -120.7356 113.6456 3.533318 -120.8844 115.2686 -1.866681 -120.0564 114.5894 3.533318 -120.7356 119.3025 -1.866682 -115.2276 115.4175 -1.866682 -119.1126 115.2686 3.533318 -120.0564 120.2462 -1.866682 -115.0788 118.4266 -1.866681 -120.7798 118.4266 -1.866681 -121.8176 118.4481 -1.866682 -114.7933 114.9832 -1.866682 -118.2582 115.4175 3.533318 -119.1126 118.0138 -1.866682 -113.9389 114.1288 -1.866682 -117.8239 114.9832 3.533318 -118.2582 118.1626 -1.866683 -112.9951 113.185 -1.866682 -117.9727 114.1288 3.533318 -117.8239 114.7218 -1.866683 -111.9888 112.5058 -1.866682 -118.652 113.185 3.533318 -117.9727 113.074 -1.866682 -114.0155 112.5058 3.533318 -118.652 114.2054 -1.866682 -112.8841 110.2456 -1.866682 -114.0155 111.1409 -1.866682 -114.5319 112.1787 -1.866682 -114.5319 118.4481 3.533317 -114.7933 118.0138 3.533317 -113.9389 119.3025 3.533318 -115.2276 120.9255 -1.866682 -114.3995 120.2462 3.533318 -115.0788 120.9697 -1.866682 -118.2367 121.0743 -1.866683 -113.4557 120.9255 3.533318 -114.3995 118.943 -1.866682 -119.8845 120.0744 -1.866682 -118.7531 128.5597 -1.866681 -124.41 120.6401 -1.866683 -112.6013 121.0743 3.533318 -113.4557 122.9028 -1.866682 -118.7531 122.0075 -1.866682 -118.2367 68.193 -1.866688 -55.55801 119.7857 -1.866683 -112.1671 120.6401 3.533317 -112.6013 134.6444 -1.866682 -122.0094 118.8419 -1.866683 -112.3159 119.7857 3.533317 -112.1671 118.8419 3.533317 -112.3159 118.1626 3.533317 -112.9951 114.2054 -1.866683 -110.0557 114.7218 -1.866683 -110.9511 73.90033 3.533313 -70.24562 73.46608 3.533313 -69.3912 74.75476 3.533313 -70.67987 76.37778 -1.866686 -69.85179 75.69853 3.533313 -70.53103 76.20989 -1.866686 -73.47687 76.52661 -1.866686 -68.90802 76.37778 3.533313 -69.85179 74.18317 -1.866685 -75.12466 75.31455 -1.866686 -73.99328 92.63865 -1.866685 -88.48897 76.09236 -1.866687 -68.05359 76.52661 3.533313 -68.90802 78.14297 -1.866686 -73.9933 77.24765 -1.866686 -73.47689 75.23794 -1.866687 -67.61934 76.09236 3.533313 -68.05358 74.29417 -1.866687 -67.76818 75.23794 3.533313 -67.61934 74.29417 3.533313 -67.76818 73.61492 3.533313 -68.44742 70.03268 -1.866687 -66.26192 136.9149 -1.866677 -161.4609 146.0907 -1.866678 -152.9021 145.3181 -1.866679 -152.27 145.3181 3.533321 -152.27 144.686 -1.866679 -151.4974 144.686 3.533321 -151.4974 139.7669 -1.866677 -163.6332 146.9544 -1.866678 -153.3632 146.0907 3.533321 -152.9021 147.9059 -1.866678 -153.6523 146.9544 3.533321 -153.3632 148.889 -1.866678 -153.748 147.9059 3.533321 -153.6523 149.8721 -1.866679 -153.6523 148.889 3.533321 -153.748 147.463 -1.866678 -157.4743 150.8236 -1.866679 -153.3632 149.8721 3.533321 -153.6523 151.6928 -1.866679 -152.8981 150.8236 3.533321 -153.3632 152.4599 -1.866679 -152.27 151.6928 3.533321 -152.8981 163.8231 -1.866681 -139.5771 153.0879 -1.866679 -151.5029 152.4599 3.533321 -152.27 148.1642 -1.866678 -156.7731 156.963 -1.86668 -147.9743 153.553 -1.866679 -150.6337 153.0879 3.533321 -151.5029 153.8422 -1.866679 -149.6822 153.5531 3.53332 -150.6337 153.9378 -1.866679 -148.6991 153.8422 3.53332 -149.6822 161.6508 -1.866681 -136.725 153.8422 -1.86668 -147.7161 153.9378 3.53332 -148.6991 153.5531 -1.86668 -146.7646 153.8422 3.53332 -147.7161 153.0919 -1.86668 -145.9008 153.5531 3.53332 -146.7646 152.4599 -1.86668 -145.1282 153.0919 3.53332 -145.9008 158.9425 -1.866681 -134.3753 151.6873 -1.86668 -144.4962 152.4599 3.53332 -145.1282 150.8236 -1.86668 -144.0351 151.6873 3.53332 -144.4962 149.872 -1.86668 -143.746 150.8236 3.53332 -144.0351 148.889 -1.86668 -143.6503 149.872 3.53332 -143.746 155.8122 -1.866682 -132.6268 147.9059 -1.86668 -143.7459 148.889 3.53332 -143.6503 150.315 -1.86668 -139.9239 146.9544 -1.86668 -144.0351 147.9059 3.53332 -143.7459 146.0852 -1.86668 -144.5002 146.9544 3.53332 -144.0351 145.3181 -1.866679 -145.1282 146.0852 3.53332 -144.5002 140.815 -1.866679 -149.4239 144.6901 -1.866679 -145.8953 145.3181 3.53332 -145.1282 149.6138 -1.86668 -140.6251 134.5652 -1.866677 -158.7527 144.2249 -1.866679 -146.7645 144.6901 3.53332 -145.8953 143.9358 -1.866679 -147.7161 144.2249 3.533321 -146.7645 143.8401 -1.866679 -148.6991 143.9358 3.533321 -147.716 143.9358 -1.866679 -149.6822 143.8401 3.533321 -148.6991 144.2249 -1.866679 -150.6337 143.9358 3.533321 -149.6822 144.2249 3.533321 -150.6337 132.8167 -1.866677 -155.6223 139.1396 -1.866679 -150.2787 138.2576 -1.866679 -149.8305 138.2576 3.533321 -149.8305 137.8094 -1.866679 -148.9485 137.8094 3.533321 -148.9485 140.1138 -1.866679 -150.1251 139.1396 3.533321 -150.2787 140.1138 3.533321 -150.1251 148.6396 -1.86668 -140.7787 140.9686 -1.866679 -148.4497 140.815 3.533321 -149.4239 147.7576 -1.86668 -140.3305 140.5204 -1.866679 -147.5677 140.9686 3.533321 -148.4497 147.3094 -1.86668 -139.4485 139.6384 -1.866679 -147.1195 140.5204 3.53332 -147.5677 147.463 -1.86668 -138.4743 138.6642 -1.866679 -147.2731 139.6384 3.53332 -147.1195 152.3904 -1.866682 -131.553 137.963 -1.866679 -147.9743 138.6642 3.533321 -147.2731 137.963 3.533321 -147.9743 131.7428 -1.866678 -152.2005 147.7576 3.533319 -140.3305 147.3094 3.533319 -139.4485 148.6396 3.53332 -140.7787 149.6138 3.533319 -140.6251 150.4686 -1.86668 -138.9497 150.315 3.533319 -139.9239 150.0204 -1.866681 -138.0678 150.4686 3.533319 -138.9497 149.1384 -1.866681 -137.6195 150.0204 3.533319 -138.0678 148.1642 -1.866681 -137.7731 149.1384 3.533319 -137.6195 148.1642 3.533319 -137.7731 147.463 3.533319 -138.4743 150.4686 -1.866678 -157.9497 158.1396 -1.866679 -150.2787 157.2576 -1.866679 -149.8305 157.2576 3.53332 -149.8305 150.0204 -1.866678 -157.0677 156.8094 -1.866679 -148.9485 156.8094 3.53332 -148.9485 150.315 -1.866678 -158.9239 159.1138 -1.866679 -150.1251 158.1396 3.53332 -150.2787 146.4831 -1.866677 -166.0323 159.815 -1.86668 -149.4239 159.1138 3.53332 -150.1251 165.3684 -1.866681 -142.8117 159.9686 -1.86668 -148.4497 159.815 3.53332 -149.4239 159.5204 -1.86668 -147.5678 159.9686 3.53332 -148.4497 158.6384 -1.86668 -147.1195 159.5204 3.53332 -147.5678 157.6642 -1.86668 -147.2731 158.6384 3.53332 -147.1195 157.6642 3.53332 -147.2731 149.1384 -1.866678 -156.6195 156.963 3.53332 -147.9743 143.0016 -1.866677 -165.1786 148.6396 -1.866678 -159.7787 147.7576 -1.866678 -159.3305 147.7576 3.533322 -159.3305 147.3094 -1.866678 -158.4485 147.3094 3.533322 -158.4485 149.6138 -1.866678 -159.6251 148.6396 3.533322 -159.7787 149.6138 3.533322 -159.6251 150.315 3.533322 -158.9239 150.4686 3.533321 -157.9497 150.0204 3.533321 -157.0677 149.1384 3.533321 -156.6195 148.1642 3.533322 -156.7731 147.463 3.533322 -157.4743 130.3556 -1.866679 -147.2771 136.7147 -1.86668 -141.7515 135.4186 -1.86668 -140.8856 135.4186 3.53332 -140.8856 134.5527 -1.86668 -139.5895 134.5527 3.53332 -139.5895 138.247 -1.86668 -142.0563 136.7147 3.53332 -141.7515 139.7794 -1.86668 -141.7515 138.247 3.53332 -142.0563 141.0755 -1.86668 -140.8856 139.7794 3.53332 -141.7515 141.9413 -1.86668 -139.5895 141.0755 3.53332 -140.8856 147.4669 -1.866682 -130.1657 142.2461 -1.86668 -138.0572 141.9413 3.53332 -139.5895 141.9413 -1.86668 -136.5248 142.2461 3.533319 -138.0572 141.0755 -1.866681 -135.2287 141.9413 3.533319 -136.5248 142.8163 -1.866682 -128.0848 139.7794 -1.866681 -134.3628 141.0755 3.533319 -135.2287 138.247 -1.866681 -134.0581 139.7794 3.533319 -134.3628 136.7147 -1.86668 -134.3629 138.247 3.533319 -134.0581 135.4186 -1.86668 -135.2287 136.7147 3.533319 -134.3629 128.2747 -1.866679 -142.6264 134.5527 -1.86668 -136.5248 135.4186 3.533319 -135.2287 138.5162 -1.866682 -125.3521 134.2479 -1.86668 -138.0572 134.5527 3.533319 -136.5248 134.2479 3.53332 -138.0572 27.62019 -1.866687 -48.71421 31.62124 -1.866688 -45.93112 30.76682 -1.866688 -45.49687 30.76682 3.533312 -45.49687 30.33257 -1.866688 -44.64246 30.33257 3.533312 -44.64246 38.36821 -1.866686 -59.46223 32.56501 -1.866688 -45.78229 31.62124 3.533312 -45.93112 33.24427 -1.866688 -45.10304 32.56501 3.533312 -45.78229 43.31796 -1.866688 -47.08787 33.39309 -1.866688 -44.15926 33.24427 3.533312 -45.10304 30.59004 -1.866689 -34.35995 32.95885 -1.866688 -43.30484 33.39309 3.533312 -44.15926 32.10443 -1.866688 -42.8706 32.95885 3.533312 -43.30484 31.16065 -1.866688 -43.01942 32.10443 3.533312 -42.8706 30.4814 -1.866688 -43.69868 31.16065 3.533312 -43.01942 26.99658 -1.866687 -47.95353 30.4814 3.533312 -43.69868 26.53683 -1.866687 -47.09188 47.27776 -1.866689 -43.12807 44.34915 -1.86669 -33.2032 43.49473 -1.86669 -32.76895 43.49473 3.53331 -32.76895 43.06049 -1.86669 -31.91454 43.06049 3.53331 -31.91454 45.29293 -1.86669 -33.05437 44.34915 3.53331 -33.2032 45.97219 -1.86669 -32.37512 45.29293 3.53331 -33.05437 48.9041 -1.866691 -27.4303 46.12101 -1.86669 -31.43134 45.97219 3.53331 -32.37512 45.68677 -1.86669 -30.57693 46.12101 3.533309 -31.43134 48.14342 -1.866691 -26.80669 44.83235 -1.86669 -30.14269 45.68677 3.533309 -30.57693 43.88858 -1.86669 -30.29151 44.83235 3.533309 -30.14269 47.28178 -1.866691 -26.34695 43.20932 -1.86669 -30.97076 43.88858 3.53331 -30.29151 41.05522 -1.86669 -25.96584 43.20932 3.53331 -30.97076 45.36857 -1.866691 -25.96584 46.34741 -1.866691 -26.06276 40.07638 -1.86669 -26.06276 42.22784 -1.866687 -56.53772 41.37342 -1.866687 -56.10348 41.37342 3.533313 -56.10348 40.93917 -1.866687 -55.24906 40.93917 3.533313 -55.24906 40.92699 -1.866686 -61.51393 43.17161 -1.866687 -56.38889 42.22784 3.533313 -56.53772 43.85086 -1.866687 -55.70964 43.17161 3.533313 -56.38889 47.03027 -1.866688 -50.80018 43.99969 -1.866687 -54.76586 43.85086 3.533313 -55.70964 43.56545 -1.866687 -53.91144 43.99969 3.533313 -54.76586 53.66709 -1.866689 -42.52114 42.71103 -1.866687 -53.4772 43.56545 3.533313 -53.91144 54.10134 -1.866689 -43.37556 53.81592 -1.866689 -41.57736 41.76725 -1.866687 -53.62603 42.71103 3.533313 -53.4772 41.088 -1.866687 -54.30528 41.76725 3.533313 -53.62602 41.088 3.533313 -54.30528 50.99007 -1.866688 -46.84038 54.95576 -1.866689 -43.8098 54.10134 3.533311 -43.37556 53.66709 3.533311 -42.52114 58.20256 -1.866688 -54.05286 55.89953 -1.866689 -43.66097 54.95576 3.533311 -43.8098 56.57879 -1.866689 -42.98172 55.89953 3.533311 -43.66097 59.65213 -1.86669 -38.17832 56.72761 -1.866689 -42.03794 56.57879 3.533311 -42.98172 61.70382 -1.86669 -40.73709 56.29337 -1.866689 -41.18352 56.72761 3.53331 -42.03794 55.43895 -1.866689 -40.74928 56.29337 3.53331 -41.18352 54.49518 -1.866689 -40.89811 55.43895 3.53331 -40.74928 54.49518 3.533311 -40.89811 53.81592 3.533311 -41.57736 59.24264 -1.866687 -61.74076 58.73288 -1.866687 -61.37142 58.73288 3.533313 -61.37142 58.36355 -1.866687 -60.86167 58.36355 3.533313 -60.86167 59.83535 -1.866687 -61.93173 59.24264 3.533313 -61.74076 60.45884 -1.866687 -61.93174 59.83535 3.533313 -61.93173 61.05314 -1.866687 -61.73971 60.45884 3.533313 -61.93174 61.56131 -1.866687 -61.37142 61.05314 3.533313 -61.73971 61.92959 -1.866687 -60.86325 61.56131 3.533313 -61.37142 66.14129 -1.866688 -52.99924 62.12163 -1.866687 -60.26895 61.92959 3.533313 -60.86325 62.12162 -1.866687 -59.64546 62.12163 3.533313 -60.26895 61.93065 -1.866687 -59.05275 62.12162 3.533313 -59.64546 61.56131 -1.866687 -58.54299 61.93065 3.533313 -59.05275 61.05156 -1.866687 -58.17366 61.56131 3.533312 -58.54299 60.45884 -1.866687 -57.98268 61.05156 3.533313 -58.17366 64.69477 -1.866688 -50.05572 59.83536 -1.866687 -57.98268 60.45884 3.533313 -57.98268 59.24106 -1.866687 -58.17471 59.83536 3.533313 -57.98268 58.73289 -1.866687 -58.54299 59.24106 3.533313 -58.1747 53.18913 -1.866686 -65.9514 58.3646 -1.866687 -59.05117 58.73289 3.533313 -58.54299 58.17257 -1.866687 -59.64547 58.3646 3.533313 -59.05117 58.17257 -1.866687 -60.26895 58.17257 3.533313 -59.64547 58.17257 3.533313 -60.26895 38.28036 -1.86669 -26.80669 37.51969 -1.86669 -27.4303 37.51969 3.533309 -27.4303 34.54984 -1.86669 -30.40015 39.14201 -1.86669 -26.34694 38.28036 3.533309 -26.80669 39.14201 3.533309 -26.34694 40.07638 3.533309 -26.06276 45.36857 3.533309 -25.96584 41.05522 3.533309 -25.96584 46.34741 3.533309 -26.06276 47.28178 3.533309 -26.34695 48.14342 3.533309 -26.80669 48.9041 3.533309 -27.4303 59.65213 3.53331 -38.17832 63.15034 -1.866689 -43.68062 61.70382 3.53331 -40.73709 63.92255 -1.866689 -46.86817 63.15034 3.53331 -43.68062 50.24561 -1.866686 -64.50489 63.92255 3.533311 -46.86817 64.69477 3.533311 -50.05572 66.14129 3.533312 -52.99924 68.193 3.533312 -55.55801 62.58662 -1.866687 -63.5281 99.70972 -1.866684 -95.56005 98.81439 -1.866684 -95.04364 97.77663 -1.866684 -95.04362 69.51626 -1.866687 -65.36658 66.54642 -1.866687 -62.39672 65.6511 -1.866687 -61.88032 64.61333 -1.866687 -61.88032 63.71799 -1.866687 -62.39673 125.542 -1.86668 -138.3263 134.6444 3.533318 -122.0094 128.5597 -1.866681 -127.2384 129.0761 -1.866681 -126.3431 129.0761 -1.866681 -125.3053 138.5162 3.533318 -125.3521 142.8163 3.533318 -128.0848 147.4669 3.533318 -130.1657 152.3904 3.533318 -131.553 155.8122 3.533318 -132.6268 158.9425 3.533318 -134.3753 161.6508 3.533318 -136.725 163.8231 3.533319 -139.5771 166.2222 -1.86668 -146.2932 165.3684 3.533319 -142.8117 150.0653 -1.866677 -166.1588 166.3487 -1.86668 -149.8754 166.2222 3.533319 -146.2932 153.598 -1.866677 -165.5528 165.7427 -1.866679 -153.4081 166.3487 3.53332 -149.8754 156.933 -1.866677 -164.2398 164.4297 -1.866679 -156.7431 165.7427 3.53332 -153.4081 159.9305 -1.866678 -162.275 162.4648 -1.866678 -159.7406 164.4297 3.533321 -156.7431 162.4648 3.533322 -159.7406 159.9305 3.533322 -162.275 156.933 3.533322 -164.2398 153.598 3.533322 -165.5528 150.0653 3.533323 -166.1588 146.4831 3.533323 -166.0323 143.0016 3.533323 -165.1786 139.7669 3.533323 -163.6332 136.9149 3.533323 -161.4609 134.5652 3.533322 -158.7527 132.8167 3.533322 -155.6223 131.7428 3.533322 -152.2005 130.3556 3.533321 -147.2771 128.2747 3.533321 -142.6264 125.542 3.53332 -138.3263 122.1993 3.53332 -134.4545 118.943 -1.866681 -122.7129 124.5999 -1.866681 -128.3698 125.4952 -1.866681 -128.8862 126.533 -1.866681 -128.8862 127.4283 -1.866681 -128.3698 90.61194 -1.866684 -92.96517 88.67887 -1.866684 -92.44876 89.57419 -1.866684 -92.96517 55.7479 3.533314 -68.00309 62.07021 -1.866686 -64.42344 62.07021 -1.866686 -65.46119 53.18913 3.533314 -65.9514 54.24275 -1.866687 -58.01266 47.05806 -1.866686 -63.73266 50.24561 3.533314 -64.50487 43.87051 -1.866686 -62.96046 47.05806 3.533314 -63.73266 43.87051 3.533314 -62.96045 40.92699 3.533314 -61.51392 38.36821 3.533314 -59.46223 27.62019 3.533313 -48.71421 26.99658 3.533313 -47.95353 26.25265 -1.866687 -46.15751 26.53683 3.533313 -47.09188 26.15573 -1.866687 -45.17868 26.25265 3.533313 -46.15751 26.15573 -1.866688 -40.86532 26.15573 3.533312 -40.86532 26.15573 3.533313 -45.17867 26.25265 -1.866688 -39.88648 26.53684 -1.866688 -38.95212 26.25265 3.533312 -39.88648 26.99658 -1.866688 -38.09047 26.53684 3.533311 -38.95212 27.62019 -1.866688 -37.32979 26.99658 3.533311 -38.09047 30.59004 3.533311 -34.35994 27.62019 3.533311 -37.32979 43.31796 3.533312 -47.08786 47.27776 3.533311 -43.12807 34.54984 3.53331 -30.40015 118.943 3.533318 -119.8845 120.9697 3.533318 -118.2367 120.0744 3.533318 -118.7531 118.4266 3.533318 -120.7798 118.4266 3.533318 -121.8176 118.943 3.533318 -122.7129 124.5999 3.533319 -128.3698 125.4952 3.533319 -128.8862 126.533 3.533318 -128.8862 128.5597 3.533318 -127.2384 127.4283 3.533318 -128.3698 129.0761 3.533318 -126.3431 129.0761 3.533318 -125.3053 128.5597 3.533318 -124.41 122.9028 3.533318 -118.7531 122.0075 3.533318 -118.2367 114.2054 3.533318 -112.8841 114.7218 3.533318 -111.9888 114.7218 3.533317 -110.9511 114.2054 3.533317 -110.0557 99.70972 3.533316 -95.56005 98.81439 3.533316 -95.04364 96.8813 -1.866684 -95.56003 97.77663 3.533316 -95.04362 93.15506 -1.866685 -89.3843 95.74993 -1.866684 -96.69141 95.74993 3.533316 -96.6914 96.8813 3.533316 -95.56003 92.63865 -1.866684 -91.31739 95.23352 -1.866683 -97.58674 93.15506 -1.866684 -90.42205 95.23352 -1.866683 -98.6245 95.23352 3.533316 -97.58673 91.50727 -1.866684 -92.44877 95.23352 3.533317 -98.6245 95.74993 3.533317 -99.51983 110.2456 3.533318 -114.0155 111.1409 3.533318 -114.5319 112.1787 3.533318 -114.5319 113.074 3.533318 -114.0155 74.18318 3.533314 -75.12465 76.20989 3.533314 -73.47687 75.31455 3.533314 -73.99328 73.66677 3.533314 -76.01999 73.66677 3.533315 -77.05775 74.18318 3.533315 -77.95308 88.67887 3.533316 -92.44876 89.57419 3.533316 -92.96517 90.61194 3.533316 -92.96517 92.63865 3.533316 -91.31739 91.50728 3.533316 -92.44876 93.15506 3.533316 -90.42205 93.15506 3.533315 -89.3843 92.63865 3.533315 -88.48897 78.14297 3.533314 -73.9933 77.24765 3.533314 -73.47689 69.51628 3.533314 -68.195 70.03268 3.533314 -67.29966 70.03268 3.533313 -66.26192 66.54642 3.533313 -62.39672 69.51626 3.533313 -65.36658 65.6511 3.533313 -61.88032 64.61333 3.533313 -61.88032 62.58662 3.533313 -63.5281 63.71799 3.533313 -62.39673 62.07021 3.533313 -64.42343 62.07021 3.533314 -65.46119 65.55648 3.533314 -69.32637 62.58662 3.533314 -66.35652 66.45182 3.533314 -69.84279 67.48957 3.533314 -69.84278 68.38491 3.533314 -69.32637 58.20256 3.533312 -54.05286 54.24275 3.533313 -58.01266 50.99007 3.533311 -46.84038 47.03027 3.533312 -50.80017 -134.5583 -1.86667 -122.0094 -76.44055 -1.86668 -68.90799 -76.0063 -1.86668 -68.05358 -76.0063 3.533319 -68.05358 -66.46035 -1.866681 -62.39672 -75.15188 -1.86668 -67.61933 -75.15188 3.533319 -67.61933 -68.10692 -1.866682 -55.55801 -76.29171 -1.86668 -69.85177 -76.44055 3.53332 -68.90799 -75.61246 -1.86668 -70.53102 -76.29171 3.53332 -69.85177 -70.78369 -1.866679 -74.56484 -74.6687 -1.86668 -70.67985 -75.61246 3.53332 -70.53102 -70.63486 -1.866679 -75.50862 -76.12382 -1.866679 -73.47686 -78.05691 -1.866679 -73.99327 -77.16159 -1.866679 -73.47686 -70.34944 -1.866679 -73.71043 -73.81427 -1.86668 -70.2456 -74.6687 3.53332 -70.67985 -69.49504 -1.86668 -73.27618 -73.38002 -1.86668 -69.39118 -73.81427 3.53332 -70.2456 -68.55125 -1.86668 -73.42501 -73.52885 -1.86668 -68.44741 -73.38002 3.53332 -69.39118 -67.40349 -1.86668 -69.84278 -74.2081 -1.86668 -67.76816 -73.52885 3.53332 -68.44741 -69.43021 -1.86668 -68.19499 -74.2081 3.533319 -67.76816 -68.29883 -1.86668 -69.32637 -69.4302 -1.86668 -65.36656 -69.94662 -1.86668 -66.2619 -69.94661 -1.86668 -67.29965 -120.9883 -1.866672 -113.4557 -120.554 -1.866672 -112.6013 -120.554 3.533328 -112.6013 -99.62366 -1.866675 -95.56002 -119.6996 -1.866672 -112.167 -119.6996 3.533328 -112.167 -120.8394 -1.866672 -114.3995 -120.9883 3.533328 -113.4557 -120.1602 -1.866672 -115.0787 -120.8394 3.533328 -114.3995 -115.3314 -1.866672 -119.1126 -119.2164 -1.866672 -115.2276 -120.1602 3.533328 -115.0787 -115.1826 -1.866671 -120.0563 -120.8837 -1.866671 -118.2367 -121.9214 -1.866671 -118.2367 -114.8972 -1.866672 -118.2582 -118.362 -1.866672 -114.7933 -119.2164 3.533328 -115.2276 -114.0428 -1.866672 -117.8239 -117.9277 -1.866672 -113.9389 -118.362 3.533328 -114.7933 -113.099 -1.866672 -117.9727 -118.0766 -1.866672 -112.9951 -117.9277 3.533328 -113.9389 -112.0926 -1.866672 -114.5319 -118.7558 -1.866672 -112.3159 -118.0766 3.533328 -112.9951 -114.1194 -1.866672 -112.8841 -118.7558 3.533327 -112.3159 -112.988 -1.866672 -114.0155 -114.1194 -1.866673 -110.0557 -114.6358 -1.866673 -110.951 -114.6358 -1.866672 -111.9888 -114.8972 3.533328 -118.2582 -114.0428 3.533328 -117.8239 -115.3314 3.533328 -119.1126 -114.5033 -1.866671 -120.7356 -115.1826 3.533328 -120.0563 -118.3406 -1.866671 -120.7798 -113.5596 -1.866671 -120.8844 -114.5033 3.533329 -120.7356 -119.9883 -1.866671 -118.7531 -118.857 -1.866671 -119.8845 -124.5138 -1.86667 -128.3698 -112.7051 -1.866671 -120.4502 -113.5596 3.533329 -120.8844 -118.857 -1.866671 -122.7129 -118.3406 -1.866671 -121.8176 -55.66184 -1.866681 -68.00308 -112.2709 -1.866672 -119.5958 -112.7051 3.533329 -120.4502 -122.1132 -1.866669 -134.4545 -112.4197 -1.866672 -118.652 -112.2709 3.533329 -119.5958 -112.4197 3.533328 -118.652 -113.099 3.533328 -117.9727 -110.1596 -1.866672 -114.0155 -111.0549 -1.866672 -114.5319 -70.34944 3.53332 -73.71043 -69.49504 3.53332 -73.27618 -70.78369 3.53332 -74.56484 -69.95561 -1.866679 -76.18788 -70.63486 3.53332 -75.50862 -73.58071 -1.866679 -76.01998 -69.01184 -1.866679 -76.3367 -69.95561 3.533321 -76.18788 -75.2285 -1.866679 -73.99327 -74.09711 -1.866679 -75.12464 -88.5928 -1.866676 -92.44876 -68.15742 -1.866679 -75.90246 -69.01184 3.533321 -76.3367 -74.09712 -1.866679 -77.95307 -73.58071 -1.866679 -77.05773 -67.72317 -1.866679 -75.04804 -68.15742 3.53332 -75.90246 -67.872 -1.866679 -74.10427 -67.72317 3.53332 -75.04804 -67.872 3.53332 -74.10427 -68.55125 3.53332 -73.42501 -66.36576 -1.86668 -69.84278 -161.5647 -1.866667 -136.725 -153.0059 -1.866666 -145.9008 -152.3738 -1.866666 -145.1282 -152.3738 3.533333 -145.1282 -151.6012 -1.866667 -144.4962 -151.6012 3.533333 -144.4962 -163.737 -1.866667 -139.577 -153.467 -1.866666 -146.7645 -153.0059 3.533333 -145.9008 -153.7561 -1.866666 -147.716 -153.467 3.533333 -146.7645 -153.8518 -1.866666 -148.6991 -153.7561 3.533333 -147.716 -153.7561 -1.866666 -149.6822 -153.8518 3.533334 -148.6991 -157.5781 -1.866666 -147.2731 -153.467 -1.866666 -150.6337 -153.7561 3.533334 -149.6822 -153.0019 -1.866666 -151.5029 -153.467 3.533334 -150.6337 -152.3738 -1.866665 -152.27 -153.0019 3.533334 -151.5029 -139.6809 -1.866665 -163.6332 -151.6067 -1.866665 -152.898 -152.3738 3.533334 -152.27 -156.8769 -1.866666 -147.9743 -148.0781 -1.866665 -156.7731 -150.7375 -1.866665 -153.3631 -151.6067 3.533334 -152.898 -149.786 -1.866665 -153.6523 -150.7375 3.533334 -153.3631 -148.8029 -1.866665 -153.748 -149.786 3.533334 -153.6523 -136.8288 -1.866665 -161.4609 -147.8199 -1.866666 -153.6523 -148.8029 3.533334 -153.748 -146.8684 -1.866666 -153.3632 -147.8199 3.533334 -153.6523 -146.0046 -1.866666 -152.902 -146.8684 3.533334 -153.3632 -145.232 -1.866666 -152.27 -146.0046 3.533334 -152.902 -134.4791 -1.866665 -158.7527 -144.6 -1.866666 -151.4974 -145.232 3.533334 -152.27 -144.1389 -1.866666 -150.6337 -144.6 3.533334 -151.4974 -143.8498 -1.866666 -149.6821 -144.1389 3.533334 -150.6337 -143.7541 -1.866666 -148.6991 -143.8498 3.533334 -149.6821 -132.7306 -1.866666 -155.6223 -143.8497 -1.866667 -147.716 -143.7541 3.533333 -148.6991 -140.0278 -1.866666 -150.1251 -144.1389 -1.866667 -146.7645 -143.8497 3.533333 -147.716 -144.604 -1.866667 -145.8953 -144.1389 3.533333 -146.7645 -145.232 -1.866667 -145.1282 -144.604 3.533333 -145.8953 -149.5278 -1.866667 -140.6251 -145.9991 -1.866667 -144.5002 -145.232 3.533333 -145.1282 -140.7289 -1.866666 -149.4239 -158.8565 -1.866668 -134.3753 -146.8683 -1.866667 -144.035 -145.9991 3.533333 -144.5002 -147.8199 -1.866667 -143.7459 -146.8683 3.533333 -144.035 -148.8029 -1.866667 -143.6502 -147.8199 3.533333 -143.7459 -149.786 -1.866667 -143.7459 -148.8029 3.533333 -143.6502 -150.7375 -1.866667 -144.035 -149.786 3.533333 -143.7459 -150.7375 3.533333 -144.035 -155.7261 -1.866668 -132.6268 -150.3825 -1.866667 -138.9497 -149.9343 -1.866667 -138.0677 -149.9343 3.533332 -138.0677 -149.0523 -1.866668 -137.6195 -149.0523 3.533332 -137.6195 -150.2289 -1.866667 -139.9239 -150.3825 3.533332 -138.9497 -150.2289 3.533332 -139.9239 -140.8825 -1.866667 -148.4497 -148.5535 -1.866667 -140.7787 -149.5278 3.533332 -140.6251 -140.4343 -1.866667 -147.5677 -147.6716 -1.866667 -140.3305 -148.5535 3.533332 -140.7787 -139.5523 -1.866667 -147.1195 -147.2233 -1.866667 -139.4485 -147.6716 3.533332 -140.3305 -138.5781 -1.866667 -147.2731 -147.3769 -1.866667 -138.4743 -147.2233 3.533332 -139.4485 -131.6568 -1.866666 -152.2005 -148.0781 -1.866668 -137.7731 -147.3769 3.533332 -138.4743 -148.0781 3.533332 -137.7731 -152.3043 -1.866668 -131.5529 -140.4343 3.533333 -147.5677 -139.5523 3.533333 -147.1195 -140.8825 3.533333 -148.4497 -140.7289 3.533333 -149.4239 -139.0535 -1.866666 -150.2787 -140.0278 3.533333 -150.1251 -138.1716 -1.866666 -149.8305 -139.0535 3.533333 -150.2787 -137.7233 -1.866667 -148.9485 -138.1716 3.533333 -149.8305 -137.8769 -1.866667 -147.9743 -137.7233 3.533333 -148.9485 -137.8769 3.533333 -147.9743 -138.5781 3.533333 -147.2731 -158.0535 -1.866666 -150.2787 -150.3825 -1.866665 -157.9497 -149.9343 -1.866665 -157.0677 -149.9343 3.533335 -157.0677 -157.1716 -1.866666 -149.8305 -149.0523 -1.866665 -156.6195 -149.0523 3.533335 -156.6195 -159.0278 -1.866665 -150.1251 -150.2289 -1.866665 -158.9239 -150.3825 3.533335 -157.9497 -166.1361 -1.866666 -146.2932 -149.5278 -1.866665 -159.6251 -150.2289 3.533335 -158.9239 -142.9155 -1.866664 -165.1786 -148.5535 -1.866665 -159.7787 -149.5278 3.533335 -159.6251 -147.6716 -1.866665 -159.3305 -148.5535 3.533335 -159.7787 -147.2233 -1.866665 -158.4485 -147.6716 3.533335 -159.3305 -147.3769 -1.866665 -157.4743 -147.2233 3.533335 -158.4485 -147.3769 3.533335 -157.4743 -156.7233 -1.866666 -148.9485 -148.0781 3.533335 -156.7731 -165.2824 -1.866666 -142.8117 -159.8825 -1.866666 -148.4497 -159.4343 -1.866666 -147.5677 -159.4343 3.533334 -147.5677 -158.5523 -1.866666 -147.1195 -158.5523 3.533334 -147.1195 -159.7289 -1.866666 -149.4239 -159.8825 3.533334 -148.4497 -159.7289 3.533334 -149.4239 -159.0278 3.533334 -150.1251 -158.0535 3.533334 -150.2787 -157.1716 3.533334 -149.8305 -156.7233 3.533334 -148.9485 -156.8769 3.533334 -147.9743 -157.5781 3.533334 -147.2731 -147.3809 -1.866669 -130.1657 -141.8553 -1.866668 -136.5248 -140.9894 -1.866668 -135.2287 -140.9894 3.533331 -135.2287 -139.6933 -1.866668 -134.3628 -139.6933 3.533331 -134.3628 -142.1601 -1.866668 -138.0571 -141.8553 3.533332 -136.5248 -141.8553 -1.866668 -139.5895 -142.1601 3.533332 -138.0571 -140.9894 -1.866667 -140.8856 -141.8553 3.533332 -139.5895 -139.6933 -1.866667 -141.7514 -140.9894 3.533332 -140.8856 -130.2695 -1.866667 -147.277 -138.161 -1.866667 -142.0562 -139.6933 3.533332 -141.7514 -136.6286 -1.866668 -141.7514 -138.161 3.533332 -142.0562 -135.3325 -1.866668 -140.8856 -136.6286 3.533332 -141.7514 -128.1886 -1.866668 -142.6264 -134.4667 -1.866668 -139.5895 -135.3325 3.533332 -140.8856 -134.1619 -1.866668 -138.0571 -134.4667 3.533331 -139.5895 -134.4667 -1.866668 -136.5248 -134.1619 3.533331 -138.0571 -135.3325 -1.866668 -135.2287 -134.4667 3.533331 -136.5248 -142.7302 -1.866669 -128.0848 -136.6286 -1.866669 -134.3628 -135.3325 3.533331 -135.2287 -125.4559 -1.866669 -138.3263 -138.161 -1.866669 -134.058 -136.6286 3.533331 -134.3628 -138.161 3.533331 -134.058 -48.81804 -1.866686 -27.43029 -46.03495 -1.866686 -31.43134 -45.60071 -1.866686 -30.57692 -45.60071 3.533314 -30.57692 -44.74629 -1.866686 -30.14268 -44.74629 3.533314 -30.14268 -59.56607 -1.866685 -38.17831 -45.88613 -1.866686 -32.37511 -46.03495 3.533314 -31.43134 -45.20687 -1.866686 -33.05437 -45.88613 3.533314 -32.37511 -47.1917 -1.866684 -43.12806 -44.26309 -1.866686 -33.20319 -45.20687 3.533314 -33.05437 -34.46378 -1.866687 -30.40015 -43.40867 -1.866686 -32.76895 -44.26309 3.533314 -33.20319 -42.97443 -1.866686 -31.91453 -43.40867 3.533314 -32.76895 -43.12326 -1.866686 -30.97076 -42.97443 3.533314 -31.91453 -43.80251 -1.866686 -30.2915 -43.12326 3.533314 -30.97076 -48.05736 -1.866687 -26.80669 -43.80251 3.533314 -30.2915 -47.19572 -1.866687 -26.34694 -43.2319 -1.866684 -47.08786 -33.30703 -1.866685 -44.15925 -32.87279 -1.866685 -43.30484 -32.87279 3.533315 -43.30484 -32.01837 -1.866685 -42.87059 -32.01837 3.533315 -42.87059 -33.15821 -1.866685 -45.10303 -33.30703 3.533315 -44.15925 -32.47895 -1.866685 -45.78229 -33.15821 3.533315 -45.10303 -27.53413 -1.866685 -48.7142 -31.53517 -1.866685 -45.93111 -32.47895 3.533315 -45.78229 -30.68076 -1.866685 -45.49687 -31.53517 3.533315 -45.93111 -26.91052 -1.866685 -47.95352 -30.24651 -1.866685 -44.64245 -30.68076 3.533315 -45.49687 -30.39533 -1.866685 -43.69868 -30.24651 3.533315 -44.64245 -26.45078 -1.866685 -47.09188 -31.07459 -1.866685 -43.01942 -30.39533 3.533315 -43.69868 -26.06967 -1.866686 -40.86532 -31.07459 3.533315 -43.01942 -26.06966 -1.866685 -45.17867 -26.16659 -1.866685 -46.15751 -26.16659 -1.866686 -39.88648 -56.64155 -1.866684 -42.03794 -56.20731 -1.866684 -41.18352 -56.20731 3.533316 -41.18352 -55.35289 -1.866684 -40.74927 -55.35289 3.533316 -40.74927 -61.61776 -1.866684 -40.73709 -56.49272 -1.866684 -42.98171 -56.64155 3.533316 -42.03794 -55.81347 -1.866684 -43.66096 -56.49272 3.533316 -42.98171 -50.90401 -1.866684 -46.84037 -54.8697 -1.866684 -43.80979 -55.81347 3.533316 -43.66096 -54.01528 -1.866684 -43.37555 -54.8697 3.533316 -43.80979 -42.62497 -1.866683 -53.47719 -53.58103 -1.866684 -42.52113 -54.01528 3.533316 -43.37555 -43.47939 -1.866683 -53.91144 -41.68119 -1.866683 -53.62602 -53.72986 -1.866684 -41.57735 -53.58103 3.533316 -42.52113 -54.40911 -1.866684 -40.8981 -53.72986 3.533316 -41.57735 -54.40911 3.533316 -40.8981 -46.94421 -1.866683 -50.80017 -43.91363 -1.866683 -54.76586 -43.47939 3.533317 -53.91144 -42.62497 3.533317 -53.47719 -54.1567 -1.866682 -58.01266 -43.7648 -1.866683 -55.70963 -43.91363 3.533317 -54.76586 -43.08555 -1.866683 -56.38889 -43.7648 3.533317 -55.70963 -38.28215 -1.866683 -59.46223 -42.14178 -1.866683 -56.53771 -43.08555 3.533317 -56.38889 -40.84093 -1.866682 -61.51392 -41.28736 -1.866683 -56.10347 -42.14178 3.533317 -56.53771 -40.85311 -1.866683 -55.24905 -41.28736 3.533317 -56.10347 -41.00194 -1.866683 -54.30528 -40.85311 3.533317 -55.24905 -41.00194 3.533317 -54.30528 -41.68119 3.533317 -53.62602 -61.84459 -1.866682 -59.05274 -61.47526 -1.866682 -58.54298 -61.47526 3.533318 -58.54298 -60.9655 -1.866682 -58.17365 -60.9655 3.533318 -58.17365 -62.03557 -1.866682 -59.64545 -61.84459 3.533318 -59.05274 -62.03557 -1.866682 -60.26894 -62.03557 3.533318 -59.64545 -61.84354 -1.866681 -60.86324 -62.03557 3.533318 -60.26894 -61.47525 -1.866681 -61.37141 -61.84354 3.533318 -60.86324 -60.96708 -1.866681 -61.7397 -61.47525 3.533318 -61.37141 -53.10307 -1.866681 -65.9514 -60.37278 -1.866681 -61.93173 -60.96708 3.533318 -61.7397 -59.7493 -1.866681 -61.93172 -60.37278 3.533318 -61.93173 -59.15658 -1.866681 -61.74075 -59.7493 3.533318 -61.93172 -58.64683 -1.866682 -61.37141 -59.15658 3.533318 -61.74075 -58.27749 -1.866682 -60.86166 -58.64683 3.533318 -61.37141 -58.08651 -1.866682 -60.26894 -58.27749 3.533318 -60.86166 -50.15955 -1.866681 -64.50486 -58.08651 -1.866682 -59.64546 -58.08651 3.533318 -60.26894 -58.27854 -1.866682 -59.05116 -58.08651 3.533318 -59.64546 -58.64683 -1.866682 -58.54299 -58.27854 3.533318 -59.05116 -66.05523 -1.866682 -52.99923 -59.155 -1.866682 -58.1747 -58.64683 3.533318 -58.54299 -59.7493 -1.866682 -57.98267 -59.155 3.533318 -58.1747 -60.37278 -1.866682 -57.98267 -59.7493 3.533318 -57.98267 -60.37278 3.533318 -57.98267 -26.91052 -1.866686 -38.09046 -27.53413 -1.866686 -37.32979 -27.53413 3.533314 -37.32979 -30.50398 -1.866686 -34.35994 -26.45077 -1.866686 -38.95211 -26.91052 3.533314 -38.09046 -26.45077 3.533314 -38.95211 -26.16659 3.533314 -39.88648 -26.06966 3.533315 -45.17867 -26.06967 3.533314 -40.86532 -26.16659 3.533315 -46.15751 -26.45078 3.533315 -47.09188 -26.91052 3.533315 -47.95352 -27.53413 3.533315 -48.7142 -38.28215 3.533317 -59.46223 -43.78445 -1.866682 -62.96044 -40.84093 3.533318 -61.51392 -46.972 -1.866682 -63.73265 -43.78445 3.533318 -62.96044 -64.60871 -1.866683 -50.05571 -46.972 3.533318 -63.73265 -50.15955 3.533318 -64.50486 -53.10307 3.533318 -65.9514 -55.66184 3.533319 -68.00308 -63.63193 -1.866681 -62.39672 -95.66387 -1.866675 -99.51982 -95.14746 -1.866675 -98.62448 -95.14746 -1.866675 -97.58673 -65.47042 -1.86668 -69.32637 -62.50056 -1.866681 -66.35652 -61.98416 -1.866681 -65.46118 -61.98415 -1.866681 -64.42343 -62.50056 -1.866681 -63.52809 -138.4301 -1.86667 -125.3521 -122.1132 3.53333 -134.4545 -127.3422 -1.86667 -128.3698 -126.4469 -1.86667 -128.8862 -125.4092 -1.86667 -128.8862 -125.4559 3.533331 -138.3263 -128.1886 3.533332 -142.6264 -130.2695 3.533333 -147.277 -131.6568 3.533333 -152.2005 -132.7306 3.533334 -155.6223 -134.4791 3.533334 -158.7527 -136.8288 3.533335 -161.4609 -139.6809 3.533335 -163.6332 -146.397 -1.866664 -166.0323 -142.9155 3.533336 -165.1786 -166.2626 -1.866665 -149.8754 -149.9792 -1.866664 -166.1588 -146.397 3.533336 -166.0323 -165.6566 -1.866665 -153.4081 -153.5119 -1.866664 -165.5528 -149.9792 3.533336 -166.1588 -164.3437 -1.866664 -156.7431 -156.8469 -1.866664 -164.2398 -153.5119 3.533336 -165.5528 -162.3788 -1.866664 -159.7406 -159.8444 -1.866664 -162.2749 -156.8469 3.533336 -164.2398 -159.8444 3.533336 -162.2749 -162.3788 3.533336 -159.7406 -164.3437 3.533335 -156.7431 -165.6566 3.533335 -153.4081 -166.2626 3.533335 -149.8754 -166.1361 3.533334 -146.2932 -165.2824 3.533334 -142.8117 -163.737 3.533333 -139.577 -161.5647 3.533333 -136.725 -158.8565 3.533332 -134.3753 -155.7261 3.533332 -132.6268 -152.3043 3.533331 -131.5529 -147.3809 3.533331 -130.1657 -142.7302 3.533331 -128.0848 -138.4301 3.53333 -125.3521 -134.5583 3.533329 -122.0094 -122.8168 -1.866671 -118.7531 -128.4736 -1.86667 -124.41 -128.99 -1.86667 -125.3053 -128.99 -1.86667 -126.3431 -128.4736 -1.86667 -127.2384 -93.069 -1.866676 -90.42205 -92.55259 -1.866677 -88.48896 -93.069 -1.866676 -89.3843 -68.10692 3.533318 -55.55801 -64.52727 -1.866681 -61.88031 -65.56502 -1.866681 -61.88031 -66.05523 3.533318 -52.99923 -58.1165 -1.866683 -54.05286 -63.83649 -1.866683 -46.86816 -64.60871 3.533317 -50.05571 -63.06429 -1.866684 -43.68061 -63.83649 3.533316 -46.86816 -63.06429 3.533316 -43.68061 -61.61776 3.533316 -40.73709 -59.56607 3.533315 -38.17831 -48.81804 3.533313 -27.43029 -48.05736 3.533313 -26.80669 -46.26134 -1.866687 -26.06275 -47.19572 3.533313 -26.34694 -45.28251 -1.866687 -25.96583 -46.26134 3.533313 -26.06275 -40.96916 -1.866687 -25.96583 -40.96916 3.533313 -25.96583 -45.28251 3.533313 -25.96583 -39.99032 -1.866687 -26.06275 -39.05595 -1.866687 -26.34694 -39.99032 3.533313 -26.06275 -38.1943 -1.866687 -26.80669 -39.05595 3.533313 -26.34694 -37.43362 -1.866687 -27.4303 -38.1943 3.533313 -26.80669 -34.46378 3.533313 -30.40015 -37.43362 3.533313 -27.4303 -47.1917 3.533316 -43.12806 -43.2319 3.533316 -47.08786 -30.50398 3.533313 -34.35994 -119.9883 3.533329 -118.7531 -118.3406 3.533329 -120.7798 -118.857 3.533329 -119.8845 -120.8837 3.533329 -118.2367 -121.9214 3.533329 -118.2367 -122.8168 3.533329 -118.7531 -128.4736 3.533329 -124.41 -128.99 3.53333 -125.3053 -128.99 3.53333 -126.3431 -127.3422 3.53333 -128.3698 -128.4736 3.53333 -127.2384 -126.4469 3.53333 -128.8862 -125.4092 3.53333 -128.8862 -124.5138 3.533329 -128.3698 -118.857 3.533329 -122.7129 -118.3406 3.533329 -121.8176 -112.988 3.533328 -114.0155 -112.0926 3.533328 -114.5319 -111.0549 3.533327 -114.5319 -110.1596 3.533327 -114.0155 -95.66387 3.533325 -99.51982 -95.14746 3.533325 -98.62448 -95.66386 -1.866675 -96.69139 -95.14746 3.533324 -97.58673 -89.48813 -1.866676 -92.96516 -96.79524 -1.866675 -95.56002 -96.79524 3.533324 -95.56002 -95.66386 3.533324 -96.69139 -91.42122 -1.866676 -92.44876 -97.69057 -1.866675 -95.0436 -90.52588 -1.866676 -92.96516 -98.72834 -1.866675 -95.04361 -97.69057 3.533324 -95.0436 -92.5526 -1.866676 -91.31737 -98.72834 3.533325 -95.04361 -99.62366 3.533325 -95.56002 -114.1194 3.533327 -110.0557 -114.6358 3.533327 -110.951 -114.6358 3.533328 -111.9888 -114.1194 3.533328 -112.8841 -75.2285 3.53332 -73.99327 -73.58071 3.53332 -76.01998 -74.09711 3.53332 -75.12464 -76.12382 3.53332 -73.47686 -77.16159 3.533321 -73.47686 -78.05691 3.533321 -73.99327 -92.55259 3.533323 -88.48896 -93.069 3.533323 -89.3843 -93.069 3.533324 -90.42205 -91.42122 3.533324 -92.44876 -92.5526 3.533324 -91.31737 -90.52588 3.533324 -92.96516 -89.48813 3.533323 -92.96516 -88.5928 3.533323 -92.44876 -74.09712 3.533321 -77.95307 -73.58071 3.533321 -77.05773 -68.29883 3.533319 -69.32637 -67.40349 3.533319 -69.84278 -66.36576 3.533319 -69.84278 -62.50056 3.533319 -66.35652 -65.47042 3.533319 -69.32637 -61.98416 3.533318 -65.46118 -61.98415 3.533318 -64.42343 -63.63193 3.533318 -62.39672 -62.50056 3.533318 -63.52809 -64.52727 3.533318 -61.88031 -65.56502 3.533318 -61.88031 -69.4302 3.533319 -65.36656 -66.46035 3.533319 -62.39672 -69.94662 3.533319 -66.2619 -69.94661 3.533319 -67.29965 -69.43021 3.533319 -68.19499 -54.1567 3.533318 -58.01266 -58.1165 3.533318 -54.05286 -46.94421 3.533316 -50.80017 -50.90401 3.533316 -46.84037 -122.1132 -1.866704 134.7482 -69.01182 -1.866699 76.63045 -68.1574 -1.866699 76.1962 -68.1574 3.533301 76.19622 -62.50055 -1.866698 66.65026 -67.72315 -1.866699 75.34178 -67.72315 3.533301 75.34178 -55.66184 -1.866699 68.29682 -69.9556 -1.866699 76.48162 -69.01182 3.533301 76.63045 -70.63485 -1.866699 75.80236 -69.9556 3.533301 76.48162 -74.66867 -1.866698 70.9736 -70.78369 -1.866699 74.85859 -70.63485 3.533301 75.80236 -75.61245 -1.866698 70.82476 -73.58069 -1.866699 76.31372 -74.0971 -1.866699 78.24681 -73.58069 -1.866699 77.35148 -73.81427 -1.866698 70.53936 -70.34943 -1.866699 74.00418 -70.78369 3.533301 74.85859 -73.38002 -1.866698 69.68493 -69.49501 -1.866699 73.56993 -70.34943 3.533301 74.00418 -73.52884 -1.866698 68.74115 -68.55124 -1.866699 73.71875 -69.49501 3.533301 73.56993 -69.9466 -1.866698 67.59339 -67.87199 -1.866699 74.39801 -68.55124 3.533301 73.71875 -68.29882 -1.866698 69.62011 -67.87199 3.533301 74.39801 -69.43019 -1.866698 68.48873 -65.47039 -1.866698 69.6201 -66.36573 -1.866698 70.13652 -67.40348 -1.866698 70.13652 -113.5595 -1.866703 121.1782 -112.7051 -1.866703 120.7439 -112.7051 3.533297 120.7439 -95.66385 -1.866701 99.81356 -112.2709 -1.866703 119.8895 -112.2709 3.533297 119.8895 -114.5033 -1.866703 121.0293 -113.5595 3.533297 121.1782 -115.1826 -1.866703 120.3501 -114.5033 3.533297 121.0293 -119.2164 -1.866702 115.5213 -115.3314 -1.866703 119.4063 -115.1826 3.533297 120.3501 -120.1602 -1.866702 115.3725 -118.3405 -1.866703 121.0736 -118.3405 -1.866703 122.1113 -118.362 -1.866702 115.0871 -114.8972 -1.866703 118.5519 -115.3314 3.533297 119.4063 -117.9277 -1.866702 114.2327 -114.0427 -1.866703 118.1176 -114.8972 3.533297 118.5519 -118.0765 -1.866702 113.2889 -113.0989 -1.866703 118.2665 -114.0427 3.533297 118.1176 -114.6357 -1.866702 112.2825 -112.4197 -1.866703 118.9457 -113.0989 3.533297 118.2665 -112.988 -1.866702 114.3093 -112.4197 3.533297 118.9457 -114.1193 -1.866702 113.1779 -110.1595 -1.866702 114.3093 -111.0549 -1.866702 114.8257 -112.0926 -1.866702 114.8257 -118.362 3.533298 115.0871 -117.9277 3.533298 114.2327 -119.2164 3.533298 115.5213 -120.8394 -1.866702 114.6932 -120.1602 3.533298 115.3725 -120.8837 -1.866702 118.5305 -120.9883 -1.866702 113.7495 -120.8394 3.533298 114.6932 -118.8569 -1.866703 120.1782 -119.9883 -1.866703 119.0469 -128.4736 -1.866703 124.7037 -120.554 -1.866702 112.895 -120.9883 3.533298 113.7495 -122.8167 -1.866702 119.0469 -121.9214 -1.866702 118.5305 -68.10691 -1.866696 55.85174 -119.6996 -1.866702 112.4608 -120.554 3.533298 112.895 -134.5583 -1.866702 122.3031 -118.7558 -1.866702 112.6096 -119.6996 3.533298 112.4608 -118.7558 3.533298 112.6096 -118.0765 3.533298 113.2889 -114.1193 -1.866702 110.3495 -114.6357 -1.866702 111.2448 -73.81427 3.533302 70.53936 -73.38002 3.533302 69.68493 -74.66867 3.533302 70.9736 -76.2917 -1.866698 70.14551 -75.61245 3.533302 70.82476 -76.12381 -1.866698 73.7706 -76.44053 -1.866698 69.20174 -76.2917 3.533302 70.14551 -74.09709 -1.866699 75.41839 -75.22847 -1.866699 74.28701 -92.55258 -1.8667 88.7827 -76.00629 -1.866698 68.34732 -76.44053 3.533302 69.20174 -78.0569 -1.866698 74.28702 -77.16156 -1.866698 73.77061 -75.15187 -1.866698 67.91307 -76.00629 3.533302 68.34732 -74.20809 -1.866698 68.0619 -75.15187 3.533302 67.91307 -74.20809 3.533302 68.0619 -73.52884 3.533302 68.74115 -69.9466 -1.866698 66.55565 -136.8288 -1.866707 161.7546 -146.0046 -1.866706 153.1958 -145.232 -1.866706 152.5637 -145.232 3.533294 152.5637 -144.6 -1.866706 151.7911 -144.6 3.533294 151.7911 -139.6808 -1.866708 163.9269 -146.8683 -1.866706 153.6569 -146.0046 3.533294 153.1958 -147.8199 -1.866706 153.946 -146.8683 3.533294 153.6569 -148.8029 -1.866706 154.0417 -147.8199 3.533294 153.946 -149.786 -1.866706 153.946 -148.8029 3.533294 154.0417 -147.3769 -1.866706 157.768 -150.7375 -1.866706 153.6569 -149.786 3.533294 153.946 -151.6067 -1.866706 153.1918 -150.7375 3.533294 153.6569 -152.3738 -1.866706 152.5637 -151.6067 3.533294 153.1918 -163.737 -1.866703 139.8708 -153.0018 -1.866705 151.7966 -152.3738 3.533294 152.5637 -148.0781 -1.866706 157.0668 -156.8769 -1.866705 148.268 -153.4669 -1.866705 150.9274 -153.0018 3.533294 151.7966 -153.7561 -1.866705 149.9759 -153.4669 3.533295 150.9274 -153.8518 -1.866705 148.9928 -153.7561 3.533295 149.9759 -161.5647 -1.866703 137.0187 -153.7561 -1.866705 148.0098 -153.8518 3.533295 148.9928 -153.467 -1.866705 147.0583 -153.7561 3.533295 148.0098 -153.0058 -1.866705 146.1945 -153.467 3.533295 147.0583 -152.3738 -1.866705 145.4219 -153.0058 3.533295 146.1945 -158.8565 -1.866703 134.669 -151.6012 -1.866705 144.7899 -152.3738 3.533295 145.4219 -150.7375 -1.866704 144.3288 -151.6012 3.533295 144.7899 -149.7859 -1.866704 144.0397 -150.7375 3.533295 144.3288 -148.8029 -1.866705 143.944 -149.7859 3.533295 144.0397 -155.7261 -1.866703 132.9205 -147.8198 -1.866705 144.0396 -148.8029 3.533295 143.944 -150.2289 -1.866704 140.2176 -146.8683 -1.866705 144.3288 -147.8198 3.533295 144.0397 -145.9991 -1.866705 144.7939 -146.8683 3.533295 144.3288 -145.232 -1.866705 145.4219 -145.9991 3.533295 144.7939 -140.7289 -1.866706 149.7176 -144.604 -1.866705 146.189 -145.232 3.533295 145.4219 -149.5277 -1.866704 140.9188 -134.4791 -1.866707 159.0464 -144.1389 -1.866705 147.0582 -144.604 3.533295 146.189 -143.8497 -1.866705 148.0098 -144.1388 3.533294 147.0583 -143.754 -1.866705 148.9928 -143.8497 3.533294 148.0098 -143.8497 -1.866706 149.9759 -143.754 3.533294 148.9928 -144.1388 -1.866706 150.9274 -143.8497 3.533294 149.9759 -144.1388 3.533294 150.9274 -132.7306 -1.866707 155.916 -139.0535 -1.866706 150.5724 -138.1715 -1.866706 150.1242 -138.1715 3.533294 150.1242 -137.7233 -1.866706 149.2422 -137.7233 3.533294 149.2422 -140.0277 -1.866706 150.4188 -139.0535 3.533294 150.5724 -140.0277 3.533294 150.4188 -148.5535 -1.866704 141.0724 -140.8825 -1.866706 148.7434 -140.7289 3.533294 149.7176 -147.6715 -1.866704 140.6242 -140.4343 -1.866705 147.8614 -140.8825 3.533294 148.7434 -147.2233 -1.866704 139.7422 -139.5523 -1.866705 147.4132 -140.4343 3.533295 147.8614 -147.3769 -1.866704 138.768 -138.5781 -1.866705 147.5668 -139.5523 3.533295 147.4132 -152.3043 -1.866703 131.8467 -137.8769 -1.866706 148.268 -138.5781 3.533294 147.5668 -137.8769 3.533294 148.268 -131.6567 -1.866706 152.4942 -147.6715 3.533296 140.6242 -147.2233 3.533296 139.7422 -148.5535 3.533295 141.0724 -149.5277 3.533296 140.9188 -150.3825 -1.866704 139.2434 -150.2289 3.533296 140.2176 -149.9343 -1.866704 138.3615 -150.3825 3.533296 139.2434 -149.0523 -1.866704 137.9132 -149.9343 3.533296 138.3615 -148.0781 -1.866704 138.0668 -149.0523 3.533296 137.9132 -148.0781 3.533296 138.0668 -147.3769 3.533296 138.768 -150.3825 -1.866706 158.2434 -158.0535 -1.866705 150.5724 -157.1715 -1.866705 150.1242 -157.1715 3.533295 150.1242 -149.9343 -1.866706 157.3614 -156.7233 -1.866705 149.2422 -156.7233 3.533295 149.2422 -150.2289 -1.866706 159.2176 -159.0277 -1.866705 150.4188 -158.0535 3.533295 150.5724 -146.397 -1.866708 166.326 -159.7289 -1.866705 149.7176 -159.0277 3.533295 150.4188 -165.2824 -1.866704 143.1054 -159.8825 -1.866705 148.7434 -159.7289 3.533295 149.7176 -159.4343 -1.866705 147.8615 -159.8825 3.533295 148.7434 -158.5523 -1.866705 147.4132 -159.4343 3.533295 147.8615 -157.5781 -1.866705 147.5668 -158.5523 3.533295 147.4132 -157.5781 3.533295 147.5668 -149.0523 -1.866706 156.9132 -156.8769 3.533295 148.268 -142.9155 -1.866708 165.4723 -148.5535 -1.866707 160.0724 -147.6715 -1.866707 159.6242 -147.6715 3.533293 159.6242 -147.2233 -1.866706 158.7422 -147.2233 3.533293 158.7422 -149.5277 -1.866707 159.9188 -148.5535 3.533293 160.0724 -149.5277 3.533293 159.9188 -150.2289 3.533293 159.2176 -150.3825 3.533294 158.2434 -149.9343 3.533294 157.3614 -149.0523 3.533294 156.9132 -148.0781 3.533293 157.0668 -147.3769 3.533293 157.768 -130.2695 -1.866706 147.5708 -136.6286 -1.866705 142.0452 -135.3325 -1.866705 141.1793 -135.3325 3.533295 141.1793 -134.4666 -1.866705 139.8832 -134.4666 3.533295 139.8832 -138.1609 -1.866705 142.35 -136.6286 3.533295 142.0452 -139.6933 -1.866705 142.0452 -138.1609 3.533295 142.35 -140.9894 -1.866704 141.1793 -139.6933 3.533295 142.0452 -141.8553 -1.866704 139.8832 -140.9894 3.533295 141.1793 -147.3809 -1.866703 130.4594 -142.16 -1.866704 138.3509 -141.8553 3.533295 139.8832 -141.8553 -1.866704 136.8185 -142.16 3.533296 138.3509 -140.9894 -1.866704 135.5224 -141.8553 3.533296 136.8185 -142.7302 -1.866703 128.3785 -139.6933 -1.866704 134.6566 -140.9894 3.533296 135.5224 -138.1609 -1.866704 134.3518 -139.6933 3.533296 134.6566 -136.6286 -1.866704 134.6566 -138.1609 3.533296 134.3518 -135.3325 -1.866704 135.5224 -136.6286 3.533296 134.6566 -128.1886 -1.866705 142.9201 -134.4667 -1.866704 136.8185 -135.3325 3.533296 135.5224 -138.4301 -1.866703 125.6458 -134.1618 -1.866704 138.3509 -134.4667 3.533296 136.8185 -134.1618 3.533295 138.3509 -27.53412 -1.866697 49.00794 -31.53517 -1.866697 46.22485 -30.68075 -1.866697 45.79061 -30.68075 3.533303 45.79061 -30.24651 -1.866697 44.93619 -30.24651 3.533303 44.93619 -38.28215 -1.866698 59.75597 -32.47894 -1.866697 46.07603 -31.53517 3.533303 46.22485 -33.1582 -1.866697 45.39677 -32.47894 3.533303 46.07603 -43.23189 -1.866696 47.3816 -33.30702 -1.866697 44.45299 -33.1582 3.533303 45.39677 -30.50397 -1.866695 34.65368 -32.87278 -1.866696 43.59857 -33.30702 3.533303 44.45299 -32.01836 -1.866696 43.16433 -32.87278 3.533303 43.59857 -31.07459 -1.866696 43.31315 -32.01836 3.533303 43.16433 -30.39533 -1.866697 43.99241 -31.07459 3.533303 43.31315 -26.91052 -1.866697 48.24726 -30.39533 3.533303 43.99241 -26.45077 -1.866697 47.38562 -47.19169 -1.866696 43.4218 -44.26309 -1.866695 33.49693 -43.40867 -1.866695 33.06269 -43.40867 3.533305 33.06269 -42.97443 -1.866694 32.20827 -42.97443 3.533305 32.20827 -45.20687 -1.866695 33.34811 -44.26309 3.533305 33.49693 -45.88612 -1.866694 32.66885 -45.20687 3.533305 33.34811 -48.81803 -1.866694 27.72403 -46.03495 -1.866694 31.72507 -45.88612 3.533305 32.66885 -45.6007 -1.866694 30.87065 -46.03495 3.533306 31.72507 -48.05736 -1.866694 27.10042 -44.74628 -1.866694 30.43641 -45.6007 3.533306 30.87065 -43.80251 -1.866694 30.58523 -44.74628 3.533306 30.43641 -47.19571 -1.866694 26.64067 -43.12325 -1.866694 31.26449 -43.80251 3.533305 30.58523 -40.96915 -1.866694 26.25956 -43.12325 3.533305 31.26449 -45.2825 -1.866694 26.25956 -46.26134 -1.866694 26.35648 -39.99031 -1.866694 26.35648 -42.14177 -1.866698 56.83145 -41.28735 -1.866698 56.39721 -41.28735 3.533302 56.39721 -40.8531 -1.866698 55.54279 -40.8531 3.533302 55.54279 -40.84092 -1.866698 61.80766 -43.08554 -1.866698 56.68262 -42.14177 3.533302 56.83145 -43.7648 -1.866698 56.00337 -43.08554 3.533302 56.68262 -46.9442 -1.866697 51.09391 -43.91363 -1.866697 55.0596 -43.7648 3.533302 56.00337 -43.47938 -1.866697 54.20518 -43.91363 3.533302 55.0596 -53.58102 -1.866695 42.81487 -42.62496 -1.866697 53.77093 -43.47938 3.533302 54.20518 -54.01527 -1.866696 43.66929 -53.72985 -1.866695 41.87109 -41.68119 -1.866697 53.91976 -42.62496 3.533302 53.77093 -41.00193 -1.866698 54.59901 -41.68119 3.533302 53.91976 -41.00193 3.533302 54.59901 -50.904 -1.866696 47.13411 -54.86969 -1.866696 44.10353 -54.01527 3.533304 43.66929 -53.58102 3.533304 42.81487 -58.11649 -1.866697 54.34659 -55.81346 -1.866696 43.9547 -54.86969 3.533304 44.10353 -56.49272 -1.866695 43.27545 -55.81346 3.533304 43.95471 -59.56606 -1.866695 38.47205 -56.64155 -1.866695 42.33168 -56.49272 3.533304 43.27545 -61.61775 -1.866695 41.03083 -56.2073 -1.866695 41.47726 -56.64155 3.533305 42.33168 -55.35288 -1.866695 41.04301 -56.2073 3.533305 41.47726 -54.40911 -1.866695 41.19184 -55.35288 3.533305 41.04301 -54.40911 3.533304 41.19184 -53.72985 3.533304 41.8711 -59.15657 -1.866698 62.03449 -58.64682 -1.866698 61.66516 -58.64682 3.533302 61.66516 -58.27748 -1.866698 61.1554 -58.27748 3.533302 61.1554 -59.74929 -1.866698 62.22547 -59.15657 3.533302 62.03449 -60.37277 -1.866698 62.22547 -59.74929 3.533302 62.22547 -60.96707 -1.866698 62.03344 -60.37277 3.533302 62.22547 -61.47525 -1.866698 61.66515 -60.96707 3.533302 62.03344 -61.84353 -1.866697 61.15698 -61.47525 3.533302 61.66515 -66.05522 -1.866696 53.29297 -62.03556 -1.866697 60.56268 -61.84353 3.533302 61.15698 -62.03556 -1.866697 59.9392 -62.03556 3.533302 60.56268 -61.84458 -1.866697 59.34648 -62.03556 3.533302 59.9392 -61.47525 -1.866697 58.83673 -61.84458 3.533302 59.34648 -60.96549 -1.866697 58.46739 -61.47525 3.533303 58.83673 -60.37277 -1.866697 58.27641 -60.96549 3.533302 58.46739 -64.60869 -1.866696 50.34945 -59.74929 -1.866697 58.27641 -60.37277 3.533302 58.27641 -59.15499 -1.866697 58.46844 -59.74929 3.533302 58.27641 -58.64682 -1.866697 58.83673 -59.15499 3.533302 58.46844 -53.10306 -1.866698 66.24514 -58.27853 -1.866697 59.3449 -58.64682 3.533302 58.83673 -58.0865 -1.866697 59.9392 -58.27853 3.533302 59.3449 -58.0865 -1.866698 60.56268 -58.0865 3.533302 59.9392 -58.0865 3.533302 60.56268 -38.1943 -1.866694 27.10042 -37.43362 -1.866694 27.72403 -37.43362 3.533306 27.72403 -34.46377 -1.866695 30.69388 -39.05595 -1.866694 26.64067 -38.1943 3.533306 27.10042 -39.05595 3.533306 26.64067 -39.99031 3.533306 26.35648 -45.2825 3.533306 26.25956 -40.96915 3.533306 26.25956 -46.26134 3.533306 26.35648 -47.19571 3.533306 26.64067 -48.05736 3.533306 27.10042 -48.81803 3.533306 27.72403 -59.56606 3.533305 38.47205 -63.06428 -1.866695 43.97435 -61.61775 3.533305 41.03083 -63.83649 -1.866696 47.1619 -63.06428 3.533305 43.97435 -50.15954 -1.866698 64.79861 -63.83649 3.533304 47.1619 -64.60869 3.533304 50.34945 -66.05522 3.533303 53.29297 -68.10691 3.533303 55.85174 -62.50055 -1.866698 63.82183 -99.62364 -1.8667 95.85377 -98.72831 -1.8667 95.33736 -97.69055 -1.8667 95.33735 -69.43019 -1.866698 65.66031 -66.46035 -1.866697 62.69046 -65.56501 -1.866697 62.17406 -64.52725 -1.866698 62.17405 -63.63192 -1.866698 62.69046 -125.4559 -1.866705 138.62 -134.5583 3.533297 122.3031 -128.4736 -1.866703 127.5321 -128.99 -1.866703 126.6368 -128.99 -1.866703 125.5991 -138.4301 3.533297 125.6458 -142.7302 3.533297 128.3785 -147.3809 3.533297 130.4594 -152.3043 3.533297 131.8467 -155.7261 3.533297 132.9205 -158.8565 3.533297 134.669 -161.5647 3.533297 137.0187 -163.737 3.533296 139.8708 -166.1361 -1.866704 146.5869 -165.2824 3.533296 143.1054 -149.9792 -1.866707 166.4525 -166.2626 -1.866705 150.1691 -166.1361 3.533296 146.5869 -153.5119 -1.866707 165.8465 -165.6566 -1.866705 153.7018 -166.2626 3.533295 150.1691 -156.8469 -1.866707 164.5335 -164.3436 -1.866706 157.0368 -165.6566 3.533295 153.7018 -159.8444 -1.866706 162.5687 -162.3787 -1.866706 160.0343 -164.3436 3.533294 157.0368 -162.3787 3.533293 160.0343 -159.8444 3.533293 162.5687 -156.8469 3.533293 164.5335 -153.5119 3.533293 165.8465 -149.9792 3.533292 166.4526 -146.397 3.533292 166.3261 -142.9155 3.533292 165.4723 -139.6808 3.533292 163.9269 -136.8288 3.533292 161.7546 -134.4791 3.533293 159.0464 -132.7306 3.533293 155.916 -131.6567 3.533293 152.4942 -130.2695 3.533294 147.5708 -128.1886 3.533294 142.9201 -125.4559 3.533295 138.62 -122.1132 3.533295 134.7482 -118.857 -1.866703 123.0067 -124.5138 -1.866704 128.6635 -125.4091 -1.866704 129.1799 -126.4469 -1.866704 129.1799 -127.3422 -1.866703 128.6635 -90.52587 -1.8667 93.25891 -88.59278 -1.8667 92.7425 -89.48812 -1.866701 93.25891 -55.66184 3.533301 68.29682 -61.98414 -1.866698 64.71717 -61.98414 -1.866698 65.75492 -53.10306 3.533301 66.24514 -54.15669 -1.866697 58.3064 -46.97199 -1.866698 64.02639 -50.15954 3.533301 64.79861 -43.78444 -1.866698 63.25419 -46.97199 3.533301 64.02639 -43.78444 3.533301 63.25419 -40.84092 3.533301 61.80766 -38.28215 3.533301 59.75597 -27.53412 3.533302 49.00794 -26.91052 3.533302 48.24726 -26.16658 -1.866697 46.45124 -26.45077 3.533302 47.38562 -26.06966 -1.866697 45.47241 -26.16658 3.533302 46.45125 -26.06966 -1.866696 41.15906 -26.06966 3.533303 41.15906 -26.06966 3.533302 45.47241 -26.16658 -1.866696 40.18022 -26.45077 -1.866696 39.24585 -26.16658 3.533303 40.18022 -26.91052 -1.866696 38.3842 -26.45077 3.533304 39.24585 -27.53413 -1.866696 37.62352 -26.91052 3.533304 38.3842 -30.50397 3.533304 34.65368 -27.53413 3.533304 37.62353 -43.23189 3.533303 47.3816 -47.19169 3.533304 43.4218 -34.46377 3.533305 30.69388 -118.8569 3.533297 120.1782 -120.8837 3.533297 118.5305 -119.9883 3.533297 119.0469 -118.3405 3.533297 121.0736 -118.3405 3.533297 122.1113 -118.857 3.533297 123.0067 -124.5138 3.533296 128.6635 -125.4091 3.533296 129.1799 -126.4469 3.533297 129.1799 -128.4736 3.533297 127.5322 -127.3422 3.533297 128.6635 -128.99 3.533297 126.6368 -128.99 3.533297 125.5991 -128.4736 3.533297 124.7037 -122.8167 3.533298 119.0469 -121.9214 3.533298 118.5305 -114.1193 3.533298 113.1779 -114.6357 3.533298 112.2826 -114.6357 3.533298 111.2448 -114.1193 3.533298 110.3495 -99.62364 3.533299 95.85377 -98.72831 3.533299 95.33736 -96.79522 -1.866701 95.85376 -97.69055 3.533299 95.33736 -93.069 -1.8667 89.67803 -95.66384 -1.866701 96.98514 -95.66384 3.533299 96.98514 -96.79521 3.533299 95.85377 -92.55258 -1.8667 91.61112 -95.14743 -1.866701 97.88047 -93.069 -1.8667 90.71578 -95.14744 -1.866701 98.91823 -95.14743 3.533299 97.88047 -91.42121 -1.8667 92.7425 -95.14744 3.533298 98.91823 -95.66385 3.533298 99.81356 -110.1595 3.533297 114.3093 -111.0549 3.533297 114.8257 -112.0926 3.533298 114.8257 -112.988 3.533298 114.3093 -74.09709 3.533301 75.41839 -76.12381 3.533301 73.7706 -75.22846 3.533301 74.28702 -73.58069 3.533301 76.31372 -73.58069 3.5333 77.35148 -74.0971 3.5333 78.24681 -88.59278 3.533299 92.7425 -89.48812 3.533299 93.25891 -90.52587 3.533299 93.25891 -92.55257 3.533299 91.61113 -91.42121 3.533299 92.7425 -93.069 3.533299 90.71579 -93.069 3.5333 89.67803 -92.55258 3.5333 88.7827 -78.0569 3.533301 74.28702 -77.16156 3.533301 73.77061 -69.43019 3.533301 68.48874 -69.9466 3.533301 67.5934 -69.9466 3.533302 66.55565 -66.46035 3.533302 62.69046 -69.43019 3.533302 65.66031 -65.56501 3.533302 62.17406 -64.52725 3.533302 62.17405 -62.50055 3.533302 63.82183 -63.63192 3.533302 62.69046 -61.98414 3.533302 64.71717 -61.98414 3.533301 65.75492 -65.47039 3.533301 69.6201 -62.50055 3.533301 66.65026 -66.36573 3.533301 70.13652 -67.40348 3.533301 70.13652 -68.29882 3.533301 69.62011 -58.11649 3.533303 54.3466 -54.15669 3.533302 58.3064 -50.904 3.533304 47.13411 -46.9442 3.533303 51.09391 134.6444 -1.866714 122.3031 76.52662 -1.866705 69.20172 76.09237 -1.866704 68.3473 76.09237 3.533296 68.3473 66.54644 -1.866703 62.69045 75.23796 -1.866704 67.91307 75.23796 3.533296 67.91307 68.193 -1.866702 55.85174 76.37779 -1.866705 70.1455 76.52662 3.533295 69.20172 75.69853 -1.866705 70.82476 76.37779 3.533295 70.1455 70.86977 -1.866705 74.85858 74.75476 -1.866705 70.97358 75.69853 3.533295 70.82476 70.72093 -1.866705 75.80236 76.20989 -1.866705 73.77059 78.14299 -1.866705 74.28701 77.24765 -1.866705 73.77059 70.43552 -1.866705 74.00416 73.90036 -1.866705 70.53933 74.75476 3.533295 70.97358 69.5811 -1.866705 73.56991 73.46611 -1.866704 69.68492 73.90036 3.533295 70.53933 68.63732 -1.866705 73.71875 73.61492 -1.866704 68.74114 73.46611 3.533295 69.68492 67.48957 -1.866704 70.13652 74.29418 -1.866704 68.06189 73.61492 3.533295 68.74114 69.51628 -1.866704 68.48873 74.29418 3.533296 68.06189 68.38491 -1.866704 69.6201 69.51628 -1.866704 65.6603 70.03269 -1.866704 66.55564 70.03269 -1.866704 67.59339 121.0743 -1.866712 113.7494 120.6401 -1.866712 112.895 120.6401 3.533288 112.895 99.70973 -1.866709 95.85375 119.7857 -1.866712 112.4608 119.7857 3.533288 112.4608 120.9255 -1.866712 114.6932 121.0743 3.533288 113.7494 120.2463 -1.866713 115.3725 120.9255 3.533288 114.6932 115.4175 -1.866713 119.4063 119.3025 -1.866713 115.5213 120.2463 3.533287 115.3725 115.2687 -1.866713 120.3501 120.9698 -1.866713 118.5304 122.0075 -1.866713 118.5304 114.9832 -1.866713 118.5519 118.4481 -1.866712 115.0871 119.3025 3.533287 115.5213 114.1288 -1.866713 118.1176 118.0138 -1.866712 114.2326 118.4481 3.533287 115.0871 113.185 -1.866713 118.2665 118.1626 -1.866712 113.2889 118.0138 3.533287 114.2326 112.1787 -1.866712 114.8256 118.8419 -1.866712 112.6096 118.1626 3.533288 113.2889 114.2054 -1.866712 113.1779 118.8419 3.533288 112.6096 113.074 -1.866712 114.3092 114.2054 -1.866712 110.3494 114.7218 -1.866712 111.2448 114.7218 -1.866712 112.2825 114.9832 3.533287 118.5519 114.1288 3.533287 118.1176 115.4175 3.533287 119.4063 114.5894 -1.866713 121.0293 115.2687 3.533287 120.3501 118.4266 -1.866713 121.0736 113.6456 -1.866713 121.1782 114.5894 3.533287 121.0293 120.0744 -1.866713 119.0468 118.943 -1.866713 120.1782 124.5999 -1.866714 128.6635 112.7912 -1.866713 120.7439 113.6456 3.533287 121.1782 118.943 -1.866714 123.0066 118.4266 -1.866713 122.1113 55.74791 -1.866703 68.29682 112.357 -1.866713 119.8895 112.7912 3.533287 120.7439 122.1993 -1.866715 134.7482 112.5058 -1.866713 118.9457 112.357 3.533287 119.8895 112.5058 3.533287 118.9457 113.185 3.533288 118.2665 110.2456 -1.866712 114.3092 111.141 -1.866712 114.8256 70.43552 3.533295 74.00416 69.5811 3.533295 73.56991 70.86977 3.533295 74.85858 70.04168 -1.866705 76.48162 70.72093 3.533295 75.80236 73.66677 -1.866705 76.31372 69.09791 -1.866705 76.63043 70.04168 3.533294 76.48162 75.31456 -1.866705 74.28701 74.18318 -1.866705 75.41838 88.67887 -1.866708 92.74248 68.24349 -1.866705 76.19619 69.09791 3.533294 76.63043 74.18319 -1.866706 78.24681 73.66678 -1.866706 77.35147 67.80924 -1.866705 75.34177 68.24349 3.533295 76.19619 67.95807 -1.866705 74.39801 67.80924 3.533295 75.34177 67.95807 3.533295 74.39801 68.63732 3.533295 73.71875 66.45182 -1.866704 70.13652 161.6508 -1.866717 137.0187 153.092 -1.866718 146.1945 152.4599 -1.866718 145.4219 152.4599 3.533282 145.4219 151.6873 -1.866718 144.7899 151.6873 3.533282 144.7899 163.8231 -1.866718 139.8707 153.5531 -1.866718 147.0582 153.092 3.533282 146.1945 153.8422 -1.866718 148.0097 153.5531 3.533282 147.0582 153.9379 -1.866718 148.9928 153.8422 3.533282 148.0097 153.8422 -1.866719 149.9759 153.9379 3.533281 148.9928 157.6642 -1.866718 147.5668 153.5531 -1.866719 150.9274 153.8422 3.533281 149.9759 153.0879 -1.866719 151.7966 153.5531 3.533281 150.9274 152.4599 -1.866719 152.5637 153.0879 3.533281 151.7966 139.767 -1.86672 163.9269 151.6928 -1.866719 153.1917 152.4599 3.533281 152.5637 156.963 -1.866718 148.268 148.1642 -1.866719 157.0668 150.8236 -1.866719 153.6568 151.6928 3.533281 153.1917 149.8721 -1.866719 153.946 150.8236 3.533281 153.6568 148.889 -1.866719 154.0417 149.8721 3.533281 153.946 136.9149 -1.866719 161.7546 147.906 -1.866719 153.946 148.889 3.533281 154.0417 146.9544 -1.866719 153.6569 147.906 3.533281 153.946 146.0907 -1.866719 153.1957 146.9544 3.533281 153.6569 145.3181 -1.866719 152.5637 146.0907 3.533281 153.1957 134.5652 -1.866719 159.0464 144.6861 -1.866718 151.7911 145.3181 3.533281 152.5637 144.225 -1.866718 150.9274 144.6861 3.533281 151.7911 143.9358 -1.866718 149.9758 144.225 3.533281 150.9274 143.8402 -1.866718 148.9928 143.9358 3.533281 149.9758 132.8167 -1.866718 155.916 143.9358 -1.866718 148.0097 143.8402 3.533282 148.9928 140.1138 -1.866718 150.4188 144.225 -1.866718 147.0582 143.9358 3.533282 148.0097 144.6901 -1.866718 146.189 144.225 3.533282 147.0582 145.3181 -1.866718 145.4219 144.6901 3.533282 146.189 149.6138 -1.866717 140.9188 146.0852 -1.866718 144.7939 145.3181 3.533282 145.4219 140.815 -1.866718 149.7176 158.9426 -1.866717 134.669 146.9544 -1.866717 144.3287 146.0852 3.533282 144.7939 147.906 -1.866718 144.0396 146.9544 3.533282 144.3287 148.889 -1.866718 143.9439 147.906 3.533282 144.0396 149.8721 -1.866718 144.0396 148.889 3.533282 143.9439 150.8236 -1.866718 144.3287 149.8721 3.533282 144.0396 150.8236 3.533282 144.3287 155.8122 -1.866716 132.9205 150.4686 -1.866717 139.2434 150.0204 -1.866717 138.3614 150.0204 3.533283 138.3614 149.1384 -1.866717 137.9132 149.1384 3.533283 137.9132 150.315 -1.866717 140.2176 150.4686 3.533283 139.2434 150.315 3.533283 140.2176 140.9686 -1.866718 148.7434 148.6396 -1.866717 141.0724 149.6138 3.533283 140.9188 140.5204 -1.866718 147.8614 147.7576 -1.866717 140.6242 148.6396 3.533283 141.0724 139.6384 -1.866718 147.4132 147.3094 -1.866717 139.7422 147.7576 3.533283 140.6242 138.6642 -1.866718 147.5668 147.463 -1.866717 138.768 147.3094 3.533283 139.7422 131.7429 -1.866718 152.4942 148.1642 -1.866717 138.0668 147.463 3.533283 138.768 148.1642 3.533283 138.0668 152.3904 -1.866716 131.8466 140.5204 3.533282 147.8614 139.6384 3.533282 147.4132 140.9686 3.533282 148.7434 140.815 3.533282 149.7176 139.1396 -1.866718 150.5724 140.1138 3.533282 150.4188 138.2577 -1.866718 150.1242 139.1396 3.533282 150.5724 137.8094 -1.866718 149.2422 138.2577 3.533282 150.1242 137.963 -1.866718 148.268 137.8094 3.533282 149.2422 137.963 3.533282 148.268 138.6642 3.533282 147.5668 158.1396 -1.866719 150.5724 150.4686 -1.866719 158.2434 150.0204 -1.866719 157.3614 150.0204 3.53328 157.3614 157.2576 -1.866719 150.1242 149.1384 -1.866719 156.9132 149.1384 3.53328 156.9132 159.1138 -1.866719 150.4188 150.315 -1.86672 159.2176 150.4686 3.53328 158.2434 166.2222 -1.866719 146.5869 149.6138 -1.86672 159.9188 150.315 3.53328 159.2176 143.0016 -1.86672 165.4723 148.6396 -1.86672 160.0724 149.6138 3.53328 159.9188 147.7577 -1.86672 159.6242 148.6396 3.53328 160.0724 147.3094 -1.866719 158.7422 147.7577 3.53328 159.6242 147.463 -1.866719 157.768 147.3094 3.53328 158.7422 147.463 3.53328 157.768 156.8094 -1.866719 149.2422 148.1642 3.53328 157.0668 165.3685 -1.866718 143.1054 159.9686 -1.866719 148.7434 159.5204 -1.866719 147.8614 159.5204 3.533281 147.8614 158.6384 -1.866718 147.4132 158.6384 3.533281 147.4132 159.815 -1.866719 149.7176 159.9686 3.533281 148.7434 159.815 3.533281 149.7176 159.1138 3.533281 150.4188 158.1396 3.533281 150.5724 157.2576 3.533281 150.1242 156.8094 3.533281 149.2422 156.963 3.533281 148.268 157.6642 3.533281 147.5668 147.467 -1.866716 130.4594 141.9414 -1.866716 136.8185 141.0755 -1.866716 135.5224 141.0755 3.533284 135.5224 139.7794 -1.866716 134.6565 139.7794 3.533284 134.6565 142.2462 -1.866716 138.3508 141.9414 3.533283 136.8185 141.9414 -1.866717 139.8832 142.2462 3.533283 138.3508 141.0755 -1.866717 141.1793 141.9414 3.533283 139.8832 139.7794 -1.866717 142.0451 141.0755 3.533283 141.1793 130.3556 -1.866717 147.5708 138.2471 -1.866717 142.3499 139.7794 3.533283 142.0451 136.7147 -1.866717 142.0451 138.2471 3.533283 142.3499 135.4186 -1.866717 141.1793 136.7147 3.533283 142.0451 128.2747 -1.866716 142.9201 134.5527 -1.866716 139.8832 135.4186 3.533283 141.1793 134.248 -1.866716 138.3508 134.5527 3.533284 139.8832 134.5528 -1.866716 136.8185 134.248 3.533284 138.3508 135.4186 -1.866716 135.5224 134.5528 3.533284 136.8185 142.8163 -1.866715 128.3785 136.7147 -1.866716 134.6566 135.4186 3.533284 135.5224 125.542 -1.866716 138.62 138.2471 -1.866716 134.3517 136.7147 3.533284 134.6566 138.2471 3.533284 134.3517 48.90411 -1.866698 27.72402 46.12102 -1.866698 31.72506 45.68677 -1.866698 30.87064 45.68677 3.533301 30.87064 44.83236 -1.866698 30.4364 44.83236 3.533301 30.4364 59.65213 -1.8667 38.47204 45.97219 -1.866698 32.66884 46.12102 3.533301 31.72506 45.29294 -1.866698 33.3481 45.97219 3.533301 32.66884 47.27777 -1.8667 43.42179 44.34916 -1.866698 33.49692 45.29294 3.533301 33.3481 34.54985 -1.866698 30.69387 43.49474 -1.866698 33.06268 44.34916 3.533301 33.49692 43.0605 -1.866698 32.20826 43.49474 3.533301 33.06268 43.20932 -1.866698 31.26448 43.0605 3.533301 32.20826 43.88858 -1.866698 30.58523 43.20932 3.533301 31.26448 48.14343 -1.866698 27.10041 43.88858 3.533301 30.58523 47.28178 -1.866698 26.64066 43.31797 -1.8667 47.38159 33.3931 -1.866699 44.45299 32.95885 -1.866699 43.59857 32.95885 3.5333 43.59857 32.10444 -1.866699 43.16432 32.10444 3.5333 43.16432 33.24427 -1.8667 45.39677 33.3931 3.5333 44.45299 32.56502 -1.8667 46.07602 33.24427 3.5333 45.39677 27.6202 -1.8667 49.00793 31.62124 -1.8667 46.22484 32.56502 3.5333 46.07602 30.76682 -1.866699 45.7906 31.62124 3.5333 46.22484 26.99659 -1.8667 48.24726 30.33258 -1.866699 44.93618 30.76682 3.5333 45.7906 30.4814 -1.866699 43.99241 30.33258 3.5333 44.93618 26.53684 -1.8667 47.38561 31.16066 -1.866699 43.31315 30.4814 3.5333 43.99241 26.15574 -1.866699 41.15905 31.16066 3.5333 43.31315 26.15573 -1.866699 45.4724 26.25266 -1.866699 46.45124 26.25266 -1.866699 40.18021 56.72762 -1.8667 42.33167 56.29338 -1.8667 41.47725 56.29338 3.533299 41.47725 55.43896 -1.8667 41.043 55.43896 3.533299 41.043 61.70383 -1.8667 41.03082 56.57879 -1.8667 43.27544 56.72762 3.533299 42.33167 55.89954 -1.8667 43.9547 56.57879 3.533299 43.27544 50.99008 -1.866701 47.1341 54.95576 -1.8667 44.10353 55.89954 3.533299 43.9547 54.10134 -1.8667 43.66928 54.95576 3.533299 44.10353 42.71104 -1.866701 53.77092 53.6671 -1.8667 42.81486 54.10134 3.533299 43.66928 43.56546 -1.866701 54.20517 41.76726 -1.866701 53.91975 53.81593 -1.8667 41.87108 53.6671 3.533299 42.81486 54.49518 -1.8667 41.19183 53.81593 3.533299 41.87108 54.49518 3.533299 41.19183 47.03028 -1.866701 51.0939 43.9997 -1.866701 55.05959 43.56546 3.533298 54.20517 42.71104 3.533298 53.77092 54.24276 -1.866702 58.30639 43.85087 -1.866701 56.00336 43.9997 3.533298 55.05959 43.17162 -1.866701 56.68262 43.85087 3.533298 56.00336 38.36822 -1.866702 59.75596 42.22784 -1.866701 56.83145 43.17162 3.533298 56.68262 40.92699 -1.866702 61.80765 41.37342 -1.866701 56.3972 42.22784 3.533298 56.83145 40.93918 -1.866701 55.54278 41.37342 3.533298 56.3972 41.08801 -1.866701 54.59901 40.93918 3.533298 55.54278 41.08801 3.533298 54.59901 41.76726 3.533298 53.91975 61.93066 -1.866703 59.34647 61.56132 -1.866703 58.83671 61.56132 3.533297 58.83671 61.05157 -1.866703 58.46738 61.05157 3.533297 58.46738 62.12163 -1.866703 59.93918 61.93066 3.533297 59.34647 62.12164 -1.866703 60.56267 62.12163 3.533297 59.93918 61.92961 -1.866703 61.15697 62.12164 3.533297 60.56267 61.56132 -1.866703 61.66514 61.92961 3.533297 61.15697 61.05315 -1.866703 62.03343 61.56132 3.533297 61.66514 53.18914 -1.866703 66.24512 60.45885 -1.866703 62.22546 61.05315 3.533297 62.03343 59.83536 -1.866703 62.22546 60.45885 3.533297 62.22546 59.24265 -1.866703 62.03448 59.83536 3.533297 62.22546 58.73289 -1.866703 61.66514 59.24265 3.533297 62.03448 58.36355 -1.866703 61.15539 58.73289 3.533297 61.66514 58.17258 -1.866703 60.56267 58.36355 3.533297 61.15539 50.24562 -1.866703 64.79859 58.17258 -1.866703 59.93919 58.17258 3.533297 60.56267 58.36461 -1.866703 59.34489 58.17258 3.533297 59.93919 58.73289 -1.866702 58.83672 58.36461 3.533297 59.34489 66.14131 -1.866702 53.29296 59.24106 -1.866702 58.46843 58.73289 3.533297 58.83672 59.83537 -1.866702 58.2764 59.24106 3.533297 58.46843 60.45885 -1.866702 58.2764 59.83537 3.533297 58.2764 60.45885 3.533297 58.2764 26.99659 -1.866698 38.3842 27.6202 -1.866698 37.62352 27.6202 3.533301 37.62352 30.59005 -1.866698 34.65367 26.53684 -1.866698 39.24584 26.99659 3.533301 38.3842 26.53684 3.533301 39.24584 26.25266 3.533301 40.18021 26.15573 3.5333 45.4724 26.15574 3.533301 41.15905 26.25266 3.5333 46.45124 26.53684 3.5333 47.38561 26.99659 3.5333 48.24726 27.6202 3.5333 49.00793 38.36822 3.533298 59.75596 43.87052 -1.866702 63.25418 40.92699 3.533298 61.80765 47.05807 -1.866703 64.02639 43.87052 3.533297 63.25418 64.69478 -1.866702 50.34944 47.05807 3.533297 64.02639 50.24562 3.533297 64.79859 53.18914 3.533297 66.24512 55.74791 3.533296 68.29682 63.718 -1.866703 62.69045 95.74994 -1.866709 99.81356 95.23353 -1.866709 98.91822 95.23352 -1.866709 97.88047 65.55648 -1.866704 69.62009 62.58662 -1.866704 66.65026 62.07022 -1.866703 65.75492 62.07022 -1.866703 64.71717 62.58663 -1.866703 63.82182 138.5162 -1.866715 125.6458 122.1993 3.533285 134.7482 127.4283 -1.866715 128.6635 126.533 -1.866715 129.1799 125.4952 -1.866715 129.1799 125.542 3.533284 138.62 128.2747 3.533283 142.9201 130.3556 3.533282 147.5708 131.7429 3.533282 152.4942 132.8167 3.533281 155.916 134.5652 3.533281 159.0464 136.9149 3.53328 161.7546 139.767 3.53328 163.9269 146.4831 -1.86672 166.326 143.0016 3.533279 165.4723 166.3487 -1.866719 150.1691 150.0653 -1.866721 166.4525 146.4831 3.533279 166.326 165.7427 -1.86672 153.7018 153.598 -1.866721 165.8465 150.0653 3.533279 166.4525 164.4297 -1.86672 157.0368 156.933 -1.866721 164.5335 153.598 3.533279 165.8465 162.4649 -1.86672 160.0343 159.9305 -1.86672 162.5686 156.933 3.533279 164.5335 159.9305 3.533279 162.5686 162.4649 3.533279 160.0343 164.4297 3.53328 157.0368 165.7427 3.53328 153.7018 166.3487 3.53328 150.1691 166.2222 3.533281 146.5869 165.3685 3.533281 143.1054 163.8231 3.533282 139.8707 161.6508 3.533282 137.0187 158.9426 3.533283 134.669 155.8122 3.533283 132.9205 152.3904 3.533284 131.8466 147.467 3.533284 130.4594 142.8163 3.533284 128.3785 138.5162 3.533285 125.6458 134.6444 3.533286 122.3031 122.9028 -1.866713 119.0469 128.5597 -1.866714 124.7037 129.0761 -1.866714 125.599 129.0761 -1.866714 126.6368 128.5597 -1.866714 127.5321 93.15509 -1.866708 90.71577 92.63867 -1.866708 88.78269 93.15509 -1.866708 89.67802 68.193 3.533297 55.85174 64.61334 -1.866703 62.17404 65.6511 -1.866703 62.17404 66.14131 3.533298 53.29296 58.20256 -1.866702 54.34659 63.92256 -1.866701 47.16189 64.69478 3.533298 50.34944 63.15036 -1.866701 43.97434 63.92256 3.533299 47.16189 63.15036 3.533299 43.97434 61.70383 3.533299 41.03082 59.65213 3.5333 38.47204 48.90411 3.533302 27.72402 48.14343 3.533302 27.10041 46.34741 -1.866698 26.35648 47.28178 3.533302 26.64066 45.36857 -1.866698 26.25956 46.34741 3.533302 26.35648 41.05522 -1.866697 26.25955 41.05522 3.533302 26.25955 45.36857 3.533302 26.25956 40.07638 -1.866697 26.35647 39.14202 -1.866697 26.64066 40.07638 3.533302 26.35647 38.28037 -1.866697 27.10041 39.14202 3.533302 26.64066 37.51969 -1.866697 27.72402 38.28037 3.533302 27.10041 34.54985 3.533302 30.69387 37.51969 3.533302 27.72402 47.27777 3.533299 43.42179 43.31797 3.533299 47.38159 30.59005 3.533302 34.65367 120.0744 3.533287 119.0468 118.4266 3.533287 121.0736 118.943 3.533287 120.1782 120.9698 3.533287 118.5304 122.0075 3.533287 118.5304 122.9028 3.533287 119.0469 128.5597 3.533286 124.7037 129.0761 3.533285 125.599 129.0761 3.533285 126.6368 127.4283 3.533285 128.6635 128.5597 3.533285 127.5321 126.533 3.533285 129.1799 125.4952 3.533285 129.1799 124.5999 3.533286 128.6635 118.943 3.533287 123.0066 118.4266 3.533287 122.1113 113.074 3.533288 114.3092 112.1787 3.533288 114.8256 111.141 3.533288 114.8256 110.2456 3.533288 114.3092 95.74994 3.53329 99.81356 95.23353 3.53329 98.91822 95.74993 -1.866709 96.98513 95.23352 3.533291 97.88047 89.57421 -1.866708 93.25889 96.88131 -1.866709 95.85375 96.88131 3.533291 95.85375 95.74993 3.533291 96.98513 91.5073 -1.866708 92.74248 97.77664 -1.866709 95.33734 90.61196 -1.866708 93.25889 98.8144 -1.866709 95.33734 97.77664 3.533291 95.33734 92.63867 -1.866708 91.6111 98.8144 3.53329 95.33734 99.70973 3.53329 95.85375 114.2054 3.533288 110.3494 114.7218 3.533288 111.2448 114.7218 3.533288 112.2825 114.2054 3.533288 113.1779 75.31456 3.533295 74.28701 73.66677 3.533295 76.31372 74.18318 3.533295 75.41838 76.20989 3.533295 73.77059 77.24765 3.533294 73.77059 78.14299 3.533294 74.28701 92.63867 3.533292 88.78269 93.15509 3.533292 89.67802 93.15509 3.533291 90.71577 91.5073 3.533291 92.74248 92.63867 3.533291 91.6111 90.61196 3.533291 93.25889 89.57421 3.533292 93.25889 88.67887 3.533292 92.74248 74.18319 3.533294 78.24681 73.66678 3.533294 77.35147 68.38491 3.533296 69.6201 67.48957 3.533296 70.13652 66.45182 3.533296 70.13652 62.58662 3.533296 66.65026 65.55648 3.533296 69.62009 62.07022 3.533297 65.75492 62.07022 3.533297 64.71717 63.718 3.533297 62.69045 62.58663 3.533297 63.82182 64.61334 3.533297 62.17404 65.6511 3.533297 62.17404 69.51628 3.533296 65.6603 66.54644 3.533296 62.69045 70.03269 3.533296 66.55564 70.03269 3.533296 67.59339 69.51628 3.533296 68.48873 54.24276 3.533298 58.30639 58.20256 3.533298 54.34659 47.03028 3.533299 51.0939 50.99008 3.533299 47.1341 -15.94689 -70.86669 30.75689 -30.567 -70.86669 16.13678 -29.54275 -70.86669 15.59051 -29.54275 -69.66669 15.59051 -15.40061 -70.86669 29.73264 -15.51332 -70.86669 1.561069 -15.51332 -69.66669 1.561069 -15.83416 -70.86669 31.91222 -31.72233 -70.86669 16.02405 -30.567 -69.66669 16.13678 -15.09693 -70.86669 32.80888 -32.61899 -70.86669 15.28682 -31.72233 -69.66669 16.02405 -41.95697 -70.86669 4.057846 -32.95696 -70.86669 14.17629 -32.61899 -69.66669 15.28682 -9.684241 -70.86669 42.14685 -42.28581 -70.86669 9.865159 -32.95697 -70.86668 -13.88258 -32.95696 -69.66669 14.17629 -41.95697 -70.86668 -36.83696 -32.61899 -70.86668 -14.99311 -32.95697 -69.66668 -13.88258 -31.72234 -70.86668 -15.73034 -32.61899 -69.66668 -14.99311 -30.567 -70.86668 -15.84307 -31.72234 -69.66668 -15.73034 -29.54275 -70.86668 -15.29679 -30.567 -69.66668 -15.84307 -15.51332 -70.86669 -1.267357 -29.54275 -69.66668 -15.29679 0.561908 -70.86669 15.18679 -14.99691 -70.86669 -0.3720198 -15.51332 -69.66669 -1.267357 1.457246 -70.86669 15.7032 -0.4758427 -70.86669 15.1868 -14.99691 -70.86669 0.6657309 -14.99691 -69.66669 -0.3720198 -1.371181 -70.86669 15.7032 -14.99691 -69.66669 0.6657309 42.04303 -70.86669 37.12655 -15.40062 -70.86668 -29.43893 -1.371183 -70.86669 -15.40949 -1.371183 -69.66669 -15.40949 15.59938 -70.86669 1.561067 -0.4758451 -70.86669 -14.89309 -0.4758451 -69.66669 -14.89309 -40.40225 -70.86668 -56.98613 -15.9469 -70.86668 -30.46318 -15.40062 -69.66668 -29.43893 -46.1276 -70.86668 -52.4675 -15.83417 -70.86668 -31.61851 -15.9469 -69.66668 -30.46318 -36.06333 -70.86668 -53.11227 -15.09694 -70.86668 -32.51516 -15.83417 -69.66668 -31.61851 -31.36122 -70.86668 -49.77588 -13.98641 -70.86668 -32.85314 -15.09694 -69.66668 -32.51516 -3.867961 -70.86668 -41.85314 14.07246 -70.86669 -32.85314 -13.98641 -69.66668 -32.85314 -9.675273 -70.86668 -42.18198 -15.35935 -70.86668 -43.1477 -20.93759 -70.86668 -44.75555 -26.27989 -70.86668 -46.9684 37.02685 -70.86669 -41.85314 15.18299 -70.86669 -32.51517 14.07246 -69.66669 -32.85314 31.80839 -70.86669 -15.73034 15.92022 -70.86669 -31.61851 15.18299 -69.66669 -32.51517 32.70505 -70.86669 -14.99311 30.65306 -70.86669 -15.84307 16.03296 -70.86669 -30.46318 15.92022 -69.66669 -31.61851 29.62881 -70.86669 -15.2968 15.48668 -70.86669 -29.43893 16.03296 -69.66669 -30.46318 15.59938 -70.86669 -1.26736 1.457244 -70.86669 -15.40949 15.48668 -69.66669 -29.43893 15.08297 -70.86669 -0.3720222 0.5619056 -70.86669 -14.89309 1.457244 -69.66669 -15.40949 15.08297 -70.86669 0.6657285 0.5619056 -69.66669 -14.89309 15.59938 -69.66669 1.561067 29.62881 -70.86669 15.5905 29.62881 -69.6667 15.5905 15.08297 -69.66669 0.6657285 15.08297 -69.66669 -0.3720222 15.59938 -69.66669 -1.26736 29.62881 -69.66669 -15.2968 30.65306 -69.66669 -15.84307 31.80839 -69.66669 -15.73034 42.04302 -70.86669 -3.764138 33.04302 -70.86669 -13.88258 32.70505 -69.66669 -14.99311 42.37187 -70.86669 -9.571451 33.04302 -70.86669 14.17629 33.04302 -69.66669 -13.88258 32.70505 -70.86669 15.28682 33.04302 -69.6667 14.17629 31.8084 -70.86669 16.02405 32.70505 -69.6667 15.28682 30.65306 -70.86669 16.13678 31.8084 -69.6667 16.02405 30.65306 -69.6667 16.13678 15.48668 -70.86669 29.73263 1.457246 -69.66669 15.7032 0.561908 -69.66669 15.18679 40.48831 -70.86669 57.27985 16.03296 -70.86669 30.75688 15.48668 -69.6667 29.73263 46.21366 -70.86669 52.76122 15.92023 -70.86669 31.91222 16.03296 -69.6667 30.75688 15.183 -70.86669 32.80887 15.92023 -69.6667 31.91222 33.97714 -70.86669 53.34279 14.07247 -70.86669 33.14685 15.183 -69.6667 32.80887 -2.082042 -70.86669 42.46666 -13.9864 -70.86669 33.14685 14.07247 -69.6667 33.14685 5.429976 -70.86669 43.41472 12.86476 -70.86669 44.99394 20.12568 -70.86669 47.18397 27.19373 -70.86669 49.97909 -13.9864 -69.66669 33.14685 -15.09693 -69.66669 32.80888 -15.83416 -69.66669 31.91222 -15.94689 -69.66669 30.75689 -15.40061 -69.66669 29.73264 -1.371181 -69.66669 15.7032 -0.4758427 -69.66669 15.1868 -41.87569 -70.86669 56.20772 -46.38005 -70.86669 41.6202 -36.83411 -70.86669 51.16614 -36.83411 -69.6667 51.16614 -41.87569 -69.6667 56.20772 -49.8797 -70.86669 31.5511 -41.92375 -70.86669 37.16389 -46.38005 -69.6667 41.6202 -53.21609 -70.86669 36.25322 -47.07223 -70.86669 26.46977 -36.94079 -70.86669 42.14685 -41.92375 -69.66669 37.16389 -36.94079 -69.66669 42.14685 -43.25152 -70.86669 15.54924 -44.85937 -70.86669 21.12747 -9.684241 -69.66669 42.14685 -2.082042 -69.66669 42.46666 5.429976 -69.6667 43.41472 12.86476 -69.6667 44.99394 20.12568 -69.6667 47.18397 27.19373 -69.6667 49.97909 33.97714 -69.6667 53.34279 40.48831 -69.6667 57.27985 41.51431 -70.86669 46.56787 51.43777 -70.86669 47.67138 46.21366 -69.6667 52.76122 37.05801 -70.86669 42.11157 51.06231 -70.86669 37.024 56.10389 -70.86669 42.06558 51.43777 -69.6667 47.67138 56.10389 -69.6667 42.06558 51.06231 -69.6667 37.024 41.51431 -69.6667 46.56787 -36.97401 -70.86668 -41.81992 37.05801 -69.6667 42.11157 42.04303 -69.6667 37.12655 42.04302 -69.66669 -3.764138 43.33758 -70.86669 -15.25553 42.37187 -69.66669 -9.571451 44.94543 -70.86669 -20.83376 43.33758 -69.66669 -15.25553 47.15829 -70.86669 -26.17606 44.94543 -69.66669 -20.83376 42.00981 -70.86669 -36.87018 49.96577 -70.86669 -31.25739 47.15829 -69.66669 -26.17606 46.46611 -70.86668 -41.32648 53.30216 -70.86668 -35.9595 49.96577 -69.66669 -31.25739 41.96175 -70.86668 -55.914 57.17602 -70.86668 -40.29842 53.30216 -69.66668 -35.9595 52.65739 -70.86668 -46.02378 57.17602 -69.66668 -40.29842 47.56755 -70.86668 -51.24788 52.65739 -69.66668 -46.02378 47.56755 -69.66668 -51.24788 36.92017 -70.86668 -50.87242 41.96175 -69.66668 -55.914 36.92017 -69.66668 -50.87242 46.46611 -69.66668 -41.32648 42.00981 -69.66669 -36.87018 37.02685 -69.66669 -41.85314 -3.867961 -69.66668 -41.85314 -9.675273 -69.66668 -42.18198 -15.35935 -69.66668 -43.1477 -20.93759 -69.66668 -44.75555 -26.27989 -69.66668 -46.9684 -31.36122 -69.66668 -49.77588 -36.06333 -69.66668 -53.11227 -40.40225 -69.66668 -56.98613 -41.43031 -70.86668 -46.27622 -51.35171 -70.86668 -47.37766 -46.1276 -69.66668 -52.4675 -50.97625 -70.86668 -36.73028 -56.01783 -70.86668 -41.77186 -51.35171 -69.66668 -47.37766 -56.01783 -69.66668 -41.77186 -50.97625 -69.66668 -36.73028 -41.43031 -69.66668 -46.27622 -36.97401 -69.66668 -41.81992 -41.95697 -69.66668 -36.83696 -41.95697 -69.66669 4.057846 -42.28581 -69.66669 9.865159 -43.25152 -69.66669 15.54924 -44.85937 -69.66669 21.12747 -47.07223 -69.66669 26.46977 -49.8797 -69.66669 31.5511 -57.08995 -70.86669 40.59214 -53.21609 -69.6667 36.25322 -52.57133 -70.86669 46.31749 -57.08995 -69.6667 40.59214 -47.48149 -70.86669 51.54159 -52.57133 -69.6667 46.31749 -47.48149 -69.6667 51.54159 -15.94689 -33.36669 30.75689 -30.567 -33.36669 16.13679 -29.54275 -33.36669 15.59051 -29.54275 -32.16669 15.59051 -15.40061 -33.36669 29.73264 -15.51331 -33.36669 1.561074 -15.51331 -32.16669 1.561074 -15.83416 -33.36669 31.91222 -31.72233 -33.36669 16.02406 -30.567 -32.16669 16.13679 -15.09693 -33.36669 32.80888 -32.61899 -33.36669 15.28683 -31.72233 -32.16669 16.02406 -41.95697 -33.36669 4.057851 -32.95696 -33.36669 14.1763 -32.61899 -32.16669 15.28683 -9.684239 -33.36669 42.14686 -42.2858 -33.36669 9.865164 -32.95697 -33.36669 -13.88257 -32.95696 -32.16669 14.1763 -41.95697 -33.36668 -36.83695 -32.61899 -33.36669 -14.9931 -32.95697 -32.16669 -13.88257 -31.72233 -33.36669 -15.73033 -32.61899 -32.16669 -14.9931 -30.567 -33.36669 -15.84306 -31.72233 -32.16669 -15.73033 -29.54275 -33.36669 -15.29679 -30.567 -32.16669 -15.84306 -15.51331 -33.36669 -1.267353 -29.54275 -32.16669 -15.29679 0.5619094 -33.36669 15.1868 -14.99691 -33.36669 -0.3720151 -15.51331 -32.16669 -1.267353 1.457248 -33.36669 15.70321 -0.4758413 -33.36669 15.1868 -14.99691 -33.36669 0.6657357 -14.99691 -32.16669 -0.3720146 -1.371179 -33.36669 15.70321 -14.99691 -32.16669 0.6657361 42.04303 -33.3667 37.12655 -15.40062 -33.36669 -29.43892 -1.371181 -33.36669 -15.40949 -1.371181 -32.16669 -15.40949 15.59938 -33.36669 1.561072 -0.4758437 -33.36669 -14.89308 -0.4758437 -32.16669 -14.89308 -40.40225 -33.36668 -56.98612 -15.9469 -33.36669 -30.46317 -15.40062 -32.16669 -29.43892 -46.1276 -33.36668 -52.4675 -15.83416 -33.36669 -31.6185 -15.9469 -32.16669 -30.46317 -36.06333 -33.36668 -53.11226 -15.09694 -33.36669 -32.51516 -15.83416 -32.16669 -31.6185 -31.36121 -33.36668 -49.77587 -13.98641 -33.36669 -32.85313 -15.09694 -32.16669 -32.51516 -3.867959 -33.36668 -41.85313 14.07247 -33.36669 -32.85313 -13.98641 -32.16669 -32.85313 -9.675271 -33.36668 -42.18198 -15.35935 -33.36668 -43.14769 -20.93758 -33.36668 -44.75554 -26.27988 -33.36668 -46.96839 37.02685 -33.36669 -41.85314 15.183 -33.36669 -32.51516 14.07247 -32.16669 -32.85313 31.8084 -33.36669 -15.73034 15.92023 -33.36669 -31.61851 15.183 -32.16669 -32.51516 32.70505 -33.36669 -14.99311 30.65306 -33.36669 -15.84307 16.03296 -33.36669 -30.46317 15.92023 -32.16669 -31.61851 29.62881 -33.36669 -15.29679 15.48668 -33.36669 -29.43893 16.03296 -32.16669 -30.46317 15.59938 -33.36669 -1.267355 1.457245 -33.36669 -15.40949 15.48668 -32.16669 -29.43893 15.08297 -33.36669 -0.3720175 0.5619071 -33.36669 -14.89308 1.457245 -32.16669 -15.40949 15.08297 -33.36669 0.6657333 0.5619071 -32.16669 -14.89308 15.59938 -32.16669 1.561072 29.62882 -33.36669 15.59051 29.62882 -32.16669 15.59051 15.08297 -32.16669 0.6657338 15.08297 -32.16669 -0.372017 15.59938 -32.16669 -1.267355 29.62881 -32.16669 -15.29679 30.65306 -32.16669 -15.84307 31.8084 -32.16669 -15.73034 42.04302 -33.36669 -3.764132 33.04302 -33.36669 -13.88258 32.70505 -32.16669 -14.99311 42.37187 -33.36669 -9.571444 33.04302 -33.36669 14.17629 33.04302 -32.16669 -13.88258 32.70505 -33.36669 15.28682 33.04302 -32.16669 14.17629 31.8084 -33.36669 16.02405 32.70505 -32.16669 15.28682 30.65306 -33.36669 16.13678 31.8084 -32.16669 16.02405 30.65306 -32.16669 16.13678 15.48668 -33.36669 29.73264 1.457248 -32.16669 15.70321 0.5619094 -32.16669 15.1868 40.48831 -33.3667 57.27985 16.03296 -33.36669 30.75689 15.48668 -32.16669 29.73264 46.21367 -33.3667 52.76122 15.92023 -33.36669 31.91222 16.03296 -32.16669 30.75689 15.183 -33.36669 32.80888 15.92023 -32.16669 31.91222 33.97714 -33.3667 53.3428 14.07247 -33.36669 33.14686 15.183 -32.16669 32.80888 -2.08204 -33.36669 42.46666 -13.9864 -33.36669 33.14686 14.07247 -32.16669 33.14686 5.429978 -33.36669 43.41473 12.86476 -33.3667 44.99394 20.12568 -33.3667 47.18397 27.19373 -33.3667 49.97909 -13.9864 -32.16669 33.14686 -15.09693 -32.16669 32.80888 -15.83416 -32.16669 31.91222 -15.94689 -32.16669 30.75689 -15.40061 -32.16669 29.73264 -1.371179 -32.16669 15.70321 -0.4758413 -32.16669 15.1868 -41.87569 -33.36669 56.20772 -46.38005 -33.36669 41.6202 -36.83411 -33.36669 51.16614 -36.83411 -32.16669 51.16614 -41.87569 -32.16669 56.20772 -49.8797 -33.36669 31.55111 -41.92375 -33.36669 37.1639 -46.38005 -32.16669 41.6202 -53.21609 -33.36669 36.25322 -47.07222 -33.36669 26.46977 -36.94079 -33.36669 42.14686 -41.92375 -32.16669 37.1639 -36.94079 -32.16669 42.14686 -43.25152 -33.36669 15.54925 -44.85937 -33.36669 21.12747 -9.684239 -32.16669 42.14686 -2.08204 -32.16669 42.46666 5.429978 -32.16669 43.41473 12.86476 -32.1667 44.99394 20.12568 -32.1667 47.18397 27.19373 -32.1667 49.97909 33.97714 -32.1667 53.3428 40.48831 -32.1667 57.27985 41.51431 -33.3667 46.56788 51.43777 -33.3667 47.67138 46.21367 -32.1667 52.76122 37.05801 -33.3667 42.11157 51.06232 -33.3667 37.024 56.1039 -33.3667 42.06558 51.43777 -32.1667 47.67138 56.1039 -32.1667 42.06558 51.06232 -32.1667 37.024 41.51431 -32.1667 46.56788 -36.97401 -33.36668 -41.81991 37.05801 -32.1667 42.11157 42.04303 -32.1667 37.12655 42.04302 -32.16669 -3.764132 43.33758 -33.36669 -15.25553 42.37187 -32.16669 -9.571444 44.94544 -33.36669 -20.83376 43.33758 -32.16669 -15.25553 47.15829 -33.36669 -26.17606 44.94544 -32.16669 -20.83376 42.00981 -33.36669 -36.87018 49.96577 -33.36669 -31.25739 47.15829 -32.16669 -26.17606 46.46611 -33.36669 -41.32648 53.30216 -33.36669 -35.9595 49.96577 -32.16669 -31.25739 41.96175 -33.36668 -55.914 57.17602 -33.36669 -40.29841 53.30216 -32.16669 -35.9595 52.65739 -33.36669 -46.02377 57.17602 -32.16669 -40.29841 47.56755 -33.36669 -51.24787 52.65739 -32.16669 -46.02377 47.56755 -32.16669 -51.24787 36.92017 -33.36668 -50.87242 41.96175 -32.16668 -55.914 36.92017 -32.16668 -50.87242 46.46611 -32.16669 -41.32648 42.00981 -32.16669 -36.87018 37.02685 -32.16669 -41.85314 -3.867959 -32.16668 -41.85313 -9.675271 -32.16668 -42.18198 -15.35935 -32.16668 -43.14769 -20.93758 -32.16668 -44.75554 -26.27988 -32.16668 -46.96839 -31.36121 -32.16668 -49.77587 -36.06333 -32.16668 -53.11226 -40.40225 -32.16668 -56.98612 -41.43031 -33.36668 -46.27622 -51.3517 -33.36668 -47.37766 -46.1276 -32.16668 -52.4675 -50.97625 -33.36668 -36.73028 -56.01783 -33.36668 -41.77186 -51.3517 -32.16668 -47.37766 -56.01783 -32.16668 -41.77186 -50.97625 -32.16668 -36.73028 -41.43031 -32.16668 -46.27622 -36.97401 -32.16668 -41.81991 -41.95697 -32.16668 -36.83695 -41.95697 -32.16669 4.057851 -42.2858 -32.16669 9.865164 -43.25152 -32.16669 15.54925 -44.85937 -32.16669 21.12747 -47.07222 -32.16669 26.46977 -49.8797 -32.16669 31.55111 -57.08995 -33.36669 40.59214 -53.21609 -32.16669 36.25322 -52.57133 -33.36669 46.3175 -57.08995 -32.16669 40.59214 -47.48149 -33.36669 51.5416 -52.57133 -32.16669 46.3175 -47.48149 -32.16669 51.5416 10.04304 59.4333 52.14687 7.541825 59.4333 49.99642 8.144082 59.4333 49.74791 8.144082 60.6333 49.74791 8.392596 59.4333 49.14565 8.393041 60.6333 49.14682 5.793038 59.4333 52.14686 6.942561 59.4333 49.74735 7.542996 60.6333 49.99687 6.693484 59.4333 49.14808 6.942 60.6333 49.74791 5.79304 59.4333 46.14687 6.941998 59.4333 48.54582 6.693039 60.6333 49.14691 7.544253 59.4333 48.29731 6.941998 60.6333 48.54582 8.143521 59.4333 48.54639 7.543084 60.6333 48.29687 8.144082 60.6333 48.54583 2.517915 59.4333 40.9984 3.154309 59.4333 40.7348 3.417914 59.4333 40.0984 1.881518 59.4333 40.7348 0.2855117 59.4333 39.15444 10.04304 59.4333 46.62267 -0.6606457 59.4333 39.00459 -1.338021 59.4333 38.32722 -5.706958 59.4333 52.14686 -7.458175 59.4333 49.99642 -6.85592 59.4333 49.74791 -6.85592 60.6333 49.74791 -6.607404 59.4333 49.14565 -6.60696 60.6333 49.14682 -8.057437 59.4333 49.74735 -7.457004 60.6333 49.99687 -9.95696 59.4333 46.62267 -8.306514 59.4333 49.14809 -8.058 60.6333 49.74791 -9.95696 59.4333 52.14687 -8.058 59.4333 48.54583 -8.30696 60.6333 49.14691 -10.14727 59.4333 45.77159 -7.455743 59.4333 48.29732 -8.058 60.6333 48.54583 -45.34283 59.4333 7.638389 -6.856481 59.4333 48.54639 -7.456914 60.6333 48.29687 -10.68048 59.4333 45.08322 -5.70696 59.4333 46.14687 -6.855916 60.6333 48.54583 1.881515 59.4333 11.03632 33.58216 59.4333 45.2187 33.85313 59.4333 45.62422 33.85313 60.6333 45.62422 35.37214 59.4333 48.64279 34.25866 59.4333 45.89519 34.25757 60.6333 45.89455 -37.99874 59.43331 -25.71473 33.48702 59.4333 44.74034 33.58281 60.6333 45.21978 33.58217 59.4333 44.26198 33.48694 60.6333 44.7399 33.85313 59.4333 43.85646 33.58261 60.6333 44.26327 34.25866 59.4333 43.58549 33.853 60.6333 43.85633 17.36715 59.4333 26.14916 34.73702 59.4333 43.49034 34.25995 60.6333 43.58594 16.73076 59.4333 25.88555 18.00355 59.4333 25.88555 35.21537 59.4333 43.58549 34.73657 60.6333 43.49026 35.62089 59.4333 43.85646 35.21646 60.6333 43.58613 40.20986 59.4333 44.71845 35.89186 59.4333 44.26198 35.62089 60.6333 43.85646 18.26715 59.4333 25.24916 18.00355 59.4333 24.61276 35.98702 59.4333 44.74034 35.89122 60.6333 44.2609 35.89186 59.4333 45.21869 35.98709 60.6333 44.74078 35.6209 59.4333 45.62422 35.89142 60.6333 45.21741 35.21537 59.4333 45.89519 35.62103 60.6333 45.62435 34.73702 59.4333 45.99034 35.21408 60.6333 45.89474 34.73746 60.6333 45.99042 44.61462 59.4333 40.31369 43.48166 59.4333 35.3192 43.75262 59.4333 35.72473 43.75262 60.6333 35.72473 44.15815 59.4333 35.99569 44.15707 60.6333 35.99505 34.69273 59.4333 39.0392 43.38651 59.4333 34.84084 43.4823 60.6333 35.32028 43.17801 59.4333 30.55392 43.48166 59.4333 34.36249 43.38643 60.6333 34.8404 43.75262 59.4333 33.95696 43.48211 60.6333 34.36378 44.15816 59.4333 33.686 43.75249 60.6333 33.95683 44.63651 59.4333 33.59084 44.15944 60.6333 33.68644 45.11486 59.4333 33.686 44.63607 60.6333 33.59077 45.52039 59.4333 33.95696 45.11595 60.6333 33.68664 48.53895 59.4333 35.47597 45.79135 59.4333 34.36249 45.52039 60.6333 33.95696 45.88651 59.4333 34.84084 45.79072 60.6333 34.3614 45.79136 59.4333 35.3192 45.88658 60.6333 34.84128 45.52039 59.4333 35.72472 45.79091 60.6333 35.31791 45.11486 59.4333 35.99569 45.52052 60.6333 35.72485 44.63651 59.4333 36.09084 45.11358 60.6333 35.99525 44.63695 60.6333 36.09092 -39.31835 59.4333 23.95192 -45.02878 59.4333 33.686 -45.43431 59.4333 33.95697 -45.43431 60.6333 33.95697 -45.70528 59.4333 34.3625 -45.70464 60.6333 34.36141 -44.55043 59.4333 33.59085 -45.02987 60.6333 33.68664 -44.07207 59.4333 33.686 -44.54999 60.6333 33.59078 -43.66654 59.4333 33.95697 -44.07336 60.6333 33.68645 -34.17258 59.4333 43.5855 -43.39558 59.4333 34.3625 -43.66642 60.6333 33.95684 -33.76705 59.4333 43.85646 -38.8493 59.4333 34.79657 -34.65093 59.4333 43.49035 -43.30043 59.4333 34.84085 -43.39603 60.6333 34.36378 -35.12929 59.4333 43.58549 -43.39558 59.4333 35.31921 -43.30035 60.6333 34.84041 -35.53482 59.4333 43.85646 -43.66654 59.4333 35.72473 -43.39622 60.6333 35.3203 -35.80578 59.4333 44.26199 -44.07207 59.4333 35.9957 -43.66654 60.6333 35.72473 -35.90093 59.4333 44.74035 -44.55043 59.4333 36.09085 -44.07099 60.6333 35.99506 -35.80578 59.4333 45.2187 -45.02878 59.4333 35.9957 -44.55087 60.6333 36.09093 -35.53482 59.4333 45.62423 -45.43431 59.4333 35.72473 -45.0275 60.6333 35.99525 -48.25056 59.4333 32.88413 -45.70528 59.4333 35.31921 -45.43444 60.6333 35.72486 -33.49032 59.4333 48.92775 -45.80043 59.4333 34.84085 -45.70483 60.6333 35.31792 -45.80051 60.6333 34.8413 -35.53482 60.6333 43.85646 -35.80514 60.6333 44.26091 -35.13038 60.6333 43.58614 -34.65049 60.6333 43.49027 -34.17387 60.6333 43.58594 -30.36401 59.4333 46.11027 -33.49608 59.4333 44.26199 -33.76692 60.6333 43.85633 -33.40093 59.4333 44.74035 -33.49653 60.6333 44.26328 -32.69421 59.4333 48.44047 -33.49609 59.4333 45.2187 -33.40086 60.6333 44.73991 -33.76705 59.4333 45.62422 -33.49673 60.6333 45.21979 -34.17258 59.4333 45.89519 -33.76705 60.6333 45.62422 -34.65093 59.4333 45.99035 -34.17149 60.6333 45.89455 -35.12929 59.4333 45.89519 -34.65138 60.6333 45.99042 -35.128 60.6333 45.89475 -35.53495 60.6333 45.62436 -35.80533 60.6333 45.21741 -35.90101 60.6333 44.74079 25.78172 59.4333 16.83459 -33.49644 59.43331 -44.92559 -33.76705 59.43331 -45.33047 -33.76705 60.63331 -45.33047 -35.28607 59.43331 -48.34904 -34.17194 59.43331 -45.60108 -34.17149 60.63331 -45.6008 38.08321 59.4333 26.01083 -33.40118 59.43331 -44.44743 -33.49673 60.63331 -44.92604 -33.49624 59.43331 -43.96887 -33.40087 60.63331 -44.44618 -33.76736 59.43331 -43.56301 -33.49653 60.63331 -43.96953 -34.17322 59.43331 -43.29189 -33.76693 60.63331 -43.56258 10.29608 59.4333 1.721744 -34.65178 59.43331 -43.19684 -34.17388 60.63331 -43.29219 10.93248 59.4333 1.985348 9.659689 59.4333 1.985349 -35.12993 59.43331 -43.2921 -34.65053 60.63331 -43.19652 -35.53482 59.43331 -43.56271 -35.13039 60.63331 -43.29238 -40.12379 59.43331 -44.4247 -35.80543 59.43331 -43.9676 -35.53482 60.63331 -43.56271 9.396085 59.4333 2.621744 9.659689 59.4333 3.25814 -35.9007 59.43331 -44.44575 -35.80515 60.63331 -43.96714 -35.80564 59.43331 -44.92432 -35.90101 60.63331 -44.447 -35.53452 59.43331 -45.33017 -35.80535 60.63331 -44.92365 -35.12866 59.43331 -45.60129 -35.53495 60.63331 -45.3306 -34.6501 59.43331 -45.69635 -35.128 60.63331 -45.601 -34.65135 60.63331 -45.69666 -44.52855 59.43331 -40.01994 -43.39594 59.43331 -35.02609 -43.66655 59.43331 -35.43098 -43.66655 60.63331 -35.43098 -44.07144 59.43331 -35.70159 -44.07099 60.63331 -35.7013 -34.60666 59.43331 -38.74546 -43.30067 59.43331 -34.54793 -43.39623 60.63331 -35.02655 -43.09194 59.43331 -30.26018 -43.39574 59.43331 -34.06937 -43.30036 60.63331 -34.54668 -43.66685 59.43331 -33.66352 -43.39603 60.63331 -34.07004 -44.07271 59.43331 -33.3924 -43.66642 60.63331 -33.66308 -44.55127 59.43331 -33.29734 -44.07337 60.63331 -33.39269 -45.02943 59.43331 -33.3926 -44.55002 60.63331 -33.29702 -45.43431 59.43331 -33.66321 -45.02988 60.63331 -33.39289 -48.45288 59.43331 -35.18222 -45.70492 59.43331 -34.0681 -45.43431 60.63331 -33.66321 -45.80019 59.43331 -34.54626 -45.70464 60.63331 -34.06765 -45.70513 59.43331 -35.02482 -45.80051 60.63331 -34.54751 -45.43401 59.43331 -35.43067 -45.70484 60.63331 -35.02415 -45.02816 59.43331 -35.7018 -45.43444 60.63331 -35.43111 -44.54959 59.43331 -35.79685 -45.02749 60.63331 -35.7015 -44.55084 60.63331 -35.79717 39.40443 59.43331 -23.65818 45.1155 59.43331 -33.39261 45.52038 59.43331 -33.66322 45.52038 60.63331 -33.66322 45.791 59.43331 -34.06811 45.79071 60.63331 -34.06766 44.63734 59.43331 -33.29735 45.11595 60.63331 -33.3929 44.15878 59.43331 -33.39241 44.63609 60.63331 -33.29703 43.75292 59.43331 -33.66353 44.15945 60.63331 -33.3927 34.25928 59.43331 -43.2919 43.4818 59.43331 -34.06938 43.75249 60.63331 -33.66309 33.85343 59.43331 -43.56302 38.93537 59.43331 -34.50282 34.73785 59.43331 -43.19684 43.38674 59.43331 -34.54794 43.4821 60.63331 -34.07004 35.216 59.43331 -43.2921 43.482 59.43331 -35.0261 43.38642 60.63331 -34.54669 35.62089 59.43331 -43.56271 43.75262 59.43331 -35.43098 43.48229 60.63331 -35.02655 35.8915 59.43331 -43.9676 44.1575 59.43331 -35.70159 43.75262 60.63331 -35.43098 35.98676 59.43331 -44.44576 44.63566 59.43331 -35.79686 44.15705 60.63331 -35.70131 35.89171 59.43331 -44.92432 45.11423 59.43331 -35.7018 44.63691 60.63331 -35.79718 35.62059 59.43331 -45.33017 45.52008 59.43331 -35.43068 45.11356 60.63331 -35.70151 48.33663 59.43331 -32.59038 45.7912 59.43331 -35.02483 45.52051 60.63331 -35.43111 33.5764 59.43331 -48.634 45.88626 59.43331 -34.54627 45.79091 60.63331 -35.02416 45.88657 60.63331 -34.54751 35.62089 60.63331 -43.56271 35.89122 60.63331 -43.96715 35.21646 60.63331 -43.29239 34.73659 60.63331 -43.19652 34.25995 60.63331 -43.29219 30.45009 59.43331 -45.81653 33.58231 59.43331 -43.96887 33.853 60.63331 -43.56258 33.48725 59.43331 -44.44743 33.5826 60.63331 -43.96954 32.78028 59.43331 -48.14673 33.58251 59.43331 -44.92559 33.48693 60.63331 -44.44618 33.85312 59.43331 -45.33048 33.5828 60.63331 -44.92605 34.25801 59.43331 -45.60109 33.85312 60.63331 -45.33048 34.73617 59.43331 -45.69635 34.25756 60.63331 -45.60081 35.21473 59.43331 -45.6013 34.73741 60.63331 -45.69667 35.21406 60.63331 -45.601 35.62102 60.63331 -45.33061 35.89141 60.63331 -44.92366 35.98708 60.63331 -44.44701 -2.078283 59.4333 0.1468715 -28.00658 59.43331 -26.65587 -27.18058 59.43331 -27.07674 -27.18058 60.63331 -27.07674 -26.75971 59.43331 -27.90275 -26.75971 60.63331 -27.90275 -28.92222 59.43331 -26.80089 -28.00658 60.63331 -26.65587 -29.57774 59.43331 -27.45641 -28.92222 60.63331 -26.80089 -34.42316 59.43331 -30.31754 -29.72277 59.43331 -28.37205 -29.57774 60.63331 -27.45641 -30.29331 59.43331 -34.4321 -29.3019 59.43331 -29.19806 -29.72277 60.63331 -28.37205 -28.47589 59.43331 -29.61893 -29.3019 60.63331 -29.19806 -27.56025 59.43331 -29.4739 -28.47589 60.63331 -29.61893 -26.90473 59.43331 -28.81838 -27.56025 60.63331 -29.4739 -26.90473 60.63331 -28.81838 0.04303669 59.4333 -1.974449 41.04795 59.4333 20.99385 27.68119 59.4333 8.059003 29.38797 59.4333 6.864382 29.38797 60.6333 6.864382 30.58259 59.4333 5.157608 30.58259 60.6333 5.157608 25.66717 59.4333 8.598933 27.68119 60.6333 8.059003 23.59352 59.4333 8.417205 25.66717 60.6333 8.598933 21.70289 59.4333 7.535687 23.59352 60.6333 8.417206 20.23138 59.4333 6.064184 21.70289 60.6333 7.535688 -33.49033 59.43331 -48.63399 19.34986 59.4333 4.173545 20.23138 60.6333 6.064185 -34.42398 59.43331 -48.70688 -23.76202 59.43331 -39.21452 19.16814 59.4333 2.099896 19.34986 60.6333 4.173546 -32.69422 59.43331 -48.14672 -18.59316 59.43331 -41.90894 19.70807 59.4333 0.08587688 19.16814 60.6333 2.099897 20.90268 59.4333 -1.620898 19.70807 60.6333 0.08587783 22.60946 59.4333 -2.815517 20.90268 60.6333 -1.620897 -13.12571 59.43331 -43.92788 24.62348 59.4333 -3.355446 22.60946 60.6333 -2.815516 26.69713 59.4333 -3.17372 24.62348 60.6333 -3.355445 28.58777 59.4333 -2.292202 26.69713 60.6333 -3.173719 -1.338027 59.43331 -36.6261 30.05927 59.4333 -0.8206993 28.58777 60.6333 -2.292201 43.35462 59.4333 15.64224 30.94079 59.4333 1.069939 30.05927 60.6333 -0.8206983 44.96618 59.4333 10.04186 31.12251 59.4333 3.143589 30.94079 60.6333 1.06994 31.12251 60.6333 3.143589 15.80195 59.4333 43.36326 5.053777 59.4333 30.68642 6.760553 59.4333 29.4918 6.760553 60.6333 29.4918 19.91698 59.4333 41.63212 7.955171 59.4333 27.78502 7.955171 60.6333 27.78502 3.039758 59.4333 31.22635 5.053777 60.6333 30.68642 11.54304 59.4333 44.68618 0.966111 59.4333 31.04462 3.039758 60.6333 31.22635 -0.9245274 59.4333 30.1631 0.966111 60.6333 31.04462 -2.396032 59.4333 28.6916 -0.9245274 60.6333 30.1631 -43.26988 59.43331 -15.34478 -3.277549 59.4333 26.80096 -2.396032 60.6333 28.6916 -3.459275 59.4333 24.72731 -3.277549 60.6333 26.80096 -2.919347 59.4333 22.71329 -3.459275 60.6333 24.72731 -40.96352 59.43331 -20.69688 -1.724728 59.4333 21.00652 -2.919347 60.6333 22.71329 -0.01795309 59.4333 19.8119 -1.724728 60.6333 21.00652 1.996065 59.4333 19.27197 -0.01795309 60.6333 19.8119 4.069715 59.4333 19.4537 1.996065 60.6333 19.27197 5.960353 59.4333 20.33521 4.069715 60.6333 19.4537 7.431858 59.4333 21.80672 5.960353 60.6333 20.33521 33.57641 59.4333 48.92774 8.313376 59.4333 23.69735 7.431858 60.6333 21.80672 34.51006 59.4333 49.00062 23.84809 59.4333 39.50827 8.4951 59.4333 25.771 8.313376 60.6333 23.69736 32.7803 59.4333 48.44047 8.4951 60.6333 25.771 2.164357 59.4333 0.1468713 0.04303681 60.6333 -1.974449 -2.078283 60.6333 0.1468718 30.37938 59.4333 34.72585 0.04303693 59.4333 2.268191 2.164357 60.6333 0.1468715 34.50794 59.4333 30.61275 0.04303705 60.6333 2.268192 39.99456 59.4333 3.521741 40.63096 59.4333 3.258138 40.63096 60.6333 3.258138 40.89456 59.4333 2.621742 40.89456 60.6333 2.621742 39.35817 59.4333 3.258136 39.99456 60.6333 3.521741 37.76216 59.4333 1.677785 39.09456 59.4333 2.62174 39.35817 60.6333 3.258136 38.61571 59.4333 1.242883 39.35817 59.4333 1.985345 39.09456 60.6333 2.62174 39.05061 59.4333 0.3893408 39.99456 59.4333 1.72174 39.35817 60.6333 1.985345 40.63096 59.4333 1.985345 39.99456 60.6333 1.72174 40.63096 60.6333 1.985345 38.90075 59.4333 -0.5568166 45.85675 59.4333 4.282533 35.98877 59.4333 -0.09560441 25.14533 59.4333 -11.3275 25.78172 59.4333 -11.5911 25.78172 60.6333 -11.5911 36.42368 59.4333 -0.9491468 26.04532 59.4333 -12.2275 26.04532 60.6333 -12.2275 24.50893 59.4333 -11.5911 25.14533 60.6333 -11.3275 1.139048 59.43331 -36.23376 24.24532 59.4333 -12.2275 24.50893 60.6333 -11.5911 0.2855079 59.43331 -35.79887 36.13863 59.4333 0.850553 24.50893 59.4333 -12.86389 24.24532 60.6333 -12.2275 1.573952 59.43331 -37.08731 25.14532 59.4333 -13.1275 24.50893 60.6333 -12.86389 25.78172 59.4333 -12.86389 25.14532 60.6333 -13.1275 25.78172 60.6333 -12.86389 1.424094 59.43331 -38.03347 37.27722 59.4333 -1.384049 25.14533 59.4333 18.37098 25.78172 59.4333 18.10738 25.78172 60.6333 18.10738 26.04533 59.4333 17.47098 26.04533 60.6333 17.47098 24.50893 59.4333 18.10738 25.14533 60.6333 18.37098 10.29609 59.4333 3.521744 24.24533 59.4333 17.47098 24.50893 60.6333 18.10738 10.93248 59.4333 3.25814 24.50893 59.4333 16.83459 24.24533 60.6333 17.47098 11.19608 59.4333 2.621745 25.14533 59.4333 16.57098 24.50893 60.6333 16.83459 25.14533 60.6333 16.57098 25.78172 60.6333 16.83459 10.93248 60.6333 3.25814 11.19608 60.6333 2.621745 10.29609 60.6333 3.521744 9.659689 60.6333 3.25814 9.396085 60.6333 2.621744 9.659689 60.6333 1.985349 10.29608 60.6333 1.721744 10.93248 60.6333 1.985348 18.00355 60.6333 25.88555 18.26715 60.6333 25.24916 17.36715 60.6333 26.14916 2.517912 59.4333 11.29992 16.46715 59.4333 25.24916 16.73076 60.6333 25.88555 3.154307 59.4333 11.03631 16.73076 59.4333 24.61276 16.46715 60.6333 25.24916 3.417912 59.4333 10.39992 17.36715 59.4333 24.34916 16.73076 60.6333 24.61276 3.154307 59.4333 9.763525 17.36715 60.6333 24.34916 18.00355 60.6333 24.61276 3.154309 60.6333 40.7348 3.417914 60.6333 40.0984 2.517915 60.6333 40.9984 1.617913 59.4333 40.0984 1.881518 60.6333 40.7348 1.139054 59.4333 38.71954 1.881516 59.4333 39.462 1.617913 60.6333 40.0984 1.573956 59.4333 37.866 2.517913 59.4333 39.1984 1.881516 60.6333 39.462 3.154309 59.4333 39.462 2.517913 60.6333 39.1984 3.154309 60.6333 39.462 10.23336 59.4333 45.77159 -1.48788 59.4333 37.38106 -12.33133 59.4333 26.14916 -11.69493 59.4333 25.88556 -11.69493 60.6333 25.88556 -1.052976 59.4333 36.52751 -11.43133 59.4333 25.24916 -11.43133 60.6333 25.24916 -12.96772 59.4333 25.88556 -12.33133 60.6333 26.14916 -36.3376 59.43331 1.242889 -13.23133 59.4333 25.24916 -12.96772 60.6333 25.88556 -37.19115 59.43331 1.677791 -12.96772 59.4333 24.61276 -13.23133 60.6333 25.24916 -35.9027 59.43331 0.3893465 -12.33133 59.4333 24.34916 -12.96772 60.6333 24.61276 -11.69493 59.4333 24.61277 -12.33133 60.6333 24.34916 -11.69493 60.6333 24.61277 -0.1994355 59.4333 36.09261 -36.05256 59.43331 -0.5568109 3.154307 60.6333 11.03631 3.417912 60.6333 10.39992 2.517912 60.6333 11.29992 1.617912 59.4333 10.39992 1.881515 60.6333 11.03632 1.881516 59.4333 9.763525 1.617912 60.6333 10.39992 2.517911 59.4333 9.499919 1.881516 60.6333 9.763525 2.517911 60.6333 9.499919 3.154307 60.6333 9.763525 1.139048 60.63331 -36.23376 1.573952 60.63331 -37.08731 -0.6606515 59.43331 -35.94872 0.2855079 60.63331 -35.79887 -0.6606515 60.63331 -35.94872 -7.447359 59.43331 -45.23918 -1.487884 59.43331 -37.57225 -1.338027 60.63331 -36.6261 -1.052982 59.43331 -38.4258 -1.487884 60.63331 -37.57225 -0.1994393 59.43331 -38.8607 -1.052982 60.63331 -38.4258 -1.649131 59.43331 -45.82198 0.7467182 59.43331 -38.71084 -0.1994393 60.63331 -38.8607 0.7467182 60.63331 -38.71084 1.424094 60.63331 -38.03347 38.22338 59.4333 -1.234192 38.61571 60.6333 1.242883 39.05061 60.6333 0.3893408 36.816 59.4333 1.527929 37.76216 60.6333 1.677785 36.816 60.6333 1.527929 36.13863 60.6333 0.850553 35.98877 60.6333 -0.09560441 36.42368 60.6333 -0.9491468 37.27722 60.6333 -1.384049 38.22338 60.6333 -1.234192 38.90075 60.6333 -0.5568166 1.139054 60.6333 38.71954 1.573956 60.6333 37.866 0.2855117 60.6333 39.15444 -0.6606457 60.6333 39.00459 -1.338021 60.6333 38.32722 -38.1373 59.43331 1.527935 -1.48788 60.6333 37.38106 -1.052976 60.6333 36.52751 0.7467239 59.4333 36.24247 -0.1994355 60.6333 36.09261 -44.88095 59.43331 -9.744289 1.4241 59.4333 36.91984 0.7467239 60.6333 36.24247 1.4241 60.6333 36.91984 -36.3376 60.63331 1.242889 -35.9027 60.63331 0.3893465 -37.19115 60.63331 1.677791 -38.81468 59.43331 0.8505587 -38.1373 60.63331 1.527935 -38.96454 59.43331 -0.09559869 -38.81468 60.63331 0.8505587 -45.771 59.43331 -3.985203 -38.52964 59.43331 -0.949141 -38.96454 60.63331 -0.09559869 -37.67609 59.43331 -1.384043 -38.52964 60.63331 -0.949141 -36.72993 59.43331 -1.234187 -37.67609 60.63331 -1.384043 -36.72993 60.63331 -1.234187 -36.05256 60.63331 -0.5568109 10.04304 60.6333 52.14687 5.793038 60.6333 52.14686 10.04304 60.6333 46.62267 10.76656 59.4333 45.08322 10.23336 60.6333 45.77159 10.76656 60.6333 45.08322 11.54304 60.6333 44.68618 15.80195 60.6333 43.36326 19.91698 60.6333 41.63212 23.84809 60.6333 39.50827 32.7803 60.6333 48.44047 33.57742 60.6333 48.92864 34.50891 60.6333 49.00135 35.37214 60.6333 48.64279 40.20986 60.6333 44.71845 44.61462 60.6333 40.31369 44.07335 59.4333 30.03751 48.89679 59.4333 34.61388 48.53895 60.6333 35.47597 45.1111 59.4333 30.03751 48.82391 59.4333 33.68024 48.89752 60.6333 34.61275 46.00644 59.4333 30.55392 48.33664 59.4333 32.88412 48.82481 60.6333 33.68125 48.33664 60.6333 32.88412 46.00644 60.6333 30.55392 45.10967 60.6333 30.03628 44.07478 60.6333 30.03629 43.17801 60.6333 30.55392 34.69273 60.6333 39.0392 30.37938 60.6333 34.72585 34.50794 60.6333 30.61275 38.08321 60.6333 26.01083 41.04795 60.6333 20.99385 43.35462 60.6333 15.64224 44.96618 60.6333 10.04186 46.01197 59.4333 -1.543349 45.85675 60.6333 4.282533 4.17606 59.43331 -45.66707 45.42929 59.4333 -7.34232 46.01197 60.6333 -1.543349 9.934892 59.43331 -44.77696 44.11795 59.4333 -13.02132 45.42929 60.6333 -7.34232 15.53511 59.43331 -43.16589 42.09899 59.4333 -18.48901 44.11795 60.6333 -13.02132 20.88696 59.43331 -40.8596 42.09899 60.6333 -18.48901 39.40443 60.63331 -23.65818 34.62201 59.43331 -30.18947 25.90464 59.43331 -37.8949 48.8239 59.43331 -33.3865 48.33663 60.63331 -32.59038 34.51005 59.43331 -48.70688 48.89678 59.43331 -34.32014 48.8248 60.63331 -33.38751 35.37213 59.43331 -48.34904 48.53895 59.43331 -35.18223 48.89751 60.63331 -34.319 40.20985 59.43331 -44.42471 44.61462 59.43331 -40.01995 48.53895 60.63331 -35.18223 44.61462 60.63331 -40.01995 40.20985 60.63331 -44.42471 35.37213 60.63331 -48.34904 34.50891 60.63331 -48.70761 33.57741 60.63331 -48.63489 32.78028 60.63331 -48.14673 29.93259 59.43331 -44.91911 30.45009 60.63331 -45.81653 29.93259 59.43331 -43.88551 29.93245 60.63331 -44.91976 30.45009 59.43331 -42.9881 29.93245 60.63331 -43.88487 30.45009 60.63331 -42.9881 38.93537 60.63331 -34.50282 30.50732 59.43331 -34.31944 34.62201 60.63331 -30.18947 30.50732 60.63331 -34.31944 25.90464 60.63331 -37.8949 20.88696 60.63331 -40.8596 15.53511 60.63331 -43.16589 9.934892 60.63331 -44.77696 4.17606 60.63331 -45.66707 -1.649131 60.63331 -45.82198 -7.447359 60.63331 -45.23918 -13.12571 60.63331 -43.92788 -18.59316 60.63331 -41.90894 -23.76202 60.63331 -39.21452 -32.69422 60.63331 -48.14672 -33.49135 60.63331 -48.63489 -34.42284 60.63331 -48.7076 -35.28607 60.63331 -48.34904 -40.12379 60.63331 -44.4247 -44.52855 60.63331 -40.01994 -43.98935 59.43331 -29.74269 -48.81072 59.43331 -34.32014 -48.45288 60.63331 -35.18222 -45.02295 59.43331 -29.74269 -48.73784 59.43331 -33.38649 -48.81144 60.63331 -34.319 -45.92036 59.43331 -30.26018 -48.25056 59.43331 -32.59037 -48.73873 60.63331 -33.3875 -48.25056 60.63331 -32.59037 -45.92036 60.63331 -30.26018 -45.02359 60.63331 -29.74254 -43.98871 60.63331 -29.74255 -43.09194 60.63331 -30.26018 -34.60666 60.63331 -38.74546 -30.29331 60.63331 -34.4321 -34.42316 60.63331 -30.31754 -37.99874 60.63331 -25.71473 -40.96352 60.63331 -20.69688 -43.26988 60.63331 -15.34478 -44.88095 60.63331 -9.744289 -45.92578 59.4333 1.840147 -45.771 60.63331 -3.985203 -45.92578 60.6333 1.840147 -11.45696 59.4333 44.68618 -44.03143 59.4333 13.31657 -45.34283 60.6333 7.638389 -16.68319 59.4333 42.99816 -42.01252 59.4333 18.78365 -44.03143 60.6333 13.31657 -21.67711 59.4333 40.69604 -42.01252 60.6333 18.78365 -39.31835 60.6333 23.95192 -34.53594 59.4333 30.48322 -26.36096 59.4333 37.81422 -48.73783 59.4333 33.68024 -48.25056 60.6333 32.88413 -34.42398 59.4333 49.00063 -48.81071 59.4333 34.61389 -48.73873 60.6333 33.68126 -35.28606 59.4333 48.64279 -48.45288 59.4333 35.47598 -48.81144 60.6333 34.61275 -40.12378 59.4333 44.71846 -44.52854 59.4333 40.3137 -48.45288 60.6333 35.47598 -44.52854 60.6333 40.3137 -40.12378 60.6333 44.71846 -35.28606 60.6333 48.64279 -34.42284 60.6333 49.00135 -33.49134 60.6333 48.92864 -32.69421 60.6333 48.44047 -29.84652 59.4333 45.21286 -30.36401 60.6333 46.11027 -29.84652 59.4333 44.17926 -29.84638 60.6333 45.2135 -30.36401 59.4333 43.28185 -29.84638 60.6333 44.17862 -30.36401 60.6333 43.28185 -38.8493 60.6333 34.79657 -30.66756 59.4333 34.3939 -34.53594 60.6333 30.48322 -30.66756 60.6333 34.3939 -26.36096 60.6333 37.81422 -21.67711 60.6333 40.69604 -16.68319 60.6333 42.99816 -11.45696 60.6333 44.68618 -10.68048 60.6333 45.08322 -10.14727 60.6333 45.77159 -9.95696 60.6333 46.62267 -9.95696 60.6333 52.14687 -5.706958 60.6333 52.14686 -5.70696 60.6333 46.14687 5.79304 60.6333 46.14687 19.84202 -7.866691 -13.99527 19.89986 -7.866692 -4.014464 19.13492 -7.866692 -3.388673 19.13492 -1.866693 -3.388672 14.18517 -7.866691 -8.338419 18.50912 -7.866692 -2.623723 18.50912 -1.866693 -2.623722 20.75502 -7.866692 -4.471016 19.89986 -1.866693 -4.014463 21.69712 -7.866692 -4.757266 20.75502 -1.866693 -4.471015 22.67045 -7.866692 -4.852006 21.69712 -1.866693 -4.757266 23.64378 -7.866692 -4.757267 22.67045 -1.866693 -4.852005 24.58587 -7.866692 -4.471017 23.64378 -1.866693 -4.757266 25.44648 -7.866692 -4.010508 24.58587 -1.866693 -4.471016 26.20598 -7.866692 -3.388673 25.44648 -1.866693 -4.010507 26.82782 -7.866692 -2.629168 26.20598 -1.866693 -3.388672 35.23733 -7.866694 10.61452 27.28833 -7.866693 -1.768565 26.82782 -1.866693 -2.629167 34.37145 -7.866694 9.318434 27.57458 -7.866693 -0.8264671 27.28833 -1.866693 -1.768564 27.66932 -7.866693 0.1468605 27.57458 -1.866693 -0.8264662 27.57458 -7.866693 1.120188 27.66932 -1.866693 0.1468614 27.28833 -7.866693 2.062285 27.57458 -1.866693 1.120189 33.07537 -7.866694 8.45256 26.83177 -7.866693 2.917444 27.28833 -1.866694 2.062286 31.54303 -7.866694 8.147768 26.20598 -7.866693 3.682394 26.83177 -1.866694 2.917445 30.01069 -7.866694 8.45256 25.44103 -7.866693 4.308185 26.20598 -1.866694 3.682394 28.71461 -7.866694 9.318434 24.58588 -7.866693 4.764738 25.44103 -1.866694 4.308186 23.64378 -7.866693 5.050989 24.58588 -1.866694 4.764739 27.84873 -7.866694 10.61452 22.67045 -7.866693 5.145729 23.64378 -1.866694 5.05099 21.69712 -7.866693 5.050988 22.67045 -1.866694 5.14573 27.54394 -7.866694 12.14686 20.75502 -7.866693 4.764739 21.69712 -1.866694 5.050989 19.89442 -7.866693 4.30423 20.75502 -1.866694 4.764739 19.13492 -7.866693 3.682394 19.89442 -1.866694 4.304231 -2.732996 -7.866689 -18.32319 18.51308 -7.866693 2.92289 19.13492 -1.866693 3.682395 -3.492501 -7.866689 -18.94502 -1.872392 -7.866689 -17.86268 18.05257 -7.866693 2.062286 18.51308 -1.866693 2.922891 -0.9302943 -7.866689 -17.57643 17.76632 -7.866692 1.120187 18.05257 -1.866693 2.062287 0.0430333 -7.866689 -17.48169 17.67158 -7.866692 0.1468614 17.76632 -1.866693 1.120188 1.016359 -7.866689 -17.57643 17.76632 -7.866692 -0.8264662 17.67158 -1.866693 0.1468625 11.35674 -7.866691 -8.338419 18.05257 -7.866692 -1.768564 17.76632 -1.866693 -0.8264652 1.958458 -7.866689 -17.86268 8.528314 -7.86669 -11.16685 13.28983 -7.866691 -7.822011 18.05257 -1.866693 -1.768563 12.25208 -7.866691 -7.822011 -7.957873 -7.866687 -31.35313 -2.727552 -7.866688 -26.64188 -3.492501 -7.866688 -26.01609 -3.492501 -1.866689 -26.01609 -8.262666 -7.866687 -29.82079 -4.118293 -7.866688 -25.25114 -4.118293 -1.866689 -25.25114 -9.128541 -7.866687 -34.18156 -1.872393 -7.866688 -27.09843 -2.727552 -1.866689 -26.64188 -8.262666 -7.866687 -32.88547 9.214606 -7.866687 -34.18156 -0.9302952 -7.866688 -27.38468 -1.872393 -1.866688 -27.09843 10.51069 -7.866687 -35.04743 0.04303228 -7.866688 -27.47942 -0.9302952 -1.866688 -27.38468 1.01636 -7.866688 -27.38468 0.04303228 -1.866689 -27.47942 1.958457 -7.866688 -27.09843 1.01636 -1.866689 -27.38468 2.819061 -7.866688 -26.63792 1.958457 -1.866689 -27.09843 3.578565 -7.866688 -26.01609 2.819061 -1.866689 -26.63792 14.18517 -7.86669 -19.65213 4.200401 -7.866688 -25.25658 3.578565 -1.866689 -26.01609 8.348731 -7.866687 -32.88547 8.043938 -7.866688 -31.35314 8.348731 -7.866688 -29.8208 4.660909 -7.866688 -24.39598 4.200401 -1.866689 -25.25658 8.528314 -7.86669 -13.99527 4.94716 -7.866689 -23.45388 4.660909 -1.866689 -24.39598 5.0419 -7.866689 -22.48055 4.94716 -1.866689 -23.45388 4.947159 -7.866689 -21.50723 5.0419 -1.866689 -22.48055 4.66091 -7.866689 -20.56513 4.947159 -1.86669 -21.50723 4.204357 -7.866689 -19.70997 4.66091 -1.86669 -20.56513 3.578566 -7.866689 -18.94502 4.204357 -1.86669 -19.70997 8.011907 -7.86669 -13.09993 2.813616 -7.866689 -18.31923 3.578566 -1.86669 -18.94502 8.011907 -7.86669 -12.06218 2.813616 -1.86669 -18.31923 1.958458 -1.86669 -17.86268 1.016359 -1.86669 -17.57642 0.0430333 -1.86669 -17.48169 -0.9302943 -1.86669 -17.57642 -1.872392 -1.86669 -17.86268 -2.732996 -1.86669 -18.32318 -11.95697 -7.866688 -27.35404 -4.114336 -7.866689 -19.70453 -3.492501 -1.86669 -18.94502 -10.42463 -7.866687 -27.65883 -4.574845 -7.866689 -20.56513 -4.114336 -1.866689 -19.70452 -4.861095 -7.866688 -21.50723 -4.574845 -1.866689 -20.56513 -4.955835 -7.866688 -22.48055 -4.861095 -1.866689 -21.50723 -9.128541 -7.866687 -28.52471 -4.861096 -7.866688 -23.45388 -4.955835 -1.866689 -22.48055 -4.574846 -7.866688 -24.39598 -4.861096 -1.866689 -23.45388 -4.574846 -1.866689 -24.39598 -29.92462 -7.866689 -8.158831 -25.35497 -7.86669 -4.01446 -26.11992 -7.86669 -3.388669 -26.11992 -1.866691 -3.388668 -31.45696 -7.866689 -7.85404 -26.74571 -7.86669 -2.623719 -26.74571 -1.866691 -2.623718 -28.62854 -7.866689 -9.024706 -24.49981 -7.86669 -4.471013 -25.35497 -1.86669 -4.014459 -23.55771 -7.86669 -4.757264 -24.49981 -1.86669 -4.471012 -27.76266 -7.866689 -10.32079 -22.58438 -7.86669 -4.852004 -23.55771 -1.86669 -4.757263 -21.61105 -7.86669 -4.757263 -22.58438 -1.86669 -4.852003 -27.45787 -7.866689 -11.85313 -20.66896 -7.86669 -4.471014 -21.61105 -1.866691 -4.757262 -19.80835 -7.86669 -4.010505 -20.66896 -1.866691 -4.471013 -19.04885 -7.86669 -3.388669 -19.80835 -1.866691 -4.010504 2.819064 -7.866694 18.61691 -18.42701 -7.86669 -2.629165 -19.04885 -1.866691 -3.388669 3.57857 -7.866694 19.23874 1.958461 -7.866694 18.1564 -17.96651 -7.86669 -1.768561 -18.42701 -1.866691 -2.629164 1.016363 -7.866694 17.87015 -17.68025 -7.866691 -0.8264623 -17.96651 -1.866691 -1.76856 0.04303514 -7.866694 17.77541 -17.58551 -7.866691 0.1468634 -17.68025 -1.866691 -0.8264614 -0.9302905 -7.866694 17.87015 -17.68025 -7.866691 1.120191 -17.58551 -1.866691 0.1468644 -11.27067 -7.866692 8.632145 -17.9665 -7.866691 2.062289 -17.68025 -1.866692 1.120192 -1.872389 -7.866694 18.1564 -8.442247 -7.866693 11.46057 -13.20376 -7.866692 8.115738 -18.42306 -7.866691 2.917448 -17.9665 -1.866692 2.06229 -12.16601 -7.866692 8.115737 -14.0991 -7.866692 8.632145 -19.04885 -7.866691 3.682398 -18.42306 -1.866692 2.917448 -19.75596 -7.866693 14.289 -19.8138 -7.866691 4.308189 -19.04885 -1.866692 3.682399 -20.66896 -7.866691 4.764741 -19.8138 -1.866692 4.30819 -21.61105 -7.866691 5.050992 -20.66896 -1.866692 4.764742 -22.58438 -7.866692 5.145731 -21.61105 -1.866692 5.050992 -23.55771 -7.866692 5.050992 -22.58438 -1.866692 5.145732 -24.49981 -7.866691 4.764742 -23.55771 -1.866692 5.050993 -25.36041 -7.866691 4.304233 -24.49981 -1.866692 4.764743 -26.11992 -7.866691 3.682398 -25.36041 -1.866692 4.304234 -26.74175 -7.866691 2.922893 -26.11992 -1.866691 3.682399 -35.15126 -7.866689 -10.32079 -27.20226 -7.866691 2.06229 -26.74175 -1.866691 2.922894 -34.28539 -7.866689 -9.024706 -27.48851 -7.866691 1.120192 -27.20226 -1.866691 2.062291 -27.58325 -7.866691 0.1468644 -27.48851 -1.866691 1.120193 -27.48851 -7.86669 -0.8264633 -27.58325 -1.866691 0.1468653 -27.20226 -7.86669 -1.76856 -27.48851 -1.866691 -0.8264623 -32.98931 -7.866689 -8.158831 -27.20226 -1.866691 -1.768559 -7.925838 -7.866693 13.39366 -2.727548 -7.866694 18.61295 -3.492498 -7.866694 19.23874 -3.492498 -1.866695 19.23874 -8.442245 -7.866693 14.289 -4.118289 -7.866694 20.00369 -4.118289 -1.866695 20.00369 -7.925839 -7.866693 12.35591 -2.727547 -1.866694 18.61295 -1.872389 -1.866694 18.1564 -0.9302905 -1.866694 17.87015 0.04303514 -1.866694 17.77541 1.016363 -1.866695 17.87015 1.958461 -1.866695 18.1564 2.819064 -1.866695 18.61691 12.04304 -7.866695 27.64776 4.200404 -7.866694 19.99825 3.57857 -1.866695 19.23874 10.5107 -7.866696 27.95256 4.660913 -7.866694 20.85885 4.200404 -1.866695 19.99825 4.947163 -7.866695 21.80095 4.660913 -1.866695 20.85885 5.041903 -7.866695 22.77428 4.947163 -1.866695 21.80095 9.214612 -7.866696 28.81843 4.947164 -7.866695 23.7476 5.041903 -1.866695 22.77428 4.660914 -7.866695 24.6897 4.947164 -1.866696 23.74761 8.348735 -7.866696 30.11452 4.204361 -7.866695 25.54486 4.660914 -1.866696 24.6897 3.57857 -7.866695 26.30981 4.204361 -1.866696 25.54486 8.043943 -7.866696 31.64686 2.81362 -7.866695 26.9356 3.57857 -1.866696 26.30981 9.214612 -7.866696 34.47529 1.958461 -7.866695 27.39216 2.81362 -1.866696 26.9356 8.348735 -7.866696 33.1792 -9.128537 -7.866696 34.47529 1.016364 -7.866695 27.6784 1.958461 -1.866696 27.39216 -10.42462 -7.866696 35.34116 0.04303616 -7.866695 27.77314 1.016364 -1.866696 27.6784 -0.9302914 -7.866695 27.6784 0.04303616 -1.866696 27.77314 -1.872388 -7.866695 27.39216 -0.9302914 -1.866696 27.6784 -2.732992 -7.866695 26.93165 -1.872388 -1.866696 27.39216 -3.492497 -7.866695 26.30981 -2.732992 -1.866696 26.93165 -14.0991 -7.866693 19.94585 -4.114333 -7.866695 25.55031 -3.492497 -1.866695 26.30981 -7.957869 -7.866695 31.64686 -8.26266 -7.866695 30.11452 -8.26266 -7.866696 33.1792 -4.574841 -7.866695 24.6897 -4.114333 -1.866695 25.55031 -4.861092 -7.866694 23.7476 -4.574841 -1.866695 24.6897 -4.955832 -7.866694 22.77428 -4.861092 -1.866695 23.74761 -4.861091 -7.866694 21.80095 -4.955832 -1.866695 22.77428 -4.574842 -7.866694 20.85885 -4.861091 -1.866695 21.80095 -4.574842 -1.866695 20.85885 9.214606 -1.866688 -34.18156 8.348731 -1.866688 -32.88547 16.62272 -7.866687 -38.35313 12.04303 -7.866688 -35.35223 10.51069 -1.866688 -35.04743 13.57537 -7.866688 -35.04743 12.04303 -1.866688 -35.35223 14.87146 -7.866687 -34.18156 13.57537 -1.866688 -35.04743 33.07537 -7.866691 -15.54744 15.73733 -7.866688 -32.88547 14.87146 -1.866688 -34.18156 34.37145 -7.866691 -14.68157 31.54303 -7.866691 -15.85223 16.04213 -7.866688 -31.35314 15.73733 -1.866688 -32.88547 30.01069 -7.866691 -15.54744 15.73733 -7.866688 -29.8208 16.04213 -1.866689 -31.35314 28.7146 -7.866691 -14.68157 14.87146 -7.866688 -28.52471 15.73733 -1.866689 -29.8208 27.84873 -7.866691 -13.38548 13.57537 -7.866688 -27.65884 14.87146 -1.866689 -28.52471 27.54394 -7.866691 -11.85314 12.04303 -7.866688 -27.35404 13.57537 -1.866689 -27.65884 27.84873 -7.866691 -10.3208 10.51069 -7.866688 -27.65884 12.04303 -1.866689 -27.35404 28.7146 -7.866692 -9.024713 9.214606 -7.866688 -28.52471 10.51069 -1.866689 -27.65884 9.214606 -1.866689 -28.52471 19.84202 -7.866691 -16.8237 15.0805 -7.86669 -20.16854 16.11825 -7.86669 -20.16854 17.01359 -7.86669 -19.65213 8.348731 -1.866689 -29.8208 8.043938 -1.866688 -31.35313 -37.15058 -7.866682 -58.57794 -13.48931 -7.866686 -35.04743 -14.78539 -7.866686 -34.18156 -14.78539 -1.866687 -34.18156 -40.77201 -7.866682 -60.07798 -15.65127 -7.866686 -32.88547 -15.65127 -1.866687 -32.88547 -16.53666 -7.866686 -38.35313 -11.95697 -7.866686 -35.35223 -13.48931 -1.866687 -35.04743 -26.41534 -7.866684 -48.23181 -10.42463 -7.866687 -35.04743 -11.95697 -1.866687 -35.35223 -10.42463 -1.866687 -35.04743 -9.128541 -1.866687 -34.18156 -8.262666 -1.866688 -32.88547 -7.957873 -1.866688 -31.35313 -8.262666 -1.866688 -29.82079 -9.128541 -1.866688 -28.52471 -10.42463 -1.866688 -27.65883 27.84873 -7.866695 13.6792 -13.48931 -7.866687 -27.65883 -11.95697 -1.866688 -27.35404 28.71461 -7.866695 14.97529 -14.78539 -7.866687 -28.52471 -13.48931 -1.866688 -27.65883 -52.87666 -7.866681 -68.5558 -15.65127 -7.866687 -29.82079 -14.78539 -1.866688 -28.52471 69.08646 -7.866702 55.65474 -55.46485 -7.86668 -68.89654 -15.95606 -7.866687 -31.35313 -15.65127 -1.866688 -29.82079 -50.46485 -7.86668 -67.5568 -15.95606 -1.866687 -31.35313 -44.1136 -7.866681 -62.12429 -47.10163 -7.866681 -64.67546 -48.39378 -7.866681 -65.96762 9.214612 -1.866696 28.81843 8.348735 -1.866696 30.11452 10.5107 -1.866696 27.95256 -27.76266 -7.866688 -13.38547 13.57538 -7.866696 27.95256 12.04304 -1.866696 27.64776 -28.62854 -7.866688 -14.68156 14.87146 -7.866696 28.81843 13.57538 -1.866696 27.95256 52.96273 -7.866703 68.84954 15.73734 -7.866696 30.11452 14.87146 -1.866697 28.81843 -69.00038 -7.866681 -55.36101 55.55092 -7.866703 69.19027 16.04213 -7.866696 31.64686 15.73734 -1.866697 30.11452 50.55091 -7.866703 67.85054 15.73734 -7.866697 33.1792 16.04213 -1.866697 31.64686 40.85807 -7.866702 60.37171 14.87146 -7.866697 34.47529 15.73734 -1.866697 33.1792 44.19967 -7.866702 62.41802 47.1877 -7.866703 64.9692 48.47985 -7.866703 66.26134 37.23664 -7.866701 58.87167 13.57538 -7.866697 35.34116 14.87146 -1.866697 34.47529 16.62273 -7.866697 38.64686 12.04304 -7.866697 35.64596 13.57538 -1.866697 35.34116 26.50141 -7.866699 48.52554 -16.53665 -7.866696 38.64686 10.5107 -7.866696 35.34116 12.04304 -1.866697 35.64596 10.5107 -1.866697 35.34116 9.214612 -1.866697 34.47529 8.348735 -1.866697 33.1792 8.043943 -1.866697 31.64686 -27.76266 -7.866692 13.6792 -13.4893 -7.866695 27.95256 -14.78539 -7.866695 28.81843 -14.78539 -1.866695 28.81843 -28.62854 -7.866692 14.97529 -15.65126 -7.866695 30.11452 -15.65126 -1.866695 30.11452 -27.45787 -7.866692 12.14686 -11.95696 -7.866695 27.64776 -13.4893 -1.866695 27.95256 -27.76266 -7.866692 10.61452 -10.42462 -7.866695 27.95256 -11.95696 -1.866695 27.64777 -28.62854 -7.866691 9.318439 -9.128537 -7.866695 28.81843 -10.42462 -1.866695 27.95256 -9.128537 -1.866696 28.81843 -19.75595 -7.866693 17.11742 -16.92753 -7.866693 19.94585 -14.99444 -7.866693 20.46226 -16.03219 -7.866693 20.46226 -8.26266 -1.866696 30.11452 -7.957869 -1.866696 31.64686 -8.26266 -1.866696 33.17921 -9.128537 -1.866696 34.47529 -11.95696 -7.866695 35.64596 -10.42462 -1.866696 35.34116 -13.4893 -7.866695 35.34116 -11.95696 -1.866696 35.64596 -14.78539 -7.866696 34.47529 -13.4893 -1.866696 35.34116 -32.9893 -7.866692 15.84117 -15.65126 -7.866695 33.1792 -14.78539 -1.866696 34.47529 -34.28539 -7.866692 14.97529 -31.45696 -7.866692 16.14596 -15.95606 -7.866695 31.64686 -15.65126 -1.866696 33.17921 -29.92462 -7.866692 15.84117 -15.95606 -1.866696 31.64686 28.7146 -1.866691 -14.68156 27.84873 -1.866692 -13.38548 30.01069 -1.866691 -15.54744 31.54303 -1.866691 -15.85223 33.07537 -1.866692 -15.54744 38.54303 -7.866691 -16.43283 35.23733 -7.866692 -13.38548 34.37145 -1.866692 -14.68156 35.54212 -7.866692 -11.85314 35.23733 -1.866692 -13.38548 38.54303 -7.866695 16.72655 35.23733 -7.866692 -10.3208 35.54212 -1.866692 -11.85314 34.37145 -7.866692 -9.024713 35.23733 -1.866692 -10.3208 33.07537 -7.866692 -8.158839 34.37145 -1.866692 -9.024712 31.54303 -7.866692 -7.854044 33.07537 -1.866693 -8.158838 30.01069 -7.866692 -8.158839 31.54303 -1.866693 -7.854043 30.01069 -1.866692 -8.158838 28.7146 -1.866692 -9.024712 20.35843 -7.866691 -15.92836 27.84873 -1.866692 -10.3208 27.54394 -1.866692 -11.85314 28.71461 -1.866695 9.318434 27.84873 -1.866695 10.61452 30.01069 -1.866695 8.45256 31.54303 -1.866695 8.147768 33.07537 -1.866695 8.45256 34.37145 -1.866695 9.318434 35.54212 -7.866695 12.14686 35.23733 -1.866695 10.61452 20.35843 -7.866691 -14.89061 35.23733 -7.866695 13.6792 35.54212 -1.866695 12.14686 58.76785 -7.866699 37.34047 34.37145 -7.866695 14.97529 35.23733 -1.866696 13.6792 64.86537 -7.866701 47.29152 33.07537 -7.866695 15.84116 34.37145 -1.866696 14.97529 62.3142 -7.8667 44.30349 60.26789 -7.8667 40.96189 68.74571 -7.866702 53.06655 31.54303 -7.866695 16.14595 33.07537 -1.866696 15.84116 67.74671 -7.866701 50.65473 30.01069 -7.866695 15.84116 31.54303 -1.866696 16.14595 30.01069 -1.866696 15.84116 28.71461 -1.866695 14.97529 27.84873 -1.866695 13.6792 27.54394 -1.866695 12.14686 -38.45697 -7.866688 -16.43282 -32.9893 -7.866691 8.452565 -34.28539 -7.866691 9.318439 -34.28539 -1.866692 9.318441 -35.15126 -7.866691 10.61452 -35.15126 -1.866692 10.61452 -31.45696 -7.866692 8.14777 -32.9893 -1.866692 8.452566 -29.92462 -7.866692 8.452565 -31.45696 -1.866692 8.147771 -29.92462 -1.866692 8.452566 -28.62854 -1.866692 9.318441 -20.27236 -7.866693 16.22209 -27.76266 -1.866692 10.61452 -27.45787 -1.866693 12.14686 -27.76266 -1.866693 13.67921 -28.62854 -1.866693 14.97529 -29.92462 -1.866693 15.84117 -31.45696 -1.866693 16.14596 -32.9893 -1.866693 15.84117 -38.45696 -7.866692 16.72656 -35.15126 -7.866692 13.67921 -34.28539 -1.866693 14.97529 -35.45606 -7.866692 12.14687 -35.15126 -1.866692 13.67921 -35.45606 -1.866692 12.14687 -64.77929 -7.866683 -46.99779 -32.98931 -7.866688 -15.54743 -34.28539 -7.866688 -14.68156 -34.28539 -1.866689 -14.68156 -58.68178 -7.866684 -37.04674 -35.15126 -7.866688 -13.38547 -35.15126 -1.866689 -13.38547 -62.22813 -7.866683 -44.00976 -60.18183 -7.866683 -40.66816 -68.65964 -7.866682 -52.77281 -31.45697 -7.866688 -15.85223 -32.98931 -1.866689 -15.54743 -67.66063 -7.866682 -50.361 -29.92462 -7.866688 -15.54743 -31.45697 -1.866689 -15.85223 -29.92462 -1.866689 -15.54743 -28.62854 -1.866689 -14.68156 -27.76266 -1.866689 -13.38547 -27.45787 -1.866689 -11.85313 -27.76266 -1.86669 -10.32079 -28.62854 -1.86669 -9.024706 -29.92462 -1.86669 -8.158831 -31.45696 -1.86669 -7.85404 -32.98931 -1.86669 -8.158831 -34.28539 -1.866689 -9.024706 -35.45606 -7.866688 -11.85313 -35.15126 -1.866689 -10.32079 -20.27236 -7.866693 15.18434 -35.45606 -1.866689 -11.85313 60.55091 -7.866703 67.85054 -5.61382 -7.866692 1.561077 -1.371179 -7.866693 5.803717 -5.61382 -1.866692 1.561077 -0.4758408 -7.866693 6.320123 -0.4758406 -1.866693 6.320124 -1.371179 -1.866693 5.803717 -57.93972 -7.866682 -53.59324 -6.130227 -7.866692 0.6657385 -67.66063 -7.866681 -60.36101 -14.0991 -7.86669 -8.338418 -6.130227 -7.866692 -0.3720122 -6.130227 -1.866692 0.6657392 -19.75596 -7.866689 -13.99527 -13.20376 -7.86669 -7.82201 -5.61382 -7.866691 -1.26735 -6.130227 -1.866692 -0.3720115 -7.92584 -7.86669 -12.06218 -1.37118 -7.866691 -5.509991 -1.37118 -1.866691 -5.50999 -8.442249 -7.86669 -11.16684 -11.27067 -7.86669 -8.338418 -12.16601 -7.86669 -7.82201 -5.61382 -1.866692 -1.267349 -7.92584 -7.86669 -13.09993 -0.4758418 -7.866691 -6.026398 -8.442249 -7.866689 -13.99527 0.561909 -7.866691 -6.026398 -0.4758415 -1.866691 -6.026397 -60.46485 -7.86668 -67.5568 1.457247 -7.866691 -5.509991 0.5619092 -1.866691 -6.026397 5.699887 -7.866692 -1.267351 5.699888 -1.866692 -1.26735 1.457247 -1.866691 -5.50999 58.02579 -7.866701 53.88697 6.216294 -7.866692 -0.3720132 67.74671 -7.866703 60.65474 14.18517 -7.866693 8.632143 6.216294 -7.866692 0.6657376 6.216295 -1.866692 -0.3720124 19.84202 -7.866694 14.289 13.28983 -7.866693 8.115736 5.699888 -7.866692 1.561076 6.216295 -1.866693 0.6657383 8.011909 -7.866693 12.35591 1.457248 -7.866692 5.803716 1.457248 -1.866693 5.803717 8.528318 -7.866693 11.46057 11.35674 -7.866693 8.632143 12.25208 -7.866693 8.115736 5.699888 -1.866693 1.561076 8.011909 -7.866693 13.39366 0.5619099 -7.866693 6.320123 8.528318 -7.866694 14.289 0.5619102 -1.866693 6.320124 -16.53666 -1.866686 -38.35313 16.62272 -1.866688 -38.35313 -33.34076 -7.866683 -57.66204 -27.14612 -7.866684 -49.42545 -26.41534 -1.866685 -48.23181 -27.25644 -7.866684 -50.82419 -27.14612 -1.866684 -49.42545 -26.72185 -7.866684 -52.11478 -27.25644 -1.866684 -50.82419 -29.42396 -7.866683 -57.35313 -25.65479 -7.866683 -53.02583 -26.72185 -1.866684 -52.11478 -24.29401 -7.866683 -53.35313 -25.65479 -1.866684 -53.02583 29.51002 -7.866685 -57.35313 24.38008 -7.866686 -53.35313 -24.29401 -1.866684 -53.35313 25.74085 -7.866686 -53.02584 24.38008 -1.866686 -53.35313 26.80791 -7.866686 -52.11478 25.74085 -1.866686 -53.02584 27.34249 -7.866686 -50.82419 26.80791 -1.866686 -52.11478 29.74151 -7.866688 -33.79426 27.23218 -7.866686 -49.42545 27.34249 -1.866687 -50.82419 26.5014 -7.866686 -48.23181 27.23218 -1.866687 -49.42545 26.5014 -1.866687 -48.23181 57.54303 -7.866698 29.61384 53.54303 -7.866697 24.48391 53.54302 -7.866691 -24.19019 53.54302 -1.866691 -24.19019 57.54302 -7.86669 -29.32013 53.21573 -7.866691 -25.55097 53.21573 -1.866691 -25.55097 53.21574 -7.866697 25.84468 53.54303 -1.866698 24.48391 57.85194 -7.866699 33.53065 52.30468 -7.866697 26.91174 53.21574 -1.866698 25.84468 51.01409 -7.866697 27.44632 52.30468 -1.866698 26.91174 49.61535 -7.866697 27.33601 51.01409 -1.866698 27.44632 48.42171 -7.866697 26.60523 49.61535 -1.866698 27.33601 48.42171 -1.866698 26.60523 38.54303 -1.866696 16.72655 33.98415 -7.866689 -29.55163 48.42171 -7.86669 -26.31151 38.54303 -1.866692 -16.43283 58.02577 -7.866687 -53.59325 49.61535 -7.86669 -27.04229 48.42171 -1.866691 -26.31151 51.01409 -7.86669 -27.15261 49.61535 -1.866691 -27.04229 52.30467 -7.866691 -26.61803 51.01409 -1.866691 -27.15261 52.30467 -1.866691 -26.61803 -29.42396 -1.866683 -57.35313 29.51002 -1.866686 -57.35313 -33.34076 -1.866683 -57.66204 -37.15058 -1.866683 -58.57794 -40.77201 -1.866683 -60.07798 -44.1136 -1.866682 -62.12429 -48.39378 -1.866681 -65.96762 -47.10163 -1.866682 -64.67546 -50.46485 -1.866681 -67.5568 -52.87666 -1.866681 -68.5558 68.74571 -7.866702 58.24293 -58.05304 -7.86668 -68.5558 -55.46485 -1.866681 -68.89654 -58.05304 -1.866681 -68.5558 -53.69708 -7.866682 -57.83588 -62.53592 -7.86668 -65.96762 -60.46485 -1.866681 -67.5568 -29.65545 -7.866686 -33.79425 -14.99444 -7.866689 -20.16853 -14.0991 -7.866688 -19.65213 -66.07145 -7.86668 -62.43207 -66.07145 -1.866681 -62.43207 -62.53592 -1.866681 -65.96762 58.13911 -7.866703 68.84954 -68.65964 -7.866681 -57.94919 -67.66063 -1.866681 -60.36101 -68.65964 -1.866682 -57.94919 -69.00038 -1.866682 -55.36101 -68.65964 -1.866682 -52.77281 -66.07145 -7.866683 -48.28994 -67.66063 -1.866683 -50.361 -64.77929 -1.866683 -46.99779 -66.07145 -1.866683 -48.28994 -62.22813 -1.866684 -44.00976 -60.18183 -1.866684 -40.66816 -50.92803 -7.866686 -27.1526 -57.76588 -7.866684 -33.23692 -58.68178 -1.866685 -37.04674 -49.52928 -7.866686 -27.04228 -48.33564 -7.866686 -26.3115 -53.12967 -7.866686 -25.55095 -57.45696 -7.866685 -29.32012 -57.76588 -1.866685 -33.23692 -52.21862 -7.866686 -26.61802 -53.45696 -7.866693 24.48391 -57.45696 -7.866693 29.61385 -57.45696 -1.866686 -29.32012 -53.45696 -7.866686 -24.19018 -57.93971 -7.866696 53.88698 -57.76587 -7.866693 33.53066 -57.45696 -1.866693 29.61385 -53.12966 -7.866693 25.84469 -52.21861 -7.866693 26.91175 -58.68177 -7.866694 37.34048 -57.76587 -1.866694 33.53066 -60.18181 -7.866694 40.96191 -58.68177 -1.866694 37.34048 -62.22812 -7.866695 44.3035 -60.18181 -1.866695 40.96191 -64.77928 -7.866695 47.29153 -62.22812 -1.866695 44.3035 -48.39377 -7.866698 66.26136 -66.07144 -7.866695 48.58368 -66.07144 -1.866696 48.58368 -47.10162 -7.866698 64.9692 -64.77928 -1.866696 47.29153 -50.46483 -7.866698 67.85054 -67.66062 -7.866695 50.65475 -52.87665 -7.866698 68.84954 -68.65963 -7.866695 53.06656 -67.66062 -1.866696 50.65475 -55.46484 -7.866698 69.19028 -69.00037 -7.866696 55.65475 -68.65963 -1.866696 53.06656 -58.05303 -7.866698 68.84954 -68.65963 -7.866696 58.24293 -69.00037 -1.866696 55.65475 -60.46484 -7.866698 67.85054 -67.66062 -7.866697 60.65475 -68.65963 -1.866697 58.24294 -62.5359 -7.866698 66.26136 -66.07144 -7.866697 62.72581 -67.66062 -1.866697 60.65475 -62.5359 -1.866698 66.26136 -66.07144 -1.866698 62.72582 -60.46484 -1.866698 67.85054 -58.05303 -1.866699 68.84954 -55.46484 -1.866699 69.19029 -52.87665 -1.866699 68.84954 -50.46483 -1.866699 67.85054 -47.10162 -1.866699 64.9692 -48.39377 -1.866699 66.26136 -53.69707 -7.866697 58.12962 -44.11359 -7.866698 62.41803 -29.65545 -7.866695 34.08799 -40.77199 -7.866698 60.37173 -44.11359 -1.866698 62.41803 -37.15057 -7.866698 58.87168 -40.77199 -1.866698 60.37173 -33.34075 -7.866697 57.95577 -37.15057 -1.866698 58.87168 -29.42395 -7.866698 57.64686 -33.34075 -1.866698 57.95578 24.38008 -7.8667 53.64686 29.51003 -7.866701 57.64686 -29.42395 -1.866698 57.64686 -24.29401 -7.866697 53.64686 -25.65478 -7.866697 53.31957 -26.72184 -7.866697 52.40851 -27.25642 -7.866697 51.11793 26.80792 -7.866699 52.40851 33.42683 -7.866701 57.95577 29.51003 -1.866701 57.64686 25.74086 -7.8667 53.31956 33.42683 -1.866701 57.95577 27.23218 -7.866699 49.71918 27.3425 -7.866699 51.11792 37.23664 -1.866701 58.87167 40.85807 -1.866702 60.37171 44.19967 -1.866702 62.41802 48.47985 -1.866703 66.26134 47.1877 -1.866703 64.9692 50.55091 -1.866703 67.85054 52.96273 -1.866703 68.84954 55.55092 -1.866704 69.19027 58.13911 -1.866704 68.84954 53.78315 -7.866701 58.12961 62.62199 -7.866703 66.26134 60.55091 -1.866704 67.85054 29.74152 -7.866697 34.08798 15.08051 -7.866694 20.46226 14.18517 -7.866695 19.94585 66.15753 -7.866703 62.7258 66.15753 -1.866703 62.7258 62.62199 -1.866704 66.26134 67.74671 -1.866703 60.65474 68.74571 -1.866703 58.24293 69.08646 -1.866702 55.65474 68.74571 -1.866702 53.06655 66.15753 -7.866701 48.58367 67.74671 -1.866702 50.65473 64.86537 -1.866701 47.29152 66.15753 -1.866701 48.58367 62.3142 -1.866701 44.30349 60.26789 -1.8667 40.96189 58.76785 -1.8667 37.34047 57.85194 -1.866699 33.53065 57.54303 -1.866698 29.61384 57.85194 -7.86669 -33.23693 57.54302 -1.866691 -29.32013 58.76784 -7.866689 -37.04675 57.85194 -1.86669 -33.23693 60.26788 -7.866689 -40.66817 58.76784 -1.86669 -37.04674 62.31419 -7.866688 -44.00977 60.26788 -1.866689 -40.66817 64.86536 -7.866688 -46.9978 62.31419 -1.866689 -44.00977 48.47984 -7.866685 -65.96762 66.15751 -7.866688 -48.28995 66.15751 -1.866689 -48.28995 47.18769 -7.866685 -64.67547 64.86536 -1.866689 -46.9978 50.5509 -7.866685 -67.5568 67.7467 -7.866688 -50.36101 52.96271 -7.866685 -68.55581 68.74571 -7.866688 -52.77283 67.7467 -1.866688 -50.36101 55.5509 -7.866685 -68.89656 69.08644 -7.866687 -55.36102 68.74571 -1.866688 -52.77283 58.13909 -7.866685 -68.55581 68.74571 -7.866687 -57.94921 69.08644 -1.866688 -55.36102 60.55091 -7.866685 -67.5568 67.7467 -7.866686 -60.36101 68.74571 -1.866688 -57.94921 62.62197 -7.866685 -65.96762 66.15751 -7.866686 -62.43209 67.7467 -1.866687 -60.36101 62.62197 -1.866686 -65.96762 66.15751 -1.866687 -62.43209 60.55091 -1.866686 -67.5568 58.13909 -1.866686 -68.55581 55.55091 -1.866685 -68.89656 52.96271 -1.866685 -68.55581 50.5509 -1.866685 -67.5568 47.18769 -1.866686 -64.67546 48.47984 -1.866686 -65.96762 53.78314 -7.866686 -57.83589 44.19966 -7.866685 -62.1243 40.85806 -7.866685 -60.07799 44.19966 -1.866686 -62.1243 37.23664 -7.866685 -58.57795 40.85806 -1.866686 -60.07799 33.42682 -7.866686 -57.66204 37.23664 -1.866686 -58.57795 33.42682 -1.866686 -57.66204 -53.45696 -1.866693 24.48391 -53.12966 -1.866693 25.84469 -53.45696 -1.866687 -24.19018 -53.12967 -1.866686 -25.55095 -52.21862 -1.866686 -26.61802 -50.92803 -1.866686 -27.1526 -49.52928 -1.866686 -27.04228 -48.33564 -1.866687 -26.3115 -38.45697 -1.866688 -16.43282 -33.89809 -7.866694 29.84535 -48.33564 -7.866693 26.60523 -38.45696 -1.866693 16.72656 -49.52928 -7.866693 27.33601 -48.33564 -1.866693 26.60524 -50.92802 -7.866693 27.44633 -49.52928 -1.866694 27.33601 -50.92802 -1.866693 27.44633 -52.21861 -1.866693 26.91175 16.62273 -1.866698 38.64686 -16.53665 -1.866696 38.64686 26.50141 -1.8667 48.52554 27.23218 -1.8667 49.71918 27.3425 -1.8667 51.11792 26.80792 -1.8667 52.40851 25.74086 -1.8667 53.31956 24.38008 -1.8667 53.64686 -24.29401 -1.866698 53.64686 -25.65478 -1.866698 53.31957 -26.72184 -1.866698 52.40851 -27.14611 -7.866697 49.71918 -27.25642 -1.866698 51.11793 -26.41533 -7.866697 48.52554 -27.14611 -1.866698 49.71918 -26.41533 -1.866697 48.52554 58.02577 -1.866688 -53.59325 29.74151 -1.866689 -33.79426 33.98415 -1.86669 -29.55162 53.78314 -1.866687 -57.83589 53.78315 -1.866702 58.12961 20.35843 -7.866694 15.18433 33.98416 -7.866697 29.84534 33.98416 -1.866698 29.84534 58.02579 -1.866702 53.88697 20.35843 -7.866695 16.22208 16.11826 -7.866695 20.46226 17.0136 -7.866695 19.94585 19.84202 -7.866695 17.11742 29.74152 -1.866698 34.08798 -57.93972 -1.866683 -53.59324 -20.27236 -7.866689 -14.89061 -33.89809 -7.866686 -29.55162 -33.89809 -1.866687 -29.55162 -53.69708 -1.866682 -57.83588 -20.27236 -7.866688 -15.92836 -16.92753 -7.866688 -19.65213 -19.75596 -7.866688 -16.8237 -16.03219 -7.866688 -20.16853 -29.65545 -1.866686 -33.79425 -29.65545 -1.866695 34.08799 -57.93971 -1.866697 53.88698 -53.69707 -1.866697 58.12962 -33.89809 -1.866695 29.84535 8.528315 -1.866691 -11.16684 12.25208 -1.866692 -7.82201 11.35674 -1.866692 -8.338418 8.011908 -1.866691 -12.06218 8.011907 -1.866691 -13.09993 8.528314 -1.866691 -13.99527 14.18517 -1.86669 -19.65213 15.0805 -1.86669 -20.16854 16.11825 -1.86669 -20.16853 19.84202 -1.866691 -16.8237 17.01359 -1.86669 -19.65213 20.35843 -1.866691 -15.92836 20.35843 -1.866691 -14.89061 19.84202 -1.866691 -13.99527 14.18517 -1.866692 -8.338418 13.28983 -1.866692 -7.822011 -19.75595 -1.866693 17.11742 -20.27236 -1.866693 16.22209 -20.27236 -1.866693 15.18434 -19.75595 -1.866693 14.289 -14.0991 -1.866693 8.632146 -13.20376 -1.866693 8.115738 -12.16601 -1.866693 8.115738 -8.442247 -1.866693 11.46057 -11.27067 -1.866693 8.632146 -7.925839 -1.866693 12.35591 -7.925838 -1.866694 13.39366 -8.442245 -1.866694 14.289 -14.0991 -1.866694 19.94585 -14.99444 -1.866694 20.46226 -16.03219 -1.866694 20.46226 -16.92753 -1.866694 19.94585 -16.92753 -1.866689 -19.65213 -20.27236 -1.866689 -15.92836 -19.75596 -1.866689 -16.8237 -16.03219 -1.866689 -20.16853 -14.99444 -1.866689 -20.16853 -14.0991 -1.866689 -19.65213 -8.442249 -1.86669 -13.99527 -7.92584 -1.86669 -13.09993 -7.92584 -1.86669 -12.06218 -11.27067 -1.866691 -8.338418 -8.442249 -1.86669 -11.16684 -12.16601 -1.866691 -7.82201 -13.20376 -1.86669 -7.822009 -14.0991 -1.86669 -8.338417 -19.75596 -1.866689 -13.99527 -20.27236 -1.866689 -14.89061 17.0136 -1.866696 19.94585 16.11826 -1.866696 20.46226 15.08051 -1.866696 20.46226 14.18517 -1.866695 19.94585 8.528318 -1.866694 14.289 8.011909 -1.866694 13.39366 8.011909 -1.866694 12.35591 11.35674 -1.866694 8.632144 8.528318 -1.866694 11.46057 12.25208 -1.866694 8.115737 13.28983 -1.866694 8.115736 14.18517 -1.866694 8.632143 19.84202 -1.866695 14.289 20.35843 -1.866695 15.18433 20.35843 -1.866695 16.22208 19.84202 -1.866695 17.11742 -156.2026 3.533335 -158.146 -139.356 3.533332 -141.2994 -140.3176 3.533332 -140.2138 -138.9034 8.53333 -138.7996 -157.2882 3.533335 -157.1844 -141.4033 3.533332 -139.2522 -141.3545 8.533331 -136.845 -155.0107 3.533335 -158.9685 -138.5335 3.533332 -142.4913 -136.9488 8.533331 -141.2506 -153.7282 3.533335 -159.6416 -137.8604 3.533333 -143.7739 -152.3737 3.533335 -160.1554 -137.3466 3.533333 -145.1283 -135.5886 8.533331 -144.0752 -150.9663 3.533335 -160.5025 -136.9996 3.533333 -146.5357 -149.527 3.533335 -160.6772 -136.8248 3.533333 -147.975 -134.891 8.533332 -147.1316 -148.0781 3.533335 -160.6771 -136.8249 3.533333 -149.424 -146.6401 3.533335 -160.5024 -136.9996 3.533333 -150.8619 -134.891 8.533332 -150.2666 -145.2336 3.533335 -160.1559 -137.3462 3.533333 -152.2684 -143.8784 3.533335 -159.6421 -137.8599 3.533333 -153.6236 -135.5886 8.533333 -153.323 -142.5945 3.533335 -158.9682 -138.5338 3.533334 -154.9075 -141.402 3.533335 -158.1449 -139.3571 3.533334 -156.1001 -136.9488 8.533333 -156.1475 -140.3177 3.533335 -157.1843 -138.9034 8.533333 -158.5986 -141.3545 8.533334 -160.5532 -144.179 8.533334 -161.9134 -147.2354 8.533334 -162.6111 -150.3704 8.533335 -162.6111 -153.4268 8.533334 -161.9135 -156.2514 8.533334 -160.5532 -158.2498 3.533335 -156.0988 -158.7024 8.533334 -158.5986 -142.5952 3.533332 -138.4297 -159.0723 3.533335 -154.9068 -160.6571 8.533334 -156.1475 -143.8777 3.533332 -137.7566 -159.7454 3.533334 -153.6243 -145.2322 3.533332 -137.2427 -160.2593 3.533334 -152.2698 -162.0173 8.533334 -153.323 -146.6395 3.533332 -136.8957 -160.6063 3.533334 -150.8625 -148.0789 3.533332 -136.721 -160.781 3.533334 -149.4232 -162.7149 8.533333 -150.2666 -149.5278 3.533332 -136.7211 -160.7809 3.533334 -147.9742 -150.9657 3.533332 -136.8957 -160.6063 3.533334 -146.5363 -162.7149 8.533332 -147.1316 -152.3723 3.533332 -137.2423 -160.2597 3.533334 -145.1298 -153.7274 3.533332 -137.7561 -159.7459 3.533334 -143.7746 -162.0173 8.533332 -144.0752 -155.0114 3.533332 -138.43 -159.072 3.533333 -142.4906 -156.2039 3.533332 -139.2533 -158.2487 3.533333 -141.2981 -160.6571 8.533332 -141.2507 -157.2881 3.533333 -140.2139 -158.7024 8.533331 -138.7996 -156.2514 8.533331 -136.845 -153.4268 8.533331 -135.4847 -150.3704 8.53333 -134.7871 -147.2354 8.53333 -134.7871 -144.179 8.533331 -135.4847 -156.0081 35.53333 -154.0922 -154.1961 35.53333 -155.9042 -155.1669 35.53333 -155.0631 -158.7024 30.53333 -158.5986 -160.6571 30.53333 -156.1475 -156.7022 35.53333 -153.0119 -153.1157 35.53333 -156.5984 -156.2514 30.53333 -160.5532 -157.2355 35.53333 -151.8438 -151.9477 35.53333 -157.1317 -157.5972 35.53333 -150.6119 -150.7157 35.53333 -157.4934 -153.4268 30.53333 -161.9135 -157.7799 35.53333 -149.341 -149.4449 35.53333 -157.6761 -150.3704 30.53333 -162.6111 -157.7799 35.53333 -148.0572 -148.161 35.53333 -157.6761 -157.5972 35.53333 -146.7863 -146.8901 35.53333 -157.4934 -147.2354 30.53333 -162.611 -157.2355 35.53333 -145.5543 -145.6582 35.53333 -157.1317 -144.179 30.53333 -161.9135 -156.7022 35.53333 -144.3863 -144.4901 35.53333 -156.5984 -149.4503 35.53333 -151.1137 -143.4097 35.53333 -155.9042 -141.3545 30.53333 -160.5532 -150.5707 35.53333 -150.4669 -147.0352 35.53333 -150.4669 -142.439 35.53333 -155.0631 -148.1556 35.53333 -151.1137 -146.3883 35.53333 -149.3465 -141.5979 35.53333 -154.0923 -138.9034 30.53333 -158.5986 -147.0352 35.53333 -146.9313 -140.9037 35.53333 -153.0119 -136.9488 30.53333 -156.1475 -146.3883 35.53333 -148.0517 -151.9477 35.53333 -140.2665 -140.3703 35.53333 -151.8438 -153.1157 35.53333 -140.7998 -150.7157 35.53333 -139.9048 -140.0086 35.53333 -150.6119 -135.5886 30.53333 -153.323 -149.4449 35.53333 -139.7221 -139.826 35.53333 -149.341 -134.891 30.53333 -150.2666 -148.161 35.53333 -139.7221 -139.826 35.53333 -148.0572 -146.8901 35.53333 -139.9048 -140.0086 35.53333 -146.7863 -134.891 30.53333 -147.1316 -145.6582 35.53333 -140.2665 -140.3703 35.53333 -145.5543 -135.5886 30.53333 -144.0752 -144.4901 35.53333 -140.7998 -140.9036 35.53333 -144.3863 -143.4098 35.53333 -141.494 -141.5978 35.53333 -143.306 -136.9488 30.53333 -141.2507 -142.439 35.53333 -142.3351 -138.9034 30.53333 -138.7996 -141.3545 30.53333 -136.845 -144.179 30.53333 -135.4847 -147.2354 30.53333 -134.7871 -150.3704 30.53333 -134.7871 -153.4268 30.53333 -135.4847 -148.1556 35.53333 -146.2845 -154.1962 35.53333 -141.494 -156.2514 30.53333 -136.845 -150.5707 35.53333 -146.9313 -155.1669 35.53333 -142.3351 -149.4503 35.53333 -146.2845 -151.2175 35.53333 -148.0517 -156.008 35.53333 -143.3059 -158.7024 30.53333 -138.7996 -160.6571 30.53333 -141.2507 -151.2175 35.53333 -149.3464 -162.0173 30.53333 -144.0752 -162.7149 30.53333 -147.1316 -162.7149 30.53333 -150.2666 -162.0173 30.53333 -153.323 -150.5707 63.53332 -150.4669 -149.4505 63.53332 -151.1137 -151.2175 63.53332 -149.3466 -151.2177 63.53332 -148.0525 -150.5706 63.53332 -146.9315 -149.4495 63.53332 -146.2843 -148.1554 63.53332 -146.2845 -147.0352 63.53332 -146.9313 -146.3883 63.53332 -148.0515 -146.3881 63.53332 -149.3457 -147.0353 63.53332 -150.4667 -148.1563 63.53332 -151.1139 -158.2498 3.533294 156.3925 -141.4032 3.533295 139.5459 -140.3176 3.533295 140.5075 -138.9034 8.533294 139.0933 -157.2882 3.533294 157.4781 -139.356 3.533295 141.5932 -136.9488 8.533294 141.5444 -159.0723 3.533294 155.2006 -142.5951 3.533296 138.7234 -141.3544 8.533294 137.1387 -159.7454 3.533294 153.9181 -143.8777 3.533296 138.0503 -160.2592 3.533294 152.5636 -145.2321 3.533296 137.5365 -144.179 8.533295 135.7785 -160.6063 3.533295 151.1562 -146.6395 3.533296 137.1894 -160.781 3.533295 149.7169 -148.0788 3.533296 137.0147 -147.2354 8.533295 135.0809 -160.7809 3.533295 148.268 -149.5278 3.533296 137.0148 -160.6062 3.533296 146.83 -150.9657 3.533297 137.1895 -150.3704 8.533295 135.0809 -160.2597 3.533296 145.4235 -152.3722 3.533296 137.5361 -159.7459 3.533296 144.0683 -153.7274 3.533296 138.0498 -153.4268 8.533296 135.7785 -159.072 3.533296 142.7844 -155.0113 3.533296 138.7237 -158.2487 3.533296 141.5919 -156.2039 3.533296 139.547 -156.2513 8.533296 137.1387 -157.2881 3.533296 140.5076 -158.7024 8.533295 139.0933 -160.657 8.533295 141.5444 -162.0173 8.533295 144.3689 -162.7149 8.533294 147.4253 -162.7149 8.533294 150.5603 -162.0173 8.533294 153.6167 -160.657 8.533292 156.4413 -156.2026 3.533294 158.4397 -158.7024 8.533292 158.8923 -138.5335 3.533295 142.7851 -155.0106 3.533293 159.2622 -156.2514 8.533292 160.847 -137.8604 3.533295 144.0676 -153.7281 3.533293 159.9353 -137.3466 3.533295 145.4221 -152.3737 3.533293 160.4492 -153.4268 8.533292 162.2072 -136.9995 3.533294 146.8294 -150.9663 3.533293 160.7962 -136.8248 3.533294 148.2687 -149.527 3.533293 160.9709 -150.3704 8.533292 162.9048 -136.8249 3.533294 149.7177 -148.078 3.533293 160.9708 -136.9996 3.533294 151.1556 -146.6401 3.533293 160.7962 -147.2354 8.533292 162.9048 -137.3461 3.533293 152.5622 -145.2336 3.533293 160.4496 -137.8599 3.533293 153.9173 -143.8784 3.533293 159.9358 -144.179 8.533291 162.2072 -138.5338 3.533293 155.2013 -142.5944 3.533293 159.2619 -139.3571 3.533293 156.3938 -141.4019 3.533293 158.4386 -141.3545 8.533291 160.847 -140.3177 3.533293 157.478 -138.9034 8.533291 158.8923 -136.9488 8.533292 156.4413 -135.5885 8.533292 153.6167 -134.8909 8.533293 150.5603 -134.8909 8.533293 147.4253 -135.5885 8.533293 144.3689 -154.196 35.53329 156.198 -156.008 35.53329 154.386 -155.1669 35.53329 155.3568 -158.7024 30.53329 158.8923 -156.2513 30.53329 160.847 -153.1157 35.53329 156.8921 -156.7022 35.53329 153.3056 -160.657 30.53329 156.4413 -151.9476 35.53329 157.4254 -157.2355 35.53329 152.1376 -150.7157 35.53329 157.7871 -157.5972 35.53329 150.9056 -162.0173 30.53329 153.6167 -149.4448 35.53329 157.9698 -157.7799 35.53329 149.6348 -162.7149 30.53329 150.5603 -148.161 35.53329 157.9698 -157.7799 35.53329 148.3509 -146.8901 35.53329 157.7871 -157.5972 35.53329 147.0801 -162.7149 30.53329 147.4253 -145.6582 35.53329 157.4255 -157.2355 35.53329 145.8481 -162.0173 30.53329 144.3689 -144.4901 35.53329 156.8921 -156.7022 35.53329 144.68 -151.2175 35.53329 149.6402 -156.008 35.53329 143.5996 -160.657 30.5333 141.5444 -150.5707 35.53329 150.7606 -150.5707 35.53329 147.2251 -155.1669 35.53329 142.6289 -151.2175 35.53329 148.3455 -149.4503 35.53329 146.5782 -154.1961 35.53329 141.7878 -158.7024 30.5333 139.0933 -147.0351 35.53329 147.225 -153.1157 35.53329 141.0935 -156.2513 30.5333 137.1387 -148.1555 35.53329 146.5782 -140.3703 35.53329 152.1376 -151.9476 35.53329 140.5602 -140.9036 35.53329 153.3057 -140.0086 35.53329 150.9056 -150.7157 35.53329 140.1985 -153.4268 30.5333 135.7785 -139.826 35.53329 149.6348 -149.4449 35.53329 140.0159 -150.3704 30.5333 135.0809 -139.826 35.53329 148.3509 -148.161 35.53329 140.0159 -140.0086 35.53329 147.08 -146.8901 35.53329 140.1985 -147.2354 30.5333 135.0809 -140.3703 35.53329 145.8481 -145.6582 35.53329 140.5602 -144.179 30.5333 135.7785 -140.9036 35.53329 144.68 -144.4901 35.53329 141.0935 -141.5978 35.53329 143.5997 -143.4098 35.53329 141.7877 -141.3545 30.5333 137.1387 -142.4389 35.53329 142.6289 -138.9034 30.5333 139.0933 -136.9488 30.5333 141.5444 -135.5885 30.5333 144.3689 -134.8909 30.5333 147.4253 -134.8909 30.5333 150.5603 -135.5885 30.5333 153.6167 -146.3883 35.53329 148.3455 -141.5979 35.53329 154.3861 -136.9488 30.5333 156.4413 -147.0351 35.53329 150.7606 -142.4389 35.53329 155.3568 -146.3883 35.53329 149.6402 -148.1555 35.53329 151.4074 -143.4097 35.53329 156.1979 -138.9034 30.5333 158.8923 -141.3545 30.5333 160.847 -149.4502 35.53329 151.4074 -144.179 30.53329 162.2072 -147.2354 30.53329 162.9048 -150.3704 30.53329 162.9048 -153.4268 30.53329 162.2072 -150.5707 63.53329 150.7606 -151.2175 63.53329 149.6404 -149.4505 63.53329 151.4074 -148.1563 63.53329 151.4076 -147.0353 63.53329 150.7605 -146.3881 63.53329 149.6394 -146.3883 63.53329 148.3453 -147.0351 63.53329 147.2251 -148.1553 63.53329 146.5782 -149.4495 63.53329 146.578 -150.5705 63.53329 147.2252 -151.2177 63.53329 148.3462 156.2887 3.53328 158.4397 139.4421 3.533283 141.5931 140.4037 3.533283 140.5075 138.9895 8.533284 139.0933 157.3743 3.53328 157.4781 141.4893 3.533283 139.5459 141.4406 8.533283 137.1387 155.0968 3.53328 159.2622 138.6196 3.533283 142.785 137.0349 8.533283 141.5443 153.8143 3.53328 159.9353 137.9465 3.533282 144.0676 152.4598 3.53328 160.4491 137.4327 3.533282 145.422 135.6746 8.533283 144.3689 151.0524 3.53328 160.7962 137.0856 3.533282 146.8294 149.6131 3.53328 160.9709 136.9109 3.533282 148.2687 134.977 8.533282 147.4253 148.1641 3.53328 160.9708 136.911 3.533282 149.7177 146.7262 3.53328 160.7961 137.0857 3.533282 151.1556 134.977 8.533282 150.5603 145.3197 3.53328 160.4496 137.4322 3.533282 152.5621 143.9645 3.53328 159.9358 137.946 3.533282 153.9173 135.6747 8.533281 153.6167 142.6806 3.53328 159.2619 138.6199 3.533281 155.2012 141.488 3.53328 158.4386 139.4432 3.533281 156.3938 137.0349 8.533281 156.4412 140.4038 3.53328 157.478 138.9895 8.533281 158.8923 141.4406 8.53328 160.8469 144.2651 8.53328 162.2071 147.3215 8.53328 162.9048 150.4565 8.533279 162.9048 153.5129 8.53328 162.2072 156.3375 8.53328 160.8469 158.3359 3.53328 156.3925 158.7885 8.53328 158.8923 142.6813 3.533283 138.7234 159.1584 3.53328 155.2005 160.7431 8.53328 156.4412 143.9638 3.533283 138.0503 159.8315 3.533281 153.918 145.3183 3.533283 137.5364 160.3454 3.533281 152.5635 162.1034 8.53328 153.6167 146.7256 3.533283 137.1894 160.6924 3.533281 151.1562 148.1649 3.533283 137.0147 160.8671 3.533281 149.7169 162.801 8.533281 150.5603 149.6139 3.533283 137.0148 160.867 3.533281 148.2679 151.0518 3.533283 137.1894 160.6924 3.533281 146.83 162.801 8.533282 147.4253 152.4584 3.533283 137.536 160.3458 3.533281 145.4235 153.8135 3.533283 138.0498 159.832 3.533281 144.0683 162.1034 8.533282 144.3689 155.0975 3.533283 138.7237 159.1581 3.533282 142.7843 156.29 3.533283 139.547 158.3348 3.533282 141.5918 160.7432 8.533282 141.5444 157.3742 3.533282 140.5076 158.7885 8.533283 139.0933 156.3375 8.533283 137.1387 153.5129 8.533283 135.7784 150.4565 8.533284 135.0808 147.3215 8.533284 135.0808 144.2651 8.533283 135.7784 156.0942 35.53328 154.3859 154.2821 35.53328 156.1979 155.253 35.53328 155.3568 158.7885 30.53328 158.8923 160.7432 30.53328 156.4412 156.7883 35.53328 153.3056 153.2018 35.53328 156.8921 156.3375 30.53328 160.8469 157.3216 35.53328 152.1375 152.0338 35.53328 157.4254 157.6833 35.53328 150.9056 150.8018 35.53328 157.7871 153.5129 30.53328 162.2072 157.866 35.53328 149.6347 149.5309 35.53328 157.9698 150.4565 30.53328 162.9048 157.866 35.53328 148.3509 148.2471 35.53328 157.9698 157.6833 35.53328 147.08 146.9762 35.53328 157.7871 147.3215 30.53328 162.9048 157.3216 35.53328 145.848 145.7443 35.53328 157.4254 144.2651 30.53328 162.2072 156.7883 35.53328 144.68 144.5762 35.53328 156.8921 149.5364 35.53328 151.4074 143.4958 35.53328 156.1979 141.4406 30.53328 160.8469 150.6568 35.53328 150.7606 147.1213 35.53328 150.7606 142.5251 35.53328 155.3568 148.2416 35.53328 151.4074 146.4744 35.53328 149.6402 141.684 35.53328 154.386 138.9895 30.53328 158.8923 147.1212 35.53328 147.225 140.9897 35.53328 153.3056 137.0349 30.53328 156.4412 146.4744 35.53328 148.3454 152.0338 35.53328 140.5602 140.4564 35.53328 152.1375 153.2018 35.53328 141.0935 150.8018 35.53328 140.1985 140.0947 35.53328 150.9056 135.6747 30.53328 153.6167 149.531 35.53328 140.0158 139.9121 35.53328 149.6347 134.9771 30.53328 150.5603 148.2471 35.53328 140.0158 139.9121 35.53328 148.3509 146.9762 35.53328 140.1985 140.0947 35.53328 147.08 134.977 30.53328 147.4253 145.7443 35.53328 140.5602 140.4564 35.53328 145.848 135.6746 30.53328 144.3689 144.5762 35.53328 141.0935 140.9897 35.53328 144.68 143.4959 35.53328 141.7877 141.6839 35.53328 143.5997 137.0349 30.53328 141.5444 142.5251 35.53328 142.6288 138.9895 30.53328 139.0933 141.4406 30.53328 137.1387 144.2651 30.53328 135.7784 147.3215 30.53328 135.0808 150.4565 30.53328 135.0808 153.5129 30.53328 135.7784 148.2417 35.53328 146.5782 154.2823 35.53328 141.7877 156.3375 30.53328 137.1387 150.6568 35.53328 147.225 155.253 35.53328 142.6288 149.5364 35.53328 146.5782 151.3036 35.53328 148.3454 156.0941 35.53328 143.5996 158.7885 30.53328 139.0933 160.7432 30.53328 141.5444 151.3036 35.53328 149.6401 162.1034 30.53328 144.3689 162.801 30.53328 147.4253 162.801 30.53328 150.5603 162.1034 30.53328 153.6167 150.6568 63.53328 150.7606 149.5366 63.53328 151.4074 151.3036 63.53328 149.6404 151.3038 63.53328 148.3462 150.6566 63.53328 147.2252 149.5356 63.53328 146.578 148.2415 63.53328 146.5782 147.1212 63.53328 147.225 146.4744 63.53328 148.3453 146.4742 63.53328 149.6394 147.1214 63.53328 150.7604 148.2424 63.53328 151.4076 158.3359 3.533321 -156.0988 141.4893 3.53332 -139.2522 140.4037 3.53332 -140.2138 138.9895 8.53332 -138.7996 157.3743 3.533321 -157.1844 139.4421 3.53332 -141.2994 137.0349 8.53332 -141.2507 159.1584 3.533321 -154.9069 142.6812 3.533319 -138.4297 141.4405 8.53332 -136.845 159.8315 3.533321 -153.6244 143.9638 3.533319 -137.7566 160.3453 3.533321 -152.2699 145.3182 3.533319 -137.2428 144.2651 8.533318 -135.4848 160.6924 3.53332 -150.8625 146.7256 3.533319 -136.8957 160.8671 3.53332 -149.4232 148.1649 3.533319 -136.721 147.3215 8.533318 -134.7872 160.867 3.53332 -147.9743 149.6139 3.533319 -136.7211 160.6923 3.533319 -146.5363 151.0518 3.533318 -136.8958 150.4565 8.533318 -134.7872 160.3458 3.533319 -145.1298 152.4583 3.533319 -137.2423 159.832 3.533319 -143.7746 153.8135 3.533319 -137.7561 153.5129 8.533317 -135.4848 159.1581 3.533319 -142.4907 155.0974 3.533319 -138.43 158.3348 3.533319 -141.2982 156.29 3.533319 -139.2533 156.3374 8.533317 -136.845 157.3742 3.533319 -140.2139 158.7885 8.533318 -138.7996 160.7431 8.533318 -141.2507 162.1033 8.533318 -144.0752 162.801 8.53332 -147.1316 162.801 8.53332 -150.2666 162.1034 8.53332 -153.323 160.7431 8.533322 -156.1476 156.2887 3.533321 -158.146 158.7885 8.533322 -158.5986 138.6196 3.53332 -142.4914 155.0967 3.533322 -158.9685 156.3374 8.533322 -160.5532 137.9465 3.53332 -143.7739 153.8142 3.533322 -159.6416 137.4326 3.53332 -145.1284 152.4597 3.533322 -160.1555 153.5129 8.533322 -161.9135 137.0856 3.533321 -146.5357 151.0524 3.533322 -160.5025 136.9109 3.533321 -147.975 149.6131 3.533322 -160.6772 150.4565 8.533322 -162.6111 136.911 3.533321 -149.424 148.1641 3.533322 -160.6771 137.0856 3.533321 -150.8619 146.7262 3.533322 -160.5025 147.3215 8.533322 -162.6111 137.4322 3.533322 -152.2684 145.3197 3.533322 -160.1559 137.946 3.533322 -153.6236 143.9645 3.533322 -159.6421 144.2651 8.533323 -161.9135 138.6199 3.533322 -154.9076 142.6805 3.533322 -158.9682 139.4432 3.533322 -156.1001 141.488 3.533322 -158.1449 141.4405 8.533323 -160.5533 140.4038 3.533322 -157.1843 138.9895 8.533323 -158.5986 137.0348 8.533322 -156.1476 135.6746 8.533322 -153.323 134.977 8.533321 -150.2666 134.977 8.533321 -147.1316 135.6746 8.533321 -144.0752 154.2821 35.53332 -155.9042 156.0941 35.53332 -154.0923 155.253 35.53332 -155.0631 158.7885 30.53332 -158.5986 156.3374 30.53332 -160.5532 153.2018 35.53332 -156.5984 156.7883 35.53332 -153.0119 160.7431 30.53332 -156.1476 152.0337 35.53332 -157.1317 157.3216 35.53332 -151.8439 150.8018 35.53332 -157.4934 157.6833 35.53332 -150.6119 162.1034 30.53332 -153.323 149.5309 35.53332 -157.6761 157.8659 35.53332 -149.341 162.801 30.53332 -150.2666 148.2471 35.53332 -157.6761 157.8659 35.53332 -148.0572 146.9762 35.53332 -157.4934 157.6833 35.53332 -146.7863 162.8009 30.53332 -147.1316 145.7442 35.53332 -157.1317 157.3216 35.53332 -145.5544 162.1034 30.53332 -144.0752 144.5762 35.53332 -156.5984 156.7883 35.53332 -144.3863 151.3036 35.53332 -149.3465 156.0941 35.53332 -143.3059 160.7431 30.53332 -141.2507 150.6568 35.53332 -150.4669 150.6567 35.53332 -146.9313 155.253 35.53332 -142.3352 151.3036 35.53332 -148.0518 149.5364 35.53332 -146.2845 154.2822 35.53332 -141.4941 158.7885 30.53332 -138.7996 147.1212 35.53332 -146.9313 153.2018 35.53332 -140.7998 156.3374 30.53332 -136.845 148.2416 35.53332 -146.2845 140.4564 35.53332 -151.8439 152.0337 35.53332 -140.2665 140.9897 35.53332 -153.0119 140.0947 35.53332 -150.6119 150.8018 35.53332 -139.9048 153.5129 30.53332 -135.4848 139.912 35.53332 -149.341 149.5309 35.53332 -139.7222 150.4565 30.53332 -134.7872 139.912 35.53332 -148.0572 148.2471 35.53332 -139.7222 140.0947 35.53332 -146.7863 146.9762 35.53332 -139.9048 147.3215 30.53332 -134.7871 140.4564 35.53332 -145.5544 145.7442 35.53332 -140.2665 144.2651 30.53332 -135.4848 140.9897 35.53332 -144.3863 144.5762 35.53332 -140.7998 141.6838 35.53332 -143.306 143.4959 35.53332 -141.494 141.4405 30.53332 -136.845 142.525 35.53332 -142.3352 138.9895 30.53332 -138.7996 137.0348 30.53332 -141.2507 135.6746 30.53332 -144.0752 134.977 30.53332 -147.1316 134.977 30.53332 -150.2666 135.6746 30.53332 -153.323 146.4744 35.53332 -148.0518 141.6839 35.53332 -154.0923 137.0348 30.53332 -156.1476 147.1212 35.53332 -150.4669 142.525 35.53332 -155.0631 146.4744 35.53332 -149.3465 148.2416 35.53332 -151.1137 143.4958 35.53332 -155.9042 138.9895 30.53332 -158.5986 141.4405 30.53332 -160.5533 149.5363 35.53332 -151.1137 144.2651 30.53332 -161.9135 147.3215 30.53332 -162.6111 150.4565 30.53332 -162.6111 153.5129 30.53332 -161.9135 150.6568 63.53332 -150.4669 151.3036 63.53332 -149.3467 149.5365 63.53332 -151.1137 148.2424 63.53332 -151.1139 147.1214 63.53332 -150.4667 146.4742 63.53332 -149.3457 146.4744 63.53332 -148.0516 147.1212 63.53332 -146.9313 148.2414 63.53332 -146.2845 149.5356 63.53332 -146.2843 150.6566 63.53332 -146.9315 151.3038 63.53332 -148.0525 -151.2177 48.53335 -149.3462 -153.561 48.53335 -150.9179 -152.5152 48.53335 -152.4114 -152.5152 52.46917 -152.4114 -150.5707 48.53335 -150.4669 -151.0217 48.53335 -153.4571 -151.4212 54.10024 -153.2496 -152.264 52.34397 -152.6467 -151.7158 53.173 -153.0669 -152.0013 52.22085 -152.8624 -148.3455 48.53334 -143.4691 -154.0329 48.53335 -149.1565 -153.561 58.53335 -150.9179 -150.5707 48.53335 -146.9313 -151.2177 48.53335 -148.0521 -153.4212 53.3458 -151.1959 -153.3716 53.07383 -151.286 -153.2384 52.88782 -151.5079 -152.9044 52.68132 -151.9763 -150.1615 48.53334 -143.628 -153.874 48.53335 -147.3405 -154.0329 58.53335 -149.1565 -151.8144 48.53335 -144.3987 -153.1033 48.53335 -145.6876 -153.874 58.53335 -147.3405 -153.1033 58.53335 -145.6876 -151.8144 58.53335 -144.3987 -150.1615 58.53334 -143.628 -149.45 48.53335 -146.2843 -146.5841 48.53334 -143.9411 -148.3455 58.53334 -143.4691 -147.0351 48.53335 -146.9313 -145.0906 48.53335 -144.9868 -146.1846 54.10024 -144.1486 -148.1558 48.53335 -146.2843 -146.5841 58.53334 -143.9411 -146.3881 48.53335 -148.0521 -144.0449 48.53335 -146.4803 -145.0906 52.46917 -144.9868 -145.89 53.173 -144.3313 -145.6045 52.22085 -144.5359 -145.3418 52.34397 -144.7515 -149.2603 48.53335 -153.9291 -143.5729 48.53335 -148.2417 -144.0449 58.53335 -146.4803 -147.0352 48.53335 -150.4669 -146.3881 48.53335 -149.3462 -144.1847 53.3458 -146.2023 -144.7014 52.68132 -145.4219 -144.2342 53.07383 -146.1123 -144.3675 52.88782 -145.8903 -147.4443 48.53335 -153.7702 -143.7318 48.53335 -150.0577 -143.5729 58.53335 -148.2417 -145.7914 48.53335 -152.9995 -144.5025 48.53335 -151.7106 -143.7318 58.53335 -150.0577 -144.5025 58.53335 -151.7106 -145.7914 58.53335 -152.9995 -147.4443 58.53335 -153.7702 -148.1559 48.53335 -151.1139 -149.2603 58.53335 -153.9291 -149.45 48.53335 -151.1139 -151.0217 58.53335 -153.4571 -150.5707 58.53335 -150.4669 -151.2177 58.53335 -149.3462 -149.45 58.53335 -151.1139 -148.1559 58.53335 -151.1139 -147.0352 58.53335 -150.4669 -146.3881 58.53335 -149.3461 -146.3881 58.53335 -148.052 -147.0351 58.53335 -146.9313 -148.1558 58.53335 -146.2843 -149.45 58.53335 -146.2843 -150.5707 58.53335 -146.9313 -151.2177 58.53335 -148.052 -152.5152 58.53335 -152.4114 -152.5152 54.59752 -152.4114 -153.3062 53.9613 -151.3978 -153.1815 54.58818 -151.5958 -153.0265 54.77139 -151.8174 -152.8189 54.76081 -152.0806 -152.6713 54.67961 -152.2485 -151.9912 54.34461 -152.8701 -145.0906 58.53335 -144.9868 -145.0906 54.59752 -144.9868 -144.9346 54.67961 -145.1497 -144.2996 53.9613 -146.0004 -144.4243 54.58818 -145.8025 -144.5794 54.77139 -145.5808 -144.787 54.76081 -145.3176 -145.6146 54.34461 -144.5281 -155.5141 52.66113 -154.6645 -155.7528 52.91808 -154.5108 -155.6532 52.76138 -154.5714 -153.5048 53.41893 -151.3172 -155.7975 53.10725 -154.4922 -153.2883 54.46337 -151.6383 -153.5302 53.52368 -151.3965 -155.4633 54.40587 -154.8264 -153.247 54.53362 -151.6332 -155.5391 54.23916 -154.7603 -155.1879 54.56924 -155.0367 -155.34 54.52198 -154.9236 -155.0304 54.54051 -155.1482 -151.5491 54.10024 -153.3775 -158.3975 53.41805 -162.8766 -146.0567 54.10024 -144.0207 -142.5754 54.54051 -142.2501 -137.3137 53.22931 -131.8937 -145.573 52.22085 -144.5044 -142.0917 52.66112 -142.7338 -152.0328 52.22085 -152.8938 -141.853 52.91814 -142.8874 -141.9955 52.72075 -142.7988 -141.9141 52.80843 -142.8512 -144.101 53.41893 -146.081 -141.807 53.17266 -142.9022 -141.8165 53.04237 -142.9048 -144.3175 54.46337 -145.7599 -144.0757 53.52368 -146.0017 -142.1791 54.45127 -142.5422 -144.3589 54.53362 -145.7651 -142.1112 54.35462 -142.5981 -142.3653 54.5618 -142.4 -142.2658 54.52194 -142.4746 -142.471 54.56811 -142.3234 -138.93 53.37158 -134.1474 -140.8519 54.41698 -140.0467 -139.1512 54.38049 -138.2041 -137.4908 54.41776 -136.6885 -135.8898 54.51683 -135.4725 -134.3634 54.66596 -134.5255 -132.4734 52.68257 -124.929 -135.1519 52.6773 -128.1926 -141.2881 52.11901 -138.3561 -141.4707 52.26998 -138.5257 -141.7126 53.21007 -138.2836 -141.6113 53.32662 -138.0633 -139.8931 53.42651 -135.5092 -140.4446 53.43906 -136.3008 -140.7391 53.43655 -136.7294 -140.8184 53.43435 -136.8457 -141.1417 53.41585 -137.3261 -141.4091 53.38161 -137.7354 -140.3042 54.42775 -139.6112 -137.844 54.42961 -137.1582 -135.0625 54.61185 -135.0848 -132.9019 54.85708 -133.8067 -131.4349 55.09227 -133.2535 -131.9629 55.02033 -133.5724 -129.9121 55.36996 -132.8097 -128.3998 55.66714 -132.4521 -128.6713 55.6286 -132.6442 -126.9453 55.96333 -132.1484 -125.4996 56.25875 -131.8505 -127.7036 52.28247 -118.6047 -124.0004 56.55637 -131.5078 -125.3391 56.30689 -131.9475 -122.534 56.82887 -131.1001 -121.1557 57.05702 -130.6083 -122.0445 56.93032 -131.0753 -119.7572 57.2542 -129.976 -118.2299 57.43107 -129.1359 -118.9122 57.37617 -129.6753 -116.5455 57.58372 -128.0447 -123.0097 52.02281 -112.9018 -114.7643 57.70387 -126.7302 -116.0013 57.64692 -127.8164 -113.1139 57.7861 -125.3994 -113.2659 57.80382 -125.6907 -111.5962 57.84561 -124.1129 -118.4215 51.86907 -107.7163 -110.0529 57.89632 -122.7667 -110.6266 57.90399 -123.4406 -108.3243 57.94213 -121.216 -106.3688 57.97999 -119.4077 -108.0395 57.97492 -121.1291 -113.9483 51.80539 -102.9956 -104.1773 58.00497 -117.3132 -105.5014 58.01927 -118.7633 -101.7102 58.01148 -114.8714 -103.0098 58.0389 -116.348 -109.5987 51.81939 -98.70045 -98.92485 57.99222 -112.0112 -100.5621 58.03573 -113.888 -95.78968 57.93867 -108.668 -98.15538 58.01174 -111.3881 -105.3947 51.88926 -94.76795 -92.33729 57.84422 -104.8486 -93.45075 57.90951 -106.2862 -95.78611 57.96898 -108.8527 -101.3438 52.00104 -91.15139 -88.60824 57.70606 -100.5828 -91.14545 57.83543 -103.6931 -97.45317 52.14292 -87.81201 -84.5885 57.52438 -95.8571 -86.60862 57.65187 -98.44303 -88.86618 57.74883 -101.0773 -90.16864 52.46769 -81.78939 -80.17726 57.29988 -90.57355 -84.36841 57.54672 -95.79425 -93.72753 52.30035 -84.69804 -83.55783 52.80747 -76.49884 -75.30628 57.04577 -84.71525 -79.92271 57.32007 -90.46791 -86.77906 52.63875 -79.06447 -82.14128 57.4354 -93.13462 -80.47412 52.97303 -74.05836 -70.40185 56.79182 -78.8241 -73.2687 56.97316 -82.46601 -75.48886 57.08781 -85.13159 -77.70684 57.20346 -87.79895 -74.50878 53.2938 -69.33942 -66.0438 56.54178 -73.49449 -68.83675 56.74011 -77.12852 -77.49874 53.13361 -71.70695 -71.04857 56.85855 -79.80052 -68.18291 53.64812 -64.39025 -62.33632 56.28173 -68.77658 -64.47731 56.47369 -71.7339 -71.43682 53.46161 -66.91946 -66.64347 56.61311 -74.44178 -64.63813 53.88528 -61.76697 -59.1495 56.00252 -64.50489 -60.25814 56.14381 -66.23297 -62.34623 56.31836 -68.99929 -58.74868 54.69371 -59.01869 -56.41185 55.70651 -60.6171 -58.22032 55.94715 -63.43101 -59.21837 54.51531 -58.79518 -59.75046 54.35963 -58.72238 -60.2901 54.24376 -58.81179 -60.78128 54.17869 -59.05015 -58.50786 54.5351 -58.76711 -56.24289 55.72528 -60.58483 -59.27613 54.2559 -58.45053 -60.12578 54.04061 -58.46369 -60.92474 53.92271 -58.80451 -69.18061 53.34223 -64.805 -77.20095 52.90139 -71.11241 -85.20104 52.47183 -77.44347 -93.14384 52.07705 -83.85231 -100.9491 51.76266 -90.436 -108.5273 51.57585 -97.28836 -115.7827 51.56117 -104.4867 -122.6541 51.73966 -112.0515 -129.1181 52.11161 -119.9608 -140.4558 52.54157 -140.6334 -139.829 52.5804 -140.0869 -137.3264 52.52609 -137.4438 -136.8306 51.34999 -132.3783 -138.6702 51.55831 -134.914 -138.8688 52.50141 -138.8903 -140.9806 52.00047 -137.985 -140.568 51.88709 -137.4582 -140.3131 51.82933 -137.1251 -140.1452 51.79466 -136.9035 -139.6399 51.70227 -136.2292 -122.0336 54.95229 -131.578 -130.3424 50.64914 -123.1669 -134.7355 51.07273 -128.6003 -123.8294 54.61591 -132.0669 -125.9475 54.18929 -132.5272 -128.1324 53.74464 -132.9845 -130.0323 53.37732 -133.4571 -131.6516 53.09587 -133.9829 -133.0675 52.88716 -134.5878 -134.429 52.72706 -135.3273 -135.8447 52.60457 -136.2671 -113.5013 55.86616 -126.5966 -123.6896 50.19921 -114.7659 -128.7014 50.50727 -120.3691 -115.0863 55.7748 -127.8266 -116.6076 55.65932 -128.8992 -117.9752 55.52752 -129.7547 -119.2424 55.37868 -130.4436 -120.5461 55.19676 -131.0404 -106.3855 56.09236 -120.3597 -117.1794 49.97192 -107.3726 -122.2378 50.13519 -112.4597 -108.4489 56.04795 -122.2506 -110.2579 55.99546 -123.8556 -111.9019 55.93658 -125.2708 -101.4487 56.13257 -115.5792 -110.9804 49.92451 -100.9893 -115.3658 49.95719 -104.8962 -104.0632 56.12276 -118.1556 -95.1463 56.05572 -108.9782 -105.0754 50.00605 -95.40116 -108.1111 49.97162 -97.69755 -98.49288 56.11351 -112.5492 -91.34352 55.94798 -104.7568 -99.49746 50.16918 -90.45706 -100.5331 50.15864 -90.84617 -87.00627 55.7791 -99.76332 -94.25557 50.37623 -86.01966 -81.97528 55.53878 -93.79856 -89.33911 50.60512 -81.99256 -92.72838 50.47302 -84.26301 -76.29949 55.2422 -86.97042 -84.73249 50.84019 -78.2993 -70.78871 54.95728 -80.35257 -80.41928 51.0706 -74.88137 -84.78612 50.86782 -77.85473 -76.39553 51.28763 -71.70095 -76.78657 51.29741 -71.5244 -66.07676 54.69425 -74.61862 -72.57646 51.49226 -68.67695 -68.7703 51.70597 -65.70114 -62.11665 54.42284 -69.60393 -64.74758 51.96276 -62.6762 -68.76707 51.73807 -65.2171 -58.7978 54.13599 -65.17055 -60.29758 52.2993 -59.53384 -55.92816 53.82713 -61.10079 -59.8064 52.36437 -59.29548 -60.51189 52.31855 -59.21737 -59.26677 52.48025 -59.20607 -59.71293 52.43646 -58.87654 -58.73468 52.63592 -59.27887 -58.86328 52.65174 -58.86339 -58.26499 52.81433 -59.50238 -55.76666 53.87488 -61.06106 -58.095 52.93095 -59.17996 -55.52642 54.02311 -60.97871 -55.61463 53.95391 -61.01342 -57.74491 54.09978 -63.9065 -59.78274 54.29645 -66.70851 -64.00196 54.62634 -72.20951 -61.87086 54.47101 -69.47486 -66.16822 54.76574 -74.91741 -72.79306 55.12604 -82.94219 -68.36155 54.89273 -77.60416 -70.57318 55.01129 -80.27645 -77.23224 55.35589 -88.27445 -75.01413 55.24028 -85.60713 -83.89347 55.69938 -96.2703 -79.44765 55.47274 -90.9439 -81.66619 55.5881 -93.61069 -88.39132 55.90149 -101.5535 -86.13375 55.80452 -98.91913 -92.97602 56.06217 -106.7625 -90.67066 55.98809 -104.1693 -95.31143 56.12163 -109.3289 -100.0876 56.18836 -114.3644 -97.68075 56.16439 -111.8644 -102.5353 56.19153 -116.8244 -105.0269 56.17189 -119.2397 -107.5651 56.12753 -121.6056 -110.1522 56.05661 -123.9171 -112.7916 55.95642 -126.1672 -115.527 55.79946 -128.2927 -118.4379 55.52869 -130.1515 -121.57 55.08282 -131.5511 -124.8647 54.4593 -132.4232 -128.1971 53.78099 -133.12 -131.4887 53.17274 -134.0483 -134.5878 52.76439 -135.5607 -137.3689 52.58223 -137.634 -142.0667 54.23916 -142.6379 -141.8249 53.29947 -142.8799 -140.4078 53.19174 -141.0441 -140.2669 54.11313 -140.3484 -139.962 54.21557 -139.9086 -57.85754 54.70759 -64.38378 -58.49966 55.68738 -64.69802 -55.62139 55.37125 -60.59141 -55.67924 55.49145 -60.56364 -55.37955 54.43156 -60.83326 -58.33728 54.19417 -58.73374 -60.64477 54.96463 -68.16973 -61.87879 55.98456 -69.23188 -59.71018 55.91333 -66.25347 -57.66754 55.71348 -63.43433 -63.88293 55.20874 -72.35643 -63.12411 56.07823 -70.84112 -61.80363 56.0906 -69.03572 -64.44371 56.16996 -72.51712 -63.9405 56.24819 -71.78489 -65.07933 55.28753 -73.85895 -65.84468 56.26013 -74.2685 -66.33934 55.36531 -75.42118 -67.32345 56.34869 -76.09134 -66.11277 56.3894 -74.50585 -67.66458 55.44236 -77.04581 -68.88642 56.4365 -77.99553 -68.31228 56.51777 -77.20415 -69.05406 55.51905 -78.73326 -70.55233 56.52544 -80.00698 -70.53048 56.63713 -79.88613 -70.51657 55.5965 -80.49671 -71.84481 56.59235 -81.55945 -72.06843 55.67651 -82.35945 -73.14457 56.65883 -83.1175 -72.75708 56.75222 -82.55986 -73.27848 55.73833 -83.8097 -74.46295 56.72636 -84.69828 -74.50653 55.8014 -85.28277 -75.79867 56.79574 -86.30358 -74.98332 56.86711 -85.23254 -75.74701 55.86601 -86.77433 -77.11759 56.86508 -87.89196 -77.01892 55.93294 -88.30628 -78.39144 56.93235 -89.42711 -77.20732 56.98298 -87.90674 -78.29419 56.00028 -89.84323 -79.63523 56.99784 -90.92537 -79.42948 57.09991 -90.58323 -79.54129 56.0659 -91.34527 -80.8514 57.06127 -92.38805 -81.95453 56.19056 -94.24287 -82.4237 57.14175 -94.27304 -81.65443 57.21577 -93.25835 -80.75656 56.12919 -92.80644 -83.50391 56.26781 -96.09243 -83.93457 57.21672 -96.07521 -83.88806 57.32776 -95.92713 -84.97744 56.33842 -97.8403 -85.39546 57.28634 -97.80659 -86.38359 56.40259 -99.49578 -86.82006 57.35089 -99.48198 -86.13502 57.4337 -98.5857 -87.73397 56.46077 -101.0722 -88.20529 57.40998 -101.0968 -89.03153 56.51307 -102.573 -89.554 57.46357 -102.6538 -88.39955 57.53153 -101.2304 -90.27436 56.5595 -103.9962 -90.86947 57.5117 -104.1563 -90.68614 57.61909 -103.8572 -93.73336 56.66744 -107.8746 -92.14999 57.5543 -105.6023 -93.39582 57.59141 -106.9923 -92.99914 57.69417 -106.4619 -96.91771 57.6711 -110.8238 -95.34262 57.75466 -109.0404 -99.59067 56.76662 -114.1173 -100.0547 57.70779 -114.1033 -97.72046 57.79842 -111.5883 -96.82263 56.73387 -111.222 -102.0756 56.77297 -116.6269 -102.8112 57.71124 -116.8733 -100.1364 57.82337 -114.1011 -104.3091 56.75926 -118.8071 -105.2407 57.69092 -119.2238 -105.0957 57.80863 -119.0031 -102.5937 57.82745 -116.5743 -106.3244 56.73069 -120.7114 -107.3913 57.65419 -121.2317 -108.1395 56.69158 -122.3746 -109.2854 57.60704 -122.9426 -107.6448 57.76496 -121.3826 -109.7577 56.64595 -123.8154 -110.9526 57.55399 -124.4037 -110.2437 57.69455 -123.7079 -111.2299 56.59557 -125.0919 -112.5632 57.49213 -125.7739 -114.055 56.46754 -127.4196 -114.3178 57.40605 -127.194 -112.8964 57.59483 -125.9732 -112.6458 56.53833 -126.2854 -115.4495 56.37793 -128.4658 -116.2286 57.27682 -128.6028 -115.6554 57.43854 -128.1249 -116.7728 56.27041 -129.3714 -118.0362 57.10994 -129.7619 -119.1141 56.01662 -130.7265 -119.6711 56.91537 -130.6408 -118.6068 57.16698 -130.0211 -117.9785 56.1505 -130.1112 -120.2786 55.85694 -131.2706 -121.179 56.69596 -131.2961 -121.5728 55.65188 -131.768 -122.7005 56.43556 -131.8059 -121.802 56.71571 -131.4629 -123.0802 55.38043 -132.2208 -124.3126 56.12845 -132.2247 -124.8365 55.03585 -132.6382 -125.8868 55.81133 -132.5668 -125.1452 56.08523 -132.3563 -126.7664 54.64197 -133.0377 -127.413 55.49894 -132.8792 -128.6256 54.26657 -133.4382 -128.9697 55.18611 -133.2203 -128.4844 55.40544 -133.0542 -130.2232 53.96199 -133.8524 -130.5651 54.88349 -133.6399 -131.6 53.7241 -134.3049 -132.1067 54.62158 -134.1639 -131.7423 54.80183 -133.9668 -132.8145 53.54228 -134.8129 -133.5977 54.4113 -134.8378 -133.9681 53.39965 -135.4123 -135.1459 54.24589 -135.7433 -134.785 54.3989 -135.4439 -136.3967 53.19957 -137.0635 -136.7848 54.13168 -136.9384 -135.1547 53.28462 -136.1519 -137.6917 53.15087 -138.1692 -138.4992 54.0826 -138.4622 -137.5272 54.21804 -137.4834 -139.0324 53.1457 -139.4899 -139.658 53.03363 -140.213 -137.2235 53.03607 -137.788 -134.4817 53.21685 -135.7486 -131.4393 53.61967 -134.2714 -128.1814 54.22324 -133.3587 -124.8421 54.90304 -132.6608 -121.4987 55.53365 -131.7676 -118.3036 55.98491 -130.3259 -115.3525 56.25649 -128.43 -112.5935 56.41283 -126.2784 -109.9406 56.51258 -124.0131 -107.3417 56.58299 -121.6878 -104.7925 56.62667 -119.3083 -102.2905 56.6455 -116.8795 -99.83306 56.64143 -114.4062 -97.41709 56.61648 -111.8933 -95.03919 56.57272 -109.3454 -92.69567 56.51224 -106.7669 -90.38262 56.43716 -104.1621 -88.09597 56.34961 -101.5353 -85.83139 56.25176 -98.89054 -83.58438 56.14583 -96.23194 -81.3506 56.03388 -93.56318 -79.12574 55.91798 -90.88796 -76.90402 55.8008 -88.21096 -74.67969 55.68503 -85.53678 -72.45261 55.57051 -82.86476 -70.22638 55.45528 -80.19078 -68.00836 55.3358 -77.50856 -65.80875 55.20745 -74.81022 -63.63643 55.06625 -72.08924 -59.40605 54.73138 -66.55773 -61.49953 54.90866 -69.34002 -57.36338 54.53153 -63.73856 -58.09543 53.25448 -58.97558 -55.37275 54.30056 -60.87013 -59.15615 53.89658 -58.39631 -55.90468 55.66514 -60.54922 -55.74921 55.57056 -60.55282 -139.6648 52.90315 -140.2121 -137.2534 52.78084 -137.7543 -139.6974 52.77861 -140.1897 -58.9143 52.95689 -58.63816 -59.8199 52.72742 -58.65217 -60.06175 53.66712 -58.41033 -60.91336 53.54144 -58.77362 -60.67151 52.60175 -59.01546 -64.95166 53.23115 -61.60628 -65.33371 52.24845 -62.30495 -138.3108 51.7834 -133.475 -136.7173 52.47961 -130.4518 -135.0325 51.36681 -128.5781 -131.6802 51.9392 -123.3149 -128.0912 50.7312 -119.1671 -126.6735 51.56169 -116.8413 -121.1325 50.36811 -110.7976 -121.8021 51.32328 -111.0437 -117.0466 51.19658 -105.7958 -114.4833 50.22922 -103.6087 -112.4134 51.16199 -101.0283 -108.1465 50.25583 -97.37535 -107.9279 51.20272 -96.70099 -102.1568 50.39448 -91.9244 -103.6043 51.29903 -92.75155 -99.45778 51.43286 -89.12511 -96.53269 50.59719 -87.08787 -95.48728 51.59086 -85.76854 -91.27299 50.83168 -82.73931 -91.69934 51.76258 -82.64779 -88.09463 51.94017 -79.73313 -86.36103 51.07701 -78.78057 -84.67678 52.11749 -77.00428 -81.77472 51.31965 -75.13706 -81.42189 52.29133 -74.42485 -77.51404 51.5497 -71.77027 -78.30659 52.45964 -71.9635 -75.19307 52.62728 -69.50135 -73.49914 51.76544 -68.59362 -72.00971 52.79919 -66.98594 -69.5251 51.98603 -65.4767 -68.63148 52.99288 -64.36032 -157.5392 53.48343 -161.6734 -156.818 54.41399 -157.4273 -158.5568 54.38068 -159.2956 -160.2534 54.42389 -160.8243 -161.8861 54.53089 -162.0412 -161.1851 52.9807 -167.3635 -161.8152 52.77865 -168.6213 -156.6051 51.96506 -159.3617 -156.1351 52.27 -158.8726 -155.8932 53.20978 -159.1145 -155.9899 53.35714 -159.3475 -156.3234 52.09007 -159.0322 -156.3566 52.07201 -159.0689 -157.2849 53.49307 -161.3108 -156.9573 53.4961 -160.8377 -156.545 53.47817 -160.2287 -156.4955 53.47366 -160.154 -156.2208 53.43331 -159.7303 -156.0224 53.37307 -159.4047 -157.4196 54.42694 -157.8212 -159.9617 54.43625 -160.3271 -163.4378 54.68887 -162.9791 -162.8428 54.63925 -162.4195 -164.9261 54.89035 -163.6845 -164.5022 52.58144 -172.232 -166.4434 55.14011 -164.2314 -166.0526 55.08426 -163.9004 -168.0108 55.43115 -164.6679 -169.5418 55.73525 -165.0173 -169.4478 55.72695 -164.7982 -171.0207 56.03745 -165.322 -172.5008 56.33866 -165.6318 -168.4297 52.2407 -177.4834 -174.0601 56.64397 -166.0048 -172.8796 56.42507 -165.5175 -175.7677 56.9479 -166.5314 -177.6249 57.22422 -167.3151 -176.26 57.03998 -166.5079 -179.5668 57.44909 -168.3832 -179.4434 57.45412 -168.0828 -172.8933 51.98558 -182.9383 -181.5714 57.6204 -169.7221 -183.6833 57.74731 -171.341 -182.3941 57.69713 -170.0893 -185.8692 57.84142 -173.1612 -185.1806 57.83861 -172.3262 -177.6254 51.83531 -188.2543 -188.113 57.91731 -175.1101 -187.8902 57.93605 -174.6571 -190.5563 57.98076 -177.3069 -190.5528 58.00743 -177.0424 -182.1916 51.78649 -193.0101 -193.2745 58.02684 -179.846 -193.1687 58.05346 -179.4794 -196.2215 58.04767 -182.7121 -195.7392 58.07543 -181.9646 -186.4453 51.80606 -197.1878 -199.3881 58.03631 -185.9228 -198.2658 58.07458 -184.4944 -190.3787 51.86951 -200.8747 -202.7834 57.98599 -189.5137 -200.7502 58.05229 -187.0655 -194.0232 51.96104 -204.1635 -206.4225 57.88983 -193.5264 -203.1947 58.00997 -189.6744 -197.4108 52.06972 -207.1289 -210.3235 57.74119 -198.0049 -207.973 57.87111 -194.9922 -205.6014 57.94907 -192.3177 -203.4982 52.31033 -212.2814 -214.5035 57.53471 -202.9873 -212.6216 57.67015 -200.4217 -200.5639 52.18796 -209.8226 -210.312 57.77762 -197.6946 -208.7629 52.5529 -216.6036 -218.9853 57.26741 -208.5077 -214.9046 57.55027 -203.1705 -206.231 52.433 -214.5376 -215.1817 52.87657 -221.7648 -223.8117 56.93954 -214.608 -219.4036 57.27955 -208.7214 -213.227 52.77566 -220.2022 -211.0934 52.66764 -218.4883 -217.1641 57.41954 -205.938 -222.1816 53.24547 -227.3313 -229.0489 56.55641 -221.3339 -226.0343 56.81971 -217.1388 -220.461 53.15439 -225.9646 -218.7462 53.06365 -224.6024 -217.0036 52.97182 -223.2166 -223.8353 56.97806 -214.3245 -221.6262 57.13187 -211.5178 -229.125 53.63025 -232.7796 -234.7876 56.13192 -228.722 -230.4158 56.49558 -222.7798 -227.416 53.52992 -231.4605 -225.6713 53.43239 -230.0947 -223.9207 53.33787 -228.7114 -228.2266 56.65836 -219.9581 -238.8571 54.69375 -238.3795 -241.1615 55.6925 -236.8033 -236.9982 56.01404 -231.2332 -238.3875 54.51535 -238.603 -237.8554 54.35968 -238.6758 -237.3157 54.2438 -238.5864 -236.8246 54.17873 -238.348 -234.5971 54.00057 -236.8129 -232.6318 53.85721 -235.4046 -230.839 53.73711 -234.0784 -234.7982 56.17188 -228.4199 -232.6052 56.3329 -225.6012 -239.098 54.53514 -238.6311 -241.4295 55.71415 -236.8407 -239.2087 55.86091 -234.0386 -238.3297 54.25594 -238.9477 -237.48 54.04066 -238.9345 -236.7369 54.07891 -238.4909 -229.7794 53.5758 -233.4882 -223.02 53.19453 -228.2103 -216.3055 52.83975 -222.8743 -209.6139 52.49859 -217.5083 -202.9808 52.19153 -212.0682 -196.4434 51.93944 -206.5103 -190.0428 51.76371 -200.7924 -183.8238 51.68609 -194.8751 -177.8363 51.72842 -188.7231 -172.1342 51.91201 -182.3077 -166.7747 52.25652 -175.6096 -241.6452 53.81311 -236.3196 -237.7994 52.36442 -238.1027 -237.3082 52.29935 -237.8644 -237.2022 52.27105 -238.0257 -239.484 53.95964 -233.5891 -234.5032 52.07739 -235.9218 -230.2445 51.76794 -233.0229 -238.3391 52.48029 -238.1921 -237.8929 52.4365 -238.5217 -237.094 52.31859 -238.1808 -238.8712 52.63597 -238.1193 -238.7425 52.65179 -238.5348 -239.3408 52.81437 -237.8958 -241.8961 53.90129 -236.3741 -239.5108 52.93099 -238.2182 -242.0632 54.01412 -236.4259 -239.6739 54.05306 -233.5733 -237.389 54.10435 -230.9318 -232.1151 51.90969 -234.1853 -235.3603 54.24727 -228.3477 -237.4634 54.20619 -230.7678 -229.9519 51.77173 -232.5581 -233.4003 54.38904 -225.8369 -235.2633 54.36404 -227.9544 -225.7104 51.52869 -229.2609 -231.5099 54.52984 -223.3994 -233.0702 54.52507 -225.1356 -227.8445 51.64738 -230.9339 -223.5732 51.41416 -227.5688 -229.2283 54.70034 -220.4553 -230.8808 54.68774 -222.3141 -221.4556 51.30205 -225.8867 -227.0246 54.86229 -217.6224 -228.6916 54.85053 -219.4924 -219.3585 51.19106 -224.2209 -224.9052 55.01675 -214.9028 -226.4991 55.01188 -216.673 -214.9699 50.96112 -220.7257 -222.8715 55.16031 -212.3113 -224.3001 55.17024 -213.8587 -217.2269 51.07876 -222.5256 -212.4959 50.8345 -218.7437 -220.9248 55.29261 -209.8506 -222.0909 55.32405 -211.0519 -209.742 50.69757 -216.5219 -219.0623 55.41398 -207.5164 -219.8683 55.47173 -208.2554 -217.2819 55.5238 -205.3093 -217.6287 55.61172 -205.4719 -206.6923 50.55247 -214.036 -215.5857 55.62208 -203.2312 -199.7017 50.25631 -208.196 -209.4817 55.91755 -195.9792 -215.3691 55.74245 -202.7043 -203.3486 50.40353 -211.271 -195.7299 50.11848 -204.7597 -204.3128 56.08328 -190.1664 -208.4373 56.06329 -194.5259 -213.086 55.86233 -199.9555 -210.7765 55.9698 -197.2283 -191.3968 50.00131 -200.882 -199.9083 56.15665 -185.4768 -203.6589 56.20213 -189.208 -206.0657 56.14125 -191.8513 -186.6188 49.92225 -196.4112 -196.1458 56.16652 -181.6759 -198.7298 56.26673 -184.0279 -201.2143 56.24445 -186.599 -181.3444 49.91242 -191.175 -192.9225 56.13608 -178.5708 -196.2031 56.26756 -181.498 -175.7417 50.01706 -185.1656 -190.1494 56.08061 -176.0133 -191.0166 56.19953 -176.5758 -193.6326 56.24559 -179.0128 -187.7874 56.01246 -173.9161 -188.354 56.1282 -174.1904 -185.7377 55.93764 -172.1571 -170.3471 50.26469 -178.8088 -183.7518 55.84633 -170.526 -185.6439 56.03046 -171.86 -181.7806 55.72081 -169.0425 -182.8577 55.88916 -169.6228 -179.9731 55.56204 -167.8519 -165.7302 50.62827 -172.7792 -178.3671 55.37848 -166.9591 -179.9073 55.64618 -167.6165 -176.695 55.14047 -166.2118 -174.6376 54.78195 -165.5475 -176.7246 55.23241 -166.0416 -172.0252 54.2644 -164.946 -173.3441 54.61708 -165.052 -161.9573 51.06357 -167.315 -169.2476 53.69989 -164.3618 -169.9121 53.9189 -164.3328 -166.9276 53.26075 -163.7481 -165.0147 52.95267 -163.0323 -166.5169 53.27623 -163.4347 -158.8812 51.53866 -162.3929 -163.2873 52.73837 -162.1376 -161.4855 52.5859 -160.9282 -163.3074 52.83132 -161.9538 -159.5776 52.50726 -159.3258 -160.4266 52.62837 -159.8615 -157.583 52.5237 -157.2674 -157.8847 52.61908 -157.3558 -158.0024 51.64682 -161.187 -156.9082 51.86911 -159.7406 -156.9602 51.8549 -159.8071 -157.3963 51.75305 -160.3752 -157.7489 51.68732 -160.845 -162.2803 50.97082 -168.1558 -167.2397 50.44868 -175.1439 -172.5991 50.10416 -181.842 -178.3012 49.92057 -188.2574 -184.2888 49.87823 -194.4095 -190.5077 49.95585 -200.3269 -196.9084 50.13158 -206.0448 -203.4458 50.38366 -211.6027 -210.0791 50.69073 -217.0429 -216.7706 51.03189 -222.4088 -223.4852 51.38667 -227.7449 -155.7808 53.29948 -154.5183 -157.3593 54.11225 -157.0736 -157.6816 54.26458 -157.5937 -157.7469 53.1668 -156.9998 -240.7173 54.52986 -234.6742 -240.6024 55.46114 -235.0757 -241.9844 55.37129 -236.8068 -241.8822 55.54235 -236.844 -242.2263 54.4316 -236.5649 -239.2686 54.19421 -238.6645 -239.2517 55.55194 -233.3721 -239.6501 55.68643 -234.0377 -239.2445 54.62927 -232.8152 -237.931 55.6432 -231.6968 -237.8066 54.7292 -230.9889 -236.6394 55.73451 -230.0504 -237.4343 55.83944 -231.2273 -236.4021 54.82913 -229.1962 -235.3763 55.82542 -228.4341 -235.03 54.92852 -227.4379 -233.8371 55.93793 -226.4578 -235.2289 55.99731 -228.4085 -233.6903 55.02687 -225.716 -232.3377 56.04877 -224.5277 -233.0306 56.15851 -225.5839 -232.3811 55.1238 -224.0302 -230.8737 56.15764 -222.6406 -230.836 56.32149 -222.756 -230.8896 55.23478 -222.1075 -229.4449 56.26401 -220.7985 -229.4333 55.34315 -220.2301 -228.0501 56.36744 -219.0019 -228.6417 56.48471 -219.9275 -228.0095 55.4486 -218.3966 -226.6861 56.46777 -217.248 -226.6185 55.55068 -216.609 -225.3507 56.5648 -215.5356 -226.4442 56.64661 -217.1009 -225.2619 55.6489 -214.8708 -224.0448 56.65814 -213.867 -224.2399 56.80561 -214.2789 -223.9414 55.74283 -213.1852 -222.766 56.74773 -212.2401 -222.4049 55.84955 -211.2341 -221.5116 56.83353 -210.6524 -222.0256 56.96015 -211.464 -220.9186 55.94964 -209.3588 -220.2825 56.9153 -209.1056 -219.4813 56.04301 -207.5588 -219.0778 56.99298 -207.599 -219.7976 57.10865 -208.6591 -218.0933 56.1296 -205.8343 -217.5051 57.0903 -205.6482 -217.5527 57.24951 -205.8668 -216.7571 56.20927 -204.1886 -215.9703 57.18034 -203.7635 -215.151 56.29981 -202.2306 -214.4726 57.26307 -201.9443 -215.2875 57.38117 -203.0901 -213.6064 56.38108 -200.3703 -213.009 57.33863 -200.1872 -212.9987 57.50202 -200.3317 -212.1285 56.45313 -198.6124 -211.5805 57.40702 -198.493 -210.7086 56.51678 -196.9452 -210.1851 57.46843 -196.8589 -210.6832 57.61048 -197.5948 -208.8992 56.58958 -194.853 -208.8222 57.52304 -195.2838 -207.492 57.57101 -193.7673 -208.3378 57.70496 -194.8823 -207.1853 56.64953 -192.9061 -206.1922 57.61264 -192.3056 -204.0113 56.73624 -189.3952 -202.4755 57.7019 -188.2422 -205.9597 57.7839 -192.1975 -205.556 56.69807 -191.0882 -201.1466 56.78622 -186.3363 -199.0149 57.74372 -184.6191 -201.0945 57.88899 -186.9239 -202.5413 56.76531 -187.8123 -203.5462 57.84575 -189.5436 -197.3562 56.80956 -182.4551 -195.7966 57.74575 -181.3928 -198.6025 57.91213 -184.342 -194.0953 56.78985 -179.2709 -192.8091 57.71539 -178.5234 -193.489 57.89244 -179.305 -196.0679 57.91374 -181.8012 -191.2767 56.74294 -176.6345 -190.0829 57.66054 -176.0102 -190.8643 57.84696 -176.857 -188.8457 56.6803 -174.4469 -187.6444 57.58965 -173.8471 -188.1924 57.77602 -174.4607 -186.7676 56.6106 -172.6396 -185.3555 57.50445 -171.8893 -185.4729 57.67886 -172.1187 -184.8399 56.53167 -171.0186 -183.1061 57.39371 -170.0702 -182.9102 56.42725 -169.4946 -180.9477 57.23981 -168.5098 -182.6706 57.53796 -169.8639 -179.3637 56.1203 -167.1409 -178.8701 57.03113 -167.243 -179.692 57.29502 -167.8292 -181.0307 56.28643 -168.1623 -177.7925 55.92313 -166.3358 -176.8496 56.76128 -166.271 -176.0239 55.65043 -165.6267 -174.9628 56.44625 -165.6084 -176.4625 56.878 -166.2198 -173.816 55.24431 -164.9968 -173.2683 56.12392 -165.1662 -171.162 54.70847 -164.4248 -171.7065 55.80921 -164.8273 -173.0371 56.25713 -165.2071 -170.1861 55.49795 -164.5162 -168.5854 54.18945 -163.8649 -168.6344 55.18605 -164.1764 -169.5935 55.55681 -164.4847 -167.0426 54.88401 -163.7583 -166.4935 53.80518 -163.2661 -165.501 54.62193 -163.235 -166.2197 54.91693 -163.5972 -164.7658 53.53879 -162.5734 -164.0144 54.41204 -162.5639 -163.1489 53.34824 -161.6969 -162.4695 54.24664 -161.6616 -163.0539 54.47629 -162.1434 -161.4449 53.21276 -160.5193 -160.8334 54.13219 -160.4702 -159.6374 53.14585 -158.9718 -159.1221 54.08263 -158.9515 -160.2039 54.27439 -160.0779 -158.0157 52.96598 -157.2593 -160.5377 52.97576 -159.7433 -163.3874 53.1776 -161.8087 -166.5531 53.61819 -163.2626 -169.9269 54.25801 -164.1502 -173.3705 54.95838 -164.8726 -176.796 55.57957 -165.8845 -180.0248 55.99631 -167.494 -183.0032 56.23924 -169.5285 -185.8051 56.37995 -171.7837 -188.5251 56.4774 -174.125 -191.197 56.54831 -176.5214 -193.8218 56.59381 -178.9694 -196.4008 56.61511 -181.4656 -198.9355 56.61352 -184.0065 -201.4276 56.59039 -186.5885 -203.8793 56.54716 -189.2082 -206.2929 56.48532 -191.8621 -208.6711 56.40638 -194.547 -211.0165 56.3119 -197.2595 -213.3322 56.20344 -199.9966 -215.621 56.08259 -202.755 -217.8863 55.95094 -205.5318 -220.1312 55.81007 -208.3242 -222.3592 55.66157 -211.1291 -224.5737 55.50703 -213.944 -226.778 55.34802 -216.7662 -228.9756 55.18612 -219.5928 -231.1699 55.0229 -222.4214 -233.3646 54.85992 -225.2494 -235.5629 54.69871 -228.0741 -237.7684 54.54083 -230.8929 -239.9843 54.38782 -233.7034 -242.2181 54.23719 -236.5081 -239.5104 53.25452 -238.4226 -238.4497 53.89662 -239.0019 -241.6909 55.66118 -236.8556 -241.8485 55.57287 -236.8483 -238.6915 52.95693 -238.7601 -237.7859 52.72747 -238.746 -237.5441 53.66716 -238.9879 -236.6925 53.54148 -238.6246 -236.6655 53.73364 -238.6407 -236.9343 52.60179 -238.3828 -234.4594 53.36249 -237.087 -229.5543 53.22086 -233.5218 -236.6811 53.92275 -238.5937 -234.1331 52.38014 -236.4428 -236.9997 52.43502 -238.3064 -158.7514 51.77373 -163.4171 -158.2695 52.75454 -163.2592 -161.0959 52.31919 -167.7772 -160.5092 52.59111 -166.9236 -161.9098 51.30332 -168.4033 -164.4581 51.92076 -172.6875 -165.7782 50.8763 -173.9309 -168.4184 51.58261 -177.9617 -165.4759 52.01227 -174.1394 -170.4963 50.52565 -180.0116 -172.9117 51.33311 -183.4245 -170.8723 51.6222 -181.0515 -175.9468 50.29623 -186.3534 -177.6515 51.19042 -188.7186 -176.6374 51.40394 -187.6646 -181.511 50.20823 -192.2596 -182.1984 51.14494 -193.4423 -186.7127 50.22772 -197.3856 -186.4393 51.16705 -197.5973 -182.7097 51.337 -193.997 -190.3612 51.23265 -201.2643 -189.0308 51.39887 -200.0777 -191.4197 50.31133 -201.7677 -193.9915 51.32534 -204.5344 -195.6964 50.43048 -205.5815 -197.3656 51.43447 -207.4846 -195.547 51.56627 -205.9435 -199.6192 50.56885 -208.9667 -200.506 51.5527 -210.1655 -203.2218 50.71571 -211.9986 -203.4295 51.67486 -212.6144 -202.2097 51.81597 -211.636 -206.5253 50.86376 -214.7269 -206.1515 51.79733 -214.8605 -208.6729 51.91698 -216.9171 -209.5372 51.00761 -217.1799 -210.9935 52.03139 -218.7931 -208.9749 52.12518 -217.1998 -212.2561 51.14311 -219.3722 -213.1181 52.13903 -220.4995 -214.7004 51.26838 -221.3298 -215.0642 52.2395 -222.0552 -216.9351 51.38495 -223.1116 -216.8805 52.33447 -223.5025 -215.8025 52.4716 -222.6813 -219.0507 51.49644 -224.794 -218.6191 52.4261 -224.885 -220.3297 52.51663 -226.2438 -221.1356 51.60683 -226.45 -222.0462 52.60755 -227.6071 -223.2419 51.71838 -228.1228 -223.7819 52.69968 -228.9848 -222.6546 52.83337 -228.1278 -225.3679 51.83238 -229.8058 -225.5303 52.79415 -230.3661 -227.4914 51.95062 -231.4699 -227.273 52.89166 -231.73 -229.5905 52.07469 -233.087 -228.982 52.99208 -233.0489 -230.6971 53.09911 -234.3481 -231.7485 52.21252 -234.7095 -232.4917 53.21932 -235.6756 -229.8882 51.92223 -233.1874 -222.9884 51.53473 -227.7932 -216.1359 51.17294 -222.3465 -209.3081 50.82651 -216.8648 -202.5427 50.51731 -211.3007 -195.8798 50.26761 -205.6081 -189.3634 50.10023 -199.742 -183.0422 50.03839 -193.661 -176.9697 50.10537 -187.3283 -171.2046 50.32368 -180.7149 -165.8083 50.71384 -173.8026 -160.8416 51.29275 -166.5866 -161.4027 51.11516 -167.166 -160.9904 52.719 -167.5796 -229.6283 53.41363 -233.519 -222.7817 53.02848 -228.1689 -215.9816 52.66934 -222.7642 -209.2055 52.32487 -217.3265 -202.4902 52.01642 -211.8096 -195.8749 51.76575 -206.1683 -189.4024 51.59509 -200.3588 -183.1198 51.52711 -194.3403 -177.0794 51.58453 -188.0767 -171.3378 51.78941 -181.5391 -165.955 52.16195 -174.7086 -241.6345 55.6802 -236.8547 -239.4625 55.80683 -234.0539 -157.5637 54.38028 -157.698 -237.2488 55.95989 -231.2454 -235.0455 56.11775 -228.4288 -232.8492 56.27888 -225.6064 -230.6566 56.44175 -222.781 -228.4643 56.6048 -219.9552 -226.2688 56.76648 -217.1314 -224.0666 56.92523 -214.3124 -221.8543 57.07949 -211.5007 -219.6284 57.22767 -208.6991 -217.3856 57.36819 -205.9103 -215.1226 57.49949 -203.1371 -212.8361 57.61996 -200.3825 -210.5229 57.72804 -197.6494 -208.18 57.82214 -194.9409 -205.8045 57.9007 -192.2601 -203.3936 57.96218 -189.6103 -200.9448 58.00506 -186.9949 -198.4557 58.02787 -184.4172 -195.9243 58.02918 -181.8806 -193.3487 58.00762 -179.3888 -190.7274 57.96193 -176.9451 -188.0592 57.89081 -174.5531 -185.3436 57.79356 -172.2155 -182.5475 57.65243 -169.9677 -179.58 57.40948 -167.9441 -176.3689 56.99361 -166.3484 -172.9616 56.37518 -165.3445 -169.5227 55.67574 -164.6234 -166.1403 55.03471 -163.7318 -162.9567 54.59227 -162.2672 -160.094 54.3899 -160.1909 -223.1944 51.42436 -227.7559 -230.041 51.80949 -233.106 -216.3941 51.06523 -222.3511 -209.6179 50.72078 -216.9133 -202.9026 50.41235 -211.3964 -196.2872 50.16169 -205.755 -189.8146 49.99106 -199.9454 -183.532 49.92311 -193.9269 -177.4915 49.98057 -187.6632 -171.75 50.18549 -181.1254 -166.3672 50.55807 -174.295 -242.2027 54.19653 -236.4941 -242.1046 54.05392 -236.442 -239.8753 54.20294 -233.6411 -157.9764 52.77639 -157.285 -237.6614 54.356 -230.8325 -235.458 54.51387 -228.0157 -233.2618 54.67501 -225.1933 -231.0691 54.83787 -222.3679 -228.8768 55.00093 -219.5419 -226.6811 55.16262 -216.7181 -224.4789 55.32137 -213.899 -222.2665 55.47563 -211.0872 -220.0406 55.62381 -208.2856 -217.7978 55.76434 -205.4967 -215.5347 55.89563 -202.7234 -213.2481 56.0161 -199.9688 -210.9349 56.12418 -197.2356 -208.5919 56.21828 -194.527 -206.2163 56.29683 -191.8462 -203.8053 56.3583 -189.1963 -201.3564 56.40118 -186.5809 -198.8673 56.42398 -184.0031 -196.3358 56.42527 -181.4666 -193.7601 56.40371 -178.9747 -191.1387 56.35799 -176.531 -188.4705 56.28693 -174.1389 -185.7544 56.18936 -171.8019 -182.9586 56.04843 -169.5537 -179.9914 55.8055 -167.5304 -176.781 55.38997 -165.9345 -173.3735 54.77114 -164.9315 -169.9346 54.07166 -164.2104 -166.5522 53.43066 -163.3186 -163.3688 52.9883 -161.854 -160.5065 52.78599 -159.7778 -56.06716 55.71218 -60.5609 -55.95375 55.68349 -60.55138 -58.04794 55.93389 -63.41393 -57.88906 55.88784 -63.40517 -57.75746 55.81246 -63.40951 -137.2264 52.90552 -137.783 -140.0272 54.31204 -139.8493 -140.11 54.38241 -139.7767 -140.2045 54.42188 -139.6955 -59.79944 56.01193 -66.22652 -61.89218 56.18888 -69.00679 -64.02828 56.3462 -71.75419 -66.19979 56.4872 -74.47356 -68.39853 56.61541 -77.17047 -70.61596 56.73466 -79.85124 -72.84179 56.84969 -82.52401 -75.06735 56.96456 -85.19589 -77.29068 57.0804 -87.86933 -79.51213 57.19729 -90.54496 -81.73635 57.31309 -93.21911 -83.96923 57.42501 -95.88684 -86.21537 57.53085 -98.54425 -88.47905 57.62859 -101.1877 -90.76477 57.71603 -103.8132 -93.07682 57.791 -106.4165 -95.41928 57.85137 -108.9935 -97.79605 57.89501 -111.5399 -100.2108 57.91986 -114.0511 -102.6669 57.92383 -116.5227 -105.1675 57.90492 -118.9498 -107.7153 57.86117 -121.3276 -110.3126 57.79071 -123.6512 -112.9637 57.69094 -125.9145 -115.7195 57.53461 -128.063 -118.6652 57.26323 -129.9542 -121.8517 56.8128 -131.3906 -125.1882 56.18334 -132.2812 -128.5266 55.50372 -132.979 -131.7895 54.89936 -133.8936 -134.8406 54.49555 -135.3757 -137.5886 54.31444 -137.42 -59.92995 56.08657 -66.21823 -62.02148 56.26288 -68.99481 -64.15626 56.41968 -71.73886 -66.32635 56.56027 -74.4552 -68.52367 56.68815 -77.14941 -70.73962 56.80718 -79.82786 -72.96395 56.9221 -82.49871 -75.18807 57.03691 -85.16893 -77.41001 57.1527 -87.84076 -79.62999 57.26952 -90.51467 -81.85272 57.3852 -93.18685 -84.08409 57.49696 -95.85247 -86.32868 57.60262 -98.5076 -88.59076 57.70016 -101.1487 -90.87479 57.78738 -103.7716 -93.18508 57.86211 -106.3722 -95.52568 57.92224 -108.9465 -97.90048 57.96566 -111.49 -100.3132 57.99028 -113.9983 -102.7671 57.99404 -116.4668 -105.2653 57.97494 -118.8908 -107.8106 57.93103 -121.2655 -110.4052 57.86044 -123.5858 -113.0532 57.76057 -125.8458 -115.8037 57.60409 -127.9883 -118.7404 57.33286 -129.8711 -121.9127 56.88361 -131.2979 -125.2381 56.25574 -132.1836 -128.5747 55.57649 -132.8811 -131.8451 54.97112 -133.7993 -134.9089 54.56608 -135.2893 -137.6657 54.38467 -137.3412 -60.0874 56.13165 -66.22178 -62.17733 56.30713 -68.99356 -64.31039 56.46324 -71.73316 -66.47864 56.60327 -74.44554 -68.67407 56.73073 -77.13623 -70.88808 56.84949 -79.81166 -73.11045 56.96426 -82.47995 -75.33269 57.07899 -85.14799 -77.55276 57.19472 -87.81772 -79.77082 57.31144 -90.48931 -81.9916 57.42696 -93.15892 -84.22097 57.53851 -95.82173 -86.46352 57.64393 -98.47389 -88.72348 57.7412 -101.1118 -91.00528 57.82812 -103.7313 -93.31324 57.90256 -106.3285 -95.65139 57.96237 -108.8991 -98.02362 58.00548 -111.4388 -100.4335 58.0298 -113.9432 -102.8845 58.03329 -116.4077 -105.3796 58.01394 -118.8277 -107.9216 57.96982 -121.1982 -110.5127 57.89907 -123.5144 -113.1567 57.79906 -125.7698 -115.9002 57.64237 -127.9044 -118.825 57.37134 -129.7762 -121.9788 56.92364 -131.1905 -125.2898 56.29783 -132.0699 -128.6243 55.61904 -132.767 -131.9044 55.01236 -133.6897 -134.9847 54.60574 -135.1901 -137.7529 54.42395 -137.252 -55.40883 54.17776 -60.91407 -134.497 52.96218 -135.7025 -55.49118 54.05848 -60.96272 -134.4788 53.08655 -135.7388 -57.39489 54.40356 -63.77215 -57.47633 54.28403 -63.81798 -57.59671 54.18053 -63.86522 -139.7534 52.66852 -140.147 -131.4281 53.49026 -134.2566 -128.1652 54.09458 -133.3418 -124.8267 54.77421 -132.6441 -121.49 55.40379 -131.7536 -118.3037 55.85422 -130.3175 -115.3581 56.12562 -128.4264 -112.6023 56.282 -126.2782 -109.9512 56.38179 -124.0148 -107.3538 56.45225 -121.6912 -104.8059 56.496 -119.3134 -102.3053 56.51493 -116.8862 -99.84907 56.51097 -114.4146 -97.43426 56.48613 -111.9033 -95.05743 56.44248 -109.3569 -92.71492 56.38212 -106.7799 -90.40283 56.30715 -104.1765 -88.11706 56.21972 -101.551 -85.85334 56.12197 -98.9075 -83.60712 56.01613 -96.25004 -81.37411 55.90426 -93.58235 -79.14997 55.78842 -90.90811 -76.92897 55.67128 -88.23195 -74.70534 55.55552 -85.55855 -72.47895 55.44104 -82.88733 -70.25345 55.32586 -80.21431 -68.0362 55.20649 -77.53327 -65.83736 55.0783 -74.83634 -63.6658 54.93731 -72.11695 -61.52965 54.77999 -69.36952 -59.4369 54.60303 -66.58921 -59.63621 54.37828 -66.67311 -61.72615 54.55377 -69.44493 -63.85924 54.70988 -72.18458 -66.02758 54.8499 -74.89698 -68.22309 54.97735 -77.58769 -70.43688 55.09622 -80.26337 -72.65896 55.21114 -82.93196 -74.88211 55.32547 -85.59932 -77.10237 55.44114 -88.26903 -79.31996 55.55811 -90.9411 -81.54071 55.67366 -93.61081 -83.77024 55.78517 -96.2736 -86.01284 55.89058 -98.92581 -88.27283 55.98786 -101.5637 -90.55468 56.07478 -104.1834 -92.8627 56.14921 -106.7805 -95.20089 56.20903 -109.3512 -97.57318 56.25213 -111.8909 -99.98316 56.27644 -114.3953 -102.4342 56.27991 -116.8599 -104.9294 56.26056 -119.2799 -107.4714 56.21643 -121.6504 -110.0625 56.14569 -123.9667 -112.7066 56.04565 -126.222 -115.4502 55.88891 -128.3566 -118.3748 55.61786 -130.2281 -121.5285 55.17015 -131.6422 -124.8397 54.54423 -132.5214 -128.1743 53.86544 -133.2185 -131.4544 53.25877 -134.1414 -134.5343 52.85228 -135.6418 -137.3021 52.67057 -137.7036 -59.51724 54.48276 -66.63108 -61.60879 54.65909 -69.40771 -63.74361 54.81589 -72.15177 -65.91378 54.95645 -74.86814 -68.11117 55.08432 -77.56237 -70.32693 55.20347 -80.2411 -72.55094 55.31854 -82.9122 -74.77594 55.43296 -85.58175 -76.99813 55.54868 -88.25357 -79.21765 55.66574 -90.92797 -81.44033 55.78146 -93.60026 -83.67183 55.89318 -96.26583 -85.9165 55.99884 -98.92102 -88.17861 56.09637 -101.5621 -90.46269 56.18359 -104.1851 -92.77302 56.25833 -106.7858 -95.11367 56.31845 -109.3601 -97.48854 56.36186 -111.9036 -99.90126 56.38647 -114.4119 -102.3552 56.39023 -116.8805 -104.8535 56.37112 -119.3045 -107.3989 56.3272 -121.6792 -109.9935 56.25662 -123.9997 -112.6416 56.15673 -126.2596 -115.3922 56.00019 -128.4019 -118.3287 55.72894 -130.2845 -121.5008 55.27969 -131.7111 -124.8264 54.65171 -132.5966 -128.1632 53.97244 -133.2941 -131.4336 53.3671 -134.2124 -274.0795 53.63161 -147.6147 -274.0795 53.65161 -147.6147 -271.6776 53.63159 -172.001 -271.6776 53.65159 -172.001 -264.5643 53.63158 -195.4501 -264.5643 53.65158 -195.4501 -253.013 53.63156 -217.061 -253.013 53.65156 -217.061 -237.4676 53.63155 -236.003 -237.4676 53.65155 -236.003 -218.5256 53.63154 -251.5483 -218.5256 53.65154 -251.5483 -196.9147 53.63153 -263.0995 -196.9147 53.65153 -263.0995 -173.4655 53.63153 -270.2127 -173.4655 53.65153 -270.2127 -149.0792 53.63153 -272.6145 -149.0792 53.65153 -272.6145 -124.693 53.63153 -270.2126 -124.693 53.65153 -270.2126 -101.2439 53.63153 -263.0993 -101.2439 53.65153 -263.0993 -79.63301 53.63154 -251.5481 -79.63301 53.65154 -251.5481 -60.69097 53.63155 -236.0027 -60.69097 53.65155 -236.0027 -45.14564 53.63156 -217.0606 -45.14564 53.65156 -217.0606 -33.59444 53.63158 -195.4497 -33.59444 53.65158 -195.4497 -26.48127 53.63159 -172.0005 -26.48127 53.65159 -172.0005 -24.07948 53.63161 -147.6142 -24.07948 53.65161 -147.6142 -26.48138 53.63162 -123.2279 -26.48138 53.65163 -123.2279 -33.59465 53.63164 -99.77878 -33.59465 53.65164 -99.77878 -45.14596 53.63165 -78.16796 -45.14596 53.65165 -78.16796 -60.69137 53.63166 -59.22591 -60.69137 53.65166 -59.22591 -79.63348 53.63167 -43.68059 -79.63348 53.65167 -43.68059 -101.2444 53.63168 -32.12941 -101.2444 53.65168 -32.12941 -124.6935 53.63169 -25.01627 -124.6935 53.65169 -25.01627 -149.0798 53.63169 -22.61449 -149.0798 53.65169 -22.61449 -173.4661 53.63169 -25.0164 -173.4661 53.65169 -25.0164 -196.9153 53.63168 -32.12969 -196.9153 53.65168 -32.12969 -218.5261 53.63167 -43.68101 -218.5261 53.65167 -43.68101 -237.4681 53.63166 -59.22642 -237.4681 53.65166 -59.22642 -253.0134 53.63165 -78.16855 -253.0134 53.65165 -78.16855 -264.5646 53.63164 -99.77945 -264.5646 53.65164 -99.77945 -271.6777 53.63162 -123.2286 -271.6777 53.65163 -123.2286 146.4742 48.53334 -149.3461 144.131 48.53334 -150.9179 145.1767 48.53334 -152.4114 145.1767 52.46916 -152.4114 147.1212 48.53334 -150.4669 146.6702 48.53334 -153.4571 146.2707 54.10023 -153.2496 145.4279 52.34396 -152.6466 145.9761 53.17299 -153.0669 145.6906 52.22084 -152.8623 149.3464 48.53334 -143.4691 143.659 48.53334 -149.1564 144.131 58.53334 -150.9179 147.1212 48.53334 -146.9313 146.4742 48.53334 -148.052 144.2707 53.34579 -151.1959 144.3203 53.07382 -151.2859 144.4535 52.88781 -151.5079 144.7875 52.68132 -151.9763 147.5304 48.53334 -143.628 143.8179 48.53334 -147.3405 143.659 58.53334 -149.1564 145.8776 48.53334 -144.3987 144.5886 48.53334 -145.6876 143.8179 58.53334 -147.3405 144.5886 58.53334 -145.6876 145.8776 58.53334 -144.3987 147.5304 58.53334 -143.628 148.242 48.53334 -146.2843 151.1078 48.53334 -143.9411 149.3464 58.53334 -143.4691 150.6568 48.53334 -146.9313 152.6013 48.53334 -144.9868 151.5073 54.10023 -144.1486 149.5361 48.53334 -146.2843 151.1078 58.53334 -143.9411 151.3038 48.53334 -148.052 153.647 48.53334 -146.4803 152.6013 52.46916 -144.9868 151.8019 53.17299 -144.3313 152.0874 52.22084 -144.5358 152.3501 52.34396 -144.7515 148.4317 48.53334 -153.9291 154.119 48.53334 -148.2417 153.647 58.53334 -146.4803 150.6568 48.53334 -150.4669 151.3038 48.53334 -149.3461 153.5073 53.34579 -146.2023 152.9905 52.68132 -145.4219 153.4577 53.07382 -146.1122 153.3245 52.88781 -145.8903 150.2476 48.53334 -153.7702 153.9601 48.53334 -150.0577 154.119 58.53334 -148.2417 151.9005 48.53334 -152.9995 153.1894 48.53334 -151.7105 153.9601 58.53334 -150.0577 153.1894 58.53334 -151.7105 151.9005 58.53334 -152.9995 150.2476 58.53334 -153.7702 149.5361 48.53334 -151.1139 148.4317 58.53334 -153.9291 148.242 48.53334 -151.1139 146.6702 58.53334 -153.4571 147.1212 58.53334 -150.4669 146.4742 58.53334 -149.3461 148.242 58.53334 -151.1139 149.5361 58.53334 -151.1139 150.6568 58.53334 -150.4668 151.3038 58.53334 -149.3461 151.3038 58.53334 -148.052 150.6568 58.53334 -146.9313 149.5361 58.53334 -146.2843 148.242 58.53334 -146.2843 147.1212 58.53334 -146.9313 146.4742 58.53334 -148.052 145.1767 58.53334 -152.4114 145.1767 54.59751 -152.4114 144.3857 53.96129 -151.3978 144.5104 54.58817 -151.5957 144.6655 54.77138 -151.8173 144.8731 54.7608 -152.0806 145.0206 54.67961 -152.2485 145.7007 54.34461 -152.8701 152.6013 58.53334 -144.9868 152.6013 54.59751 -144.9868 152.7574 54.67961 -145.1497 153.3923 53.96129 -146.0004 153.2676 54.58817 -145.8024 153.1126 54.77138 -145.5808 152.905 54.7608 -145.3176 152.0773 54.34461 -144.5281 142.1778 52.66112 -154.6644 141.9391 52.91807 -154.5108 142.0387 52.76137 -154.5713 144.1871 53.41892 -151.3172 141.8944 53.10725 -154.4922 144.4036 54.46336 -151.6383 144.1618 53.52367 -151.3964 142.2286 54.40586 -154.8264 144.4449 54.53361 -151.6331 142.1528 54.23915 -154.7603 142.504 54.56923 -155.0366 142.3519 54.52197 -154.9236 142.6615 54.5405 -155.1481 146.1428 54.10023 -153.3775 139.2944 53.41805 -162.8766 151.6352 54.10023 -144.0207 155.1165 54.5405 -142.25 160.3782 53.2293 -131.8937 152.1189 52.22084 -144.5044 155.6002 52.66112 -142.7337 145.6591 52.22084 -152.8938 155.8389 52.91813 -142.8874 155.6964 52.72074 -142.7988 155.7778 52.80842 -142.8512 153.5909 53.41892 -146.081 155.8849 53.17266 -142.9022 155.8754 53.04236 -142.9048 153.3744 54.46336 -145.7599 153.6163 53.52367 -146.0017 155.5128 54.45127 -142.5422 153.3331 54.53361 -145.765 155.5807 54.35461 -142.598 155.3266 54.56179 -142.4 155.4261 54.52194 -142.4746 155.2209 54.56811 -142.3233 158.7619 53.37157 -134.1474 156.84 54.41698 -140.0467 158.5408 54.38049 -138.2041 160.2012 54.41775 -136.6885 161.8022 54.51682 -135.4724 163.3285 54.66595 -134.5255 165.2186 52.68257 -124.929 162.54 52.67729 -128.1926 156.4038 52.119 -138.3561 156.2212 52.26998 -138.5256 155.9794 53.21007 -138.2835 156.0806 53.32662 -138.0632 157.7988 53.4265 -135.5091 157.2474 53.43905 -136.3008 156.9528 53.43655 -136.7293 156.8735 53.43434 -136.8457 156.5502 53.41585 -137.3261 156.2829 53.3816 -137.7353 157.3877 54.42774 -139.6112 159.8479 54.4296 -137.1582 162.6295 54.61184 -135.0848 164.79 54.85707 -133.8067 166.2571 55.09226 -133.2534 165.729 55.02033 -133.5724 167.7798 55.36995 -132.8096 169.2921 55.66713 -132.452 169.0206 55.6286 -132.6442 170.7467 55.96332 -132.1483 172.1924 56.25874 -131.8505 169.9883 52.28246 -118.6046 173.6915 56.55636 -131.5078 172.3529 56.30688 -131.9475 175.158 56.82887 -131.1001 176.5363 57.05702 -130.6083 175.6475 56.93032 -131.0753 177.9347 57.2542 -129.976 179.462 57.43107 -129.1359 178.7797 57.37617 -129.6753 181.1464 57.58372 -128.0446 174.6822 52.0228 -112.9018 182.9277 57.70387 -126.7302 181.6907 57.64691 -127.8164 184.578 57.7861 -125.3994 184.426 57.80382 -125.6907 186.0958 57.84561 -124.1129 179.2704 51.86907 -107.7163 187.639 57.89632 -122.7666 187.0653 57.90399 -123.4406 189.3677 57.94213 -121.216 191.3231 57.97999 -119.4077 189.6524 57.97492 -121.1291 183.7436 51.80538 -102.9956 193.5146 58.00497 -117.3132 192.1906 58.01927 -118.7633 195.9817 58.01148 -114.8714 194.6821 58.0389 -116.348 188.0932 51.81938 -98.70043 198.7671 57.99222 -112.0112 197.1298 58.03573 -113.888 201.9023 57.93867 -108.668 199.5366 58.01174 -111.388 192.2972 51.88925 -94.76791 205.3546 57.84422 -104.8486 204.2412 57.90951 -106.2862 201.9058 57.96898 -108.8526 196.3481 52.00104 -91.15136 209.0837 57.70606 -100.5827 206.5465 57.83543 -103.6931 200.2388 52.14292 -87.81199 213.1035 57.52438 -95.85708 211.0833 57.65187 -98.44303 208.8258 57.74883 -101.0773 207.5233 52.46769 -81.78936 217.5147 57.29988 -90.57351 213.3235 57.54672 -95.79423 203.9644 52.30034 -84.69802 214.1341 52.80747 -76.49881 222.3856 57.04577 -84.71521 217.7692 57.32007 -90.46789 210.9129 52.63875 -79.06446 215.5507 57.4354 -93.13459 217.2178 52.97303 -74.05834 227.2901 56.79182 -78.82409 224.4232 56.97316 -82.46596 222.2031 57.08781 -85.13156 219.9851 57.20346 -87.79892 223.1832 53.2938 -69.3394 231.6482 56.54177 -73.49449 228.8552 56.74011 -77.1285 220.1932 53.13361 -71.70693 226.6434 56.85855 -79.80052 229.509 53.64812 -64.39022 235.3556 56.28172 -68.77658 233.2146 56.47369 -71.7339 226.2551 53.4616 -66.91944 231.0485 56.61311 -74.44178 233.0538 53.88528 -61.76695 238.5424 56.00251 -64.50489 237.4338 56.14381 -66.23294 235.3457 56.31835 -68.99925 238.9432 54.69371 -59.01867 241.2801 55.7065 -60.61708 239.4716 55.94714 -63.43099 238.4736 54.5153 -58.79515 237.9415 54.35963 -58.72236 237.4019 54.24375 -58.81177 236.9107 54.17868 -59.05014 239.1841 54.53509 -58.7671 241.449 55.72527 -60.58481 238.4158 54.25589 -58.45051 237.5662 54.04061 -58.46367 236.7672 53.9227 -58.80448 228.5113 53.34223 -64.80498 220.491 52.90139 -71.11239 212.4909 52.47183 -77.44345 204.5481 52.07705 -83.85229 196.7428 51.76266 -90.43598 189.1646 51.57585 -97.28836 181.9092 51.56116 -104.4867 175.0379 51.73965 -112.0515 168.5738 52.1116 -119.9608 157.2361 52.54156 -140.6333 157.863 52.58039 -140.0869 160.3656 52.52608 -137.4437 160.8613 51.34999 -132.3782 159.0218 51.5583 -134.914 158.8232 52.50141 -138.8902 156.7113 52.00046 -137.985 157.124 51.88708 -137.4582 157.3788 51.82932 -137.1251 157.5467 51.79466 -136.9035 158.052 51.70227 -136.2292 175.6583 54.95228 -131.578 167.3495 50.64913 -123.1669 162.9565 51.07272 -128.6002 173.8625 54.6159 -132.0668 171.7445 54.18928 -132.5272 169.5595 53.74463 -132.9845 167.6596 53.37731 -133.4571 166.0403 53.09586 -133.9829 164.6245 52.88715 -134.5877 163.2629 52.72705 -135.3273 161.8472 52.60457 -136.2671 184.1906 55.86615 -126.5965 174.0023 50.1992 -114.7658 168.9905 50.50726 -120.3691 182.6056 55.7748 -127.8266 181.0843 55.65931 -128.8992 179.7168 55.52752 -129.7547 178.4495 55.37868 -130.4436 177.1458 55.19675 -131.0404 191.3064 56.09236 -120.3597 180.5125 49.97191 -107.3726 175.4542 50.13519 -112.4597 189.243 56.04795 -122.2506 187.434 55.99546 -123.8556 185.7901 55.93658 -125.2707 196.2432 56.13257 -115.5791 186.7115 49.9245 -100.9893 182.3261 49.95719 -104.8962 193.6287 56.12276 -118.1556 202.5457 56.05572 -108.9781 192.6165 50.00605 -95.40114 189.5808 49.97161 -97.69754 199.1991 56.11351 -112.5492 206.3484 55.94799 -104.7567 198.1945 50.16918 -90.45703 197.1588 50.15864 -90.84616 210.6857 55.7791 -99.76329 203.4364 50.37622 -86.01963 215.7167 55.53878 -93.79856 208.3528 50.60512 -81.99253 204.9636 50.47302 -84.263 221.3925 55.2422 -86.97039 212.9594 50.84018 -78.2993 226.9032 54.95728 -80.35256 217.2727 51.0706 -74.88134 212.9058 50.86781 -77.85472 221.2964 51.28763 -71.70092 220.9054 51.29741 -71.52437 231.6152 54.69425 -74.6186 225.1155 51.49226 -68.67694 228.9216 51.70596 -65.70112 235.5753 54.42283 -69.60391 232.9444 51.96276 -62.67619 228.9249 51.73807 -65.21708 238.8941 54.13599 -65.17052 237.3943 52.2993 -59.53382 241.7638 53.82712 -61.10077 237.8855 52.36437 -59.29546 237.18 52.31854 -59.21736 238.4252 52.48024 -59.20605 237.979 52.43645 -58.87653 238.9573 52.63592 -59.27884 238.8287 52.65174 -58.86337 239.4269 52.81432 -59.50236 241.9253 53.87488 -61.06105 239.5969 52.93094 -59.17994 242.1655 54.0231 -60.97871 242.0773 53.95391 -61.01341 239.947 54.09978 -63.90647 237.9092 54.29644 -66.70848 233.69 54.62634 -72.20949 235.8211 54.471 -69.47484 231.5237 54.76574 -74.91741 224.8989 55.12604 -82.94218 229.3304 54.89273 -77.60414 227.1188 55.01129 -80.27642 220.4597 55.35589 -88.27442 222.6778 55.24028 -85.6071 213.7985 55.69938 -96.27028 218.2443 55.47274 -90.94387 216.0258 55.5881 -93.61067 209.3006 55.90149 -101.5534 211.5582 55.80452 -98.91912 204.7159 56.06217 -106.7625 207.0213 55.98809 -104.1693 202.3805 56.12163 -109.3289 197.6044 56.18836 -114.3643 200.0112 56.16439 -111.8644 195.1566 56.19153 -116.8244 192.665 56.17189 -119.2397 190.1268 56.12753 -121.6055 187.5397 56.05661 -123.9171 184.9003 55.95642 -126.1672 182.1649 55.79946 -128.2927 179.2541 55.52868 -130.1514 176.1219 55.08282 -131.5511 172.8272 54.45929 -132.4232 169.4949 53.78099 -133.1199 166.2032 53.17274 -134.0482 163.1041 52.76438 -135.5607 160.323 52.58222 -137.634 155.6252 54.23915 -142.6379 155.867 53.29946 -142.8798 157.2842 53.19174 -141.0441 157.425 54.11313 -140.3484 157.7299 54.21556 -139.9085 239.8344 54.70758 -64.38376 239.1923 55.68737 -64.698 242.0705 55.37124 -60.5914 242.0127 55.49144 -60.56363 242.3124 54.43155 -60.83325 239.3547 54.19416 -58.73371 237.0472 54.96462 -68.16973 235.8131 55.98456 -69.23185 237.9817 55.91332 -66.25344 240.0244 55.71348 -63.43431 233.809 55.20874 -72.35639 234.5678 56.07822 -70.84111 235.8883 56.09059 -69.0357 233.2483 56.16996 -72.5171 233.7514 56.24818 -71.78487 232.6126 55.28753 -73.85894 231.8473 56.26013 -74.26847 231.3526 55.36531 -75.42116 230.3685 56.34869 -76.09133 231.5792 56.3894 -74.50583 230.0273 55.44236 -77.04579 228.8055 56.43651 -77.99552 229.3796 56.51777 -77.20413 228.6379 55.51905 -78.73323 227.1396 56.52544 -80.00696 227.1614 56.63713 -79.88611 227.1754 55.59651 -80.49671 225.8471 56.59235 -81.55942 225.6235 55.67651 -82.35942 224.5474 56.65883 -83.11748 224.9349 56.75222 -82.55983 224.4134 55.73833 -83.80966 223.229 56.72636 -84.69828 223.1854 55.8014 -85.28276 221.8933 56.79574 -86.30356 222.7086 56.86711 -85.23252 221.9449 55.86601 -86.7743 220.5743 56.86508 -87.89192 220.673 55.93294 -88.30627 219.3005 56.93235 -89.4271 220.4846 56.98298 -87.90673 219.3977 56.00028 -89.8432 218.0567 56.99784 -90.92536 218.2625 57.09991 -90.58322 218.1506 56.0659 -91.34526 216.8405 57.06127 -92.38803 215.7374 56.19056 -94.24285 215.2682 57.14175 -94.27301 216.0375 57.21577 -93.25833 216.9354 56.12919 -92.80643 214.188 56.26781 -96.09243 213.7574 57.21672 -96.07521 213.8039 57.32776 -95.92712 212.7145 56.33842 -97.84028 212.2965 57.28634 -97.80657 211.3084 56.40259 -99.49575 210.8719 57.35089 -99.48197 211.5569 57.4337 -98.58567 209.958 56.46077 -101.0722 209.4866 57.40998 -101.0968 208.6604 56.51307 -102.573 208.1379 57.46357 -102.6537 209.2924 57.53154 -101.2304 207.4176 56.55951 -103.9962 206.8225 57.51171 -104.1562 207.0058 57.61909 -103.8572 203.9586 56.66744 -107.8746 205.542 57.5543 -105.6022 204.2961 57.59141 -106.9923 204.6928 57.69417 -106.4619 200.7742 57.6711 -110.8238 202.3493 57.75466 -109.0403 198.1013 56.76662 -114.1173 197.6373 57.70779 -114.1033 199.9715 57.79842 -111.5883 200.8693 56.73387 -111.222 195.6164 56.77297 -116.6268 194.8807 57.71124 -116.8733 197.5556 57.82337 -114.1011 193.3828 56.75926 -118.8071 192.4512 57.69092 -119.2238 192.5963 57.80863 -119.0031 195.0982 57.82745 -116.5743 191.3676 56.73069 -120.7113 190.3006 57.65418 -121.2317 189.5524 56.69158 -122.3746 188.4065 57.60704 -122.9426 190.0471 57.76496 -121.3826 187.9342 56.64595 -123.8154 186.7393 57.55399 -124.4037 187.4483 57.69455 -123.7078 186.4621 56.59557 -125.0918 185.1288 57.49213 -125.7738 183.6369 56.46754 -127.4196 183.3741 57.40604 -127.194 184.7955 57.59483 -125.9731 185.0461 56.53833 -126.2854 182.2424 56.37792 -128.4658 181.4633 57.27682 -128.6027 182.0365 57.43853 -128.1249 180.9191 56.2704 -129.3714 179.6557 57.10994 -129.7619 178.5778 56.01661 -130.7265 178.0208 56.91536 -130.6408 179.0852 57.16697 -130.0211 179.7134 56.1505 -130.1111 177.4133 55.85694 -131.2706 176.513 56.69595 -131.2961 176.1191 55.65187 -131.768 174.9914 56.43555 -131.8058 175.8899 56.7157 -131.4629 174.6117 55.38043 -132.2207 173.3793 56.12844 -132.2247 172.8554 55.03585 -132.6382 171.8051 55.81132 -132.5667 172.5467 56.08522 -132.3563 170.9255 54.64196 -133.0377 170.2789 55.49893 -132.8791 169.0664 54.26656 -133.4382 168.7223 55.1861 -133.2203 169.2075 55.40543 -133.0542 167.4687 53.96198 -133.8524 167.1268 54.88349 -133.6399 166.0919 53.72409 -134.3048 165.5852 54.62157 -134.1638 165.9496 54.80182 -133.9667 164.8774 53.54228 -134.8129 164.0942 54.4113 -134.8378 163.7238 53.39964 -135.4123 162.5461 54.24589 -135.7432 162.9069 54.39889 -135.4439 161.2952 53.19956 -137.0635 160.9071 54.13167 -136.9384 162.5373 53.28461 -136.1519 160.0003 53.15087 -138.1692 159.1927 54.0826 -138.4621 160.1647 54.21803 -137.4834 158.6595 53.14569 -139.4898 158.034 53.03363 -140.2129 160.4684 53.03606 -137.7879 163.2103 53.21685 -135.7486 166.2527 53.61966 -134.2713 169.5105 54.22323 -133.3587 172.8498 54.90304 -132.6607 176.1932 55.53365 -131.7676 179.3883 55.98491 -130.3259 182.3394 56.25649 -128.43 185.0985 56.41283 -126.2784 187.7513 56.51258 -124.0131 190.3502 56.58298 -121.6878 192.8995 56.62667 -119.3082 195.4015 56.6455 -116.8794 197.8589 56.64143 -114.4062 200.2748 56.61648 -111.8933 202.6528 56.57272 -109.3454 204.9963 56.51224 -106.7669 207.3093 56.43716 -104.1621 209.596 56.34961 -101.5353 211.8605 56.25176 -98.89052 214.1076 56.14583 -96.23192 216.3413 56.03388 -93.56317 218.5662 55.91798 -90.88794 220.7879 55.8008 -88.21093 223.0122 55.68503 -85.53675 225.2393 55.57051 -82.86473 227.4656 55.45528 -80.19075 229.6836 55.3358 -77.50853 231.8832 55.20745 -74.81021 234.0555 55.06624 -72.08924 238.2859 54.73137 -66.55772 236.1924 54.90866 -69.34001 240.3286 54.53153 -63.73854 239.5965 53.25447 -58.97556 242.3192 54.30055 -60.87012 238.5358 53.89657 -58.39629 241.7873 55.66514 -60.54919 241.9427 55.57055 -60.5528 158.0272 52.90314 -140.2121 160.4385 52.78084 -137.7543 157.9945 52.77861 -140.1896 238.7776 52.95688 -58.63814 237.872 52.72742 -58.65215 237.6302 53.66711 -58.4103 236.7786 53.54143 -58.7736 237.0204 52.60174 -59.01544 232.7403 53.23114 -61.60626 232.3582 52.24845 -62.30493 159.3811 51.78339 -133.475 160.9746 52.4796 -130.4518 162.6594 51.3668 -128.5781 166.0117 51.93919 -123.3149 169.6007 50.73119 -119.1671 171.0185 51.56168 -116.8413 176.5595 50.36811 -110.7976 175.8898 51.32328 -111.0436 180.6453 51.19657 -105.7958 183.2087 50.22921 -103.6087 185.2785 51.16199 -101.0283 189.5454 50.25582 -97.37535 189.764 51.20271 -96.70098 195.5351 50.39448 -91.9244 194.0877 51.29902 -92.75154 198.2342 51.43286 -89.12509 201.1593 50.59718 -87.08786 202.2046 51.59086 -85.76852 206.4189 50.83168 -82.73928 205.9926 51.76258 -82.64778 209.5973 51.94016 -79.7331 211.3309 51.077 -78.78055 213.0152 52.11749 -77.00424 215.9172 51.31965 -75.13703 216.27 52.29133 -74.42483 220.1779 51.5497 -71.77025 219.3853 52.45964 -71.96348 222.4989 52.62727 -69.50133 224.1928 51.76543 -68.59358 225.6822 52.79918 -66.98593 228.1669 51.98603 -65.47667 229.0605 52.99287 -64.3603 140.1527 53.48342 -161.6734 140.8739 54.41399 -157.4273 139.1351 54.38067 -159.2955 137.4385 54.42388 -160.8243 135.8058 54.53088 -162.0412 136.5068 52.9807 -167.3635 135.8767 52.77865 -168.6213 141.0868 51.96506 -159.3617 141.5568 52.26999 -158.8725 141.7987 53.20977 -159.1144 141.702 53.35713 -159.3475 141.3685 52.09006 -159.0321 141.3353 52.07201 -159.0689 140.407 53.49306 -161.3107 140.7346 53.4961 -160.8377 141.1469 53.47816 -160.2286 141.1964 53.47365 -160.154 141.4711 53.4333 -159.7303 141.6695 53.37306 -159.4047 140.2723 54.42693 -157.8212 137.7303 54.43624 -160.3271 134.2542 54.68886 -162.979 134.8491 54.63925 -162.4195 132.7659 54.89034 -163.6845 133.1897 52.58144 -172.2319 131.2485 55.14011 -164.2314 131.6393 55.08425 -163.9004 129.6811 55.43115 -164.6679 128.1502 55.73524 -165.0173 128.2442 55.72694 -164.7982 126.6712 56.03744 -165.322 125.1911 56.33865 -165.6318 129.2623 52.24069 -177.4833 123.6318 56.64396 -166.0048 124.8123 56.42506 -165.5175 121.9243 56.94789 -166.5314 120.067 57.22421 -167.3151 121.4319 57.03997 -166.5079 118.1251 57.44908 -168.3832 118.2485 57.45411 -168.0828 124.7986 51.98558 -182.9383 116.1205 57.62039 -169.7221 114.0086 57.7473 -171.3409 115.2978 57.69712 -170.0893 111.8227 57.84141 -173.1612 112.5113 57.8386 -172.3262 120.0665 51.83531 -188.2543 109.5789 57.9173 -175.1101 109.8017 57.93604 -174.6571 107.1356 57.98075 -177.3069 107.1391 58.00742 -177.0424 115.5004 51.78649 -193.0101 104.4175 58.02684 -179.846 104.5232 58.05346 -179.4794 101.4705 58.04766 -182.7121 101.9527 58.07542 -181.9646 111.2467 51.80606 -197.1878 98.30384 58.0363 -185.9228 99.42617 58.07458 -184.4944 107.3132 51.8695 -200.8747 94.9085 57.98598 -189.5137 96.94168 58.05229 -187.0655 103.6687 51.96104 -204.1635 91.26943 57.88982 -193.5264 94.49723 58.00996 -189.6744 100.2811 52.06972 -207.1289 87.36848 57.74119 -198.0049 89.71897 57.87111 -194.9922 92.09053 57.94907 -192.3177 94.19369 52.31033 -212.2814 83.18841 57.5347 -202.9873 85.07036 57.67015 -200.4217 97.12799 52.18796 -209.8226 87.37989 57.77762 -197.6946 88.92897 52.5529 -216.6036 78.7066 57.26741 -208.5077 82.78737 57.55026 -203.1705 91.46088 52.433 -214.5376 82.51024 52.87656 -221.7647 73.88021 56.93953 -214.608 78.28834 57.27954 -208.7214 84.46489 52.77566 -220.2021 86.59851 52.66764 -218.4882 80.52777 57.41954 -205.938 75.51031 53.24547 -227.3313 68.64299 56.55641 -221.3339 71.65763 56.8197 -217.1388 77.23088 53.15438 -225.9646 78.94569 53.06365 -224.6024 80.68828 52.97182 -223.2166 73.85665 56.97806 -214.3245 76.06575 57.13186 -211.5178 68.56697 53.63024 -232.7796 62.9043 56.13191 -228.7219 67.27613 56.49558 -222.7797 70.2759 53.52991 -231.4605 72.02064 53.43239 -230.0946 73.7712 53.33787 -228.7114 69.46527 56.65836 -219.9581 58.83477 54.69375 -238.3795 56.53037 55.69249 -236.8033 60.69369 56.01403 -231.2332 59.30446 54.51535 -238.603 59.83655 54.35967 -238.6758 60.37619 54.24379 -238.5864 60.86736 54.17873 -238.348 63.09482 54.00056 -236.8128 65.06008 53.85721 -235.4046 66.85298 53.73711 -234.0783 62.89375 56.17187 -228.4199 65.08676 56.3329 -225.6012 58.59394 54.53514 -238.6311 56.26243 55.71414 -236.8407 58.48325 55.8609 -234.0386 59.36222 54.25593 -238.9476 60.21187 54.04065 -238.9345 60.95496 54.0789 -238.4909 67.91259 53.5758 -233.4882 74.6719 53.19453 -228.2103 81.38642 52.83975 -222.8742 88.07795 52.49859 -217.5083 94.71118 52.19153 -212.0682 101.2485 51.93944 -206.5103 107.6492 51.76371 -200.7924 113.8681 51.68608 -194.8751 119.8556 51.72842 -188.7231 125.5577 51.912 -182.3076 130.9172 52.25652 -175.6095 56.04667 53.81311 -236.3196 59.8925 52.36441 -238.1027 60.38367 52.29934 -237.8643 60.48969 52.27104 -238.0256 58.20789 53.95963 -233.589 63.18869 52.07738 -235.9217 67.44736 51.76794 -233.0228 59.35287 52.48028 -238.1921 59.799 52.43649 -238.5216 60.59797 52.31858 -238.1808 58.82077 52.63596 -238.1193 58.94936 52.65178 -238.5348 58.35108 52.81436 -237.8958 55.79584 53.90129 -236.3741 58.1811 52.93098 -238.2182 55.62867 54.01411 -236.4259 58.01804 54.05305 -233.5733 60.30289 54.10434 -230.9317 65.57678 51.90969 -234.1853 62.33166 54.24726 -228.3477 60.22854 54.20618 -230.7678 67.73999 51.77173 -232.5581 64.29159 54.38903 -225.8369 62.42866 54.36403 -227.9543 71.98149 51.52869 -229.2609 66.18201 54.52984 -223.3994 64.62172 54.52506 -225.1356 69.84741 51.64737 -230.9338 74.11869 51.41416 -227.5687 68.4636 54.70034 -220.4553 66.81114 54.68774 -222.3141 76.23635 51.30205 -225.8867 70.66729 54.86229 -217.6224 69.00035 54.85053 -219.4923 78.33343 51.19106 -224.2209 72.78668 55.01675 -214.9028 71.19277 55.01188 -216.673 82.72203 50.96111 -220.7257 74.82042 55.1603 -212.3113 73.39184 55.17023 -213.8586 80.46506 51.07875 -222.5256 85.19599 50.8345 -218.7437 76.76705 55.2926 -209.8506 75.60102 55.32404 -211.0518 87.94989 50.69757 -216.5219 78.62964 55.41398 -207.5164 77.82364 55.47172 -208.2554 80.41003 55.5238 -205.3093 80.06315 55.61172 -205.4719 90.99958 50.55247 -214.0359 82.10626 55.62208 -203.2312 97.99024 50.25631 -208.196 88.21028 55.91755 -195.9791 82.32283 55.74244 -202.7043 94.34329 50.40353 -211.271 101.9621 50.11848 -204.7597 93.3791 56.08327 -190.1664 89.25465 56.06328 -194.5258 84.60588 55.86233 -199.9554 86.91548 55.9698 -197.2283 106.2951 50.0013 -200.882 97.78359 56.15665 -185.4768 94.03306 56.20213 -189.2079 91.62627 56.14124 -191.8513 111.0731 49.92225 -196.4112 101.5461 56.16652 -181.6759 98.96215 56.26673 -184.0279 96.4776 56.24445 -186.599 116.3475 49.91242 -191.1749 104.7694 56.13608 -178.5708 101.4888 56.26756 -181.498 121.9502 50.01705 -185.1656 107.5425 56.0806 -176.0133 106.6753 56.19953 -176.5758 104.0593 56.24559 -179.0128 109.9045 56.01245 -173.916 109.3379 56.12819 -174.1904 111.9542 55.93763 -172.1571 127.3449 50.26469 -178.8088 113.9401 55.84632 -170.526 112.048 56.03045 -171.86 115.9113 55.7208 -169.0425 114.8342 55.88916 -169.6228 117.7188 55.56203 -167.8519 131.9618 50.62826 -172.7792 119.3248 55.37847 -166.9591 117.7846 55.64617 -167.6165 120.9969 55.14046 -166.2118 123.0543 54.78194 -165.5474 120.9673 55.2324 -166.0415 125.6667 54.26439 -164.946 124.3478 54.61707 -165.0519 135.7346 51.06357 -167.3149 128.4443 53.69988 -164.3618 127.7798 53.91889 -164.3327 130.7643 53.26074 -163.7481 132.6772 52.95266 -163.0323 131.175 53.27622 -163.4347 138.8107 51.53866 -162.3929 134.4046 52.73836 -162.1375 136.2064 52.5859 -160.9281 134.3845 52.83132 -161.9538 138.1143 52.50725 -159.3258 137.2653 52.62837 -159.8615 140.1089 52.5237 -157.2673 139.8072 52.61907 -157.3557 139.6895 51.64681 -161.1869 140.7837 51.8691 -159.7406 140.7318 51.8549 -159.807 140.2956 51.75304 -160.3751 139.943 51.68731 -160.845 135.4116 50.97081 -168.1558 130.4522 50.44868 -175.1439 125.0928 50.10416 -181.842 119.3908 49.92057 -188.2574 113.4032 49.87823 -194.4095 107.1842 49.95585 -200.3269 100.7835 50.13158 -206.0447 94.24615 50.38366 -211.6027 87.61288 50.69072 -217.0428 80.92129 51.03188 -222.4088 74.20671 51.38667 -227.7449 141.9111 53.29947 -154.5183 140.3326 54.11224 -157.0736 140.0103 54.26457 -157.5937 139.9451 53.1668 -156.9998 56.97462 54.52986 -234.6741 57.08948 55.46113 -235.0756 55.70749 55.37128 -236.8068 55.80972 55.54234 -236.844 55.46565 54.43159 -236.5649 58.42337 54.19421 -238.6644 58.44025 55.55193 -233.3721 58.04178 55.68642 -234.0377 58.44736 54.62926 -232.8151 59.76094 55.64319 -231.6968 59.88532 54.7292 -230.9889 61.05257 55.7345 -230.0504 60.25763 55.83943 -231.2273 61.28979 54.82912 -229.1961 62.3156 55.82542 -228.4341 62.66188 54.92852 -227.4378 63.85483 55.93792 -226.4577 62.46302 55.9973 -228.4085 64.00165 55.02687 -225.716 65.35424 56.04877 -224.5276 64.6613 56.15851 -225.5839 65.31079 55.1238 -224.0302 66.81826 56.15764 -222.6406 66.85588 56.32149 -222.756 66.80236 55.23478 -222.1074 68.24708 56.26401 -220.7985 68.25863 55.34314 -220.2301 69.64177 56.36743 -219.0019 69.05022 56.48471 -219.9275 69.68241 55.4486 -218.3966 71.00582 56.46777 -217.248 71.07338 55.55068 -216.609 72.34127 56.5648 -215.5356 71.24776 56.64661 -217.1009 72.43 55.64889 -214.8707 73.64714 56.65814 -213.867 73.45201 56.80561 -214.2789 73.75055 55.74283 -213.1852 74.92594 56.74773 -212.2401 75.28701 55.84955 -211.234 76.18032 56.83352 -210.6524 75.66636 56.96015 -211.464 76.77336 55.94964 -209.3588 77.40937 56.91529 -209.1056 78.21061 56.04301 -207.5587 78.61409 56.99298 -207.599 77.89429 57.10864 -208.6591 79.59865 56.1296 -205.8343 80.18684 57.0903 -205.6481 80.13919 57.24951 -205.8668 80.93482 56.20926 -204.1886 81.72165 57.18034 -203.7635 82.54093 56.29981 -202.2306 83.21936 57.26307 -201.9443 82.40441 57.38117 -203.0901 84.08554 56.38108 -200.3703 84.68293 57.33863 -200.1871 84.69319 57.50202 -200.3317 85.56343 56.45313 -198.6124 86.11138 57.40702 -198.493 86.98327 56.51678 -196.9452 87.50682 57.46843 -196.8589 87.00873 57.61048 -197.5948 88.7927 56.58957 -194.8529 88.86975 57.52303 -195.2838 90.19989 57.571 -193.7673 89.35408 57.70496 -194.8823 90.50666 56.64952 -192.9061 91.49975 57.61264 -192.3056 93.68061 56.73624 -189.3952 95.21646 57.7019 -188.2421 91.73217 57.7839 -192.1975 92.13594 56.69806 -191.0882 96.54531 56.78622 -186.3363 98.67697 57.74372 -184.6191 96.59741 57.88898 -186.9239 95.15058 56.76531 -187.8123 94.14576 57.84575 -189.5436 100.3358 56.80956 -182.4552 101.8954 57.74574 -181.3928 99.08946 57.91212 -184.342 103.5966 56.78984 -179.2709 104.8828 57.71538 -178.5234 104.2029 57.89244 -179.305 101.624 57.91373 -181.8012 106.4152 56.74293 -176.6345 107.609 57.66054 -176.0102 106.8277 57.84696 -176.857 108.8462 56.6803 -174.4469 110.0475 57.58964 -173.8471 109.4995 57.77601 -174.4607 110.9243 56.61059 -172.6396 112.3364 57.50445 -171.8893 112.219 57.67885 -172.1187 112.8521 56.53166 -171.0186 114.5858 57.3937 -170.0702 114.7817 56.42724 -169.4946 116.7442 57.23981 -168.5098 115.0213 57.53795 -169.8639 118.3282 56.12029 -167.1408 118.8219 57.03113 -167.2429 117.9999 57.29501 -167.8292 116.6612 56.28643 -168.1623 119.8994 55.92312 -166.3358 120.8424 56.76128 -166.271 121.668 55.65042 -165.6267 122.7291 56.44624 -165.6083 121.2294 56.87799 -166.2198 123.8759 55.24431 -164.9968 124.4236 56.12391 -165.1662 126.5299 54.70846 -164.4248 125.9854 55.8092 -164.8273 124.6548 56.25712 -165.2071 127.5058 55.49794 -164.5162 129.1065 54.18944 -163.8649 129.0575 55.18605 -164.1764 128.0984 55.55681 -164.4846 130.6493 54.884 -163.7583 131.1984 53.80517 -163.2661 132.1909 54.62192 -163.2349 131.4722 54.91693 -163.5972 132.9261 53.53878 -162.5734 133.6775 54.41204 -162.5638 134.543 53.34824 -161.6969 135.2225 54.24664 -161.6616 134.6381 54.47628 -162.1434 136.2471 53.21276 -160.5193 136.8585 54.13219 -160.4702 138.0545 53.14584 -158.9718 138.5698 54.08262 -158.9515 137.488 54.27439 -160.0778 139.6762 52.96597 -157.2593 137.1542 52.97576 -159.7433 134.3045 53.1776 -161.8087 131.1388 53.61818 -163.2625 127.7651 54.25801 -164.1502 124.3214 54.95837 -164.8726 120.8959 55.57957 -165.8844 117.6671 55.9963 -167.494 114.6888 56.23923 -169.5284 111.8868 56.37994 -171.7837 109.1668 56.47739 -174.125 106.4949 56.5483 -176.5214 103.8701 56.59381 -178.9694 101.2911 56.61511 -181.4656 98.75648 56.61351 -184.0065 96.26436 56.59038 -186.5885 93.81263 56.54716 -189.2081 91.39897 56.48531 -191.8621 89.02082 56.40637 -194.547 86.67539 56.3119 -197.2595 84.35978 56.20344 -199.9965 82.07093 56.08259 -202.755 79.80564 55.95093 -205.5318 77.56067 55.81007 -208.3241 75.33267 55.66157 -211.1291 73.11827 55.50702 -213.944 70.91397 55.34802 -216.7661 68.71635 55.18612 -219.5928 66.52196 55.0229 -222.4214 64.3273 54.85991 -225.2493 62.12899 54.6987 -228.074 59.92354 54.54082 -230.8929 57.70762 54.38781 -233.7034 55.47381 54.23719 -236.5081 58.18152 53.25451 -238.4226 59.24223 53.89661 -239.0019 56.00101 55.66117 -236.8556 55.84341 55.57286 -236.8483 59.00038 52.95692 -238.76 59.90599 52.72746 -238.746 60.14784 53.66715 -238.9878 60.99942 53.54148 -238.6246 61.02643 53.73363 -238.6406 60.75758 52.60178 -238.3827 63.23254 53.36248 -237.0869 68.13768 53.22086 -233.5218 61.01084 53.92274 -238.5937 63.5588 52.38013 -236.4427 60.69221 52.43502 -238.3064 138.9406 51.77373 -163.4171 139.4225 52.75454 -163.2591 136.5961 52.31918 -167.7771 137.1828 52.5911 -166.9235 135.7822 51.30331 -168.4033 133.2339 51.92076 -172.6874 131.9138 50.8763 -173.9309 129.2735 51.58261 -177.9616 132.216 52.01227 -174.1394 127.1956 50.52565 -180.0115 124.7802 51.33311 -183.4244 126.8196 51.62219 -181.0514 121.7451 50.29623 -186.3534 120.0405 51.19042 -188.7186 121.0545 51.40394 -187.6646 116.1809 50.20823 -192.2596 115.4935 51.14494 -193.4423 110.9792 50.22772 -197.3856 111.2526 51.16704 -197.5973 114.9822 51.337 -193.997 107.3307 51.23265 -201.2643 108.6611 51.39887 -200.0777 106.2722 50.31133 -201.7677 103.7004 51.32534 -204.5344 101.9955 50.43048 -205.5815 100.3263 51.43447 -207.4845 102.1449 51.56627 -205.9435 98.0727 50.56885 -208.9666 97.18595 51.55271 -210.1655 94.4701 50.71571 -211.9986 94.26239 51.67486 -212.6144 95.48223 51.81598 -211.636 91.16661 50.86376 -214.7268 91.54045 51.79733 -214.8605 89.019 51.91698 -216.917 88.15468 51.00761 -217.1798 86.69842 52.03139 -218.793 88.71699 52.12518 -217.1997 85.43585 51.14311 -219.3722 84.57382 52.13903 -220.4994 82.99151 51.26838 -221.3298 82.62773 52.2395 -222.0551 80.75682 51.38494 -223.1116 80.81141 52.33447 -223.5025 81.88945 52.47159 -222.6813 78.64122 51.49644 -224.7939 79.07286 52.4261 -224.885 77.36225 52.51663 -226.2438 76.55627 51.60683 -226.45 75.64574 52.60755 -227.6071 74.45005 51.71838 -228.1227 73.91006 52.69968 -228.9848 75.0373 52.83337 -228.1278 72.32405 51.83238 -229.8058 72.16168 52.79415 -230.3661 70.20055 51.95062 -231.4699 70.41894 52.89165 -231.73 68.10144 52.07469 -233.087 68.70989 52.99207 -233.0488 66.99485 53.0991 -234.348 65.9434 52.21252 -234.7095 65.20021 53.21932 -235.6756 67.80372 51.92223 -233.1874 74.70359 51.53473 -227.7931 81.55597 51.17294 -222.3465 88.38376 50.82651 -216.8648 95.14921 50.51731 -211.3007 101.8121 50.26761 -205.608 108.3285 50.10022 -199.742 114.6498 50.03839 -193.661 120.7222 50.10537 -187.3283 126.4873 50.32368 -180.7149 131.8836 50.71383 -173.8026 136.8503 51.29274 -166.5866 136.2892 51.11515 -167.166 136.7015 52.71899 -167.5796 68.06369 53.41363 -233.5189 74.9102 53.02848 -228.1689 81.71033 52.66933 -222.7642 88.48645 52.32487 -217.3264 95.20173 52.01643 -211.8096 101.817 51.76575 -206.1683 108.2895 51.59508 -200.3588 114.5721 51.5271 -194.3403 120.6125 51.58453 -188.0767 126.3541 51.78941 -181.539 131.7369 52.16195 -174.7086 56.05746 55.68019 -236.8547 58.22938 55.80682 -234.0539 140.1282 54.38027 -157.6979 60.44314 55.95988 -231.2454 62.64647 56.11774 -228.4287 64.8427 56.27888 -225.6064 67.03527 56.44175 -222.781 69.2276 56.6048 -219.9552 71.42314 56.76648 -217.1314 73.62535 56.92523 -214.3124 75.83766 57.07948 -211.5007 78.0635 57.22766 -208.699 80.30628 57.36819 -205.9103 82.56929 57.49949 -203.1371 84.85581 57.61996 -200.3825 87.169 57.72804 -197.6493 89.5119 57.82213 -194.9408 91.8874 57.90069 -192.2601 94.2983 57.96217 -189.6103 96.74713 58.00505 -186.9949 99.23622 58.02786 -184.4172 101.7676 58.02917 -181.8806 104.3432 58.00762 -179.3888 106.9645 57.96192 -176.9451 109.6327 57.8908 -174.5531 112.3483 57.79355 -172.2155 115.1444 57.65243 -169.9677 118.1119 57.40948 -167.9441 121.323 56.99361 -166.3484 124.7304 56.37517 -165.3445 128.1692 55.67573 -164.6233 131.5516 55.0347 -163.7318 134.7353 54.59226 -162.2672 137.5979 54.3899 -160.1909 74.49755 51.42436 -227.7559 67.65093 51.80949 -233.106 81.29779 51.06522 -222.3511 88.07398 50.72078 -216.9133 94.78936 50.41236 -211.3963 101.4047 50.16169 -205.755 107.8773 49.99106 -199.9454 114.16 49.92311 -193.9268 120.2004 49.98057 -187.6631 125.942 50.18549 -181.1254 131.3247 50.55807 -174.295 55.4892 54.19652 -236.494 55.58734 54.05392 -236.4419 57.81665 54.20293 -233.641 139.7155 52.77638 -157.2849 60.03049 54.35599 -230.8325 62.23386 54.51386 -228.0157 64.43017 54.675 -225.1933 66.62279 54.83787 -222.3678 68.81518 55.00093 -219.5419 71.01078 55.16261 -216.7181 73.21303 55.32136 -213.899 75.42539 55.47562 -211.0872 77.65132 55.6238 -208.2855 79.89415 55.76433 -205.4967 82.15724 55.89563 -202.7234 84.44382 56.0161 -199.9687 86.75708 56.12418 -197.2355 89.10005 56.21827 -194.527 91.47565 56.29682 -191.8461 93.88662 56.3583 -189.1963 96.33551 56.40117 -186.5809 98.82467 56.42397 -184.0031 101.3562 56.42527 -181.4666 103.9318 56.4037 -178.9747 106.5532 56.35799 -176.531 109.2214 56.28692 -174.1389 111.9375 56.18935 -171.8018 114.7333 56.04842 -169.5537 117.7005 55.80549 -167.5303 120.9109 55.38996 -165.9345 124.3184 54.77114 -164.9315 127.7573 54.07165 -164.2104 131.1398 53.43066 -163.3186 134.3231 52.9883 -161.854 137.1854 52.78598 -159.7778 241.6248 55.71217 -60.56088 241.7382 55.68349 -60.55137 239.644 55.93388 -63.41391 239.8029 55.88784 -63.40515 239.9345 55.81245 -63.4095 160.4655 52.90551 -137.783 157.6647 54.31203 -139.8493 157.5819 54.38241 -139.7767 157.4874 54.42188 -139.6955 237.8925 56.01192 -66.2265 235.7998 56.18887 -69.00679 233.6636 56.3462 -71.75418 231.4922 56.4872 -74.47355 229.2934 56.61541 -77.17045 227.076 56.73466 -79.85123 224.8501 56.84969 -82.52399 222.6246 56.96456 -85.19587 220.4012 57.0804 -87.86931 218.1798 57.19729 -90.54496 215.9556 57.31309 -93.21908 213.7227 57.42501 -95.88681 211.4766 57.53085 -98.54421 209.2129 57.6286 -101.1877 206.9272 57.71604 -103.8131 204.6151 57.791 -106.4165 202.2727 57.85137 -108.9935 199.8959 57.89501 -111.5399 197.4811 57.91986 -114.0511 195.025 57.92383 -116.5227 192.5244 57.90492 -118.9498 189.9766 57.86117 -121.3276 187.3793 57.79071 -123.6511 184.7283 57.69094 -125.9145 181.9725 57.53461 -128.0629 179.0267 57.26323 -129.9542 175.8402 56.8128 -131.3906 172.5037 56.18333 -132.2812 169.1653 55.50371 -132.9789 165.9024 54.89936 -133.8936 162.8514 54.49554 -135.3757 160.1033 54.31443 -137.42 237.762 56.08656 -66.2182 235.6705 56.26288 -68.99481 233.5357 56.41967 -71.73883 231.3656 56.56027 -74.45517 229.1683 56.68815 -77.1494 226.9523 56.80718 -79.82785 224.728 56.9221 -82.49868 222.5038 57.03691 -85.16889 220.2819 57.1527 -87.84075 218.0619 57.26952 -90.51464 215.8392 57.3852 -93.18684 213.6078 57.49696 -95.85243 211.3632 57.60262 -98.50759 209.1012 57.70016 -101.1486 206.8171 57.78738 -103.7716 204.5069 57.86211 -106.3722 202.1663 57.92224 -108.9465 199.7915 57.96566 -111.49 197.3788 57.99028 -113.9983 194.9249 57.99404 -116.4668 192.4266 57.97494 -118.8908 189.8814 57.93103 -121.2655 187.2867 57.86044 -123.5858 184.6388 57.76057 -125.8458 181.8882 57.60409 -127.9882 178.9516 57.33286 -129.8711 175.7792 56.88361 -131.2978 172.4539 56.25574 -132.1836 169.1172 55.57648 -132.881 165.8468 54.97111 -133.7992 162.783 54.56607 -135.2892 160.0262 54.38466 -137.3412 237.6045 56.13164 -66.22177 235.5146 56.30712 -68.99353 233.3816 56.46323 -71.73316 231.2133 56.60327 -74.44554 229.0178 56.73074 -77.13621 226.8039 56.84949 -79.81164 224.5815 56.96426 -82.47994 222.3592 57.07899 -85.14797 220.1392 57.19472 -87.81771 217.9211 57.31144 -90.48931 215.7004 57.42696 -93.15892 213.471 57.53851 -95.82171 211.2284 57.64393 -98.47387 208.9685 57.7412 -101.1118 206.6867 57.82813 -103.7313 204.3787 57.90256 -106.3285 202.0406 57.96237 -108.8991 199.6683 58.00548 -111.4388 197.2584 58.0298 -113.9432 194.8074 58.03329 -116.4077 192.3123 58.01394 -118.8276 189.7704 57.96982 -121.1982 187.1792 57.89907 -123.5144 184.5353 57.79906 -125.7697 181.7918 57.64236 -127.9044 178.8669 57.37134 -129.7762 175.7131 56.92364 -131.1905 172.4021 56.29782 -132.0698 169.0676 55.61904 -132.7669 165.7875 55.01235 -133.6897 162.7072 54.60573 -135.1901 159.939 54.42395 -137.2519 242.2831 54.17776 -60.91405 163.195 52.96217 -135.7024 242.2008 54.05847 -60.9627 163.2131 53.08655 -135.7387 240.2971 54.40356 -63.77212 240.2156 54.28403 -63.81797 240.0952 54.18052 -63.86521 157.9385 52.66852 -140.147 166.2639 53.49025 -134.2566 169.5268 54.09457 -133.3418 172.8652 54.77421 -132.6441 176.2019 55.40379 -131.7536 179.3882 55.85421 -130.3175 182.3338 56.12562 -128.4264 185.0896 56.282 -126.2782 187.7408 56.38179 -124.0148 190.3381 56.45225 -121.6912 192.886 56.496 -119.3134 195.3867 56.51493 -116.8862 197.8429 56.51097 -114.4146 200.2577 56.48613 -111.9033 202.6345 56.44248 -109.3569 204.977 56.38212 -106.7799 207.2891 56.30716 -104.1765 209.5749 56.21972 -101.551 211.8386 56.12197 -98.90748 214.0848 56.01613 -96.25003 216.3178 55.90426 -93.58234 218.542 55.78842 -90.90809 220.763 55.67128 -88.23194 222.9866 55.55552 -85.55854 225.213 55.44104 -82.88731 227.4385 55.32586 -80.21428 229.6557 55.2065 -77.53326 231.8546 55.0783 -74.83633 234.0261 54.93731 -72.11693 236.1623 54.77999 -69.3695 238.255 54.60303 -66.58918 238.0557 54.37828 -66.67311 235.9658 54.55377 -69.44491 233.8327 54.70988 -72.18457 231.6644 54.8499 -74.89696 229.4689 54.97735 -77.58768 227.2551 55.09623 -80.26335 225.033 55.21114 -82.93193 222.8098 55.32547 -85.59931 220.5895 55.44114 -88.26902 218.372 55.55811 -90.94107 216.1512 55.67366 -93.6108 213.9217 55.78517 -96.27359 211.6791 55.89058 -98.92578 209.4191 55.98786 -101.5637 207.1372 56.07479 -104.1833 204.8292 56.14921 -106.7805 202.491 56.20903 -109.3511 200.1188 56.25213 -111.8909 197.7088 56.27644 -114.3953 195.2577 56.27991 -116.8599 192.7626 56.26056 -119.2798 190.2205 56.21643 -121.6504 187.6294 56.14569 -123.9667 184.9853 56.04565 -126.222 182.2418 55.8889 -128.3566 179.3171 55.61785 -130.2281 176.1634 55.17014 -131.6421 172.8522 54.54423 -132.5213 169.5176 53.86543 -133.2185 166.2375 53.25876 -134.1414 163.1577 52.85227 -135.6418 160.3899 52.67056 -137.7035 238.1747 54.48276 -66.63105 236.0831 54.65908 -69.40769 233.9483 54.81588 -72.15176 231.7782 54.95645 -74.86812 229.5808 55.08433 -77.56237 227.365 55.20348 -80.24108 225.141 55.31854 -82.91217 222.916 55.43296 -85.58174 220.6938 55.54868 -88.25354 218.4743 55.66574 -90.92794 216.2516 55.78146 -93.60023 214.0201 55.89318 -96.2658 211.7754 55.99884 -98.92102 209.5133 56.09638 -101.5621 207.2292 56.1836 -104.1851 204.9189 56.25833 -106.7858 202.5782 56.31845 -109.3601 200.2034 56.36186 -111.9036 197.7907 56.38647 -114.4119 195.3367 56.39023 -116.8805 192.8384 56.37112 -119.3045 190.2931 56.3272 -121.6792 187.6984 56.25662 -123.9996 185.0503 56.15673 -126.2596 182.2998 56.00019 -128.4019 179.3632 55.72893 -130.2845 176.1911 55.27969 -131.7111 172.8655 54.65171 -132.5966 169.5287 53.97243 -133.2941 166.2584 53.36709 -134.2124 23.25591 52.77006 -148.0638 23.25591 52.79005 -148.0638 25.65779 52.77004 -172.4501 25.65779 52.79004 -172.4501 32.77105 52.77003 -195.8992 32.77105 52.79002 -195.8992 44.32234 52.77001 -217.51 44.32234 52.79001 -217.51 59.86773 52.77 -236.4521 59.86773 52.79 -236.4521 78.80983 52.76999 -251.9974 78.80983 52.78999 -251.9974 100.4207 52.76998 -263.5486 100.4207 52.78998 -263.5486 123.8699 52.76998 -270.6618 123.8699 52.78998 -270.6618 148.2561 52.76998 -273.0635 148.2561 52.78997 -273.0635 172.6424 52.76998 -270.6617 172.6424 52.78998 -270.6617 196.0915 52.76998 -263.5484 196.0915 52.78998 -263.5484 217.7024 52.76999 -251.9971 217.7024 52.78999 -251.9971 236.6444 52.77 -236.4517 236.6444 52.79 -236.4517 252.1898 52.77001 -217.5096 252.1898 52.79001 -217.5096 263.7409 52.77003 -195.8987 263.7409 52.79002 -195.8987 270.8541 52.77004 -172.4496 270.8541 52.79004 -172.4496 273.2559 52.77006 -148.0633 273.2559 52.79005 -148.0633 270.854 52.77007 -123.677 270.854 52.79007 -123.677 263.7407 52.77009 -100.2278 263.7407 52.79008 -100.2278 252.1894 52.7701 -78.61701 252.1894 52.7901 -78.61701 236.644 52.77011 -59.67498 236.644 52.79011 -59.67498 217.7019 52.77012 -44.12966 217.7019 52.79012 -44.12966 196.091 52.77013 -32.57847 196.091 52.79013 -32.57847 172.6418 52.77013 -25.46533 172.6418 52.79013 -25.46533 148.2555 52.77014 -23.06355 148.2555 52.79013 -23.06355 123.8693 52.77013 -25.46546 123.8693 52.79013 -25.46546 100.4201 52.77013 -32.57876 100.4201 52.79013 -32.57876 78.80931 52.77012 -44.13007 78.80931 52.79012 -44.13007 59.86727 52.77011 -59.67548 59.86727 52.79011 -59.67548 44.32197 52.7701 -78.61763 44.32197 52.7901 -78.61763 32.7708 52.77009 -100.2285 32.7708 52.79008 -100.2285 25.65766 52.77007 -123.6777 25.65766 52.79007 -123.6777 146.4742 48.53326 148.3458 144.131 48.53326 146.774 145.1767 48.53326 145.2805 145.1767 52.46908 145.2805 147.1212 48.53326 147.2251 146.6702 48.53326 144.2348 146.2707 54.10015 144.4423 145.4279 52.34388 145.0453 145.9761 53.17291 144.625 145.6906 52.22077 144.8296 149.3464 48.53326 154.2229 143.659 48.53326 148.5355 144.131 58.53326 146.774 147.1212 48.53326 150.7606 146.4742 48.53326 149.6399 144.2707 53.34572 146.496 144.3203 53.07375 146.406 144.4535 52.88774 146.184 144.7875 52.68124 145.7156 147.5304 48.53326 154.0639 143.8179 48.53326 150.3514 143.659 58.53326 148.5355 145.8775 48.53326 153.2932 144.5886 48.53326 152.0043 143.8179 58.53326 150.3515 144.5886 58.53326 152.0043 145.8775 58.53326 153.2932 147.5304 58.53326 154.064 148.242 48.53326 151.4076 151.1078 48.53326 153.7509 149.3464 58.53326 154.2229 150.6568 48.53326 150.7606 152.6013 48.53326 152.7051 151.5073 54.10015 153.5433 149.5361 48.53326 151.4076 151.1078 58.53326 153.7509 151.3038 48.53326 149.6399 153.647 48.53326 151.2116 152.6013 52.46908 152.7051 151.8019 53.17291 153.3606 152.0874 52.22077 153.1561 152.3501 52.34388 152.9404 148.4316 48.53327 143.7628 154.119 48.53326 149.4502 153.647 58.53326 151.2116 150.6568 48.53326 147.2251 151.3038 48.53326 148.3458 153.5073 53.34572 151.4897 152.9905 52.68124 152.27 153.4577 53.07375 151.5797 153.3245 52.88774 151.8016 150.2476 48.53327 143.9217 153.9601 48.53326 147.6342 154.119 58.53326 149.4502 151.9005 48.53326 144.6924 153.1894 48.53326 145.9814 153.9601 58.53326 147.6342 153.1894 58.53326 145.9814 151.9005 58.53326 144.6925 150.2476 58.53327 143.9217 149.5361 48.53326 146.578 148.4316 58.53327 143.7628 148.2419 48.53326 146.578 146.6702 58.53326 144.2348 147.1212 58.53326 147.2251 146.4742 58.53326 148.3458 148.2419 58.53326 146.578 149.5361 58.53326 146.578 150.6568 58.53326 147.2251 151.3038 58.53326 148.3458 151.3038 58.53326 149.6399 150.6568 58.53326 150.7606 149.5361 58.53326 151.4077 148.242 58.53326 151.4076 147.1212 58.53326 150.7606 146.4742 58.53326 149.6399 145.1767 58.53326 145.2805 145.1767 54.59744 145.2805 144.3857 53.96121 146.2941 144.5104 54.58809 146.0962 144.6654 54.7713 145.8746 144.873 54.76073 145.6113 145.0206 54.67953 145.4434 145.7007 54.34453 144.8218 152.6013 58.53326 152.7052 152.6013 54.59744 152.7051 152.7574 54.67953 152.5422 153.3923 53.96121 151.6915 153.2676 54.58809 151.8895 153.1126 54.7713 152.1111 152.905 54.76073 152.3743 152.0773 54.34453 153.1638 142.1778 52.66105 143.0275 141.9391 52.918 143.1811 142.0387 52.7613 143.1206 144.1871 53.41884 146.3747 141.8944 53.10717 143.1998 144.4036 54.46329 146.0536 144.1618 53.52359 146.2955 142.2286 54.40579 142.8655 144.4449 54.53353 146.0588 142.1528 54.23908 142.9316 142.504 54.56916 142.6553 142.3519 54.5219 142.7683 142.6615 54.54043 142.5438 146.1428 54.10015 144.3144 139.2944 53.41798 134.8154 151.6352 54.10015 153.6712 155.1165 54.54043 155.4419 160.3782 53.22924 165.7982 152.1189 52.22077 153.1876 155.6002 52.66104 154.9582 145.6591 52.22077 144.7981 155.8389 52.91806 154.8045 155.6964 52.72067 154.8931 155.7778 52.80835 154.8407 153.5909 53.41884 151.6109 155.8849 53.17258 154.7897 155.8754 53.04229 154.7871 153.3744 54.46329 151.932 153.6163 53.52359 151.6902 155.5128 54.45119 155.1497 153.333 54.53353 151.9269 155.5807 54.35454 155.0939 155.3266 54.56172 155.2919 155.4261 54.52186 155.2173 155.2209 54.56803 155.3686 158.7619 53.3715 163.5445 156.84 54.41691 157.6452 158.5407 54.38042 159.4878 160.2011 54.41769 161.0034 161.8021 54.51675 162.2195 163.3285 54.66588 163.1664 165.2185 52.68249 172.7629 162.54 52.67722 169.4993 156.4038 52.11893 159.3358 156.2212 52.26991 159.1663 155.9793 53.21 159.4084 156.0806 53.32655 159.6286 157.7988 53.42643 162.1828 157.2473 53.43898 161.3912 156.9528 53.43647 160.9626 156.8735 53.43427 160.8462 156.5502 53.41577 160.3658 156.2828 53.38153 159.9566 157.3877 54.42767 158.0807 159.8479 54.42953 160.5337 162.6295 54.61177 162.6071 164.79 54.857 163.8852 166.257 55.09219 164.4385 165.729 55.02025 164.1195 167.7798 55.36988 164.8823 169.2921 55.66706 165.2399 169.0206 55.62852 165.0477 170.7466 55.96325 165.5436 172.1923 56.25867 165.8414 169.9883 52.28239 179.0873 173.6915 56.55629 166.1841 172.3529 56.30681 165.7444 175.158 56.82879 166.5918 176.5362 57.05694 167.0836 175.6474 56.93024 166.6167 177.9347 57.25412 167.7159 179.462 57.43099 168.556 178.7797 57.37609 168.0166 181.1464 57.58364 169.6473 174.6822 52.02273 184.7901 182.9276 57.70379 170.9617 181.6906 57.64684 169.8755 184.578 57.78602 172.2925 184.426 57.80375 172.0012 186.0957 57.84554 173.579 179.2704 51.869 189.9756 187.639 57.89624 174.9253 187.0653 57.90391 174.2513 189.3676 57.94205 176.4759 191.3231 57.97991 178.2842 189.6524 57.97484 176.5628 183.7436 51.80531 194.6963 193.5146 58.00489 180.3787 192.1905 58.01919 178.9286 195.9817 58.0114 182.8205 194.6821 58.03882 181.3439 188.0932 51.81931 198.9915 198.7671 57.99214 185.6807 197.1298 58.03565 183.8039 201.9022 57.9386 189.0239 199.5365 58.01166 186.3039 192.2972 51.88918 202.924 205.3546 57.84414 192.8433 204.2411 57.90944 191.4057 201.9058 57.96891 188.8393 196.3481 52.00096 206.5405 209.0837 57.70598 197.1092 206.5465 57.83535 193.9989 200.2388 52.14285 209.8799 213.1034 57.52431 201.8348 211.0833 57.65179 199.2489 208.8258 57.74876 196.6146 207.5233 52.46761 215.9025 217.5147 57.2998 207.1184 213.3235 57.54664 201.8977 203.9644 52.30027 212.9939 214.1341 52.8074 221.1931 222.3856 57.04569 212.9767 217.7692 57.31999 207.224 210.9129 52.63867 218.6274 215.5506 57.43533 204.5573 217.2178 52.97295 223.6336 227.2901 56.79175 218.8678 224.4232 56.97308 215.2259 222.2031 57.08773 212.5604 219.9851 57.20338 209.893 223.1831 53.29373 228.3525 231.6481 56.5417 224.1974 228.8552 56.74003 220.5634 220.1932 53.13354 225.985 226.6434 56.85847 217.8914 229.509 53.64804 233.3017 235.3556 56.28165 228.9153 233.2146 56.47362 225.958 226.2551 53.46154 230.7725 231.0485 56.61304 223.2501 233.0538 53.88521 235.925 238.5424 56.00244 233.187 237.4338 56.14373 231.4589 235.3457 56.31828 228.6927 238.9432 54.69363 238.6732 241.2801 55.70643 237.0748 239.4716 55.94707 234.2609 238.4736 54.51523 238.8967 237.9415 54.35955 238.9695 237.4018 54.24368 238.8801 236.9106 54.17861 238.6418 239.184 54.53502 238.9248 241.449 55.7252 237.1071 238.4158 54.25582 239.2414 237.5661 54.04053 239.2282 236.7672 53.92263 238.8874 228.5113 53.34215 232.8869 220.491 52.90131 226.5795 212.4909 52.47176 220.2485 204.5481 52.07697 213.8396 196.7428 51.76259 207.2559 189.1646 51.57577 200.4036 181.9092 51.56109 193.2052 175.0379 51.73958 185.6404 168.5738 52.11152 177.7311 157.2361 52.54149 157.0586 157.8629 52.58032 157.605 160.3656 52.52601 160.2482 160.8613 51.34992 165.3137 159.0217 51.55823 162.7779 158.8231 52.50134 158.8017 156.7113 52.00039 159.7069 157.1239 51.88701 160.2337 157.3788 51.82925 160.5668 157.5467 51.79458 160.7884 158.052 51.7022 161.4627 175.6583 54.95221 166.1139 167.3495 50.64906 174.525 162.9564 51.07265 169.0917 173.8625 54.61583 165.6251 171.7445 54.18921 165.1647 169.5595 53.74456 164.7074 167.6596 53.37724 164.2348 166.0403 53.09579 163.709 164.6244 52.88708 163.1042 163.2629 52.72698 162.3646 161.8472 52.6045 161.4249 184.1906 55.86608 171.0954 174.0023 50.19913 182.926 168.9905 50.50718 177.3228 182.6056 55.77472 169.8653 181.0843 55.65924 168.7927 179.7167 55.52744 167.9373 178.4495 55.3786 167.2483 177.1458 55.19668 166.6515 191.3064 56.09228 177.3322 180.5125 49.97184 190.3194 175.4541 50.13511 185.2322 189.243 56.04788 175.4413 187.434 55.99538 173.8363 185.79 55.9365 172.4212 196.2432 56.13249 182.1128 186.7115 49.92443 196.7026 182.3261 49.95711 192.7957 193.6287 56.12268 179.5363 202.5456 56.05564 188.7138 192.6165 50.00598 202.2908 189.5808 49.97154 199.9944 199.199 56.11343 185.1427 206.3484 55.94791 192.9352 198.1945 50.16911 207.2348 197.1588 50.15856 206.8457 210.6856 55.77902 197.9286 203.4363 50.37615 211.6722 215.7166 55.53871 203.8934 208.3528 50.60504 215.6994 204.9635 50.47294 213.4289 221.3924 55.24212 210.7215 212.9594 50.84011 219.3926 226.9032 54.9572 217.3394 217.2726 51.07052 222.8106 212.9058 50.86774 219.8372 221.2964 51.28756 225.991 220.9053 51.29734 226.1675 231.6151 54.69417 223.0733 225.1155 51.49219 229.015 228.9216 51.70589 231.9908 235.5753 54.42276 228.088 232.9443 51.96269 235.0157 228.9249 51.738 232.4748 238.8941 54.13591 232.5214 237.3943 52.29922 238.1581 241.7638 53.82705 236.5911 237.8855 52.36429 238.3964 237.18 52.31847 238.4745 238.4252 52.48017 238.4858 237.979 52.43638 238.8154 238.9572 52.63584 238.413 238.8286 52.65166 238.8285 239.4269 52.81425 238.1895 241.9253 53.8748 236.6309 239.5969 52.93087 238.512 242.1655 54.02303 236.7132 242.0773 53.95383 236.6785 239.947 54.0997 233.7854 237.9092 54.29637 230.9834 233.69 54.62626 225.4824 235.8211 54.47093 228.2171 231.5237 54.76567 222.7745 224.8988 55.12596 214.7497 229.3303 54.89265 220.0878 227.1187 55.01121 217.4155 220.4597 55.35581 209.4175 222.6778 55.2402 212.0848 213.7984 55.6993 201.4216 218.2443 55.47266 206.7481 216.0257 55.58803 204.0812 209.3006 55.90142 196.1385 211.5581 55.80445 198.7728 204.7159 56.06209 190.9294 207.0213 55.98801 193.5226 202.3805 56.12156 188.363 197.6043 56.18828 183.3276 200.0112 56.16431 185.8275 195.1566 56.19145 180.8675 192.665 56.17181 178.4522 190.1268 56.12745 176.0863 187.5397 56.05653 173.7748 184.9003 55.95634 171.5247 182.1649 55.79938 169.3992 179.2541 55.52861 167.5405 176.1219 55.08274 166.1408 172.8272 54.45922 165.2687 169.4948 53.78091 164.572 166.2032 53.17266 163.6437 163.1041 52.76432 162.1312 160.3229 52.58215 160.0579 155.6252 54.23908 155.054 155.8669 53.29939 154.812 157.2841 53.19167 156.6478 157.425 54.11305 157.3435 157.7299 54.21549 157.7834 239.8344 54.70751 233.3081 239.1922 55.6873 232.9939 242.0705 55.37117 237.1005 242.0127 55.49137 237.1283 242.3124 54.43148 236.8587 239.3546 54.19409 238.9582 237.0471 54.96455 229.5222 235.8131 55.98448 228.46 237.9817 55.91325 231.4385 240.0244 55.7134 234.2576 233.809 55.20866 225.3355 234.5678 56.07815 226.8508 235.8883 56.09052 228.6562 233.2482 56.16988 225.1748 233.7514 56.24811 225.9071 232.6126 55.28746 223.833 231.8472 56.26006 223.4234 231.3526 55.36523 222.2707 230.3685 56.34862 221.6006 231.5791 56.38933 223.1861 230.0273 55.44229 220.6461 228.8055 56.43643 219.6964 229.3796 56.5177 220.4878 228.6378 55.51897 218.9587 227.1396 56.52536 217.685 227.1614 56.63706 217.8058 227.1753 55.59643 217.1952 225.8471 56.59227 216.1325 225.6235 55.67643 215.3325 224.5473 56.65875 214.5744 224.9348 56.75214 215.1321 224.4134 55.73825 213.8822 223.229 56.72628 212.9937 223.1854 55.80132 212.4092 221.8932 56.79566 211.3884 222.7086 56.86703 212.4594 221.9449 55.86593 210.9176 220.5743 56.865 209.8 220.673 55.93286 209.3856 219.3005 56.93227 208.2648 220.4846 56.9829 209.7852 219.3977 56.00021 207.8487 218.0567 56.99776 206.7666 218.2624 57.09983 207.1087 218.1506 56.06583 206.3467 216.8405 57.0612 205.3039 215.7374 56.19048 203.4491 215.2682 57.14167 203.4189 216.0375 57.21569 204.4336 216.9354 56.12911 204.8855 214.188 56.26774 201.5995 213.7573 57.21665 201.6167 213.8038 57.32768 201.7648 212.7145 56.33835 199.8516 212.2965 57.28627 199.8854 211.3083 56.40252 198.1962 210.8719 57.35081 198.21 211.5569 57.43362 199.1062 209.9579 56.4607 196.6197 209.4866 57.4099 196.5951 208.6604 56.513 195.1189 208.1379 57.4635 195.0382 209.2924 57.53146 196.4615 207.4176 56.55943 193.6957 206.8225 57.51163 193.5357 207.0057 57.61901 193.8347 203.9586 56.66737 189.8173 205.5419 57.55422 192.0897 204.2961 57.59133 190.6997 204.6928 57.69409 191.23 200.7742 57.67102 186.8681 202.3493 57.75458 188.6515 198.1012 56.76654 183.5746 197.6373 57.70771 183.5886 199.9714 57.79835 186.1036 200.8693 56.73379 186.47 195.6163 56.77289 181.0651 194.8807 57.71116 180.8186 197.5555 57.82329 183.5908 193.3828 56.75918 178.8848 192.4512 57.69084 178.4681 192.5962 57.80855 178.6888 195.0982 57.82737 181.1176 191.3675 56.73061 176.9806 190.3006 57.6541 176.4602 189.5524 56.69151 175.3173 188.4065 57.60696 174.7493 190.0471 57.76488 176.3093 187.9342 56.64587 173.8765 186.7393 57.55392 173.2882 187.4483 57.69447 173.9841 186.462 56.5955 172.6001 185.1287 57.49205 171.9181 183.6369 56.46746 170.2724 183.3741 57.40597 170.4979 184.7955 57.59475 171.7188 185.0461 56.53826 171.4065 182.2424 56.37785 169.2261 181.4633 57.27674 169.0892 182.0364 57.43846 169.567 180.9191 56.27033 168.3205 179.6557 57.10986 167.93 178.5778 56.01654 166.9654 178.0208 56.91529 167.0511 179.0852 57.1669 167.6709 179.7134 56.15042 167.5808 177.4133 55.85686 166.4213 176.5129 56.69588 166.3958 176.1191 55.6518 165.9239 174.9914 56.43548 165.8861 175.8899 56.71563 166.229 174.6117 55.38035 165.4712 173.3793 56.12837 165.4672 172.8554 55.03577 165.0537 171.8051 55.81125 165.1252 172.5467 56.08515 165.3356 170.9255 54.64189 164.6542 170.2789 55.49886 164.8128 169.0663 54.26649 164.2537 168.7222 55.18603 164.4716 169.2075 55.40536 164.6377 167.4687 53.96191 163.8396 167.1268 54.88341 164.052 166.0919 53.72402 163.3871 165.5852 54.6215 163.5281 165.9496 54.80175 163.7252 164.8774 53.5422 162.879 164.0942 54.41123 162.8541 163.7238 53.39957 162.2797 162.546 54.24582 161.9487 162.9069 54.39882 162.248 161.2952 53.19949 160.6285 160.9071 54.13161 160.7535 162.5372 53.28454 161.5401 160.0002 53.15079 159.5227 159.1927 54.08253 159.2298 160.1647 54.21796 160.2085 158.6595 53.14562 158.2021 158.0339 53.03355 157.479 160.4684 53.03599 159.904 163.2102 53.21678 161.9434 166.2526 53.61959 163.4206 169.5105 54.22316 164.3333 172.8498 54.90296 165.0312 176.1932 55.53357 165.9243 179.3882 55.98483 167.366 182.3394 56.25641 169.2619 185.0984 56.41275 171.4135 187.7513 56.51251 173.6788 190.3502 56.58291 176.0041 192.8995 56.62659 178.3837 195.4014 56.64542 180.8125 197.8589 56.64135 183.2857 200.2748 56.6164 185.7986 202.6527 56.57264 188.3465 204.9962 56.51216 190.925 207.3093 56.43709 193.5298 209.5959 56.34954 196.1566 211.8605 56.25169 198.8014 214.1075 56.14576 201.46 216.3413 56.0338 204.1287 218.5662 55.9179 206.804 220.7879 55.80072 209.481 223.0122 55.68495 212.1552 225.2393 55.57043 214.8272 227.4655 55.4552 217.5011 229.6835 55.33573 220.1834 231.8832 55.20738 222.8817 234.0555 55.06617 225.6027 238.2859 54.7313 231.1342 236.1924 54.90858 228.3519 240.3285 54.53145 233.9534 239.5965 53.2544 238.7163 242.3192 54.30048 236.8218 238.5358 53.8965 239.2956 241.7872 55.66506 237.1427 241.9427 55.57048 237.1391 158.0271 52.90307 157.4798 160.4385 52.78077 159.9376 157.9945 52.77854 157.5023 238.7776 52.95681 239.0538 237.872 52.72734 239.0398 237.6302 53.66704 239.2816 236.7786 53.54136 238.9183 237.0204 52.60167 238.6764 232.7403 53.23107 236.0856 232.3582 52.24838 235.387 159.3811 51.78332 164.217 160.9746 52.47953 167.2401 162.6594 51.36673 169.1139 166.0116 51.93912 174.377 169.6007 50.73111 178.5248 171.0184 51.5616 180.8506 176.5595 50.36804 186.8944 175.8898 51.32321 186.6483 180.6453 51.1965 191.8961 183.2087 50.22914 194.0832 185.2785 51.16191 196.6636 189.5454 50.25575 200.3165 189.764 51.20264 200.9909 195.5351 50.39441 205.7675 194.0876 51.29895 204.9403 198.2341 51.43279 208.5668 201.1592 50.59711 210.604 202.2046 51.59079 211.9234 206.4189 50.8316 214.9526 205.9926 51.7625 215.0441 209.5973 51.94009 217.9588 211.3309 51.07693 218.9113 213.0151 52.11742 220.6876 215.9172 51.31958 222.5549 216.27 52.29126 223.2671 220.1779 51.54963 225.9217 219.3853 52.45956 225.7284 222.4989 52.6272 228.1906 224.1928 51.76536 229.0983 225.6822 52.79911 230.706 228.1668 51.98596 232.2152 229.0604 52.9928 233.3316 140.1527 53.48336 136.0186 140.8739 54.41392 140.2646 139.1351 54.3806 138.3964 137.4385 54.42381 136.8676 135.8058 54.53081 135.6507 136.5068 52.98062 130.3285 135.8767 52.77857 129.0706 141.0868 51.96499 138.3302 141.5568 52.26992 138.8194 141.7987 53.2097 138.5775 141.702 53.35707 138.3444 141.3685 52.08999 138.6598 141.3353 52.07194 138.6231 140.407 53.493 136.3811 140.7346 53.49603 136.8542 141.1469 53.47809 137.4632 141.1964 53.47358 137.5379 141.4711 53.43323 137.9617 141.6695 53.373 138.2872 140.2723 54.42686 139.8707 137.7303 54.43617 137.3648 134.2541 54.68879 134.7129 134.8491 54.63917 135.2724 132.7658 54.89027 134.0074 133.1897 52.58136 125.46 131.2485 55.14003 133.4605 131.6393 55.08418 133.7915 129.6811 55.43107 133.024 128.1501 55.73517 132.6746 128.2441 55.72687 132.8937 126.6712 56.03737 132.3699 125.1911 56.33858 132.0601 129.2622 52.24061 120.2086 123.6318 56.64389 131.6872 124.8123 56.42499 132.1745 121.9242 56.94782 131.1605 120.067 57.22414 130.3769 121.4319 57.0399 131.184 118.1251 57.44901 129.3088 118.2484 57.45404 129.6092 124.7986 51.9855 114.7536 116.1205 57.62032 127.9698 114.0086 57.74723 126.351 115.2978 57.69705 127.6026 111.8227 57.84135 124.5308 112.5113 57.83853 125.3657 120.0665 51.83523 109.4377 109.5789 57.91723 122.5818 109.8017 57.93597 123.0348 107.1356 57.98068 120.3851 107.1391 58.00735 120.6495 115.5003 51.78641 104.6818 104.4174 58.02676 117.8459 104.5232 58.05338 118.2125 101.4704 58.04759 114.9799 101.9527 58.07535 115.7274 111.2466 51.80598 100.5042 98.30381 58.03623 111.7691 99.42613 58.0745 113.1975 107.3132 51.86943 96.81726 94.90847 57.98591 108.1782 96.94168 58.05222 110.6264 103.6687 51.96097 93.52843 91.2694 57.88975 104.1655 94.49723 58.00989 108.0175 100.2811 52.06964 90.56308 87.36845 57.74112 99.68708 89.71895 57.87104 102.6997 92.09049 57.949 105.3742 94.19367 52.31025 85.41053 83.18838 57.53463 94.70468 85.07032 57.67007 97.27027 97.12797 52.18788 87.86937 87.37985 57.77755 99.99739 88.92894 52.55282 81.08832 78.70658 57.26733 89.18428 82.78734 57.55019 94.52146 91.46086 52.43292 83.15435 82.51023 52.87649 75.9272 73.88019 56.93946 83.08391 78.28833 57.27947 88.97055 84.46488 52.77559 77.48981 86.59849 52.66757 79.20372 80.52775 57.41946 91.75392 75.51028 53.2454 70.36065 68.64297 56.55634 76.35805 71.65763 56.81963 80.55313 77.23088 53.15431 71.72732 78.94567 53.06358 73.08957 80.68827 52.97175 74.47537 73.85663 56.97798 83.36743 76.06575 57.13179 86.17414 68.56694 53.63017 64.91236 62.9043 56.13184 68.97002 67.27611 56.49551 74.9122 70.27587 53.52984 66.23146 72.02063 53.43232 67.59729 73.77119 53.3378 68.98059 69.46525 56.65829 77.73385 58.83476 54.69367 59.31245 56.53035 55.69242 60.88868 60.69367 56.01396 66.45874 59.30444 54.51527 59.08894 59.83653 54.3596 59.01614 60.37617 54.24372 59.10555 60.86735 54.17865 59.34391 63.09481 54.00049 60.87909 65.06007 53.85714 62.28736 66.85295 53.73704 63.61358 62.89372 56.1718 69.27207 65.08674 56.33283 72.09075 58.59394 54.53506 59.06087 56.26241 55.71407 60.85123 58.48324 55.86083 63.65332 59.36221 54.25586 58.74429 60.21186 54.04058 58.75745 60.95496 54.07883 59.20101 67.91255 53.57572 64.20378 74.67189 53.19445 69.48167 81.38642 52.83967 74.81771 88.07793 52.49851 80.18367 94.71115 52.19145 85.62377 101.2485 51.93937 91.18167 107.6491 51.76363 96.8995 113.8681 51.68601 102.8168 119.8556 51.72834 108.9688 125.5577 51.91192 115.3843 130.9172 52.25644 122.0824 56.04666 53.81303 61.37237 59.89248 52.36434 59.58924 60.38366 52.29927 59.8276 60.48968 52.27097 59.66628 58.20788 53.95956 64.1029 63.18867 52.07731 61.7702 67.44734 51.76786 64.66912 59.35284 52.48021 59.49983 59.79899 52.43642 59.1703 60.59796 52.31851 59.51113 58.82075 52.63589 59.57263 58.94935 52.65171 59.15715 58.35107 52.81429 59.79614 55.79584 53.90121 61.31781 58.18108 52.93091 59.47372 55.62866 54.01404 61.26607 58.01802 54.05298 64.11869 60.30287 54.10427 66.7602 65.57675 51.90961 63.50666 62.33164 54.24719 69.34426 60.22853 54.20611 66.92418 67.73996 51.77166 65.13385 64.29158 54.38896 71.85506 62.42864 54.36396 69.7376 71.98147 51.52862 68.43103 66.182 54.52977 74.29256 64.62171 54.52499 72.55635 69.84739 51.6473 66.75807 74.11866 51.41409 70.12322 68.46357 54.70027 77.23665 66.81114 54.68767 75.37786 76.23633 51.30198 71.80529 70.66726 54.86222 80.06961 69.00035 54.85046 78.1996 78.3334 51.19099 73.47109 72.78666 55.01667 82.78913 71.19275 55.01181 81.01895 82.72201 50.96104 76.96625 74.82039 55.16023 85.38066 73.39183 55.17016 83.83332 80.46504 51.07868 75.16635 85.19597 50.83443 78.94823 76.76704 55.29253 87.84136 75.60099 55.32397 86.64009 87.94986 50.69749 81.1701 78.62963 55.4139 90.17555 77.82363 55.47165 89.43656 80.41001 55.52373 92.38265 80.06314 55.61164 92.22003 90.99955 50.55239 83.65602 82.10624 55.62201 94.46076 97.99021 50.25623 89.49591 88.21025 55.91748 101.7128 82.32279 55.74237 94.98762 94.34326 50.40345 86.42098 101.962 50.11841 92.93225 93.37905 56.0832 107.5256 89.25463 56.06322 103.1661 84.60585 55.86226 97.73651 86.91545 55.96973 100.4637 106.2951 50.00123 96.80995 97.78357 56.15657 112.2152 94.03305 56.20206 108.484 91.62625 56.14117 105.8406 111.0731 49.92217 101.2808 101.5461 56.16644 116.0161 98.96212 56.26665 113.6641 96.47756 56.24438 111.0929 116.3475 49.91234 106.517 104.7694 56.136 119.1211 101.4888 56.26748 116.194 121.9502 50.01698 112.5263 107.5425 56.08053 121.6786 106.6753 56.19945 121.1162 104.0593 56.24551 118.6791 109.9045 56.01238 123.7759 109.3379 56.12812 123.5016 111.9542 55.93756 125.5348 127.3448 50.26461 118.8831 113.9401 55.84625 127.1659 112.048 56.03038 125.8319 115.9113 55.72073 128.6494 114.8342 55.88908 128.0691 117.7188 55.56196 129.84 131.9617 50.62819 124.9127 119.3248 55.3784 130.7329 117.7846 55.6461 130.0754 120.9969 55.14039 131.4801 123.0543 54.78187 132.1445 120.9673 55.23233 131.6504 125.6667 54.26432 132.7459 124.3478 54.617 132.64 135.7346 51.06349 130.377 128.4443 53.69981 133.3301 127.7797 53.91882 133.3592 130.7643 53.26067 133.9438 132.6772 52.95259 134.6596 131.1749 53.27615 134.2573 138.8107 51.53859 135.299 134.4046 52.73829 135.5544 136.2064 52.58583 136.7638 134.3845 52.83124 135.7381 138.1143 52.50718 138.3661 137.2653 52.6283 137.8304 140.1089 52.52363 140.4246 139.8072 52.61901 140.3362 139.6895 51.64674 136.505 140.7837 51.86903 137.9513 140.7317 51.85483 137.8849 140.2956 51.75297 137.3168 139.943 51.68724 136.8469 135.4115 50.97074 129.5361 130.4522 50.4486 122.548 125.0928 50.10408 115.85 119.3907 49.92049 109.4345 113.4032 49.87815 103.2825 107.1842 49.95577 97.36508 100.7835 50.1315 91.6472 94.24611 50.38358 86.08926 87.61286 50.69065 80.6491 80.92128 51.03181 75.28311 74.20671 51.3866 69.94705 141.911 53.2994 143.1736 140.3326 54.11217 140.6183 140.0103 54.26451 140.0982 139.945 53.16673 140.6921 56.9746 54.52978 63.01782 57.08946 55.46106 62.61629 55.70747 55.37121 60.88518 55.8097 55.54227 60.84798 55.46562 54.43152 61.12702 58.42335 54.19413 59.0275 58.44025 55.55186 64.31985 58.04177 55.68635 63.65426 58.44735 54.62919 64.8768 59.76093 55.64312 65.99517 59.8853 54.72912 66.70307 61.05255 55.73443 67.64154 60.25761 55.83936 66.46464 61.28977 54.82905 68.49578 62.31558 55.82534 69.25785 62.66187 54.92844 70.25408 63.85481 55.93785 71.23419 62.46299 55.99723 69.28344 64.00164 55.02679 71.97597 65.35424 56.0487 73.16431 64.6613 56.15844 72.10807 65.31076 55.12373 73.66175 66.81824 56.15757 75.05136 66.85588 56.32142 74.93595 66.80233 55.23471 75.58451 68.24707 56.26393 76.89344 68.25862 55.34307 77.46186 69.64176 56.36737 78.69004 69.0502 56.48464 77.76448 69.68238 55.44853 79.29539 71.00579 56.4677 80.44392 71.07335 55.5506 81.08298 72.34124 56.56472 82.15639 71.24775 56.64653 80.59106 72.42997 55.64882 82.82122 73.64712 56.65806 83.82495 73.45198 56.80553 83.4131 73.75052 55.74275 84.50677 74.92592 56.74765 85.45183 75.28699 55.84947 86.4579 76.18029 56.83345 87.03955 75.66635 56.96007 86.22792 76.77333 55.94956 88.33316 77.40935 56.91522 88.58634 78.21059 56.04294 90.13321 78.61408 56.9929 90.09292 77.89427 57.10857 89.03285 79.59864 56.12952 91.85766 80.1868 57.09022 92.0438 80.13919 57.24944 91.82511 80.93479 56.20919 93.50337 81.72161 57.18027 93.92846 82.5409 56.29973 95.46131 83.21933 57.263 95.74763 82.40439 57.38109 94.60189 84.08551 56.38101 97.3217 84.68291 57.33856 97.50481 84.69317 57.50194 97.36023 85.5634 56.45306 99.07955 86.11136 57.40695 99.19898 86.98326 56.51671 100.7467 87.50679 57.46836 100.833 87.00872 57.6104 100.0972 88.79267 56.5895 102.839 88.86972 57.52296 102.4081 90.19987 57.57093 103.9247 89.35406 57.70489 102.8097 90.50663 56.64945 104.7859 91.49974 57.61256 105.3863 93.68058 56.73617 108.2968 95.21643 57.70182 109.4498 91.73215 57.78383 105.4945 92.13591 56.69799 106.6038 96.54528 56.78614 111.3557 98.67695 57.74364 113.0728 96.59738 57.88891 110.768 95.15058 56.76523 109.8797 94.14573 57.84568 108.1484 100.3357 56.80948 115.2368 101.8954 57.74567 116.2991 99.08943 57.91205 113.35 103.5966 56.78977 118.421 104.8828 57.71531 119.1686 104.2029 57.89236 118.387 101.624 57.91366 115.8908 106.4152 56.74286 121.0574 107.609 57.66046 121.6817 106.8276 57.84688 120.835 108.8462 56.68022 123.245 110.0475 57.58958 123.8448 109.4995 57.77594 123.2312 110.9243 56.61053 125.0523 112.3364 57.50438 125.8026 112.219 57.67879 125.5732 112.852 56.53159 126.6734 114.5858 57.39363 127.6217 114.7817 56.42717 128.1973 116.7442 57.23973 129.1822 115.0213 57.53788 127.828 118.3282 56.12022 130.5511 118.8218 57.03105 130.449 117.9999 57.29494 129.8627 116.6612 56.28635 129.5296 119.8993 55.92305 131.3562 120.8423 56.7612 131.4209 121.668 55.65035 132.0652 122.729 56.44617 132.0836 121.2294 56.87792 131.4721 123.8759 55.24423 132.6951 124.4236 56.12384 132.5257 126.5299 54.70839 133.2671 125.9854 55.80913 132.8646 124.6548 56.25705 132.4848 127.5058 55.49787 133.1757 129.1065 54.18937 133.827 129.0575 55.18597 133.5155 128.0984 55.55673 133.2073 130.6493 54.88393 133.9337 131.1984 53.8051 134.4258 132.1909 54.62185 134.457 131.4722 54.91685 134.0947 132.9261 53.53871 135.1185 133.6775 54.41197 135.1281 134.543 53.34817 135.995 135.2224 54.24657 136.0303 134.638 54.47621 135.5486 136.247 53.21268 137.1727 136.8585 54.13212 137.2217 138.0545 53.14577 138.7201 138.5698 54.08255 138.7404 137.488 54.27431 137.6141 139.6762 52.9659 140.4326 137.1542 52.97568 137.9486 134.3045 53.17753 135.8832 131.1388 53.61811 134.4294 127.765 54.25793 133.5417 124.3214 54.9583 132.8193 120.8959 55.57949 131.8075 117.6671 55.99623 130.1979 114.6887 56.23916 128.1635 111.8868 56.37987 125.9083 109.1668 56.47732 123.5669 106.4949 56.54823 121.1706 103.8701 56.59373 118.7225 101.2911 56.61503 116.2263 98.75646 56.61344 113.6855 96.26433 56.59031 111.1035 93.81261 56.54708 108.4838 91.39895 56.48524 105.8298 89.02079 56.40631 103.145 86.67536 56.31182 100.4324 84.35976 56.20337 97.69541 82.0709 56.08252 94.93698 79.80562 55.95086 92.16014 77.56066 55.80999 89.36782 75.33265 55.66149 86.56282 73.11824 55.50695 83.74791 70.91394 55.34794 80.92581 68.71633 55.18605 78.09915 66.52194 55.02283 75.27056 64.3273 54.85984 72.44261 62.12896 54.69863 69.61791 59.92353 54.54075 66.79902 57.7076 54.38774 63.98855 55.4738 54.23711 61.18389 58.18151 53.25444 59.26934 59.24222 53.89654 58.69007 56.00099 55.6611 60.83634 55.8434 55.57279 60.84367 59.00038 52.95685 58.93191 59.90598 52.72739 58.94593 60.14782 53.66708 58.70409 60.99941 53.5414 59.06736 61.02641 53.73356 59.05131 60.75757 52.60171 59.30921 63.23253 53.36241 60.605 68.13766 53.22079 64.17015 61.01082 53.92267 59.09827 63.55878 52.38006 61.2492 60.69219 52.43494 59.38553 138.9405 51.77365 134.2748 139.4224 52.75447 134.4328 136.596 52.31911 129.9148 137.1827 52.59103 130.7683 135.7821 51.30324 129.2886 133.2338 51.92068 125.0045 131.9137 50.87622 123.761 129.2735 51.58253 119.7303 132.216 52.01219 123.5525 127.1956 50.52557 117.6804 124.7802 51.33303 114.2675 126.8196 51.62211 116.6405 121.7451 50.29616 111.3385 120.0404 51.19034 108.9733 121.0545 51.40386 110.0274 116.1809 50.20815 105.4323 115.4935 51.14486 104.2497 110.9792 50.22764 100.3064 111.2526 51.16697 100.0946 114.9822 51.33692 103.695 107.3307 51.23257 96.42768 108.6611 51.39879 97.61422 106.2722 50.31125 95.92425 103.7004 51.32526 93.15754 101.9955 50.4304 92.11051 100.3263 51.43439 90.20742 102.1449 51.5662 91.74845 98.07267 50.56877 88.72531 97.18592 51.55263 87.52646 94.47006 50.71563 85.69333 94.26237 51.67478 85.07756 95.4822 51.8159 86.056 91.16659 50.86368 82.96511 91.54042 51.79725 82.83145 89.01898 51.9169 80.77491 88.15467 51.00753 80.51213 86.69841 52.03132 78.89891 88.71697 52.1251 80.49219 85.43584 51.14303 78.31977 84.57379 52.13896 77.19252 82.9915 51.26831 76.36217 82.6277 52.23943 75.63681 80.7568 51.38487 74.58039 80.8114 52.3344 74.18949 81.88945 52.47152 75.01066 78.6412 51.49637 72.89801 79.07286 52.42603 72.80697 77.36225 52.51656 71.44815 76.55627 51.60676 71.24198 75.64573 52.60748 70.08487 74.45005 51.71831 69.5692 73.91004 52.69961 68.70717 75.03728 52.8333 69.56418 72.32403 51.83231 67.88613 72.16165 52.79408 67.32585 70.20053 51.95055 66.22204 70.41893 52.89158 65.96195 68.1014 52.07461 64.60498 68.70988 52.992 64.6431 66.99481 53.09903 63.34391 65.94338 52.21244 62.9825 65.20018 53.21925 62.01638 67.80369 51.92216 64.50457 74.70357 51.53466 69.89881 81.55596 51.17287 75.34548 88.38375 50.82643 80.82721 95.14918 50.51723 86.39123 101.8121 50.26753 92.08393 108.3284 50.10015 97.94993 114.6497 50.03831 104.031 120.7222 50.10529 110.3637 126.4873 50.3236 116.977 131.8836 50.71376 123.8893 136.8503 51.29267 131.1053 136.2892 51.11508 130.5259 136.7015 52.71892 130.1123 68.06365 53.41355 64.17298 74.91018 53.02841 69.52307 81.71032 52.66926 74.92778 88.48642 52.32479 80.36552 95.20172 52.01635 85.88238 101.817 51.76567 91.52368 108.2895 51.59501 97.33314 114.5721 51.52703 103.3516 120.6125 51.58445 109.6152 126.354 51.78933 116.1529 131.7369 52.16187 122.9833 56.05745 55.68012 60.83728 58.22937 55.80675 63.63803 140.1282 54.3802 139.994 60.44313 55.95981 66.44651 62.64645 56.11767 69.26322 64.84269 56.27881 72.08554 67.03527 56.44168 74.91093 69.22758 56.60473 77.7368 71.42311 56.76641 80.56056 73.62532 56.92515 83.3796 75.83764 57.07941 86.19126 78.06349 57.22759 88.99287 80.30625 57.36812 91.78167 82.56927 57.49942 94.55484 84.85579 57.61989 97.30947 87.16897 57.72797 100.0426 89.51187 57.82207 102.7511 91.88739 57.90062 105.4319 94.29828 57.9621 108.0816 96.7471 58.00498 110.6971 99.23619 58.02779 113.2748 101.7676 58.0291 115.8113 104.3432 58.00754 118.3031 106.9645 57.96185 120.7469 109.6327 57.89073 123.1388 112.3483 57.79348 125.4764 115.1444 57.65235 127.7242 118.1119 57.4094 129.7478 121.323 56.99353 131.3435 124.7303 56.3751 132.3474 128.1692 55.67566 133.0686 131.5516 55.03463 133.9601 134.7352 54.59219 135.4247 137.5979 54.38982 137.5011 74.49753 51.42428 69.93608 67.65091 51.80941 64.5859 81.29776 51.06515 75.34085 88.07397 50.7207 80.77867 94.78934 50.41228 86.2956 101.4047 50.16162 91.93698 107.8773 49.99098 97.74652 114.1599 49.92303 103.7651 120.2004 49.98049 110.0288 125.9419 50.18541 116.5665 131.3247 50.55799 123.3969 55.48918 54.19645 61.19789 55.58734 54.05384 61.25 57.81663 54.20286 64.05091 139.7155 52.77631 140.407 60.03047 54.35592 66.85947 62.23384 54.51379 69.67623 64.43016 54.67493 72.49864 66.62277 54.8378 75.32411 68.81514 55.00086 78.15005 71.01074 55.16254 80.97387 73.21302 55.32129 83.79298 75.42539 55.47555 86.60472 77.65129 55.62373 89.40641 79.89413 55.76426 92.19528 82.15721 55.89556 94.96852 84.44381 56.01603 97.72322 86.75706 56.12411 100.4564 89.10003 56.2182 103.165 91.47563 56.29675 105.8458 93.88659 56.35823 108.4956 96.33549 56.4011 111.1111 98.82463 56.4239 113.6888 101.3561 56.42519 116.2254 103.9318 56.40363 118.7173 106.5532 56.35791 121.161 109.2214 56.28685 123.5531 111.9375 56.18928 125.8901 114.7332 56.04835 128.1383 117.7005 55.80542 130.1616 120.9109 55.38989 131.7575 124.3184 54.77106 132.7604 127.7573 54.07158 133.4815 131.1397 53.43058 134.3733 134.3231 52.98822 135.8379 137.1854 52.78591 137.9142 241.6248 55.7121 237.131 241.7382 55.68341 237.1405 239.644 55.93381 234.278 239.8028 55.88776 234.2868 239.9345 55.81238 234.2824 160.4654 52.90544 159.9089 157.6647 54.31196 157.8426 157.5819 54.38233 157.9152 157.4874 54.42181 157.9964 237.8925 56.01185 231.4654 235.7997 56.1888 228.6851 233.6636 56.34612 225.9378 231.4921 56.48713 223.2184 229.2934 56.61534 220.5215 227.0759 56.73459 217.8407 224.8501 56.84961 215.1679 222.6246 56.96448 212.4961 220.4012 57.08032 209.8226 218.1798 57.19722 207.147 215.9556 57.31302 204.4728 213.7227 57.42493 201.8051 211.4765 57.53078 199.1477 209.2128 57.62852 196.5042 206.9271 57.71596 193.8788 204.6151 57.79092 191.2754 202.2726 57.85129 188.6984 199.8959 57.89494 186.1521 197.4811 57.91978 183.6408 195.025 57.92375 181.1692 192.5244 57.90484 178.7421 189.9766 57.86109 176.3643 187.3793 57.79063 174.0408 184.7283 57.69087 171.7774 181.9724 57.53453 169.629 179.0267 57.26315 167.7377 175.8401 56.81272 166.3014 172.5037 56.18326 165.4107 169.1653 55.50364 164.713 165.9024 54.89928 163.7983 162.8513 54.49547 162.3162 160.1033 54.31436 160.2719 237.762 56.08649 231.4737 235.6705 56.2628 228.6971 233.5357 56.4196 225.9531 231.3656 56.56019 223.2367 229.1683 56.68807 220.5425 226.9523 56.80711 217.8641 224.728 56.92202 215.1932 222.5038 57.03683 212.523 220.2819 57.15262 209.8512 218.0619 57.26945 207.1773 215.8392 57.38513 204.5051 213.6078 57.49688 201.8395 211.3632 57.60255 199.1843 209.1011 57.70008 196.5433 206.8171 57.7873 193.9203 204.5068 57.86204 191.3197 202.1662 57.92217 188.7454 199.7914 57.96558 186.202 197.3788 57.9902 183.6937 194.9248 57.99396 181.2251 192.4266 57.97486 178.8011 189.8814 57.93095 176.4264 187.2867 57.86037 174.1061 184.6387 57.7605 171.8461 181.8882 57.60401 169.7037 178.9515 57.33278 167.8208 175.7792 56.88353 166.3941 172.4538 56.25566 165.5083 169.1172 55.57641 164.8109 165.8468 54.97104 163.8927 162.783 54.566 162.4027 160.0262 54.38459 160.3507 237.6045 56.13157 231.4701 235.5146 56.30705 228.6984 233.3815 56.46316 225.9588 231.2133 56.6032 223.2464 229.0178 56.73066 220.5557 226.8038 56.84941 217.8803 224.5815 56.96418 215.212 222.3592 57.07891 212.544 220.1392 57.19464 209.8742 217.9211 57.31137 207.2026 215.7003 57.42689 204.533 213.4709 57.53843 201.8702 211.2284 57.64386 199.218 208.9684 57.74113 196.5802 206.6866 57.82805 193.9606 204.3787 57.90248 191.3634 202.0405 57.9623 188.7929 199.6683 58.00541 186.2531 197.2584 58.02972 183.7487 194.8074 58.03321 181.2842 192.3123 58.01386 178.8643 189.7703 57.96974 176.4937 187.1792 57.89899 174.1775 184.5352 57.79898 171.9222 181.7917 57.64229 169.7875 178.8669 57.37126 167.9157 175.7131 56.92356 166.5015 172.4021 56.29775 165.6221 169.0676 55.61896 164.925 165.7875 55.01228 164.0022 162.7072 54.60567 162.5019 159.939 54.42388 160.44 242.2831 54.17768 236.7778 163.1949 52.9621 161.9895 242.2007 54.0584 236.7292 163.2131 53.08648 161.9532 240.297 54.40348 233.9198 240.2156 54.28395 233.8739 240.0952 54.18045 233.8267 157.9385 52.66845 157.5449 166.2638 53.49018 163.4353 169.5267 54.0945 164.3501 172.8652 54.77413 165.0479 176.2019 55.40371 165.9383 179.3882 55.85414 167.3744 182.3338 56.12554 169.2655 185.0896 56.28192 171.4137 187.7408 56.38172 173.6771 190.3381 56.45217 176.0007 192.886 56.49592 178.3786 195.3866 56.51485 180.8057 197.8428 56.51089 183.2773 200.2577 56.48605 185.7886 202.6345 56.44241 188.335 204.977 56.38204 190.912 207.2891 56.30708 193.5154 209.5749 56.21965 196.1409 211.8386 56.1219 198.7844 214.0848 56.01606 201.4419 216.3178 55.90419 204.1096 218.5419 55.78834 206.7838 220.7629 55.6712 209.46 222.9866 55.55544 212.1334 225.213 55.44096 214.8046 227.4385 55.32578 217.4776 229.6557 55.20642 220.1587 231.8546 55.07823 222.8556 234.0261 54.93723 225.575 236.1623 54.77991 228.3224 238.255 54.60295 231.1027 238.0557 54.3782 231.0188 235.9658 54.55369 228.247 233.8327 54.7098 225.5073 231.6643 54.84983 222.795 229.4689 54.97728 220.1042 227.255 55.09615 217.4286 225.0329 55.21106 214.76 222.8098 55.32539 212.0926 220.5895 55.44106 209.4229 218.3719 55.55803 206.7509 216.1512 55.67358 204.0811 213.9217 55.78509 201.4183 211.6791 55.89051 198.7661 209.4191 55.98778 196.1282 207.1372 56.07471 193.5085 204.8292 56.14913 190.9114 202.491 56.20895 188.3408 200.1187 56.25205 185.801 197.7088 56.27636 183.2966 195.2577 56.27983 180.832 192.7625 56.26048 178.412 190.2205 56.21635 176.0415 187.6294 56.14561 173.7252 184.9853 56.04558 171.4699 182.2417 55.88883 169.3353 179.3171 55.61778 167.4638 176.1634 55.17007 166.0498 172.8522 54.54415 165.1706 169.5176 53.86536 164.4735 166.2375 53.25869 163.5505 163.1576 52.8522 162.0501 160.3898 52.67049 159.9884 238.1747 54.48268 231.0609 236.0831 54.65901 228.2842 233.9483 54.81581 225.5402 231.7781 54.95638 222.8238 229.5807 55.08425 220.1295 227.365 55.2034 217.4508 225.1409 55.31846 214.7797 222.916 55.43288 212.1102 220.6938 55.5486 209.4384 218.4743 55.66567 206.764 216.2516 55.78139 204.0917 214.0201 55.8931 201.4261 211.7754 55.99876 198.7709 209.5133 56.0963 196.1298 207.2292 56.18352 193.5068 204.9189 56.25825 190.9061 202.5782 56.31838 188.3319 200.2034 56.36179 185.7883 197.7906 56.38639 183.28 195.3367 56.39015 180.8114 192.8384 56.37104 178.3874 190.2931 56.32712 176.0127 187.6984 56.25654 173.6923 185.0503 56.15665 171.4323 182.2998 56.00011 169.29 179.3632 55.72886 167.4074 176.1911 55.27961 165.9808 172.8655 54.65163 165.0953 169.5287 53.97236 164.3978 166.2583 53.36702 163.4795 23.98895 53.46782 149.7149 23.98895 53.48781 149.7149 26.39084 53.4678 125.3286 26.39084 53.4878 125.3286 33.5041 53.46779 101.8795 33.5041 53.48778 101.8795 45.05539 53.46777 80.26866 45.05539 53.48777 80.26866 60.60078 53.46776 61.32661 60.60078 53.48776 61.32661 79.54288 53.46775 45.78129 79.54288 53.48775 45.78129 101.1538 53.46774 34.23009 101.1538 53.48774 34.23009 124.6029 53.46774 27.11693 124.6029 53.48774 27.11693 148.9892 53.46774 24.71513 148.9892 53.48773 24.71513 173.3755 53.46774 27.11701 173.3755 53.48774 27.11701 196.8246 53.46774 34.23028 196.8246 53.48774 34.23028 218.4354 53.46775 45.78156 218.4354 53.48775 45.78156 237.3775 53.46776 61.32696 237.3775 53.48776 61.32696 252.9228 53.46777 80.26906 252.9228 53.48777 80.26906 264.474 53.46779 101.8799 264.474 53.48778 101.8799 271.5872 53.4678 125.3291 271.5872 53.4878 125.3291 273.989 53.46782 149.7154 273.989 53.48781 149.7154 271.5871 53.46783 174.1017 271.5871 53.48783 174.1017 264.4738 53.46785 197.5508 264.4738 53.48785 197.5508 252.9225 53.46786 219.1617 252.9225 53.48786 219.1617 237.3771 53.46787 238.1037 237.3771 53.48787 238.1037 218.435 53.46788 253.649 218.435 53.48788 253.649 196.8241 53.46789 265.2002 196.8241 53.48789 265.2002 173.3749 53.46789 272.3134 173.3749 53.48789 272.3134 148.9886 53.4679 274.7152 148.9886 53.48789 274.7152 124.6023 53.46789 272.3132 124.6023 53.48789 272.3132 101.1532 53.46789 265.1999 101.1532 53.48789 265.1999 79.54235 53.46788 253.6486 79.54235 53.48788 253.6486 60.60032 53.46787 238.1032 60.60032 53.48787 238.1032 45.05501 53.46786 219.1611 45.05501 53.48786 219.1611 33.50384 53.46785 197.5502 33.50384 53.48785 197.5502 26.39071 53.46783 174.101 26.39071 53.48783 174.101 -151.2177 48.53327 148.3458 -153.561 48.53327 146.774 -152.5152 48.53327 145.2805 -152.5152 52.46909 145.2805 -150.5707 48.53327 147.225 -151.0217 48.53327 144.2348 -151.4212 54.10016 144.4423 -152.264 52.34389 145.0453 -151.7158 53.17292 144.625 -152.0013 52.22077 144.8296 -148.3456 48.53327 154.2229 -154.033 48.53327 148.5355 -153.561 58.53327 146.774 -150.5707 48.53327 150.7606 -151.2177 48.53327 149.6399 -153.4212 53.34572 146.496 -153.3716 53.07376 146.406 -153.2384 52.88774 146.184 -152.9044 52.68125 145.7156 -150.1615 48.53327 154.0639 -153.874 48.53327 150.3514 -154.033 58.53327 148.5355 -151.8144 48.53327 153.2932 -153.1033 48.53327 152.0043 -153.874 58.53327 150.3514 -153.1033 58.53327 152.0043 -151.8144 58.53327 153.2932 -150.1615 58.53327 154.0639 -149.45 48.53327 151.4076 -146.5841 48.53327 153.7509 -148.3456 58.53327 154.2229 -147.0351 48.53327 150.7606 -145.0906 48.53327 152.7051 -146.1846 54.10016 153.5433 -148.1559 48.53327 151.4076 -146.5841 58.53327 153.7509 -146.3881 48.53327 149.6399 -144.0449 48.53327 151.2116 -145.0906 52.46909 152.7051 -145.89 53.17292 153.3606 -145.6045 52.22077 153.1561 -145.3418 52.34389 152.9404 -149.2603 48.53327 143.7628 -143.5729 48.53327 149.4502 -144.0449 58.53327 151.2116 -147.0352 48.53327 147.225 -146.3881 48.53327 148.3458 -144.1846 53.34572 151.4897 -144.7014 52.68125 152.27 -144.2342 53.07376 151.5797 -144.3675 52.88774 151.8016 -147.4443 48.53327 143.9217 -143.7318 48.53327 147.6342 -143.5729 58.53327 149.4502 -145.7915 48.53327 144.6924 -144.5025 48.53327 145.9813 -143.7318 58.53327 147.6342 -144.5025 58.53327 145.9813 -145.7915 58.53327 144.6924 -147.4443 58.53327 143.9217 -148.1559 48.53327 146.578 -149.2603 58.53327 143.7628 -149.45 48.53327 146.578 -151.0217 58.53327 144.2348 -150.5707 58.53327 147.225 -151.2177 58.53327 148.3458 -149.45 58.53327 146.578 -148.1559 58.53327 146.578 -147.0352 58.53327 147.225 -146.3881 58.53327 148.3458 -146.3881 58.53327 149.6399 -147.0351 58.53327 150.7606 -148.1559 58.53327 151.4076 -149.45 58.53327 151.4076 -150.5707 58.53327 150.7606 -151.2177 58.53327 149.6399 -152.5152 58.53327 145.2805 -152.5152 54.59745 145.2805 -153.3062 53.96122 146.2941 -153.1815 54.5881 146.0962 -153.0265 54.77131 145.8746 -152.8189 54.76073 145.6113 -152.6713 54.67954 145.4434 -151.9912 54.34454 144.8218 -145.0906 58.53327 152.7051 -145.0906 54.59745 152.7051 -144.9345 54.67954 152.5422 -144.2996 53.96122 151.6915 -144.4243 54.5881 151.8895 -144.5794 54.77131 152.1111 -144.787 54.76073 152.3743 -145.6146 54.34454 153.1638 -155.5141 52.66106 143.0275 -155.7528 52.91801 143.1811 -155.6532 52.76131 143.1205 -153.5048 53.41885 146.3747 -155.7975 53.10718 143.1997 -153.2883 54.46329 146.0536 -153.5302 53.5236 146.2955 -155.4633 54.4058 142.8655 -153.247 54.53354 146.0588 -155.5391 54.23909 142.9316 -155.1879 54.56916 142.6553 -155.34 54.5219 142.7683 -155.0304 54.54044 142.5438 -151.5491 54.10016 144.3144 -158.3975 53.41798 134.8153 -146.0567 54.10016 153.6712 -142.5754 54.54043 155.4418 -137.3137 53.22924 165.7982 -145.573 52.22077 153.1875 -142.0917 52.66105 154.9582 -152.0328 52.22077 144.7981 -141.853 52.91806 154.8045 -141.9956 52.72068 154.8931 -141.9141 52.80836 154.8407 -144.101 53.41885 151.6109 -141.807 53.17259 154.7897 -141.8165 53.0423 154.7871 -144.3175 54.46329 151.932 -144.0757 53.5236 151.6902 -142.1791 54.4512 155.1497 -144.3589 54.53354 151.9268 -142.1113 54.35454 155.0939 -142.3654 54.56172 155.2919 -142.2658 54.52187 155.2173 -142.471 54.56804 155.3685 -138.93 53.37151 163.5445 -140.852 54.41691 157.6452 -139.1512 54.38042 159.4878 -137.4908 54.41769 161.0034 -135.8898 54.51676 162.2195 -134.3634 54.66589 163.1664 -132.4734 52.6825 172.7629 -135.1519 52.67723 169.4993 -141.2881 52.11894 159.3358 -141.4707 52.26992 159.1663 -141.7126 53.21001 159.4084 -141.6113 53.32656 159.6286 -139.8931 53.42644 162.1828 -140.4446 53.43899 161.3911 -140.7391 53.43648 160.9626 -140.8184 53.43428 160.8462 -141.1417 53.41578 160.3658 -141.4091 53.38154 159.9565 -140.3042 54.42768 158.0807 -137.844 54.42954 160.5337 -135.0625 54.61178 162.6071 -132.902 54.857 163.8852 -131.4349 55.0922 164.4385 -131.9629 55.02026 164.1195 -129.9122 55.36989 164.8823 -128.3998 55.66707 165.2399 -128.6713 55.62853 165.0477 -126.9453 55.96326 165.5436 -125.4996 56.25868 165.8414 -127.7036 52.28239 179.0872 -124.0005 56.5563 166.1841 -125.3391 56.30681 165.7444 -122.534 56.8288 166.5918 -121.1557 57.05695 167.0836 -122.0445 56.93025 166.6166 -119.7572 57.25413 167.7159 -118.2299 57.431 168.556 -118.9122 57.3761 168.0166 -116.5455 57.58365 169.6473 -123.0097 52.02273 184.7901 -114.7643 57.7038 170.9617 -116.0013 57.64685 169.8755 -113.1139 57.78603 172.2925 -113.2659 57.80376 172.0012 -111.5962 57.84555 173.579 -118.4216 51.869 189.9756 -110.0529 57.89625 174.9253 -110.6266 57.90392 174.2513 -108.3243 57.94206 176.4759 -106.3689 57.97991 178.2842 -108.0395 57.97484 176.5628 -113.9483 51.80531 194.6963 -104.1774 58.00489 180.3787 -105.5014 58.01919 178.9286 -101.7103 58.0114 182.8205 -103.0098 58.03882 181.3439 -109.5987 51.81932 198.9915 -98.92488 57.99214 185.6807 -100.5622 58.03565 183.8039 -95.78969 57.9386 189.0239 -98.15539 58.01167 186.3038 -105.3947 51.88918 202.924 -92.33731 57.84415 192.8433 -93.45077 57.90944 191.4057 -95.78614 57.96891 188.8393 -101.3439 52.00096 206.5405 -88.60826 57.70599 197.1092 -91.14546 57.83536 193.9988 -97.45318 52.14284 209.8799 -84.5885 57.52431 201.8348 -86.60865 57.65179 199.2489 -88.86618 57.74876 196.6146 -90.16865 52.46761 215.9025 -80.17729 57.2998 207.1184 -84.36843 57.54664 201.8977 -93.72753 52.30027 212.9938 -83.55784 52.8074 221.1931 -75.30632 57.04569 212.9767 -79.92273 57.32 207.224 -86.77909 52.63868 218.6274 -82.14128 57.43533 204.5573 -80.47412 52.97296 223.6336 -70.40187 56.79175 218.8678 -73.26874 56.97309 215.2259 -75.48887 57.08773 212.5603 -77.70687 57.20338 209.893 -74.50881 53.29373 228.3525 -66.04381 56.5417 224.1974 -68.83677 56.74004 220.5634 -77.49875 53.13354 225.985 -71.04858 56.85848 217.8914 -68.18293 53.64805 233.3017 -62.33634 56.28165 228.9153 -64.47731 56.47362 225.958 -71.43682 53.46154 230.7725 -66.64347 56.61304 223.2501 -64.63816 53.88521 235.9249 -59.14952 56.00245 233.187 -60.25817 56.14374 231.4589 -62.34625 56.31829 228.6927 -58.7487 54.69364 238.6732 -56.41187 55.70644 237.0748 -58.22034 55.94707 234.2609 -59.21839 54.51524 238.8967 -59.75049 54.35956 238.9695 -60.29012 54.24369 238.8801 -60.78129 54.17862 238.6417 -58.50787 54.53503 238.9248 -56.24291 55.7252 237.1071 -59.27615 54.25582 239.2414 -60.1258 54.04054 239.2282 -60.92477 53.92263 238.8874 -69.18064 53.34216 232.8869 -77.20098 52.90132 226.5795 -85.20106 52.47176 220.2485 -93.14386 52.07697 213.8396 -100.9491 51.76259 207.2559 -108.5273 51.57578 200.4035 -115.7827 51.5611 193.2052 -122.6541 51.73958 185.6404 -129.1181 52.11153 177.7311 -140.4558 52.5415 157.0586 -139.829 52.58033 157.605 -137.3264 52.52602 160.2482 -136.8306 51.34992 165.3136 -138.6702 51.55824 162.7779 -138.8688 52.50135 158.8017 -140.9806 52.0004 159.7069 -140.568 51.88702 160.2337 -140.3131 51.82926 160.5668 -140.1452 51.79459 160.7884 -139.6399 51.7022 161.4627 -122.0336 54.95222 166.1139 -130.3425 50.64907 174.525 -134.7355 51.07265 169.0917 -123.8295 54.61584 165.6251 -125.9475 54.18922 165.1647 -128.1324 53.74457 164.7074 -130.0323 53.37725 164.2348 -131.6516 53.09579 163.709 -133.0675 52.88708 163.1041 -134.429 52.72698 162.3646 -135.8447 52.6045 161.4248 -113.5013 55.86608 171.0953 -123.6897 50.19913 182.926 -128.7015 50.50719 177.3228 -115.0863 55.77473 169.8653 -116.6076 55.65924 168.7927 -117.9752 55.52745 167.9372 -119.2424 55.37861 167.2483 -120.5461 55.19668 166.6515 -106.3855 56.09228 177.3321 -117.1794 49.97184 190.3193 -122.2378 50.13512 185.2322 -108.4489 56.04788 175.4413 -110.2579 55.99539 173.8363 -111.9019 55.93651 172.4211 -101.4487 56.13249 182.1127 -110.9805 49.92443 196.7026 -115.3658 49.95712 192.7957 -104.0633 56.12269 179.5363 -95.14632 56.05565 188.7138 -105.0754 50.00598 202.2908 -108.1112 49.97154 199.9944 -98.49288 56.11343 185.1427 -91.34353 55.94791 192.9351 -99.49748 50.16911 207.2348 -100.5331 50.15856 206.8457 -87.00628 55.77902 197.9286 -94.25559 50.37615 211.6722 -81.97528 55.53871 203.8934 -89.33912 50.60504 215.6994 -92.7284 50.47294 213.4289 -76.2995 55.24213 210.7215 -84.7325 50.84011 219.3926 -70.78872 54.95721 217.3394 -80.41928 51.07053 222.8105 -84.78614 50.86774 219.8372 -76.39556 51.28757 225.991 -76.78659 51.29734 226.1675 -66.07678 54.69417 223.0733 -72.57648 51.49219 229.0149 -68.77032 51.70589 231.9908 -62.11668 54.42277 228.088 -64.74759 51.96269 235.0157 -68.76708 51.738 232.4748 -58.79783 54.13592 232.5214 -60.29761 52.29923 238.1581 -55.92818 53.82706 236.5911 -59.80643 52.3643 238.3964 -60.5119 52.31848 238.4745 -59.2668 52.48017 238.4858 -59.71294 52.43638 238.8154 -58.7347 52.63585 238.413 -58.8633 52.65167 238.8285 -58.26501 52.81425 238.1895 -55.76667 53.87481 236.6308 -58.09503 52.93087 238.5119 -55.52643 54.02304 236.7132 -55.61465 53.95384 236.6785 -57.74493 54.09971 233.7854 -59.78277 54.29638 230.9834 -64.00199 54.62627 225.4824 -61.87088 54.47093 228.2171 -66.16822 54.76567 222.7745 -72.79309 55.12596 214.7497 -68.36157 54.89266 220.0878 -70.57318 55.01122 217.4155 -77.23226 55.35581 209.4175 -75.01416 55.2402 212.0848 -83.8935 55.69931 201.4216 -79.44766 55.47267 206.748 -81.66622 55.58803 204.0812 -88.39135 55.90142 196.1384 -86.13378 55.80445 198.7728 -92.97605 56.06209 190.9294 -90.67068 55.98802 193.5226 -95.31144 56.12156 188.363 -100.0876 56.18829 183.3275 -97.68075 56.16432 185.8275 -102.5353 56.19145 180.8675 -105.0269 56.17182 178.4522 -107.5651 56.12746 176.0863 -110.1522 56.05654 173.7748 -112.7916 55.95635 171.5247 -115.5271 55.79939 169.3992 -118.4379 55.52861 167.5405 -121.57 55.08275 166.1408 -124.8648 54.45922 165.2687 -128.1971 53.78092 164.572 -131.4888 53.17267 163.6436 -134.5879 52.76432 162.1312 -137.369 52.58216 160.0579 -142.0667 54.23908 155.054 -141.825 53.2994 154.812 -140.4078 53.19168 156.6478 -140.2669 54.11306 157.3435 -139.962 54.2155 157.7834 -57.85757 54.70752 233.3081 -58.49969 55.68731 232.9939 -55.62142 55.37118 237.1005 -55.67925 55.49137 237.1283 -55.37958 54.43148 236.8586 -58.3373 54.1941 238.9582 -60.6448 54.96455 229.5222 -61.87881 55.98449 228.46 -59.71022 55.91326 231.4384 -57.66757 55.71341 234.2576 -63.88296 55.20867 225.3355 -63.12414 56.07815 226.8508 -61.80366 56.09053 228.6562 -64.44371 56.16988 225.1748 -63.94053 56.24811 225.907 -65.07934 55.28746 223.833 -65.84469 56.26006 223.4234 -66.33935 55.36523 222.2707 -67.32347 56.34862 221.6006 -66.11277 56.38933 223.1861 -67.66461 55.44229 220.6461 -68.88643 56.43643 219.6964 -68.3123 56.5177 220.4878 -69.0541 55.51898 218.9587 -70.55236 56.52536 217.6849 -70.5305 56.63706 217.8058 -70.5166 55.59643 217.1952 -71.84484 56.59228 216.1325 -72.06846 55.67644 215.3325 -73.14459 56.65875 214.5744 -72.75708 56.75214 215.1321 -73.27851 55.73825 213.8822 -74.46296 56.72629 212.9936 -74.50654 55.80132 212.4091 -75.79869 56.79566 211.3883 -74.98334 56.86704 212.4594 -75.74703 55.86594 210.9176 -77.11763 56.86501 209.8 -77.01892 55.93287 209.3856 -78.39144 56.93227 208.2648 -77.20734 56.98291 209.7852 -78.29421 56.00021 207.8487 -79.63523 56.99776 206.7665 -79.4295 57.09983 207.1087 -79.5413 56.06583 206.3466 -80.85144 57.0612 205.3039 -81.95455 56.19049 203.449 -82.42372 57.14168 203.4189 -81.65445 57.21569 204.4336 -80.75657 56.12911 204.8855 -83.50393 56.26774 201.5995 -83.93458 57.21665 201.6167 -83.88807 57.32769 201.7648 -84.97747 56.33835 199.8516 -85.39548 57.28627 199.8853 -86.3836 56.40252 198.1961 -86.82006 57.35081 198.2099 -86.13504 57.43362 199.1062 -87.734 56.4607 196.6197 -88.20532 57.40991 196.5951 -89.03157 56.513 195.1189 -89.55403 57.4635 195.0382 -88.39958 57.53147 196.4615 -90.27436 56.55944 193.6957 -90.86948 57.51163 193.5357 -90.68616 57.61902 193.8347 -93.73337 56.66737 189.8173 -92.15 57.55422 192.0897 -93.39585 57.59133 190.6996 -92.99917 57.6941 191.23 -96.91773 57.67102 186.8681 -95.34263 57.75458 188.6515 -99.59069 56.76654 183.5746 -100.0547 57.70771 183.5886 -97.72048 57.79835 186.1036 -96.82266 56.73379 186.4699 -102.0756 56.77289 181.065 -102.8112 57.71116 180.8186 -100.1364 57.8233 183.5908 -104.3091 56.75918 178.8848 -105.2408 57.69084 178.4681 -105.0957 57.80855 178.6888 -102.5938 57.82737 181.1176 -106.3244 56.73061 176.9805 -107.3913 57.65411 176.4602 -108.1395 56.69151 175.3173 -109.2854 57.60697 174.7493 -107.6449 57.76488 176.3093 -109.7577 56.64588 173.8764 -110.9526 57.55392 173.2882 -110.2437 57.69448 173.984 -111.2299 56.5955 172.6 -112.5632 57.49206 171.918 -114.055 56.46747 170.2723 -114.3178 57.40597 170.4978 -112.8964 57.59476 171.7187 -112.6459 56.53826 171.4065 -115.4495 56.37786 169.2261 -116.2287 57.27675 169.0892 -115.6555 57.43846 169.567 -116.7728 56.27033 168.3205 -118.0363 57.10987 167.93 -119.1141 56.01654 166.9654 -119.6712 56.91529 167.0511 -118.6068 57.1669 167.6708 -117.9785 56.15043 167.5808 -120.2786 55.85687 166.4213 -121.179 56.69588 166.3958 -121.5728 55.6518 165.9239 -122.7005 56.43548 165.8861 -121.8021 56.71564 166.229 -123.0802 55.38036 165.4712 -124.3126 56.12837 165.4672 -124.8365 55.03578 165.0537 -125.8869 55.81126 165.1252 -125.1452 56.08515 165.3356 -126.7665 54.6419 164.6542 -127.413 55.49887 164.8128 -128.6256 54.2665 164.2537 -128.9697 55.18604 164.4716 -128.4844 55.40536 164.6377 -130.2232 53.96191 163.8395 -130.5651 54.88342 164.052 -131.6 53.72403 163.3871 -132.1067 54.62151 163.5281 -131.7423 54.80175 163.7252 -132.8145 53.54221 162.879 -133.5977 54.41123 162.8541 -133.9681 53.39958 162.2796 -135.1459 54.24582 161.9487 -134.785 54.39883 162.248 -136.3967 53.1995 160.6284 -136.7848 54.13161 160.7535 -135.1547 53.28454 161.54 -137.6917 53.1508 159.5227 -138.4992 54.08253 159.2298 -137.5273 54.21796 160.2085 -139.0324 53.14563 158.2021 -139.658 53.03356 157.479 -137.2235 53.03599 159.904 -134.4817 53.21678 161.9433 -131.4393 53.6196 163.4206 -128.1814 54.22317 164.3332 -124.8421 54.90297 165.0311 -121.4987 55.53358 165.9243 -118.3037 55.98484 167.366 -115.3525 56.25642 169.2619 -112.5935 56.41276 171.4135 -109.9406 56.51251 173.6788 -107.3417 56.58291 176.0041 -104.7925 56.62659 178.3836 -102.2905 56.64542 180.8125 -99.83307 56.64135 183.2857 -97.41711 56.61641 185.7986 -95.03919 56.57265 188.3465 -92.69568 56.51217 190.925 -90.38264 56.43709 193.5298 -88.096 56.34954 196.1566 -85.83142 56.25169 198.8014 -83.58438 56.14576 201.46 -81.35061 56.03381 204.1287 -79.12574 55.91791 206.804 -76.90403 55.80073 209.481 -74.67971 55.68495 212.1551 -72.45263 55.57044 214.8272 -70.2264 55.4552 217.5011 -68.00839 55.33573 220.1834 -65.80876 55.20738 222.8817 -63.63645 55.06618 225.6027 -59.40607 54.73131 231.1342 -61.49954 54.90859 228.3519 -57.3634 54.53146 233.9533 -58.09545 53.2544 238.7163 -55.37276 54.30049 236.8218 -59.15616 53.89651 239.2956 -55.90471 55.66507 237.1427 -55.74923 55.57048 237.1391 -139.6648 52.90308 157.4798 -137.2534 52.78077 159.9376 -139.6974 52.77854 157.5022 -58.91431 52.95682 239.0538 -59.81992 52.72735 239.0397 -60.06177 53.66704 239.2816 -60.91339 53.54137 238.9183 -60.67153 52.60168 238.6764 -64.95169 53.23107 236.0856 -65.33374 52.24838 235.387 -138.3108 51.78332 164.2169 -136.7174 52.47953 167.2401 -135.0325 51.36674 169.1138 -131.6803 51.93912 174.377 -128.0913 50.73112 178.5248 -126.6735 51.56161 180.8506 -121.1325 50.36804 186.8943 -121.8021 51.32321 186.6482 -117.0466 51.19651 191.896 -114.4833 50.22914 194.0832 -112.4135 51.16192 196.6636 -108.1465 50.25576 200.3165 -107.9279 51.20264 200.9909 -102.1568 50.39441 205.7675 -103.6043 51.29895 204.9403 -99.4578 51.43279 208.5668 -96.53269 50.59711 210.604 -95.4873 51.59078 211.9234 -91.27302 50.8316 214.9526 -91.69934 51.7625 215.0441 -88.09466 51.94009 217.9588 -86.36103 51.07693 218.9113 -84.67681 52.11742 220.6876 -81.77474 51.31958 222.5549 -81.42192 52.29126 223.2671 -77.51406 51.54964 225.9216 -78.30661 52.45957 225.7284 -75.19308 52.6272 228.1906 -73.49917 51.76536 229.0983 -72.00972 52.79911 230.706 -69.52513 51.98596 232.2152 -68.6315 52.9928 233.3316 -157.5392 53.48336 136.0186 -156.818 54.41392 140.2646 -158.5568 54.38061 138.3964 -160.2534 54.42382 136.8676 -161.8861 54.53082 135.6507 -161.1851 52.98063 130.3284 -161.8153 52.77858 129.0706 -156.6051 51.96499 138.3302 -156.1351 52.26992 138.8193 -155.8932 53.2097 138.5775 -155.9899 53.35707 138.3444 -156.3234 52.09 138.6598 -156.3566 52.07194 138.623 -157.2849 53.493 136.3811 -156.9573 53.49603 136.8542 -156.5451 53.4781 137.4632 -156.4955 53.47359 137.5379 -156.2208 53.43324 137.9617 -156.0225 53.373 138.2872 -157.4196 54.42686 139.8707 -159.9617 54.43618 137.3648 -163.4378 54.6888 134.7129 -162.8428 54.63918 135.2724 -164.9261 54.89027 134.0074 -164.5022 52.58137 125.46 -166.4434 55.14004 133.4605 -166.0526 55.08419 133.7915 -168.0108 55.43108 133.024 -169.5418 55.73517 132.6746 -169.4478 55.72687 132.8937 -171.0207 56.03738 132.3699 -172.5008 56.33858 132.0601 -168.4297 52.24062 120.2086 -174.0601 56.64389 131.6871 -172.8796 56.425 132.1744 -175.7677 56.94783 131.1605 -177.625 57.22414 130.3768 -176.26 57.0399 131.184 -179.5668 57.44901 129.3087 -179.4435 57.45404 129.6091 -172.8934 51.9855 114.7536 -181.5714 57.62033 127.9698 -183.6833 57.74723 126.351 -182.3941 57.69705 127.6026 -185.8692 57.84135 124.5307 -185.1807 57.83853 125.3657 -177.6254 51.83524 109.4376 -188.113 57.91724 122.5818 -187.8902 57.93597 123.0348 -190.5563 57.98068 120.385 -190.5528 58.00735 120.6495 -182.1916 51.78642 104.6818 -193.2745 58.02676 117.8459 -193.1687 58.05338 118.2125 -196.2215 58.04759 114.9798 -195.7392 58.07535 115.7274 -186.4453 51.80599 100.5041 -199.3881 58.03623 111.7691 -198.2658 58.0745 113.1975 -190.3787 51.86943 96.81723 -202.7835 57.98591 108.1782 -200.7503 58.05222 110.6264 -194.0232 51.96097 93.52841 -206.4225 57.88975 104.1655 -203.1947 58.00989 108.0175 -197.4108 52.06964 90.56306 -210.3235 57.74112 99.68704 -207.973 57.87104 102.6997 -205.6014 57.949 105.3742 -203.4982 52.31025 85.41053 -214.5035 57.53463 94.70468 -212.6216 57.67007 97.27024 -200.5639 52.18788 87.86935 -210.3121 57.77755 99.99736 -208.763 52.55282 81.08831 -218.9853 57.26733 89.18426 -214.9046 57.55019 94.52143 -206.2311 52.43292 83.15433 -215.1817 52.87649 75.92718 -223.8117 56.93946 83.08391 -219.4036 57.27947 88.97053 -213.227 52.77559 77.4898 -211.0934 52.66757 79.20368 -217.1641 57.41946 91.7539 -222.1816 53.2454 70.36061 -229.0489 56.55634 76.35803 -226.0343 56.81963 80.55311 -220.4611 53.15431 71.72731 -218.7462 53.06358 73.08956 -217.0037 52.97175 74.47536 -223.8353 56.97798 83.36743 -221.6262 57.13179 86.17412 -229.125 53.63018 64.91233 -234.7876 56.13185 68.97001 -230.4158 56.49551 74.91217 -227.4161 53.52985 66.23143 -225.6713 53.43233 67.59727 -223.9207 53.33781 68.98056 -228.2266 56.65829 77.73384 -238.8572 54.69368 59.31243 -241.1616 55.69243 60.88865 -236.9983 56.01397 66.45871 -238.3875 54.51528 59.08891 -237.8554 54.3596 59.01612 -237.3158 54.24373 59.10553 -236.8246 54.17866 59.34389 -234.5971 54.00049 60.87907 -232.6319 53.85714 62.28734 -230.839 53.73704 63.61356 -234.7982 56.17181 69.27205 -232.6052 56.33283 72.09072 -239.098 54.53507 59.06086 -241.4295 55.71408 60.8512 -239.2087 55.86084 63.6533 -238.3297 54.25587 58.74427 -237.4801 54.04058 58.75743 -236.737 54.07884 59.201 -229.7794 53.57573 64.20375 -223.02 53.19446 69.48165 -216.3055 52.83968 74.81771 -209.614 52.49851 80.18363 -202.9808 52.19145 85.62374 -196.4434 51.93937 91.18164 -190.0428 51.76364 96.89949 -183.8238 51.68601 102.8168 -177.8363 51.72835 108.9688 -172.1342 51.91193 115.3843 -166.7747 52.25645 122.0824 -241.6453 53.81304 61.37235 -237.7994 52.36434 59.58922 -237.3083 52.29927 59.82758 -237.2023 52.27098 59.66627 -239.484 53.95956 64.10289 -234.5033 52.07732 61.77017 -230.2446 51.76787 64.66909 -238.3391 52.48022 59.49981 -237.8929 52.43643 59.17028 -237.094 52.31852 59.51111 -238.8712 52.63589 59.5726 -238.7426 52.65171 59.15713 -239.3408 52.8143 59.79612 -241.8961 53.90122 61.31779 -239.5108 52.93091 59.4737 -242.0633 54.01405 61.26606 -239.6739 54.05299 64.11866 -237.389 54.10428 66.76017 -232.1152 51.90962 63.50665 -235.3603 54.2472 69.34423 -237.4634 54.20612 66.92417 -229.952 51.77166 65.13383 -233.4003 54.38896 71.85504 -235.2633 54.36396 69.73757 -225.7104 51.52862 68.43101 -231.5099 54.52977 74.29254 -233.0702 54.52499 72.55632 -227.8445 51.6473 66.75805 -223.5733 51.4141 70.12319 -229.2283 54.70027 77.23664 -230.8808 54.68767 75.37786 -221.4556 51.30198 71.80525 -227.0246 54.86221 80.06958 -228.6916 54.85046 78.19957 -219.3585 51.19099 73.47106 -224.9053 55.01667 82.78913 -226.4992 55.0118 81.01892 -214.9699 50.96104 76.96623 -222.8715 55.16023 85.38064 -224.3001 55.17016 83.83332 -217.2269 51.07868 75.16633 -212.4959 50.83443 78.94822 -220.9249 55.29253 87.84134 -222.0909 55.32397 86.64009 -209.742 50.6975 81.17007 -219.0623 55.4139 90.17554 -219.8683 55.47165 89.43656 -217.2819 55.52373 92.38262 -217.6288 55.61164 92.22001 -206.6924 50.5524 83.65599 -215.5857 55.62201 94.46075 -199.7017 50.25624 89.49589 -209.4817 55.91748 101.7128 -215.3691 55.74237 94.9876 -203.3487 50.40345 86.42095 -195.7299 50.11841 92.93222 -204.3128 56.0832 107.5256 -208.4373 56.06321 103.1661 -213.0861 55.86226 97.73649 -210.7765 55.96973 100.4637 -191.3968 50.00123 96.80992 -199.9083 56.15657 112.2151 -203.6589 56.20206 108.484 -206.0657 56.14117 105.8406 -186.6188 49.92218 101.2808 -196.1458 56.16644 116.0161 -198.7298 56.26665 113.664 -201.2144 56.24438 111.0929 -181.3444 49.91235 106.517 -192.9225 56.136 119.1211 -196.2032 56.26748 116.1939 -175.7417 50.01698 112.5263 -190.1494 56.08053 121.6786 -191.0166 56.19945 121.1161 -193.6326 56.24551 118.6791 -187.7874 56.01238 123.7759 -188.354 56.12812 123.5015 -185.7377 55.93756 125.5348 -170.3471 50.26462 118.8831 -183.7519 55.84625 127.1659 -185.6439 56.03038 125.8319 -181.7806 55.72074 128.6494 -182.8577 55.88909 128.0691 -179.9731 55.56196 129.84 -165.7302 50.6282 124.9127 -178.3671 55.37841 130.7328 -179.9073 55.6461 130.0754 -176.695 55.14039 131.4801 -174.6376 54.78187 132.1445 -176.7246 55.23233 131.6504 -172.0252 54.26433 132.7459 -173.3441 54.617 132.64 -161.9573 51.0635 130.3769 -169.2476 53.69982 133.3301 -169.9122 53.91883 133.3592 -166.9276 53.26068 133.9438 -165.0148 52.95259 134.6596 -166.517 53.27616 134.2572 -158.8812 51.5386 135.299 -163.2873 52.7383 135.5544 -161.4855 52.58583 136.7638 -163.3074 52.83125 135.7381 -159.5776 52.50719 138.3661 -160.4266 52.62831 137.8304 -157.583 52.52363 140.4246 -157.8847 52.61901 140.3362 -158.0024 51.64674 136.505 -156.9082 51.86904 137.9513 -156.9602 51.85483 137.8848 -157.3963 51.75297 137.3168 -157.749 51.68724 136.8469 -162.2804 50.97075 129.5361 -167.2397 50.44861 122.548 -172.5991 50.10409 115.85 -178.3012 49.9205 109.4345 -184.2888 49.87816 103.2824 -190.5077 49.95578 97.36506 -196.9084 50.1315 91.64717 -203.4458 50.38358 86.08924 -210.0791 50.69065 80.64908 -216.7706 51.03181 75.28311 -223.4852 51.3866 69.94702 -155.7809 53.2994 143.1736 -157.3593 54.11217 140.6183 -157.6817 54.26451 140.0982 -157.7469 53.16673 140.6921 -240.7173 54.52979 63.0178 -240.6024 55.46107 62.61627 -241.9844 55.37122 60.88516 -241.8822 55.54227 60.84796 -242.2263 54.43152 61.12701 -239.2686 54.19414 59.02746 -239.2517 55.55186 64.31983 -239.6502 55.68635 63.65423 -239.2446 54.62919 64.87678 -237.931 55.64313 65.99514 -237.8066 54.72913 66.70304 -236.6394 55.73443 67.64154 -237.4343 55.83937 66.46463 -236.4022 54.82905 68.49576 -235.3763 55.82535 69.25783 -235.0301 54.92845 70.25408 -233.8371 55.93785 71.23417 -235.2289 55.99724 69.28342 -233.6903 55.02679 71.97595 -232.3377 56.0487 73.1643 -233.0306 56.15844 72.10805 -232.3812 55.12373 73.66172 -230.8737 56.15757 75.05134 -230.8361 56.32142 74.93592 -230.8896 55.23471 75.58448 -229.4449 56.26393 76.89341 -229.4333 55.34307 77.46186 -228.0502 56.36736 78.69001 -228.6417 56.48464 77.76445 -228.0095 55.44853 79.29537 -226.6861 56.46769 80.4439 -226.6186 55.5506 81.08296 -225.3507 56.56472 82.15636 -226.4442 56.64653 80.59105 -225.262 55.64882 82.82119 -224.0448 56.65806 83.82495 -224.2399 56.80553 83.4131 -223.9414 55.74275 84.50674 -222.766 56.74765 85.45182 -222.4049 55.84947 86.45788 -221.5116 56.83345 87.03953 -222.0256 56.96007 86.22792 -220.9186 55.94956 88.33314 -220.2826 56.91522 88.58634 -219.4813 56.04294 90.1332 -219.0778 56.9929 90.09291 -219.7976 57.10857 89.03285 -218.0933 56.12952 91.85765 -217.5051 57.09022 92.04376 -217.5527 57.24944 91.82511 -216.7571 56.20919 93.50335 -215.9703 57.18027 93.92845 -215.151 56.29973 95.46131 -214.4726 57.263 95.74761 -215.2875 57.38109 94.60186 -213.6064 56.38101 97.32167 -213.009 57.33856 97.50477 -212.9987 57.50194 97.36021 -212.1285 56.45306 99.07954 -211.5806 57.40695 99.19896 -210.7087 56.51671 100.7467 -210.1851 57.46836 100.833 -210.6832 57.6104 100.0972 -208.8992 56.5895 102.839 -208.8222 57.52296 102.4081 -207.492 57.57093 103.9246 -208.3379 57.70489 102.8096 -207.1853 56.64945 104.7859 -206.1922 57.61256 105.3863 -204.0113 56.73617 108.2967 -202.4755 57.70182 109.4498 -205.9598 57.78383 105.4945 -205.556 56.69799 106.6037 -201.1466 56.78614 111.3556 -199.0149 57.74364 113.0728 -201.0945 57.88891 110.768 -202.5413 56.76523 109.8797 -203.5462 57.84568 108.1484 -197.3562 56.80948 115.2368 -195.7966 57.74567 116.2991 -198.6025 57.91205 113.35 -194.0953 56.78977 118.421 -192.8091 57.71531 119.1686 -193.489 57.89236 118.387 -196.0679 57.91366 115.8908 -191.2767 56.74286 121.0574 -190.0829 57.66047 121.6817 -190.8643 57.84688 120.835 -188.8457 56.68023 123.245 -187.6444 57.58958 123.8448 -188.1924 57.77594 123.2312 -186.7676 56.61053 125.0523 -185.3555 57.50438 125.8026 -185.4729 57.67879 125.5732 -184.8399 56.53159 126.6733 -183.1061 57.39363 127.6217 -182.9102 56.42717 128.1973 -180.9477 57.23974 129.1821 -182.6706 57.53788 127.828 -179.3638 56.12022 130.5511 -178.8701 57.03106 130.449 -179.692 57.29494 129.8627 -181.0307 56.28636 129.5296 -177.7926 55.92305 131.3561 -176.8496 56.76121 131.4209 -176.0239 55.65035 132.0652 -174.9629 56.44617 132.0836 -176.4625 56.87792 131.4721 -173.816 55.24424 132.6951 -173.2683 56.12384 132.5257 -171.162 54.7084 133.2671 -171.7066 55.80913 132.8646 -173.0371 56.25706 132.4848 -170.1861 55.49788 133.1757 -168.5854 54.18938 133.827 -168.6344 55.18598 133.5155 -169.5936 55.55674 133.2073 -167.0427 54.88393 133.9336 -166.4935 53.80511 134.4258 -165.501 54.62186 134.457 -166.2198 54.91686 134.0947 -164.7658 53.53872 135.1185 -164.0144 54.41197 135.128 -163.149 53.34817 135.995 -162.4695 54.24657 136.0303 -163.0539 54.47622 135.5485 -161.4449 53.21269 137.1726 -160.8334 54.13212 137.2217 -159.6374 53.14578 138.7201 -159.1221 54.08255 138.7404 -160.2039 54.27432 137.6141 -158.0157 52.9659 140.4326 -160.5377 52.97569 137.9486 -163.3874 53.17753 135.8832 -166.5531 53.61811 134.4294 -169.9269 54.25794 133.5417 -173.3705 54.9583 132.8193 -176.796 55.5795 131.8075 -180.0248 55.99623 130.1979 -183.0032 56.23916 128.1635 -185.8052 56.37987 125.9082 -188.5251 56.47732 123.5669 -191.197 56.54823 121.1705 -193.8218 56.59373 118.7225 -196.4008 56.61503 116.2263 -198.9355 56.61344 113.6855 -201.4276 56.59031 111.1035 -203.8793 56.54708 108.4838 -206.293 56.48524 105.8298 -208.6711 56.4063 103.145 -211.0166 56.31182 100.4324 -213.3322 56.20337 97.69538 -215.621 56.08252 94.93698 -217.8863 55.95086 92.16014 -220.1313 55.80999 89.3678 -222.3592 55.66149 86.56282 -224.5737 55.50695 83.74789 -226.778 55.34794 80.92579 -228.9756 55.18605 78.09913 -231.17 55.02283 75.27053 -233.3646 54.85984 72.4426 -235.563 54.69863 69.61788 -237.7684 54.54076 66.79901 -239.9843 54.38774 63.98853 -242.2181 54.23712 61.18387 -239.5104 53.25445 59.26932 -238.4497 53.89655 58.69005 -241.6909 55.6611 60.8363 -241.8485 55.57279 60.84366 -238.6916 52.95686 58.9319 -237.7859 52.72739 58.94591 -237.5441 53.66709 58.70405 -236.6925 53.54141 59.06735 -236.6655 53.73357 59.05128 -236.9344 52.60172 59.30919 -234.4594 53.36241 60.60498 -229.5543 53.22079 64.17015 -236.6811 53.92267 59.09824 -234.1331 52.38007 61.24917 -236.9997 52.43495 59.3855 -158.7514 51.77366 134.2748 -158.2695 52.75447 134.4328 -161.0959 52.31911 129.9148 -160.5092 52.59103 130.7683 -161.9098 51.30324 129.2886 -164.4581 51.92069 125.0045 -165.7782 50.87623 123.761 -168.4184 51.58254 119.7303 -165.4759 52.0122 123.5525 -170.4963 50.52558 117.6804 -172.9118 51.33304 114.2675 -170.8723 51.62212 116.6405 -175.9468 50.29616 111.3385 -177.6515 51.19035 108.9733 -176.6374 51.40387 110.0273 -181.511 50.20816 105.4323 -182.1984 51.14487 104.2497 -186.7127 50.22765 100.3064 -186.4393 51.16698 100.0946 -182.7097 51.33693 103.6949 -190.3612 51.23258 96.42765 -189.0308 51.3988 97.6142 -191.4197 50.31126 95.92424 -193.9915 51.32526 93.15751 -195.6964 50.4304 92.11048 -197.3657 51.43439 90.2074 -195.5471 51.5662 91.74842 -199.6192 50.56877 88.72529 -200.506 51.55263 87.52645 -203.2218 50.71564 85.69332 -203.4295 51.67479 85.07754 -202.2097 51.8159 86.05598 -206.5253 50.86368 82.96511 -206.1515 51.79725 82.83143 -208.6729 51.9169 80.7749 -209.5373 51.00753 80.5121 -210.9935 52.03132 78.89891 -208.9749 52.1251 80.49217 -212.2561 51.14304 78.31975 -213.1181 52.13896 77.19252 -214.7004 51.26831 76.36215 -215.0642 52.23943 75.63679 -216.9351 51.38488 74.58037 -216.8805 52.3344 74.18947 -215.8025 52.47153 75.01065 -219.0507 51.49637 72.89799 -218.6191 52.42603 72.80696 -220.3297 52.51656 71.44813 -221.1357 51.60676 71.24197 -222.0462 52.60748 70.08486 -223.2419 51.71831 69.56919 -223.7819 52.69961 68.70716 -222.6546 52.8333 69.56415 -225.3679 51.83231 67.88611 -225.5303 52.79408 67.32582 -227.4914 51.95055 66.22203 -227.273 52.89159 65.96193 -229.5905 52.07462 64.60496 -228.9821 52.992 64.64308 -230.6971 53.09904 63.34388 -231.7485 52.21245 62.98248 -232.4917 53.21925 62.01635 -229.8882 51.92216 64.50454 -222.9884 51.53466 69.89878 -216.136 51.17287 75.34547 -209.3082 50.82644 80.82718 -202.5427 50.51723 86.39122 -195.8798 50.26753 92.0839 -189.3635 50.10015 97.94993 -183.0422 50.03832 104.0309 -176.9697 50.1053 110.3636 -171.2046 50.32361 116.977 -165.8083 50.71376 123.8893 -160.8416 51.29267 131.1053 -161.4027 51.11508 130.5259 -160.9904 52.71892 130.1123 -229.6283 53.41356 64.17296 -222.7817 53.02841 69.52305 -215.9816 52.66926 74.92776 -209.2055 52.3248 80.3655 -202.4902 52.01635 85.88235 -195.8749 51.76567 91.52367 -189.4024 51.59502 97.33313 -183.1198 51.52703 103.3516 -177.0794 51.58446 109.6152 -171.3379 51.78934 116.1529 -165.955 52.16188 122.9833 -241.6345 55.68013 60.83727 -239.4626 55.80676 63.63801 -157.5637 54.38021 139.994 -237.2488 55.95981 66.44651 -235.0455 56.11768 69.2632 -232.8492 56.27881 72.08554 -230.6567 56.44168 74.91091 -228.4643 56.60472 77.73678 -226.2688 56.7664 80.56053 -224.0666 56.92515 83.37958 -221.8543 57.07941 86.19124 -219.6284 57.22759 88.99286 -217.3856 57.36812 91.78166 -215.1226 57.49942 94.55482 -212.8361 57.61989 97.30947 -210.5229 57.72797 100.0426 -208.18 57.82206 102.7511 -205.8045 57.90062 105.4319 -203.3936 57.9621 108.0816 -200.9448 58.00498 110.697 -198.4557 58.02779 113.2748 -195.9243 58.0291 115.8113 -193.3487 58.00754 118.3031 -190.7275 57.96185 120.7468 -188.0592 57.89073 123.1388 -185.3436 57.79348 125.4764 -182.5476 57.65236 127.7242 -179.58 57.40941 129.7478 -176.3689 56.99354 131.3435 -172.9616 56.37511 132.3474 -169.5227 55.67567 133.0685 -166.1403 55.03464 133.9601 -162.9567 54.5922 135.4247 -160.0941 54.38983 137.501 -223.1944 51.42429 69.93605 -230.041 51.80942 64.58589 -216.3942 51.06515 75.34082 -209.618 50.72071 80.77864 -202.9026 50.41228 86.29558 -196.2872 50.16162 91.93695 -189.8146 49.99099 97.7465 -183.532 49.92304 103.765 -177.4915 49.9805 110.0288 -171.75 50.18542 116.5665 -166.3672 50.558 123.3969 -242.2028 54.19646 61.19787 -242.1046 54.05385 61.24997 -239.8753 54.20286 64.05088 -157.9764 52.77632 140.407 -237.6614 54.35593 66.85945 -235.4581 54.51379 69.67623 -233.2618 54.67493 72.49862 -231.0691 54.8378 75.32408 -228.8768 55.00085 78.15001 -226.6812 55.16254 80.97384 -224.4789 55.32129 83.79296 -222.2665 55.47555 86.60472 -220.0406 55.62373 89.40639 -217.7978 55.76426 92.19526 -215.5347 55.89556 94.96849 -213.2481 56.01603 97.72322 -210.9349 56.12411 100.4564 -208.5919 56.2182 103.165 -206.2163 56.29675 105.8458 -203.8053 56.35823 108.4956 -201.3564 56.4011 111.1111 -198.8673 56.4239 113.6888 -196.3358 56.42519 116.2254 -193.7601 56.40363 118.7173 -191.1388 56.35792 121.161 -188.4705 56.28685 123.553 -185.7544 56.18928 125.8901 -182.9587 56.04835 128.1383 -179.9914 55.80542 130.1616 -176.781 55.38989 131.7574 -173.3736 54.77107 132.7604 -169.9346 54.07159 133.4815 -166.5522 53.43059 134.3733 -163.3688 52.98823 135.8379 -160.5065 52.78592 137.9141 -56.06718 55.71211 237.131 -55.95376 55.68342 237.1405 -58.04796 55.93382 234.278 -57.88908 55.88777 234.2867 -57.75748 55.81239 234.2824 -137.2265 52.90545 159.9089 -140.0272 54.31197 157.8426 -140.11 54.38234 157.9152 -140.2045 54.42181 157.9964 -59.79946 56.01185 231.4654 -61.8922 56.18881 228.6851 -64.02832 56.34613 225.9377 -66.19979 56.48713 223.2183 -68.39855 56.61534 220.5214 -70.61598 56.73459 217.8407 -72.84181 56.84962 215.1679 -75.06737 56.96448 212.496 -77.29071 57.08032 209.8226 -79.51216 57.19722 207.1469 -81.73637 57.31302 204.4728 -83.96923 57.42493 201.8051 -86.2154 57.53078 199.1477 -88.47908 57.62852 196.5042 -90.76477 57.71596 193.8787 -93.07682 57.79093 191.2754 -95.41929 57.85129 188.6984 -97.79606 57.89494 186.152 -100.2108 57.91978 183.6408 -102.6669 57.92375 181.1692 -105.1675 57.90484 178.7421 -107.7153 57.86109 176.3643 -110.3127 57.79064 174.0408 -112.9637 57.69087 171.7774 -115.7195 57.53454 169.629 -118.6652 57.26316 167.7377 -121.8518 56.81273 166.3013 -125.1882 56.18326 165.4107 -128.5266 55.50365 164.713 -131.7895 54.89929 163.7983 -134.8406 54.49548 162.3162 -137.5886 54.31436 160.2719 -59.92998 56.08649 231.4737 -62.02149 56.26281 228.6971 -64.15628 56.4196 225.9531 -66.32637 56.56019 223.2367 -68.52368 56.68808 220.5425 -70.73963 56.80711 217.864 -72.96397 56.92203 215.1932 -75.18811 57.03683 212.523 -77.41003 57.15263 209.8511 -79.63002 57.26945 207.1773 -81.85274 57.38513 204.5051 -84.0841 57.49689 201.8395 -86.32872 57.60255 199.1843 -88.59078 57.70009 196.5433 -90.87481 57.78731 193.9203 -93.18509 57.86204 191.3197 -95.52569 57.92217 188.7454 -97.90049 57.96559 186.2019 -100.3132 57.9902 183.6936 -102.7671 57.99396 181.2251 -105.2653 57.97486 178.8011 -107.8106 57.93096 176.4264 -110.4052 57.86037 174.1061 -113.0532 57.7605 171.8461 -115.8037 57.60402 169.7037 -118.7404 57.33279 167.8208 -121.9127 56.88354 166.394 -125.2381 56.25567 165.5083 -128.5748 55.57642 164.8108 -131.8451 54.97105 163.8927 -134.9089 54.56601 162.4027 -137.6657 54.3846 160.3507 -60.08742 56.13158 231.4701 -62.17736 56.30706 228.6984 -64.3104 56.46316 225.9587 -66.47866 56.6032 223.2464 -68.67409 56.73067 220.5557 -70.88809 56.84942 217.8802 -73.11046 56.96419 215.212 -75.33271 57.07892 212.5439 -77.55279 57.19464 209.8742 -79.77082 57.31137 207.2026 -81.9916 57.42689 204.533 -84.221 57.53844 201.8702 -86.46354 57.64386 199.218 -88.72349 57.74113 196.5802 -91.00529 57.82806 193.9606 -93.31327 57.90248 191.3634 -95.65142 57.9623 188.7928 -98.02362 58.00541 186.2531 -100.4335 58.02973 183.7487 -102.8845 58.03321 181.2842 -105.3797 58.01386 178.8643 -107.9216 57.96974 176.4937 -110.5127 57.899 174.1775 -113.1567 57.79899 171.9221 -115.9002 57.64229 169.7875 -118.825 57.37127 167.9157 -121.9788 56.92357 166.5014 -125.2898 56.29776 165.6221 -128.6244 55.61897 164.925 -131.9044 55.01229 164.0022 -134.9847 54.60567 162.5018 -137.7529 54.42388 160.44 -55.40885 54.17769 236.7778 -134.497 52.96211 161.9894 -55.49119 54.05841 236.7292 -134.4788 53.08648 161.9532 -57.39491 54.40349 233.9198 -57.47634 54.28396 233.8739 -57.59673 54.18045 233.8267 -139.7534 52.66846 157.5449 -131.4281 53.49018 163.4353 -128.1652 54.0945 164.3501 -124.8267 54.77414 165.0478 -121.49 55.40372 165.9383 -118.3037 55.85414 167.3744 -115.3582 56.12555 169.2655 -112.6023 56.28193 171.4137 -109.9512 56.38172 173.6771 -107.3538 56.45218 176.0007 -104.8059 56.49593 178.3785 -102.3053 56.51485 180.8057 -99.84909 56.51089 183.2773 -97.43428 56.48606 185.7886 -95.05745 56.44241 188.335 -92.71493 56.38205 190.912 -90.40283 56.30709 193.5154 -88.11708 56.21965 196.1409 -85.85335 56.1219 198.7844 -83.60713 56.01606 201.4419 -81.37413 55.90419 204.1096 -79.14997 55.78835 206.7838 -76.92898 55.6712 209.46 -74.70536 55.55545 212.1334 -72.47896 55.44096 214.8046 -70.25348 55.32579 217.4776 -68.03623 55.20642 220.1586 -65.83737 55.07823 222.8556 -63.66583 54.93724 225.5749 -61.52968 54.77992 228.3224 -59.43692 54.60296 231.1027 -59.63622 54.37821 231.0188 -61.72617 54.5537 228.247 -63.85926 54.70981 225.5073 -66.02758 54.84983 222.7949 -68.22309 54.97728 220.1042 -70.43692 55.09615 217.4285 -72.65899 55.21107 214.76 -74.88214 55.3254 212.0926 -77.1024 55.44107 209.4229 -79.31999 55.55804 206.7508 -81.54074 55.67359 204.0811 -83.77024 55.78509 201.4183 -86.01287 55.89051 198.7661 -88.27285 55.98779 196.1282 -90.55471 56.07471 193.5086 -92.86271 56.14914 190.9114 -95.20092 56.20895 188.3408 -97.57318 56.25205 185.801 -99.98316 56.27637 183.2966 -102.4342 56.27984 180.832 -104.9294 56.26048 178.412 -107.4714 56.21636 176.0415 -110.0625 56.14562 173.7252 -112.7066 56.04558 171.4698 -115.4502 55.88883 169.3353 -118.3749 55.61779 167.4638 -121.5285 55.17007 166.0498 -124.8397 54.54416 165.1706 -128.1743 53.86536 164.4734 -131.4544 53.2587 163.5505 -134.5343 52.85221 162.0501 -137.3021 52.6705 159.9883 -59.51726 54.48269 231.0608 -61.60882 54.65901 228.2842 -63.74363 54.81581 225.5401 -65.91378 54.95638 222.8238 -68.11119 55.08425 220.1295 -70.32696 55.2034 217.4508 -72.55097 55.31847 214.7797 -74.77597 55.43288 212.1102 -76.99816 55.5486 209.4384 -79.21768 55.66567 206.7639 -81.44036 55.78139 204.0917 -83.67185 55.8931 201.4261 -85.91651 55.99876 198.7709 -88.17862 56.0963 196.1298 -90.4627 56.18352 193.5068 -92.77304 56.25825 190.9061 -95.1137 56.31838 188.3318 -97.48855 56.36179 185.7883 -99.90129 56.3864 183.28 -102.3553 56.39015 180.8114 -104.8535 56.37104 178.3874 -107.3989 56.32713 176.0127 -109.9935 56.25655 173.6922 -112.6416 56.15666 171.4323 -115.3922 56.00012 169.29 -118.3287 55.72887 167.4074 -121.5009 55.27962 165.9808 -124.8264 54.65164 165.0953 -128.1632 53.97237 164.3978 -131.4336 53.36703 163.4795 -274.6046 52.48308 149.666 -274.6046 52.50307 149.666 -272.2028 52.48306 125.2797 -272.2028 52.50306 125.2797 -265.0895 52.48305 101.8306 -265.0895 52.50304 101.8306 -253.5382 52.48303 80.21972 -253.5382 52.50303 80.21972 -237.9928 52.48302 61.27768 -237.9928 52.50302 61.27768 -219.0507 52.48301 45.73236 -219.0507 52.50301 45.73236 -197.4398 52.483 34.18116 -197.4398 52.503 34.18116 -173.9907 52.483 27.06799 -173.9907 52.503 27.06799 -149.6044 52.483 24.6662 -149.6044 52.50299 24.6662 -125.2181 52.483 27.06808 -125.2181 52.503 27.06808 -101.769 52.483 34.18134 -101.769 52.503 34.18134 -80.15816 52.48301 45.73263 -80.15816 52.50301 45.73263 -61.21612 52.48302 61.27802 -61.21612 52.50302 61.27802 -45.67078 52.48303 80.22013 -45.67078 52.50303 80.22013 -34.11959 52.48305 101.831 -34.11959 52.50304 101.831 -27.00642 52.48306 125.2802 -27.00642 52.50306 125.2802 -24.60463 52.48308 149.6665 -24.60463 52.50307 149.6665 -27.00652 52.48309 174.0528 -27.00652 52.50309 174.0528 -34.1198 52.48311 197.5019 -34.1198 52.5031 197.5019 -45.6711 52.48312 219.1127 -45.6711 52.50312 219.1127 -61.21651 52.48313 238.0548 -61.21651 52.50313 238.0548 -80.15863 52.48314 253.6001 -80.15863 52.50314 253.6001 -101.7695 52.48315 265.1513 -101.7695 52.50315 265.1513 -125.2187 52.48315 272.2644 -125.2187 52.50315 272.2644 -149.605 52.48316 274.6662 -149.605 52.50315 274.6662 -173.9913 52.48315 272.2643 -173.9913 52.50315 272.2643 -197.4404 52.48315 265.151 -197.4404 52.50315 265.151 -219.0512 52.48314 253.5997 -219.0512 52.50314 253.5997 -237.9933 52.48313 238.0543 -237.9933 52.50313 238.0543 -253.5386 52.48312 219.1121 -253.5386 52.50312 219.1121 -265.0897 52.48311 197.5012 -265.0897 52.5031 197.5012 -272.2029 52.48309 174.0521 -272.2029 52.50309 174.0521 -29.97302 -31.59387 30.24789 -29.97302 -31.59392 -29.7521 30.02697 -31.5939 -29.7521 30.02697 -31.59385 30.24789 -29.97303 -19.59387 30.24788 -29.97303 -19.59392 -29.75211 30.02697 -19.5939 -29.75211 30.02697 -19.59385 30.24788 -29.9233 -69.17951 81.3134 -29.92331 -69.17963 -78.68663 30.07668 -69.17961 -78.68663 30.07669 -69.17948 81.3134 -29.92331 -39.1795 81.31336 -29.92332 -39.17963 -78.68664 30.07667 -39.17961 -78.68664 30.07668 -39.17948 81.31336 -44.26984 29.5873 42.84998 -44.26984 29.58723 -47.15002 45.73016 29.58726 -47.15002 45.73016 29.58733 42.84997 -44.26984 31.5873 42.84998 -44.26984 31.58723 -47.15002 45.73016 31.58726 -47.15002 45.73016 31.58733 42.84997 81.69725 -3.190926 -67.46562 67.55513 -3.190945 -81.60774 93.01095 -3.190961 -107.0636 107.1531 -3.190943 -92.92147 81.69725 4.809074 -67.46562 67.55513 4.809056 -81.60775 93.01095 4.809039 -107.0636 107.1531 4.809057 -92.92148 -106.3959 -3.191068 -92.03672 -92.25376 -3.191072 -106.1788 -66.79795 -3.191048 -80.72299 -80.94007 -3.191043 -66.58086 -106.3959 4.808932 -92.03672 -92.25376 4.808928 -106.1788 -66.79795 4.808953 -80.72299 -80.94007 4.808957 -66.58086 46.2756 -94.6697 -41.72864 41.93641 -94.6697 -46.06781 41.93643 -203.5216 -46.06777 46.27562 -203.5216 -41.72859 47.10384 -89.22564 -42.55689 42.76465 -89.22565 -46.89606 42.67138 -208.0807 -46.80271 47.01057 -208.0807 -42.46354 48.95594 -86.81713 -44.409 44.61675 -86.81714 -48.74817 44.6003 -211.0723 -48.73163 48.93949 -211.0723 -44.39246 51.37465 -86.32157 -46.82772 47.03546 -86.32157 -51.16689 46.2206 -163.9427 -50.35197 46.22061 -201.2779 -50.35196 47.0355 -211.9904 -51.16684 51.37469 -211.9904 -46.82767 50.5598 -201.2779 -46.01279 50.55979 -163.9427 -46.0128 51.34848 -93.14408 -46.80154 51.37465 -93.13746 -46.82772 48.81835 -86.32157 -52.94978 53.15753 -86.32157 -48.61061 47.00929 -93.14408 -51.14071 47.03546 -93.13747 -51.16689 46.4259 -202.8417 -50.55725 46.45195 -162.0754 -50.58333 53.15757 -211.9904 -48.61056 48.81838 -211.9904 -52.94973 51.30387 -203.8678 -46.75686 51.37468 -203.9005 -46.82767 46.96468 -203.8678 -51.09603 47.03549 -203.9005 -51.16685 50.79114 -162.0754 -46.24415 50.76509 -202.8417 -46.21808 51.4301 -93.12353 -46.88316 50.83115 -93.97016 -46.28421 52.02407 -92.97409 -47.47714 51.53623 -93.09682 -46.9893 50.60124 -86.32157 -54.73268 54.94042 -86.32157 -50.3935 47.68488 -92.97409 -51.81631 47.19704 -93.09683 -51.32847 47.09091 -93.12355 -51.22233 46.49196 -93.97016 -50.62338 46.96928 -161.2493 -51.10066 54.94046 -211.9904 -50.39345 50.60128 -211.9904 -54.73263 53.15757 -204.1826 -48.61056 48.81838 -204.1826 -52.94974 51.98407 -204.1826 -47.43706 47.64488 -204.1826 -51.77624 51.30847 -161.2493 -46.76148 51.47525 -93.11216 -46.92831 50.5998 -95.83741 -46.05286 47.13605 -93.11217 -51.26747 52.52207 -92.97409 -47.97513 53.31619 -92.97409 -48.76926 56.72331 -86.32157 -52.1764 52.38412 -86.32157 -56.51557 50.44258 -92.97409 -54.57402 48.18288 -92.97409 -52.3143 46.26061 -95.83742 -50.39203 46.26062 -133.1726 -50.39202 47.03548 -161.2327 -51.16686 52.38416 -211.9904 -56.51552 56.72335 -211.9904 -52.17635 50.60127 -204.1826 -54.73263 52.98006 -204.1826 -48.43305 52.48207 -204.1826 -47.93506 48.14288 -204.1826 -52.27423 48.64087 -204.1826 -52.77223 49.13887 -204.1826 -53.27023 49.63686 -204.1826 -53.76822 51.37467 -161.2327 -46.82769 50.59981 -133.1726 -46.05284 53.02006 -92.97409 -48.47313 53.15754 -92.97409 -48.61061 53.51806 -92.97409 -48.97113 54.01605 -92.97409 -49.46912 53.23037 -92.97409 -48.68344 53.27469 -92.97409 -48.72776 55.07618 -92.97409 -50.52926 54.16701 -86.32157 -58.29846 58.5062 -86.32157 -53.95929 52.22547 -92.97409 -56.35691 50.17486 -92.97409 -54.30629 49.67686 -92.97409 -53.8083 50.51542 -92.97409 -54.64685 48.68087 -92.97409 -52.8123 48.81835 -92.97409 -52.94978 46.46591 -134.7364 -50.5973 58.50624 -211.9904 -53.95924 54.16705 -211.9904 -58.29841 54.97204 -204.1826 -50.42505 54.94046 -204.1826 -50.39346 50.63286 -204.1826 -54.76422 53.97605 -204.1826 -49.42905 53.47805 -204.1826 -48.93105 50.13486 -204.1826 -54.26622 47.64487 -161.0794 -51.77625 50.80509 -134.7364 -46.25813 54.51405 -92.97409 -49.96712 49.17887 -92.97409 -53.3103 55.51004 -92.97409 -50.96311 56.00804 -92.97409 -51.46112 55.01205 -92.97409 -50.46512 54.98756 -92.97409 -50.44063 57.00403 -92.97409 -52.45711 56.88197 -92.97409 -52.33505 60.28908 -86.32157 -55.74218 55.9499 -86.32157 -60.08135 54.02978 -92.97409 -58.16122 52.16685 -92.97409 -56.29829 51.66885 -92.97409 -55.80029 52.22828 -92.97409 -56.35972 54.94043 -92.97409 -50.3935 50.60124 -92.97409 -54.73267 47.0047 -135.7625 -51.13609 55.94993 -211.9904 -60.08131 60.28912 -211.9904 -55.74213 58.50624 -204.1582 -53.95925 56.72335 -204.1807 -52.17635 52.46203 -204.1823 -56.5934 52.38416 -204.1823 -56.51552 54.47405 -204.1826 -49.92705 55.96804 -204.1826 -51.42104 55.47004 -204.1826 -50.92304 51.13085 -204.1826 -55.26221 51.62885 -204.1826 -55.76021 47.03548 -135.7767 -51.16687 47.44013 -135.9641 -51.57153 51.98406 -161.0794 -47.43708 51.34389 -135.7625 -46.79692 56.50603 -92.97409 -51.95911 56.72332 -92.97409 -52.17639 51.17085 -92.97409 -55.30229 50.67286 -92.97409 -54.80429 56.87768 -92.97409 -52.33076 52.38413 -92.97409 -56.51557 52.36123 -92.97409 -56.49267 57.50202 -92.97409 -52.9551 58.00002 -92.97409 -53.4531 59.49401 -92.97409 -54.9471 60.12306 -93.28329 -55.57615 57.73279 -86.32157 -61.86425 62.07197 -86.32157 -57.52508 55.15482 -92.97409 -59.28627 55.78387 -93.2833 -59.91532 53.66083 -92.97409 -57.79228 53.16283 -92.97409 -57.29428 54.11841 -92.97409 -58.24986 56.74473 -92.97409 -52.19781 52.2726 -92.97409 -56.40404 62.07201 -211.9904 -57.52503 57.73283 -211.9904 -61.8642 54.16705 -204.1681 -58.29842 57.18852 -204.1708 -52.64153 58.45801 -204.1582 -53.91102 56.68928 -204.1821 -52.14228 51.964 -204.1826 -56.09537 52.12685 -204.1823 -56.25821 56.19122 -204.1826 -51.64423 47.68489 -136.0774 -51.81629 51.77932 -135.9641 -47.23236 52.02408 -136.0774 -47.47712 52.48205 -161.0794 -47.93507 48.14287 -161.0794 -52.27425 51.37466 -135.7767 -46.8277 56.83337 -92.97409 -52.28644 52.66484 -92.97409 -56.79628 58.49802 -92.97409 -53.9511 60.14427 -93.29373 -55.59735 58.50621 -92.97409 -53.95929 58.99601 -92.97409 -54.4491 60.66547 -93.96045 -56.11856 60.28909 -93.47898 -55.74218 63.85486 -86.32157 -59.30797 59.51567 -86.32157 -63.64714 56.32628 -93.96046 -60.45773 55.9499 -93.47899 -60.08135 55.80508 -93.29374 -59.93653 54.65682 -92.97409 -58.78827 54.16702 -92.97409 -58.29846 54.15883 -92.97409 -58.29027 59.51571 -211.9904 -63.64709 63.8549 -211.9904 -59.30792 60.61751 -202.9538 -56.07053 60.28912 -203.5453 -55.74214 56.27832 -202.9538 -60.4097 55.94993 -203.5453 -60.08131 58.95601 -204.1786 -54.40903 58.68389 -204.1582 -54.1369 54.61682 -204.1802 -58.7482 54.45557 -204.1681 -58.58694 58.1875 -204.1437 -53.64051 57.68842 -204.1535 -53.14143 56.96403 -204.1708 -52.41703 56.46603 -204.1821 -51.91904 52.96077 -204.1756 -57.09214 54.11883 -204.1681 -58.2502 47.77251 -136.0774 -51.9039 52.1117 -136.0774 -47.56473 52.98005 -161.0794 -48.43307 48.64086 -161.0794 -52.77224 60.21026 -93.37813 -55.66336 60.27153 -93.4565 -55.72462 61.05772 -95.90283 -56.51081 65.63775 -86.32157 -61.09087 61.29856 -86.32157 -65.43004 55.93233 -93.45652 -60.06378 56.71853 -95.90284 -60.84998 55.82511 -93.31937 -59.95656 61.2986 -211.9904 -65.43 65.63779 -211.9904 -61.09082 60.11012 -203.8678 -55.56314 61.01771 -201.5132 -56.47073 55.77093 -203.8678 -59.90231 56.67853 -201.5132 -60.8099 59.45401 -204.1826 -54.90702 59.17964 -204.1786 -54.63266 55.11482 -204.1826 -59.2462 54.95224 -204.1802 -59.08361 57.96002 -204.1437 -53.41303 57.46202 -204.1535 -52.91503 53.95852 -204.1596 -58.0899 52.62484 -204.1756 -56.75621 53.12284 -204.1654 -57.25421 53.45989 -204.1654 -57.59126 52.52208 -136.0774 -47.97512 48.18289 -136.0774 -52.31429 48.81837 -161.0794 -52.94975 61.05773 -133.4079 -56.51079 67.42064 -86.32157 -62.87376 63.08145 -86.32157 -67.21293 56.67852 -164.0081 -60.80992 61.0177 -164.0081 -56.47075 55.87108 -93.37815 -60.00253 56.71854 -133.4079 -60.84996 63.08149 -211.9904 -67.21289 53.62083 -204.1596 -57.7522 52.56128 -136.0774 -48.01432 48.22209 -136.0774 -52.3535 49.13885 -161.0794 -53.27024 53.15756 -161.0794 -48.61058 60.62546 -162.0657 -56.0785 67.16262 -104.5097 -62.61572 67.29917 -94.88478 -62.75227 69.20353 -86.32157 -64.65666 64.86434 -86.32157 -68.99583 63.05477 -94.11965 -67.18624 63.08145 -94.07701 -67.21292 62.82342 -95.98691 -66.95489 62.82343 -133.3221 -66.95487 56.28627 -162.0657 -60.41767 63.08148 -203.173 -67.21289 62.948 -202.9188 -67.07939 63.02872 -134.8859 -67.16016 63.08147 -134.9864 -67.21292 63.08147 -161.981 -67.2129 62.97404 -162.1525 -67.10547 62.74272 -201.355 -66.87411 62.74271 -164.0198 -66.87413 67.42158 -211.9876 -62.87281 53.02007 -136.0774 -48.47311 48.68088 -136.0774 -52.81229 48.81836 -136.0774 -52.94976 49.41463 -136.0774 -53.54603 49.67687 -136.0774 -53.80828 53.47805 -161.0794 -48.93107 56.31833 -134.8485 -60.44976 60.65752 -134.8485 -56.11058 67.16283 -133.3221 -62.6155 67.16262 -95.98691 -62.61572 67.39399 -94.11965 -62.84703 69.10707 -93.12358 -64.5601 66.64723 -86.32157 -70.77872 70.98641 -86.32157 -66.43955 64.86434 -93.12358 -68.99582 63.57209 -93.29354 -67.70356 67.36824 -134.8859 -62.82067 63.5675 -135.912 -67.69894 63.40426 -161.4656 -67.53569 63.13714 -203.279 -67.26854 64.86438 -211.9904 -68.99578 67.42151 -203.173 -62.87288 67.28796 -202.9188 -62.73945 67.421 -134.9864 -62.87339 67.31372 -162.1525 -62.76581 67.42121 -161.981 -62.87319 67.08255 -201.355 -62.53429 67.08229 -164.0198 -62.53457 53.15755 -136.0774 -48.61059 49.17888 -136.0774 -53.31029 49.63685 -161.0794 -53.76824 49.95938 -136.0774 -54.09079 53.7023 -136.0774 -49.15534 53.51807 -136.0774 -48.97111 53.97604 -161.0794 -49.42906 55.94991 -135.5122 -60.08134 60.28911 -161.6355 -55.74215 60.2891 -135.5122 -55.74216 67.4207 -94.07701 -62.8737 69.20465 -93.12358 -64.65554 68.58692 -93.12358 -64.03994 69.08491 -93.12358 -64.53794 70.89099 -93.12358 -66.34188 72.7693 -86.32157 -68.22245 68.43013 -86.32157 -72.56163 64.74568 -93.12358 -68.87715 64.24768 -93.12358 -68.37916 67.91133 -93.29354 -63.36434 55.94992 -161.6355 -60.08132 64.24771 -136.2268 -68.37915 63.86278 -161.233 -67.99421 63.49138 -161.3264 -67.62281 63.21335 -203.4241 -67.34475 64.86438 -204.2597 -68.99578 64.665 -204.2597 -68.79638 63.28008 -203.5512 -67.41149 63.48678 -203.9449 -67.61818 64.16699 -204.2597 -68.29838 69.22428 -211.9274 -64.63591 67.47715 -203.2789 -62.92852 67.90705 -135.912 -63.35942 67.74398 -161.4656 -63.19597 50.13485 -161.0794 -54.26623 50.17487 -136.0774 -54.30628 54.03375 -136.0774 -49.48679 54.01606 -136.0774 -49.46911 54.47404 -161.0794 -49.92707 55.82826 -135.7313 -59.95968 60.10425 -161.399 -55.5573 60.16744 -135.7313 -55.62051 69.58399 -93.12358 -65.03486 70.08198 -93.12358 -65.53285 70.98919 -93.12358 -66.43676 70.57997 -93.12358 -66.03086 72.67546 -93.12358 -68.12303 70.21302 -86.32157 -74.34452 74.5522 -86.32157 -70.00534 66.64723 -93.12358 -70.77871 65.74167 -93.12358 -69.87316 65.24369 -93.12358 -69.37516 55.76507 -161.399 -59.89647 68.49647 -136.1848 -63.94884 64.74569 -136.2268 -68.87714 64.16697 -161.1564 -68.2984 64.86436 -136.2268 -68.99581 64.27771 -161.1564 -68.40914 64.95391 -204.2597 -69.0853 66.64727 -211.9904 -70.77867 69.15986 -204.2597 -64.5754 67.83005 -203.9449 -63.27493 67.54328 -203.4049 -62.99464 69.0214 -204.2597 -64.43998 68.51786 -204.2597 -63.94752 67.8311 -161.3264 -63.2831 68.14106 -161.2484 -63.59306 50.60126 -161.0794 -54.73265 50.60125 -136.0774 -54.73266 54.51406 -136.0774 -49.9671 54.34417 -136.0774 -49.79721 55.81095 -135.7625 -59.94237 59.45399 -161.0794 -54.90704 60.15013 -135.7625 -55.6032 71.07963 -93.12358 -66.52719 71.57762 -93.12358 -67.02519 66.23966 -93.12358 -70.37114 72.77304 -93.12358 -68.21871 72.57363 -93.12358 -68.02119 74.45925 -93.12358 -69.90493 76.33509 -86.32157 -71.78823 71.99591 -86.32157 -76.12741 68.43013 -93.12358 -72.56161 66.73767 -93.12358 -70.86914 55.11481 -161.0794 -59.24621 68.58826 -136.2268 -64.0386 69.09178 -136.2268 -64.53106 64.86437 -161.1564 -68.9958 64.66497 -161.1564 -68.7964 65.00473 -204.2597 -69.13613 65.04631 -204.2597 -69.1777 66.15898 -204.2597 -70.29039 66.64727 -204.2597 -70.77867 65.16298 -204.2597 -69.29438 65.66098 -204.2597 -69.79238 71.03772 -211.8346 -66.38823 69.22303 -204.2597 -64.63716 68.51074 -161.1564 -63.95464 68.79771 -161.1564 -64.23532 50.67287 -136.0774 -54.80428 51.17086 -136.0774 -55.30227 54.94044 -136.0774 -50.39348 55.01206 -136.0774 -50.46511 54.94045 -161.0794 -50.39347 50.63285 -161.0794 -54.76424 59.73457 -135.9619 -55.18763 72.07563 -93.12358 -67.5232 67.23566 -93.12358 -71.36714 73.07257 -93.12358 -68.51823 68.23165 -93.12358 -72.36314 74.55452 -93.12358 -70.003 74.06855 -93.12358 -69.51423 78.11798 -86.32157 -73.57112 73.77878 -86.32157 -77.9103 70.21302 -93.12358 -74.3445 76.23958 -93.21226 -71.68801 69.22766 -93.12358 -73.35913 68.72966 -93.12358 -72.86113 55.39538 -135.9619 -59.5268 69.01428 -161.1564 -64.4471 69.21589 -161.1564 -64.64429 69.21177 -136.2268 -64.64841 69.59111 -136.2268 -65.02774 65.24369 -136.2268 -69.37514 65.74169 -136.2268 -69.87313 65.45301 -161.1564 -69.58444 65.16297 -161.1564 -69.29441 66.65697 -204.2597 -70.78837 66.70732 -204.2597 -70.83872 68.43016 -211.9904 -72.56157 69.33185 -204.2597 -64.746 70.99311 -204.2597 -66.3512 70.53796 -204.2597 -65.91141 69.52487 -204.2597 -64.93251 70.03141 -204.2597 -65.42195 69.31188 -204.2597 -64.72602 51.19752 -136.0774 -55.32893 55.29291 -136.0774 -50.74596 55.51005 -136.0774 -50.9631 54.97203 -161.0794 -50.42506 51.21854 -136.0774 -55.34996 55.15483 -136.0774 -59.28625 59.49402 -136.0774 -54.94708 58.956 -161.0794 -54.40904 54.61681 -161.0794 -58.74821 67.73365 -93.12358 -71.86515 73.57056 -93.12358 -69.01623 74.56515 -93.12358 -70.01364 75.06314 -93.12358 -70.51162 80.44599 -87.25347 -75.89914 76.1068 -87.25347 -80.23831 72.36788 -93.4432 -76.49938 71.99591 -93.26036 -76.12739 76.70748 -93.4432 -72.1598 76.33547 -93.26036 -71.78783 70.22364 -93.12358 -74.35514 69.72563 -93.12358 -73.85713 76.05915 -93.12358 -71.50762 69.8043 -161.1564 -65.2327 70.08911 -136.2268 -65.52574 69.51449 -161.1564 -64.94289 66.23968 -136.2268 -70.37113 65.78715 -161.1564 -69.91858 65.66096 -161.1564 -69.79239 66.80894 -204.2597 -70.94034 67.15496 -204.2597 -71.28637 68.15095 -204.2597 -72.28237 68.43016 -204.2597 -72.56157 67.65296 -204.2597 -71.78437 72.8381 -211.7814 -68.15364 71.03462 -204.2597 -66.39133 55.9558 -136.0774 -51.40885 55.47003 -161.0794 -50.92306 55.96803 -161.0794 -51.42106 51.13084 -161.0794 -55.26223 51.54999 -136.0774 -55.6814 59.10258 -136.0733 -54.55564 59.21659 -136.0733 -54.66965 58.50622 -161.0794 -53.95926 55.06267 -136.076 -59.19409 75.56114 -93.12358 -71.00962 70.72163 -93.12358 -74.85312 78.11801 -211.9904 -73.57109 80.46699 -211.0723 -75.92007 77.97277 -89.19734 -82.10428 82.31195 -89.19734 -77.76511 76.1278 -211.0723 -80.25924 73.77882 -211.9904 -77.91025 71.71762 -93.12358 -75.84912 72.88908 -94.10993 -77.02058 77.2287 -94.10993 -72.68097 69.93655 -161.1564 -65.36495 70.2863 -136.2268 -65.72293 66.64724 -136.2268 -70.7787 66.0606 -161.1564 -70.19203 70.04463 -204.2407 -74.17604 70.21305 -211.9904 -74.34446 69.98575 -204.2429 -74.11717 68.48991 -204.2597 -72.62133 69.64495 -204.2429 -73.77636 68.64895 -204.2594 -72.78036 69.48666 -204.2529 -73.61808 68.98794 -204.2594 -73.11935 69.14694 -204.2529 -73.27836 71.14223 -204.2597 -66.49893 71.54625 -204.2597 -66.89509 72.76396 -204.2597 -68.08911 72.55204 -204.2597 -67.8813 72.04914 -204.2597 -67.38819 71.0437 -204.2597 -66.40039 56.46602 -161.0794 -51.91905 51.62884 -161.0794 -55.76023 54.98919 -136.0749 -59.12061 54.76336 -136.0749 -58.89478 54.16704 -161.0794 -58.29843 58.458 -161.0794 -53.91104 71.21962 -93.12358 -75.35112 82.2835 -208.4076 -77.73657 77.6225 -133.5574 -73.07167 83.71624 -94.86036 -79.16941 79.37705 -94.86036 -83.50857 77.9443 -208.4077 -82.07575 73.28134 -133.5574 -77.41281 73.28133 -96.0523 -77.41282 77.62107 -96.0523 -73.0731 70.73915 -161.1564 -66.14046 70.59226 -136.2268 -66.01856 70.52033 -161.1564 -65.92903 70.01379 -161.1564 -65.43959 71.00682 -136.2268 -66.41915 66.64725 -161.1564 -70.77869 66.15896 -161.1564 -70.29039 70.09555 -204.2389 -74.22696 74.59513 -211.86 -69.96239 71.04433 -204.2597 -66.40103 72.83397 -204.2596 -68.15777 72.77958 -204.2597 -68.10443 52.12683 -161.0794 -56.25823 56.00805 -136.0774 -51.4611 51.66886 -136.0774 -55.80027 52.00094 -136.0774 -56.13235 58.99602 -136.0733 -54.44908 54.65684 -136.0749 -58.78826 54.11882 -161.0794 -58.25021 57.90908 -136.0413 -53.36214 57.87704 -136.0424 -53.3301 76.3422 -211.9688 -71.7811 83.71627 -204.2075 -79.16936 77.62249 -121.3794 -73.07167 77.44113 -134.2129 -72.88883 79.37709 -204.2076 -83.50853 72.88114 -134.998 -77.01261 71.017 -161.1564 -66.40895 71.09725 -136.2268 -66.50957 66.73768 -136.2268 -70.86914 67.23567 -136.2268 -71.36713 67.04206 -161.1564 -71.1735 66.65695 -161.1564 -70.78839 70.14656 -204.2372 -74.27798 70.14294 -204.2372 -74.27436 71.99594 -211.9904 -76.12735 74.52198 -204.2212 -69.89237 74.25834 -204.2309 -69.62097 73.05114 -204.2592 -68.37818 72.94087 -204.2594 -68.26467 74.03266 -204.2309 -69.38864 73.27337 -204.2592 -68.60697 73.76555 -204.248 -69.11363 73.5419 -204.248 -68.88341 72.83634 -204.2596 -68.16014 52.21288 -136.0771 -56.34429 52.38415 -161.0794 -56.51554 56.22817 -136.0774 -51.68122 52.16686 -136.0771 -56.29827 54.49255 -136.0626 -58.62397 58.72087 -136.0527 -54.17393 58.50622 -136.0527 -53.95927 57.96001 -161.0794 -53.41305 53.62082 -161.0794 -57.75222 54.15884 -136.0626 -58.29026 54.16703 -136.0626 -58.29845 57.7254 -136.0479 -53.17846 58.00003 -136.038 -53.45309 53.49687 -136.0598 -57.62828 76.45436 -204.0334 -71.89416 76.63813 -203.9449 -72.07939 77.1435 -203.0309 -72.58879 77.04827 -162.0103 -72.49283 77.15142 -162.1428 -72.5968 77.5421 -164.0852 -72.9906 77.54211 -201.5903 -72.9906 77.22307 -134.998 -72.6707 72.86322 -162.4144 -76.99467 72.37375 -135.912 -76.50522 73.20063 -164.0852 -77.33207 73.20063 -180.6834 -77.33206 71.07762 -161.1564 -66.46957 71.02671 -161.1564 -66.41865 71.59526 -136.2268 -67.00757 67.73368 -136.2268 -71.86512 68.23167 -136.2268 -72.36312 67.71033 -161.1564 -71.84177 67.15496 -161.1564 -71.28638 67.65294 -161.1564 -71.78438 70.19764 -204.2372 -74.32907 71.81317 -204.1752 -75.94461 70.21305 -204.2372 -74.34446 70.48437 -204.2372 -74.61579 71.63694 -204.2597 -75.76834 70.64093 -204.2456 -74.77235 71.47814 -204.2574 -75.60958 70.98146 -204.2456 -75.11286 71.13893 -204.2574 -75.27035 72.93561 -204.2594 -68.2594 74.56649 -204.2212 -69.93819 74.52343 -204.2212 -69.89389 72.8638 -204.2596 -68.18759 52.38414 -136.0771 -56.51555 56.72333 -161.0794 -52.17637 52.62483 -161.0794 -56.75622 56.72333 -136.0769 -52.17638 56.50605 -136.0769 -51.9591 58.49803 -136.0527 -53.95108 57.46201 -161.0794 -52.91505 53.12282 -161.0794 -57.25422 53.80366 -136.0539 -57.93508 53.99551 -136.0539 -58.12693 57.54592 -136.0479 -52.99898 58.22449 -136.038 -53.67754 53.66084 -136.0539 -57.79226 53.16284 -136.0598 -57.29426 71.99594 -204.0875 -76.12735 72.29304 -203.9449 -76.42446 73.20063 -201.5903 -77.33206 72.80043 -203.0309 -76.93185 76.43289 -204.0437 -71.87271 76.91587 -161.841 -72.36046 76.71573 -135.912 -72.16326 71.99591 -136.0933 -76.12738 72.28717 -161.4761 -76.41862 71.99592 -161.3329 -76.12738 72.80838 -162.1428 -76.93983 71.73688 -161.1564 -67.12883 72.08081 -136.2268 -67.49314 71.5247 -161.1564 -66.91665 72.09336 -136.2268 -67.50544 72.59626 -136.2268 -67.99855 68.15093 -161.1564 -72.28238 68.43013 -136.2268 -72.56159 68.43014 -161.1564 -72.56159 71.8641 -204.1507 -75.99552 74.74361 -204.2212 -70.11785 76.34175 -204.0874 -71.78155 75.98997 -204.2597 -71.41532 74.7516 -204.2212 -70.12615 75.72435 -204.2557 -71.1388 75.01399 -204.2356 -70.3993 75.50199 -204.2557 -70.90731 75.23829 -204.2356 -70.6328 72.88592 -204.2595 -68.20971 74.59252 -204.2212 -69.965 52.49897 -136.0771 -56.63039 56.72622 -136.0769 -52.17927 56.96401 -161.0794 -52.41705 57.50203 -136.0479 -52.95509 71.96696 -204.1014 -76.09838 76.381 -204.0686 -71.8208 76.63059 -161.4761 -72.07521 76.59028 -161.4563 -72.03491 71.71765 -136.2268 -75.84912 71.80953 -161.2413 -75.94097 72.0255 -161.1564 -67.41184 72.33909 -161.1564 -67.71932 72.52839 -161.1564 -67.90494 72.81034 -161.1564 -68.18141 72.79667 -136.2268 -68.19507 68.56653 -136.2268 -72.69799 69.10831 -161.1565 -73.23976 68.64894 -161.1565 -72.78038 71.91536 -204.1261 -76.04679 74.70101 -204.2212 -70.07349 74.69419 -204.2212 -70.06666 52.99773 -136.0702 -57.12914 52.66485 -136.0702 -56.79626 56.88349 -136.0704 -52.33655 57.22548 -136.0654 -52.67853 53.14093 -136.0612 -57.27235 76.3379 -136.0933 -71.7854 76.33934 -161.3329 -71.78398 71.47509 -161.1565 -75.60655 71.21965 -136.2244 -75.35111 71.55477 -136.2244 -75.68624 71.63691 -161.1565 -75.76836 72.8204 -136.2268 -68.21879 72.82624 -161.1564 -68.19731 68.72966 -136.2266 -72.86112 69.06456 -136.2266 -73.19602 69.44247 -161.1565 -73.57392 69.14693 -161.1565 -73.27838 57.00404 -136.0654 -52.45709 76.06523 -136.2268 -71.50154 75.58068 -161.1564 -70.99421 75.98754 -161.1564 -71.41777 75.79576 -136.2228 -71.221 71.14112 -161.1565 -75.27256 70.72164 -136.2124 -74.85311 71.05812 -136.2124 -75.18959 73.01103 -161.1564 -68.38211 73.0962 -136.2263 -68.49459 73.31845 -136.2263 -68.71685 69.22766 -136.2198 -73.35913 69.5633 -136.2198 -73.69477 69.77714 -161.1565 -73.90858 69.64492 -161.1565 -73.77637 75.64347 -136.2228 -71.06246 75.29788 -161.1564 -70.69982 75.49954 -161.1564 -70.90975 75.57588 -136.2228 -70.99488 70.80718 -161.1565 -74.93862 70.22365 -136.2038 -74.35511 70.56106 -136.2038 -74.69252 71.13891 -161.1565 -75.27037 75.30303 -136.2023 -70.72206 75.07788 -136.2023 -70.49689 73.15995 -161.1564 -68.53102 73.02913 -161.1564 -68.40019 73.5942 -136.2149 -68.9926 73.81771 -136.2149 -69.21611 70.06243 -136.2096 -74.1939 70.11201 -161.1565 -74.24346 69.72566 -136.2096 -73.85711 75.25258 -161.1564 -70.65452 70.64093 -161.1565 -74.77236 70.21303 -161.1565 -74.34449 70.21302 -136.2041 -74.34449 74.80664 -136.1878 -70.22566 74.57987 -136.1878 -69.9989 73.49436 -161.1564 -68.86544 73.87059 -136.2116 -69.26898 74.08895 -136.1976 -69.49382 74.31127 -136.1976 -69.72268 70.14292 -161.1565 -74.27437 74.56925 -136.1882 -69.98828 74.57779 -161.1564 -69.97973 75.00568 -161.1564 -70.40763 73.52976 -161.1564 -68.90084 73.52713 -161.1564 -68.8982 74.10949 -161.1564 -69.49765 74.40491 -161.1564 -69.80175 74.5087 -161.1564 -69.90861 74.01794 -161.1564 -69.40338 -83.80677 -94.36756 -79.18653 -79.46759 -94.36756 -83.52571 -79.4676 -203.2194 -83.52558 -83.80678 -203.2194 -79.1864 -82.97851 -88.9235 -78.35828 -78.63933 -88.9235 -82.69746 -78.73265 -207.7786 -82.79063 -83.07183 -207.7786 -78.45145 -81.12641 -86.51499 -76.50617 -76.78722 -86.51499 -80.84535 -76.80372 -210.7702 -80.8617 -81.1429 -210.7702 -76.52252 -78.70768 -86.01941 -74.08747 -74.3685 -86.01942 -78.42665 -75.18339 -163.6405 -79.24144 -75.18341 -200.9758 -79.2414 -74.36853 -211.6882 -78.42652 -78.70771 -211.6882 -74.08734 -79.52259 -200.9758 -74.90222 -79.52257 -163.6405 -74.90226 -78.73386 -92.84191 -74.11363 -78.70768 -92.83531 -74.08747 -72.58561 -86.01942 -76.64376 -76.92479 -86.01941 -72.30458 -74.39468 -92.84192 -78.45281 -74.3685 -92.83531 -78.42665 -74.97811 -202.5395 -79.03611 -74.95205 -161.7733 -79.0101 -76.92481 -211.6882 -72.30445 -72.58563 -211.6882 -76.64363 -78.77851 -203.5656 -74.15815 -78.70771 -203.5984 -74.08734 -74.43933 -203.5656 -78.49733 -74.36853 -203.5984 -78.42652 -79.29123 -161.7733 -74.67092 -79.31729 -202.5395 -74.69693 -78.65223 -92.82138 -74.03202 -79.25119 -93.66799 -74.63096 -78.05828 -92.67193 -73.43804 -78.54611 -92.79467 -73.92588 -70.80272 -86.01942 -74.86087 -75.1419 -86.01941 -70.52169 -73.7191 -92.67195 -77.77722 -74.20693 -92.79467 -78.26506 -74.31306 -92.82138 -78.3712 -74.91201 -93.668 -78.97014 -74.43473 -160.9472 -78.49277 -75.14192 -211.6882 -70.52156 -70.80274 -211.6882 -74.86074 -76.92481 -203.8805 -72.30445 -72.58563 -203.8805 -76.64363 -78.09832 -203.8805 -73.47795 -73.75914 -203.8805 -77.81713 -78.77391 -160.9472 -74.15359 -78.6071 -92.81002 -73.98686 -79.48254 -95.53527 -74.8623 -74.26792 -92.81002 -78.32605 -77.56027 -92.67193 -72.94005 -76.76615 -92.67193 -72.14591 -73.35901 -86.01941 -68.7388 -69.01983 -86.01941 -73.07798 -70.96138 -92.67195 -75.01953 -73.22109 -92.67195 -77.27923 -75.14336 -95.53527 -79.20148 -75.14337 -132.8705 -79.20144 -74.36851 -160.9305 -78.42656 -69.01985 -211.6882 -73.07785 -73.35903 -211.6882 -68.73867 -70.80274 -203.8805 -74.86074 -77.10232 -203.8805 -72.48196 -77.60031 -203.8805 -72.97995 -73.26113 -203.8805 -77.31913 -72.76314 -203.8805 -76.82114 -72.26514 -203.8805 -76.32315 -71.76715 -203.8805 -75.82514 -78.70769 -160.9305 -74.08738 -79.48255 -132.8705 -74.86226 -77.06227 -92.67193 -72.44205 -76.92479 -92.67193 -72.30458 -76.56427 -92.67193 -71.94406 -76.06628 -92.67193 -71.44606 -76.85195 -92.67193 -72.23175 -76.80764 -92.67193 -72.18743 -75.00614 -92.67193 -70.38594 -67.23693 -86.01941 -71.29509 -71.57611 -86.0194 -66.95591 -69.17848 -92.67193 -73.23664 -71.22911 -92.67195 -75.28724 -71.7271 -92.67195 -75.78524 -70.88854 -92.67195 -74.94668 -72.72309 -92.67195 -76.78123 -72.58561 -92.67195 -76.64376 -74.93808 -134.4342 -78.99617 -71.57614 -211.6882 -66.95578 -67.23696 -211.6882 -71.29496 -75.11033 -203.8805 -70.48997 -75.14192 -203.8805 -70.52156 -70.77115 -203.8805 -74.82915 -76.10633 -203.8805 -71.48596 -76.60433 -203.8805 -71.98397 -71.26914 -203.8805 -75.32714 -73.75912 -160.7772 -77.81717 -79.27726 -134.4342 -74.65699 -75.56829 -92.67193 -70.94806 -72.22509 -92.67195 -76.28324 -74.57228 -92.67193 -69.95207 -74.07429 -92.67193 -69.45407 -75.07028 -92.67193 -70.45006 -75.09477 -92.67193 -70.47455 -73.0783 -92.67193 -68.45808 -73.20035 -92.67193 -68.58013 -69.79322 -86.0194 -65.17302 -65.45404 -86.01941 -69.5122 -67.37417 -92.67193 -71.43231 -69.23711 -92.67193 -73.29525 -69.73511 -92.67193 -73.79325 -69.17568 -92.67193 -73.23381 -75.1419 -92.67193 -70.52169 -70.80272 -92.67195 -74.86087 -74.39929 -135.4603 -78.45737 -65.45407 -211.6882 -69.51206 -69.79325 -211.6882 -65.17288 -71.57614 -203.856 -66.95578 -73.35903 -203.8786 -68.73867 -68.94197 -203.8802 -72.99997 -69.01985 -203.8802 -73.07785 -75.60832 -203.8805 -70.98797 -74.11434 -203.8805 -69.49398 -74.61233 -203.8805 -69.99198 -70.27315 -203.8805 -74.33116 -69.77516 -203.8805 -73.83316 -74.36851 -135.4746 -78.42659 -73.96385 -135.6619 -78.02194 -78.0983 -160.7772 -73.47799 -78.73847 -135.4603 -74.11819 -73.57629 -92.67193 -68.95607 -73.35901 -92.67193 -68.7388 -70.2331 -92.67195 -74.29125 -70.7311 -92.67195 -74.78924 -73.20465 -92.67193 -68.58442 -69.01983 -92.67193 -73.07798 -69.04273 -92.67193 -73.10087 -72.5803 -92.67193 -67.96009 -72.0823 -92.67193 -67.46208 -70.58831 -92.67192 -65.9681 -69.95925 -92.98114 -65.33905 -63.67115 -86.01941 -67.72931 -68.01033 -86.0194 -63.39012 -66.24913 -92.67193 -70.30728 -65.62007 -92.98114 -69.67823 -67.74312 -92.67193 -71.80126 -68.24112 -92.67193 -72.29927 -67.28554 -92.67193 -71.34368 -73.3376 -92.67193 -68.71737 -69.13137 -92.67193 -73.1895 -68.01036 -211.6882 -63.38999 -63.67116 -211.6882 -67.72917 -67.23696 -203.866 -71.29496 -72.89385 -203.8686 -68.27349 -71.62435 -203.856 -67.004 -73.39309 -203.88 -68.77275 -69.44001 -203.8805 -73.498 -69.27716 -203.8802 -73.33516 -73.89115 -203.8805 -69.27079 -73.7191 -135.7752 -77.77719 -78.30303 -135.6619 -73.68276 -78.05828 -135.7752 -73.43801 -77.60031 -160.7772 -72.98001 -73.26113 -160.7772 -77.31919 -78.70769 -135.4746 -74.08741 -73.24897 -92.67193 -68.62874 -68.73912 -92.67193 -72.79726 -71.58432 -92.67192 -66.96409 -69.93805 -92.99156 -65.31784 -71.57611 -92.67192 -66.9559 -71.08631 -92.67192 -66.46609 -69.41685 -93.65829 -64.79664 -69.79322 -93.17682 -65.17301 -66.22743 -86.0194 -61.60724 -61.88825 -86.0194 -65.94643 -65.07767 -93.6583 -69.13582 -65.45404 -93.17683 -69.51219 -65.59887 -92.99157 -69.65702 -66.74713 -92.67193 -70.80527 -67.23693 -92.67193 -71.29508 -67.24514 -92.67193 -71.30327 -61.88827 -211.6882 -65.94629 -66.22745 -211.6882 -61.6071 -69.46485 -202.6517 -64.8445 -69.79325 -203.2432 -65.17289 -65.12567 -202.6517 -69.18368 -65.45407 -203.2432 -69.51207 -71.12635 -203.8764 -66.506 -71.39847 -203.856 -66.77812 -66.78717 -203.8781 -70.84518 -66.94844 -203.866 -71.00643 -71.89487 -203.8415 -67.27452 -72.39395 -203.8513 -67.77359 -73.11834 -203.8686 -68.498 -73.61634 -203.88 -68.99598 -68.44323 -203.8735 -72.50125 -67.28517 -203.866 -71.34318 -73.63148 -135.7752 -77.68956 -77.97066 -135.7752 -73.35038 -77.10231 -160.7772 -72.482 -72.76313 -160.7772 -76.82118 -69.87205 -93.07598 -65.25184 -69.81079 -93.15435 -65.19058 -69.0246 -95.60067 -64.40438 -64.44454 -86.0194 -59.82434 -60.10536 -86.0194 -64.16353 -65.47161 -93.15435 -69.52976 -64.68542 -95.60068 -68.74356 -65.57884 -93.01721 -69.63698 -60.10538 -211.6882 -64.16339 -64.44456 -211.6882 -59.82421 -69.97224 -203.5656 -65.35189 -69.06465 -201.211 -64.4443 -65.63306 -203.5656 -69.69107 -64.72547 -201.211 -68.78348 -70.62836 -203.8805 -66.00801 -70.90272 -203.8764 -66.28237 -66.28918 -203.8805 -70.34719 -66.45175 -203.8781 -70.50978 -72.12236 -203.8415 -67.50199 -72.62034 -203.8513 -68 -67.44548 -203.8574 -71.50348 -68.77916 -203.8735 -72.83718 -68.28116 -203.8632 -72.33917 -67.94411 -203.8632 -72.00212 -77.56028 -135.7752 -72.94001 -73.2211 -135.7752 -77.27919 -72.58562 -160.7772 -76.64367 -69.02462 -133.1058 -64.40435 -62.66165 -86.0194 -58.04146 -58.32247 -86.0194 -62.38064 -64.72546 -163.7059 -68.78353 -69.06464 -163.7059 -64.44435 -65.53287 -93.07598 -69.59102 -64.68544 -133.1058 -68.74353 -58.32249 -211.6882 -62.3805 -67.78318 -203.8574 -71.84117 -77.52108 -135.7752 -72.90081 -73.1819 -135.7752 -77.23999 -72.26514 -160.7772 -76.32319 -76.9248 -160.7772 -72.30449 -69.45688 -161.7635 -64.8366 -62.91969 -104.2076 -58.29947 -62.78314 -94.58259 -58.16293 -60.87875 -86.0194 -56.25857 -56.53958 -86.0194 -60.59775 -58.34917 -93.81748 -62.40732 -58.32247 -93.77484 -62.38063 -58.58051 -95.68474 -62.63867 -58.58052 -133.02 -62.63862 -65.1177 -161.7635 -69.17578 -58.32249 -202.8708 -62.38051 -58.45597 -202.6166 -62.514 -58.37523 -134.5837 -62.43334 -58.32248 -134.6842 -62.38059 -58.32248 -161.6788 -62.38056 -58.42991 -161.8504 -62.48798 -58.66126 -201.0529 -62.71929 -58.66125 -163.7176 -62.71933 -62.66256 -211.6855 -58.04042 -77.06228 -135.7752 -72.442 -72.7231 -135.7752 -76.78118 -72.58562 -135.7752 -76.6437 -71.98935 -135.7752 -76.04743 -71.72711 -135.7752 -75.78519 -76.60431 -160.7772 -71.984 -65.08563 -134.5464 -69.14373 -69.42481 -134.5464 -64.80455 -62.9199 -133.02 -58.29924 -62.91969 -95.68473 -58.29948 -62.68838 -93.81747 -58.06809 -60.97531 -92.82141 -56.35501 -54.75669 -86.0194 -58.81486 -59.09586 -86.0194 -54.47568 -56.53958 -92.82141 -60.59774 -57.83184 -92.99137 -61.88999 -62.71473 -134.5837 -58.09384 -57.83644 -135.6098 -61.89455 -57.9997 -161.1634 -62.05777 -58.26683 -202.9768 -62.32485 -56.53959 -211.6882 -60.59761 -62.6625 -202.8708 -58.04049 -62.79592 -202.6166 -58.17405 -62.662 -134.6842 -58.04106 -62.76958 -161.8504 -58.14831 -62.6622 -161.6788 -58.04083 -63.00109 -201.0529 -58.37945 -63.00082 -163.7176 -58.37976 -76.9248 -135.7752 -72.30452 -72.2251 -135.7752 -76.28318 -71.76715 -160.7772 -75.82519 -71.44461 -135.7752 -75.50268 -76.38005 -135.7752 -71.75978 -76.56428 -135.7752 -71.944 -76.10633 -160.7772 -71.48601 -65.45405 -135.21 -69.51216 -69.79323 -161.3333 -65.17295 -69.79323 -135.21 -65.17298 -62.6617 -93.77484 -58.04139 -60.87988 -92.82141 -56.25744 -61.49547 -92.82141 -56.87517 -60.99747 -92.82141 -56.37717 -59.19354 -92.82141 -54.5711 -57.31297 -86.0194 -52.69279 -52.97379 -86.0194 -57.03197 -56.65825 -92.82141 -60.71641 -57.15624 -92.82141 -61.2144 -62.17106 -92.99137 -57.55076 -65.45405 -161.3333 -69.51213 -57.15625 -135.9247 -61.21435 -57.54117 -160.9308 -61.59925 -57.91258 -161.0243 -61.97066 -58.19062 -203.1219 -62.24865 -56.53959 -203.9576 -60.59762 -56.73899 -203.9576 -60.79702 -58.12389 -203.249 -62.18192 -57.91719 -203.6427 -61.97521 -57.23699 -203.9576 -61.29502 -60.89948 -211.6253 -56.23772 -62.60686 -202.9768 -57.98485 -62.17597 -135.6098 -57.55501 -62.33942 -161.1634 -57.71806 -71.26914 -160.7772 -75.3272 -71.22911 -135.7752 -75.2872 -76.0486 -135.7752 -71.42832 -76.06629 -135.7752 -71.44601 -75.60832 -160.7772 -70.98801 -65.57571 -135.4291 -69.63381 -69.97809 -161.0968 -65.35779 -69.91489 -135.4291 -65.29463 -60.50054 -92.82141 -55.8781 -60.00255 -92.82141 -55.38011 -59.09864 -92.82141 -54.4729 -59.50455 -92.82141 -54.88211 -57.41237 -92.82141 -52.78662 -51.1909 -86.0194 -55.24908 -55.53007 -86.01939 -50.9099 -54.75669 -92.82141 -58.81486 -55.66225 -92.82141 -59.72042 -56.16025 -92.82141 -60.21841 -65.63891 -161.0968 -69.69697 -61.58655 -135.8827 -56.96559 -56.65825 -135.9247 -60.71636 -57.23699 -160.8543 -61.29506 -56.53958 -135.9247 -60.59769 -57.12624 -160.8543 -61.18432 -56.45007 -203.9576 -60.5081 -54.7567 -211.6882 -58.81473 -60.95998 -203.9576 -56.30215 -62.26044 -203.6427 -57.63195 -62.54073 -203.1027 -57.91873 -61.09539 -203.9576 -56.44061 -61.58786 -203.9576 -56.94414 -62.25229 -161.0243 -57.63094 -61.94233 -160.9463 -57.32098 -70.80273 -160.7772 -74.86078 -70.80273 -135.7752 -74.86081 -75.56829 -135.7752 -70.94802 -75.73818 -135.7752 -71.11791 -65.59302 -135.4603 -69.65113 -70.62835 -160.7772 -66.00805 -69.9322 -135.4603 -65.31195 -59.00821 -92.82141 -54.38246 -58.51021 -92.82141 -53.88447 -55.16426 -92.82141 -59.22242 -57.3167 -92.82141 -52.68906 -57.51422 -92.82141 -52.88847 -55.63047 -92.82141 -51.00283 -53.74718 -86.01939 -49.12701 -49.40801 -86.0194 -53.46619 -52.9738 -92.82141 -57.03197 -54.66625 -92.82141 -58.72442 -66.28917 -160.7772 -70.34723 -61.49679 -135.9247 -56.8738 -61.00434 -135.9247 -56.37026 -56.53959 -160.8543 -60.59767 -56.73899 -160.8543 -60.79706 -56.39926 -203.9576 -60.45729 -56.35767 -203.9576 -60.4157 -55.245 -203.9576 -59.30303 -54.7567 -203.9576 -58.81473 -56.24099 -203.9576 -60.29902 -55.743 -203.9576 -59.80103 -59.14714 -211.5324 -54.42428 -60.89821 -203.9576 -56.23899 -61.58075 -160.8543 -56.95129 -61.30009 -160.8543 -56.66432 -70.73111 -135.7752 -74.78919 -70.23311 -135.7752 -74.2912 -75.14191 -135.7752 -70.52163 -75.07029 -135.7752 -70.45001 -75.14191 -160.7772 -70.5216 -70.77114 -160.7772 -74.8292 -70.34777 -135.6598 -65.7275 -58.01222 -92.82141 -53.38647 -54.16826 -92.82141 -58.22643 -57.01717 -92.82141 -52.38953 -53.17226 -92.82141 -57.23043 -55.5324 -92.82141 -50.90756 -56.02118 -92.82141 -51.39353 -51.96429 -86.01939 -47.34412 -47.62512 -86.0194 -51.68331 -51.1909 -92.82141 -55.24907 -53.8474 -92.91007 -49.22251 -52.17627 -92.82141 -56.23444 -52.67427 -92.82141 -56.73244 -66.00859 -135.6598 -70.06668 -61.08828 -160.8543 -56.44776 -60.8911 -160.8543 -56.24615 -60.88699 -135.9247 -56.25028 -60.50765 -135.9247 -55.87095 -56.16025 -135.9247 -60.21836 -55.66225 -135.9247 -59.72037 -55.95094 -160.8543 -60.00902 -56.24099 -160.8543 -60.29907 -54.747 -203.9576 -58.80503 -54.69666 -203.9576 -58.75469 -52.97381 -211.6882 -57.03184 -60.78937 -203.9576 -56.13016 -59.18418 -203.9576 -54.46891 -59.62397 -203.9576 -54.92406 -60.60287 -203.9576 -55.93714 -60.11342 -203.9576 -55.4306 -60.80935 -203.9576 -56.15013 -70.20646 -135.7752 -74.26454 -74.78944 -135.7752 -70.16916 -74.57229 -135.7752 -69.95202 -75.11032 -160.7772 -70.49002 -70.18544 -135.7752 -74.24353 -66.24914 -135.7752 -70.30723 -70.58832 -135.7752 -65.96805 -71.12635 -160.7772 -66.50605 -66.78717 -160.7772 -70.84523 -53.67026 -92.82141 -57.72843 -56.51917 -92.82141 -51.89153 -55.52178 -92.82141 -50.89694 -55.02378 -92.82141 -50.39895 -49.63627 -86.95127 -45.0161 -45.2971 -86.95127 -49.35528 -49.03603 -93.14102 -53.0942 -49.40801 -92.95819 -53.46619 -53.37561 -93.14102 -48.75462 -53.74758 -92.95819 -49.12661 -51.18028 -92.82141 -55.23845 -51.67828 -92.82141 -55.73645 -54.02778 -92.82141 -49.40295 -60.30269 -160.8543 -55.65774 -60.00966 -135.9247 -55.37295 -60.5925 -160.8543 -55.94755 -55.16426 -135.9247 -59.22237 -55.6168 -160.8543 -59.67488 -55.743 -160.8543 -59.80107 -54.59503 -203.9576 -58.65306 -54.249 -203.9576 -58.30704 -53.25301 -203.9576 -57.31105 -52.97381 -203.9576 -57.03184 -53.75101 -203.9576 -57.80904 -57.38174 -211.4793 -52.6239 -59.14405 -203.9576 -54.42738 -74.12654 -135.7752 -69.50627 -74.61232 -160.7772 -69.99202 -74.11433 -160.7772 -69.49402 -70.27314 -160.7772 -74.3312 -69.85399 -135.7752 -73.91207 -70.97975 -135.7711 -66.35949 -70.86574 -135.7711 -66.24549 -71.57612 -160.7772 -66.95584 -66.3413 -135.7738 -70.39939 -54.52578 -92.82141 -49.90095 -50.68228 -92.82141 -54.74045 -51.96431 -211.6882 -47.34399 -49.61532 -210.7701 -44.99501 -43.43113 -88.89515 -47.48932 -47.77031 -88.89514 -43.15014 -45.27614 -210.7701 -49.33419 -47.62513 -211.6882 -51.68317 -49.68628 -92.82141 -53.74446 -48.51482 -93.80775 -52.573 -52.85444 -93.80774 -48.23337 -60.17044 -160.8543 -55.52549 -59.81247 -135.9247 -55.17576 -54.75669 -135.9247 -58.81481 -55.34335 -160.8543 -59.40143 -51.35933 -203.9386 -55.41737 -51.19091 -211.6882 -55.24894 -51.41821 -203.9407 -55.47625 -52.91406 -203.9576 -56.97209 -51.75902 -203.9407 -55.81705 -52.75501 -203.9573 -56.81305 -51.91731 -203.9507 -55.97534 -52.41603 -203.9573 -56.47406 -52.25702 -203.9507 -56.31505 -59.03645 -203.9576 -54.31978 -58.64028 -203.9576 -53.91575 -57.44627 -203.9576 -52.69805 -57.65408 -203.9576 -52.90997 -58.14718 -203.9576 -53.41286 -59.13499 -203.9576 -54.41832 -73.61634 -160.7772 -68.99604 -69.77515 -160.7772 -73.8332 -66.41478 -135.7728 -70.47287 -66.64061 -135.7728 -70.6987 -67.23694 -160.7772 -71.29502 -71.62435 -160.7772 -67.00405 -50.18428 -92.82141 -54.24246 -47.79882 -208.1055 -43.1785 -52.46373 -133.2552 -47.83955 -46.36601 -94.55817 -41.74584 -42.02684 -94.55818 -46.08502 -43.45964 -208.1055 -47.51769 -48.12258 -133.2552 -52.18071 -48.12258 -95.75012 -52.18075 -52.4623 -95.75012 -47.84102 -59.39493 -160.8543 -54.7229 -59.51683 -135.9247 -54.8698 -59.60636 -160.8543 -54.94171 -60.09581 -160.8543 -55.44825 -59.11625 -135.9247 -54.45524 -54.7567 -160.8543 -58.81478 -55.24499 -160.8543 -59.30308 -51.30841 -203.9367 -55.36645 -55.57299 -211.5578 -50.86686 -59.13435 -203.9576 -54.41768 -57.37762 -203.9575 -52.62803 -57.43095 -203.9576 -52.68243 -69.27716 -160.7772 -73.33522 -74.07431 -135.7752 -69.45402 -69.73513 -135.7752 -73.7932 -69.40303 -135.7752 -73.46112 -71.08631 -135.7711 -66.46604 -66.74713 -135.7728 -70.80522 -67.28517 -160.7772 -71.34323 -72.17327 -135.7391 -67.553 -72.2053 -135.7403 -67.58503 -53.75428 -211.6667 -49.1198 -46.36602 -203.9054 -41.74572 -52.46373 -121.0772 -47.83956 -52.64656 -133.9107 -48.02093 -42.02685 -203.9054 -46.0849 -48.52278 -134.6958 -52.58091 -59.12644 -160.8543 -54.44503 -59.02582 -135.9247 -54.36481 -54.66626 -135.9247 -58.72437 -54.16827 -135.9247 -58.22638 -54.36188 -160.8543 -58.41997 -54.747 -160.8543 -58.80508 -51.2574 -203.935 -55.31544 -51.26102 -203.935 -55.31906 -49.40802 -211.6882 -53.46606 -55.64301 -203.9191 -50.94003 -55.91441 -203.9287 -51.20366 -57.15719 -203.957 -52.41086 -57.27072 -203.9573 -52.52114 -56.14673 -203.9287 -51.42934 -56.92842 -203.957 -52.18863 -56.42174 -203.9458 -51.69646 -56.65197 -203.9458 -51.9201 -57.37525 -203.9575 -52.62567 -69.1911 -135.7749 -73.24919 -69.01984 -160.7772 -73.07791 -73.85417 -135.7752 -69.2339 -69.23712 -135.7749 -73.29521 -66.91143 -135.7605 -70.96952 -71.36148 -135.7505 -66.74121 -71.57612 -135.7505 -66.95586 -72.12234 -160.7772 -67.50204 -67.78316 -160.7772 -71.84122 -67.24514 -135.7605 -71.30323 -67.23694 -135.7605 -71.29504 -72.35694 -135.7457 -67.73667 -72.08232 -135.7358 -67.46205 -67.90711 -135.7576 -71.9652 -53.64122 -203.7312 -49.00765 -53.45599 -203.6427 -48.82387 -52.94659 -202.7287 -48.3185 -53.04256 -161.7082 -48.41376 -52.93859 -161.8406 -48.31062 -52.54479 -163.783 -47.91993 -52.54479 -201.2881 -47.91989 -52.8647 -134.6958 -48.23899 -48.54072 -162.1122 -52.59881 -49.03018 -135.6098 -53.0883 -48.20332 -163.783 -52.26141 -48.20332 -180.3812 -52.26139 -59.06583 -160.8543 -54.38441 -59.11674 -160.8543 -54.43533 -58.52782 -135.9247 -53.86681 -53.67027 -135.9247 -57.72838 -53.17227 -135.9247 -57.23038 -53.69362 -160.8543 -57.7517 -54.249 -160.8543 -58.30709 -53.751 -160.8543 -57.80909 -51.20632 -203.935 -55.26436 -49.59078 -203.873 -53.64882 -51.19091 -203.935 -55.24895 -50.91959 -203.935 -54.97763 -49.76703 -203.9576 -53.82507 -50.76303 -203.9434 -54.82107 -49.92581 -203.9552 -53.98386 -50.42251 -203.9434 -54.48055 -50.26503 -203.9552 -54.32307 -57.27598 -203.9573 -52.52639 -55.59719 -203.919 -50.89553 -55.64151 -203.919 -50.93857 -57.3478 -203.9574 -52.59821 -69.01984 -135.7749 -73.07793 -73.35902 -160.7772 -68.73873 -68.77915 -160.7772 -72.83721 -73.35902 -135.7747 -68.73875 -73.5763 -135.7747 -68.95603 -71.58432 -135.7505 -66.96405 -72.62033 -160.7772 -68.00003 -68.28115 -160.7772 -72.33921 -67.60031 -135.7517 -71.6584 -67.40847 -135.7517 -71.46656 -72.53643 -135.7457 -67.91616 -71.85785 -135.7358 -67.23759 -67.74314 -135.7517 -71.80123 -68.24113 -135.7576 -72.29922 -49.40802 -203.7853 -53.46606 -49.11091 -203.6427 -53.16896 -48.20332 -201.2881 -52.26137 -48.60353 -202.7287 -52.66157 -53.66268 -203.7415 -49.0291 -53.17493 -161.5388 -48.54616 -53.37215 -135.6098 -48.74632 -49.40802 -135.7911 -53.46614 -49.11677 -161.1739 -53.17486 -49.40802 -161.0307 -53.46611 -48.59556 -161.8406 -52.65365 -58.40656 -160.8543 -53.72515 -58.04225 -135.9247 -53.38124 -58.61874 -160.8543 -53.93733 -58.02995 -135.9247 -53.36869 -57.53684 -135.9247 -52.8658 -53.25301 -160.8543 -57.31109 -52.9738 -135.9247 -57.03192 -52.9738 -160.8543 -57.03189 -49.53985 -203.8485 -53.5979 -55.41754 -203.919 -50.71839 -53.75383 -203.7853 -49.12025 -54.12007 -203.9575 -49.47203 -55.40924 -203.919 -50.71041 -54.39658 -203.9535 -49.73765 -55.13607 -203.9334 -50.44801 -54.62807 -203.9535 -49.96002 -54.90258 -203.9334 -50.22372 -57.32567 -203.9574 -52.57608 -55.57038 -203.919 -50.86948 -68.905 -135.7749 -72.96309 -73.35612 -135.7747 -68.73585 -73.11833 -160.7772 -68.49803 -72.58031 -135.7457 -67.96004 -49.437 -203.7992 -53.49504 -53.71459 -203.7664 -49.081 -53.46018 -161.1739 -48.83144 -53.50049 -161.1541 -48.87176 -49.68629 -135.9247 -53.74441 -49.59441 -160.9391 -53.65251 -58.12355 -160.8543 -53.43653 -57.81607 -160.8543 -53.12294 -57.63045 -160.8543 -52.93364 -57.35399 -160.8543 -52.65169 -57.34032 -135.9247 -52.66539 -52.8374 -135.9247 -56.89552 -52.29563 -160.8543 -56.35372 -52.75501 -160.8543 -56.81309 -49.4886 -203.8239 -53.54664 -55.46189 -203.919 -50.76099 -55.46872 -203.919 -50.76782 -68.40625 -135.7681 -72.46434 -68.73912 -135.7681 -72.79721 -73.19886 -135.7682 -68.57859 -72.85686 -135.7632 -68.23659 -68.26304 -135.759 -72.32113 -53.75 -135.7911 -49.12415 -53.75142 -161.0307 -49.1227 -49.92884 -160.8543 -53.98693 -50.18429 -135.9223 -54.24241 -49.84915 -135.9223 -53.90727 -49.76703 -160.8543 -53.82512 -57.3166 -135.9247 -52.64166 -57.33809 -160.8543 -52.63579 -52.67427 -135.9244 -56.73239 -52.33937 -135.9244 -56.39749 -51.96148 -160.8543 -56.01956 -52.25701 -160.8543 -56.3151 -73.0783 -135.7632 -68.45803 -54.03387 -135.9247 -49.39682 -54.54118 -160.8543 -49.88137 -54.11763 -160.8543 -49.47451 -54.31439 -135.9206 -49.6663 -50.26283 -160.8543 -54.32092 -50.68229 -135.9102 -54.7404 -50.34582 -135.9102 -54.40394 -57.1533 -160.8543 -52.451 -57.0408 -135.9242 -52.36586 -56.81854 -135.9242 -52.1436 -52.17627 -135.9176 -56.23439 -51.84064 -135.9176 -55.89875 -51.62681 -160.8543 -55.68489 -51.75902 -160.8543 -55.8171 -54.47294 -135.9206 -49.81859 -54.83557 -160.8543 -50.16415 -54.62564 -160.8543 -49.96249 -54.54051 -135.9206 -49.88617 -50.59677 -160.8543 -54.65485 -51.18028 -135.9016 -55.2384 -50.84287 -135.9016 -54.90098 -50.26503 -160.8543 -54.32312 -54.81334 -135.9002 -50.15901 -55.03851 -135.9002 -50.38418 -57.00438 -160.8543 -52.30208 -57.13519 -160.8543 -52.4329 -56.54279 -135.9128 -51.86786 -56.31928 -135.9128 -51.64436 -51.34151 -135.9074 -55.39962 -51.29193 -160.8543 -55.35002 -51.67828 -135.9074 -55.7364 -54.88087 -160.8543 -50.20946 -50.76302 -160.8543 -54.82111 -51.19091 -160.8543 -55.249 -51.19091 -135.902 -55.24902 -55.30974 -135.8856 -50.65542 -55.5365 -135.8856 -50.88218 -56.66996 -160.8543 -51.96767 -56.26641 -135.9094 -51.59148 -56.04158 -135.8954 -51.3731 -55.81271 -135.8954 -51.15079 -51.26102 -160.8543 -55.31911 -55.54712 -135.886 -50.8928 -55.55566 -160.8543 -50.88424 -55.12777 -160.8543 -50.45635 -56.63457 -160.8543 -51.93227 -56.6372 -160.8543 -51.9349 -56.03776 -160.8543 -51.35254 -55.73364 -160.8543 -51.05713 -55.62679 -160.8543 -50.95333 -56.13201 -160.8543 -51.44409 -47.94122 -94.41591 43.97925 -43.60203 -94.41591 48.31843 -43.60207 -203.2678 48.31848 -47.94125 -203.2678 43.9793 -48.76947 -88.97187 44.8075 -44.43028 -88.97187 49.14668 -44.33702 -207.8269 49.05343 -48.6762 -207.8269 44.71425 -50.62157 -86.56335 46.65961 -46.28239 -86.56335 50.99879 -46.26594 -210.8185 50.98235 -50.60512 -210.8185 46.64318 -53.04029 -86.06778 49.07833 -48.70109 -86.06778 53.41749 -47.88624 -163.6889 52.60265 -47.88625 -201.0241 52.60266 -48.70114 -211.7366 53.41756 -53.04032 -211.7366 49.07837 -52.22544 -201.0241 48.26349 -52.22542 -163.6889 48.26347 -53.01411 -92.89029 49.05215 -53.04029 -92.88368 49.07833 -50.48399 -86.06778 55.20039 -54.82317 -86.06778 50.86121 -48.67492 -92.89029 53.39133 -48.70109 -92.88368 53.4175 -48.09154 -202.5879 52.80796 -48.11759 -161.8217 52.83399 -54.82321 -211.7366 50.86127 -50.48403 -211.7366 55.20044 -52.96951 -203.614 49.00756 -53.04032 -203.6467 49.07837 -48.63033 -203.614 53.34674 -48.70114 -203.6467 53.41755 -52.45677 -161.8217 48.49482 -52.43073 -202.5879 48.46878 -53.09573 -92.86975 49.13377 -52.49678 -93.71636 48.53482 -53.6897 -92.7203 49.72775 -53.20186 -92.84304 49.23991 -52.26688 -86.06777 56.98328 -56.60606 -86.06777 52.64411 -49.35052 -92.7203 54.06692 -48.86268 -92.84304 53.57908 -48.75654 -92.86975 53.47294 -48.15759 -93.71636 52.874 -48.63492 -160.9955 53.35132 -56.6061 -211.7366 52.64416 -52.26692 -211.7366 56.98334 -54.82321 -203.9288 50.86126 -50.48403 -203.9288 55.20044 -53.64971 -203.9288 49.68776 -49.31052 -203.9288 54.02693 -52.9741 -160.9955 49.01215 -53.14087 -92.85839 49.17892 -52.26543 -95.58364 48.30347 -48.80169 -92.85839 53.51809 -54.1877 -92.7203 50.22574 -54.98183 -92.7203 51.01987 -58.38895 -86.06777 54.42699 -54.04977 -86.06777 58.76617 -52.10823 -92.72029 56.82463 -49.84851 -92.7203 54.56492 -47.92625 -95.58364 52.64265 -47.92626 -132.9189 52.64266 -48.70113 -160.9789 53.41753 -54.04981 -211.7366 58.76622 -58.38899 -211.7366 54.42705 -52.26692 -203.9288 56.98333 -54.6457 -203.9288 50.68376 -54.1477 -203.9288 50.18576 -49.80852 -203.9288 54.52493 -50.30652 -203.9288 55.02293 -50.80451 -203.9288 55.52093 -51.30251 -203.9288 56.01892 -53.04031 -160.9789 49.07836 -52.26544 -132.9189 48.30349 -54.68569 -92.7203 50.72374 -54.82317 -92.7203 50.86122 -55.18369 -92.7203 51.22174 -55.68169 -92.7203 51.71973 -54.89601 -92.7203 50.93405 -54.94032 -92.7203 50.97837 -56.74182 -92.72029 52.77986 -55.83266 -86.06777 60.54906 -60.17184 -86.06777 56.20989 -53.89111 -92.72029 58.60752 -51.8405 -92.72029 56.5569 -51.34251 -92.72029 56.05891 -52.18106 -92.72029 56.89746 -50.34651 -92.7203 55.06291 -50.48399 -92.7203 55.20039 -48.13154 -134.4826 52.84795 -60.17189 -211.7366 56.20994 -55.8327 -211.7366 60.54912 -56.63769 -203.9288 52.67574 -56.6061 -203.9288 52.64416 -52.29851 -203.9288 57.01492 -55.6417 -203.9288 51.67975 -55.1437 -203.9288 51.18175 -51.80051 -203.9288 56.51692 -49.31051 -160.8256 54.02692 -52.47073 -134.4826 48.50877 -56.17969 -92.72029 52.21773 -50.84451 -92.7203 55.56091 -57.17568 -92.72029 53.21372 -57.67367 -92.72029 53.71172 -56.67768 -92.72029 52.71573 -56.65319 -92.72029 52.69123 -58.66967 -92.72029 54.70771 -58.54761 -92.72029 54.58565 -61.95473 -86.06777 57.99278 -57.61555 -86.06777 62.33195 -55.69543 -92.72029 60.41183 -53.83249 -92.72029 58.54889 -53.33449 -92.72029 58.05089 -53.89392 -92.72029 58.61033 -56.60606 -92.72029 52.64411 -52.26688 -92.72029 56.98329 -48.67033 -135.5087 53.38674 -57.61559 -211.7366 62.33201 -61.95478 -211.7366 57.99283 -60.17188 -203.9044 56.20994 -58.38899 -203.9269 54.42704 -54.12768 -203.9285 58.84409 -54.04981 -203.9285 58.76622 -56.13969 -203.9288 52.17774 -57.63368 -203.9288 53.67174 -57.13568 -203.9288 53.17374 -52.7965 -203.9288 57.51291 -53.2945 -203.9288 58.01091 -48.70111 -135.5229 53.41752 -49.10577 -135.7103 53.82218 -53.6497 -160.8256 49.68774 -53.00952 -135.5087 49.04756 -58.17167 -92.72029 54.20972 -58.38895 -92.72029 54.427 -52.83649 -92.72029 57.5529 -52.3385 -92.72029 57.0549 -58.54332 -92.72029 54.58137 -54.04977 -92.72029 58.76617 -54.02687 -92.72029 58.74328 -59.16766 -92.72029 55.20571 -59.66566 -92.72029 55.70371 -61.15965 -92.72029 57.1977 -61.7887 -93.02951 57.82675 -59.39844 -86.06777 64.11486 -63.73763 -86.06777 59.77567 -56.82046 -92.72029 61.53687 -57.44952 -93.02951 62.16593 -55.32648 -92.72029 60.04288 -54.82848 -92.72029 59.54488 -55.78406 -92.72029 60.50046 -58.41037 -92.72029 54.44842 -53.93824 -92.72029 58.65465 -63.73767 -211.7366 59.77573 -59.39849 -211.7366 64.11491 -55.8327 -203.9144 60.54911 -58.85417 -203.917 54.89222 -60.12366 -203.9044 56.16172 -58.35492 -203.9283 54.39298 -53.62965 -203.9288 58.34606 -53.79249 -203.9285 58.50891 -57.85687 -203.9288 53.89492 -49.35054 -135.8236 54.06694 -53.44496 -135.7103 49.483 -53.68972 -135.8236 49.72776 -54.14769 -160.8256 50.18574 -49.80851 -160.8256 54.52491 -53.0403 -135.5229 49.07835 -58.499 -92.72029 54.53705 -54.33048 -92.72029 59.04689 -60.16365 -92.72029 56.2017 -61.80991 -93.03994 57.84796 -60.17184 -92.72029 56.20989 -60.66165 -92.72029 56.6997 -62.33111 -93.70668 58.36915 -61.95473 -93.22519 57.99278 -65.52053 -86.06777 61.55856 -61.18133 -86.06777 65.89775 -57.99192 -93.70668 62.70833 -57.61555 -93.22519 62.33196 -57.47072 -93.03994 62.18713 -56.32247 -92.72029 61.03888 -55.83266 -92.72029 60.54907 -55.82447 -92.72029 60.54088 -61.18138 -211.7366 65.8978 -65.52057 -211.7366 61.55862 -62.28316 -202.7 58.32122 -61.95477 -203.2915 57.99283 -57.94398 -202.7 62.66039 -57.61559 -203.2915 62.332 -60.62166 -203.9248 56.65972 -60.34954 -203.9044 56.38759 -56.28248 -203.9264 60.99889 -56.12122 -203.9144 60.83764 -59.85314 -203.8899 55.89119 -59.35407 -203.8997 55.39212 -58.62967 -203.917 54.66773 -58.13168 -203.9283 54.16973 -54.62641 -203.9218 59.34283 -55.78448 -203.9144 60.50089 -49.43814 -135.8236 54.15455 -53.77733 -135.8236 49.81538 -54.64569 -160.8256 50.68374 -50.30651 -160.8256 55.02291 -61.87591 -93.12434 57.91395 -61.93717 -93.20272 57.97521 -62.72336 -95.64904 58.7614 -67.30342 -86.06777 63.34145 -62.96422 -86.06777 67.68064 -57.59798 -93.20272 62.31439 -58.38418 -95.64904 63.10058 -57.49076 -93.06557 62.20717 -62.96426 -211.7366 67.68069 -67.30345 -211.7366 63.34151 -61.77577 -203.614 57.81383 -62.68337 -201.2594 58.72142 -57.43659 -203.614 62.153 -58.34418 -201.2594 63.0606 -61.11965 -203.9288 57.15771 -60.84529 -203.9248 56.88335 -56.78047 -203.9288 61.49689 -56.61789 -203.9264 61.33431 -59.62567 -203.8899 55.66372 -59.12767 -203.8997 55.16572 -55.62417 -203.9058 60.34059 -54.29049 -203.9218 59.0069 -54.78849 -203.9116 59.5049 -55.12554 -203.9116 59.84196 -54.18771 -135.8236 50.22576 -49.84853 -135.8236 54.56493 -50.48402 -160.8256 55.20042 -62.72338 -133.1541 58.76142 -69.08631 -86.06777 65.12435 -64.74713 -86.06777 69.46353 -58.34417 -163.7543 63.06058 -62.68336 -163.7543 58.7214 -57.53672 -93.12434 62.25313 -58.38419 -133.1541 63.1006 -64.74716 -211.7366 69.46358 -55.28648 -203.9058 60.0029 -54.22692 -135.8236 50.26496 -49.88774 -135.8236 54.60414 -50.8045 -160.8256 55.52091 -54.8232 -160.8256 50.86124 -62.29111 -161.8119 58.32915 -68.82827 -104.2559 64.86632 -68.96482 -94.63096 65.00286 -70.86919 -86.06777 66.90724 -66.53001 -86.06777 71.24642 -64.72043 -93.86584 69.43683 -64.74713 -93.82321 69.46353 -64.48908 -95.7331 69.20549 -64.4891 -133.0683 69.20552 -57.95193 -161.8119 62.66833 -64.74716 -202.9192 69.46358 -64.61367 -202.665 69.3301 -64.69438 -134.6321 69.4108 -64.74713 -134.7326 69.46355 -64.74714 -161.7272 69.46356 -64.63971 -161.8987 69.35614 -64.40839 -201.1012 69.1248 -64.40837 -163.766 69.12478 -69.08724 -211.7338 65.1235 -54.68571 -135.8236 50.72375 -50.34653 -135.8236 55.06293 -50.484 -135.8236 55.20041 -51.08028 -135.8236 55.79668 -51.34252 -135.8236 56.05892 -55.14369 -160.8256 51.18173 -57.98398 -134.5947 62.70039 -62.32316 -134.5947 58.36121 -68.82849 -133.0683 64.86613 -68.82826 -95.7331 64.86631 -69.05966 -93.86584 65.09761 -70.77275 -92.86978 66.81068 -68.3129 -86.06777 73.02931 -72.65208 -86.06777 68.69013 -66.53001 -92.86978 71.24642 -65.23777 -93.03974 69.95417 -69.03388 -134.6321 65.0713 -65.23316 -135.6582 69.94958 -65.06993 -161.2118 69.78634 -64.80281 -203.0252 69.51924 -66.53005 -211.7365 71.24647 -69.08718 -202.9192 65.12356 -68.95362 -202.665 64.99015 -69.08666 -134.7326 65.12403 -68.97938 -161.8987 65.01646 -69.08686 -161.7272 65.12384 -68.74822 -201.1012 64.78496 -68.74794 -163.766 64.78521 -54.82319 -135.8236 50.86123 -50.84452 -135.8236 55.56093 -51.3025 -160.8256 56.0189 -51.62502 -135.8236 56.34143 -55.36794 -135.8236 51.40598 -55.18371 -135.8236 51.22175 -55.64168 -160.8256 51.67973 -57.61557 -135.2584 62.33197 -61.95476 -161.3817 57.99281 -61.95475 -135.2584 57.9928 -69.08636 -93.82321 65.12429 -70.87031 -92.86978 66.90612 -70.25259 -92.86978 66.29052 -70.75058 -92.86978 66.78852 -72.55665 -92.86978 68.59246 -74.43497 -86.06777 70.47303 -70.09579 -86.06777 74.81221 -66.41135 -92.86978 71.12775 -65.91336 -92.86978 70.62976 -69.57699 -93.03974 65.61493 -57.61558 -161.3817 62.33198 -65.91337 -135.973 70.62979 -65.52845 -160.9792 70.24488 -65.15705 -161.0726 69.87346 -64.87902 -203.1703 69.59545 -66.53005 -204.0059 71.24647 -66.33065 -204.0059 71.04708 -64.94575 -203.2974 69.66217 -65.15245 -203.6911 69.86888 -65.83265 -204.0059 70.54907 -70.88996 -211.6736 66.88658 -69.14282 -203.0252 65.1792 -69.5727 -135.6582 65.61004 -69.40964 -161.2118 65.44661 -51.80049 -160.8256 56.5169 -51.84052 -135.8236 56.55692 -55.69939 -135.8236 51.73743 -55.6817 -135.8236 51.71975 -56.13968 -160.8256 52.17772 -57.49391 -135.4775 62.21031 -61.7699 -161.1452 57.80795 -61.83309 -135.4775 57.87114 -71.24964 -92.86978 67.28546 -71.74765 -92.86978 67.78344 -72.65486 -92.86978 68.68735 -72.24565 -92.86978 68.28144 -74.34114 -92.86978 70.37362 -71.87868 -86.06776 76.5951 -76.21786 -86.06776 72.25592 -68.3129 -92.86978 73.02931 -67.40734 -92.86978 72.12374 -66.90934 -92.86978 71.62575 -57.43072 -161.1452 62.14713 -70.16213 -135.931 66.19947 -66.41136 -135.973 71.12777 -65.83264 -160.9027 70.54905 -66.53002 -135.973 71.24644 -65.94338 -160.9027 70.65979 -66.61957 -204.0059 71.33599 -68.31295 -211.7365 73.02936 -70.82553 -204.0059 66.82608 -69.49571 -203.6911 65.52561 -69.20894 -203.1511 65.24533 -70.68706 -204.0059 66.69067 -70.18354 -204.0059 66.1982 -69.49678 -161.0726 65.53376 -69.80672 -160.9947 65.84371 -52.26691 -160.8256 56.98331 -52.26689 -135.8236 56.9833 -56.1797 -135.8236 52.21774 -56.00981 -135.8236 52.04785 -57.4766 -135.5087 62.193 -61.11964 -160.8256 57.15769 -61.81578 -135.5087 57.85383 -72.7453 -92.86978 68.77778 -73.2433 -92.86978 69.27578 -67.90534 -92.86978 72.62174 -74.4387 -92.86978 70.46929 -74.23928 -92.86978 70.27178 -76.12493 -92.86977 72.15552 -78.00077 -86.06776 74.03881 -73.66159 -86.06776 78.37799 -70.09579 -92.86978 74.81221 -68.40335 -92.86978 73.11975 -56.78046 -160.8256 61.49687 -70.25392 -135.973 66.28923 -70.75746 -135.973 66.78168 -66.53003 -160.9026 71.24645 -66.33065 -160.9026 71.04705 -66.67038 -204.0059 71.38681 -66.71197 -204.0059 71.42839 -67.82464 -204.0059 72.54106 -68.31295 -204.0059 73.02936 -66.82865 -204.0059 71.54507 -67.32664 -204.0059 72.04306 -72.70339 -211.5808 68.63891 -70.88867 -204.0059 66.88784 -70.1764 -160.9027 66.20529 -70.46338 -160.9027 66.48594 -52.33851 -135.8236 57.05492 -52.83651 -135.8236 57.55291 -56.60608 -135.8236 52.64413 -56.6777 -135.8236 52.71574 -56.60609 -160.8256 52.64414 -52.2985 -160.8256 57.0149 -61.40022 -135.7081 57.43827 -73.74128 -92.86978 69.77378 -68.90133 -92.86978 73.61774 -74.73823 -92.86978 70.76882 -69.89733 -92.86978 74.61373 -76.22019 -92.86977 72.25358 -75.73423 -92.86978 71.76481 -79.78366 -86.06776 75.8217 -75.44448 -86.06776 80.16088 -71.87868 -92.86977 76.5951 -77.90525 -92.95845 73.93859 -70.89332 -92.86978 75.60974 -70.39532 -92.86978 75.11174 -57.06104 -135.7081 61.77745 -70.67994 -160.9027 66.69775 -70.88156 -160.9027 66.89493 -70.87744 -135.973 66.89904 -71.25677 -135.973 67.27836 -66.90937 -135.973 71.62577 -67.40736 -135.973 72.12377 -67.11869 -160.9026 71.8351 -66.82863 -160.9026 71.54505 -68.32263 -204.0059 73.03907 -68.37298 -204.0059 73.0894 -70.09584 -211.7365 74.81225 -70.99752 -204.0059 66.99668 -72.65876 -204.0059 68.60189 -72.20362 -204.0059 68.16209 -71.19053 -204.0059 67.18318 -71.69707 -204.0059 67.67263 -70.97754 -204.0059 66.97671 -52.86316 -135.8236 57.57957 -56.95855 -135.8236 52.99659 -57.17569 -135.8236 53.21374 -56.63768 -160.8256 52.67572 -52.88418 -135.8236 57.60059 -56.82048 -135.8236 61.53689 -61.15966 -135.8236 57.19771 -60.62165 -160.8256 56.6597 -56.28247 -160.8256 60.99887 -69.39933 -92.86978 74.11573 -75.23623 -92.86978 71.26683 -76.23082 -92.86977 72.26422 -76.72882 -92.86977 72.76221 -82.11167 -86.99964 78.14971 -77.77248 -86.99964 82.48889 -74.03356 -93.18939 78.74997 -73.66159 -93.00656 78.37799 -78.37316 -93.18939 74.4104 -78.00115 -93.00656 74.03842 -71.88932 -92.86977 76.60572 -71.39131 -92.86977 76.10771 -77.7248 -92.86977 73.7582 -71.46997 -160.9026 67.48334 -71.75477 -135.973 67.77635 -71.18016 -160.9026 67.19353 -67.90535 -135.973 72.62178 -67.45281 -160.9026 72.16923 -67.32662 -160.9026 72.04304 -68.4746 -204.0059 73.19104 -68.82064 -204.0059 73.53707 -69.81663 -204.0059 74.53305 -70.09584 -204.0059 74.81225 -69.31863 -204.0059 74.03505 -74.50377 -211.5276 70.40431 -72.70029 -204.0059 68.64202 -57.62144 -135.8236 53.65948 -57.13567 -160.8256 53.17372 -57.63367 -160.8256 53.67172 -52.79649 -160.8256 57.51289 -53.21563 -135.8236 57.93204 -60.76823 -135.8195 56.80627 -60.88224 -135.8195 56.92029 -60.17187 -160.8256 56.20992 -56.72832 -135.8222 61.44473 -77.22681 -92.86977 73.2602 -72.38731 -92.86977 77.10372 -79.7837 -211.7365 75.82175 -82.13267 -210.8185 78.17073 -79.63845 -88.94352 84.35485 -83.97763 -88.94352 80.01567 -77.79349 -210.8185 82.50991 -75.44451 -211.7365 80.16093 -73.3833 -92.86977 78.0997 -74.55477 -93.85611 79.27117 -78.89439 -93.85611 74.93155 -71.60222 -160.9026 67.6156 -71.95195 -135.973 67.97354 -68.31291 -135.973 73.02933 -67.72628 -160.9026 72.44269 -71.71031 -203.9869 76.42673 -71.87873 -211.7365 76.59514 -71.65143 -203.9891 76.36785 -70.15558 -204.0059 74.872 -71.31063 -203.9891 76.02704 -70.31462 -204.0056 75.03105 -71.15233 -203.9991 75.86875 -70.65361 -204.0056 75.37004 -70.81262 -203.9991 75.52904 -72.80789 -204.0059 68.74961 -73.21192 -204.0059 69.14576 -74.42963 -204.0059 70.33979 -74.2177 -204.0059 70.13198 -73.71482 -204.0059 69.63887 -72.70935 -204.0059 68.65107 -58.13167 -160.8256 54.16971 -53.29449 -160.8256 58.01089 -56.65484 -135.8211 61.37125 -56.429 -135.8211 61.14541 -55.83269 -160.8256 60.54909 -60.12365 -160.8256 56.1617 -72.8853 -92.86977 77.60171 -83.94918 -208.1539 79.98723 -79.28818 -133.3036 75.32228 -85.38192 -94.60655 81.41997 -81.04274 -94.60654 85.75915 -79.61 -208.1539 84.32641 -74.94702 -133.3036 79.66344 -74.94701 -95.7985 79.66342 -79.28675 -95.7985 75.32369 -72.4048 -160.9026 68.3911 -72.25792 -135.973 68.26921 -72.18599 -160.9026 68.17967 -71.67945 -160.9026 67.69023 -72.67248 -135.973 68.66976 -68.31292 -160.9026 73.02935 -67.82463 -160.9026 72.54104 -71.76123 -203.9851 76.47764 -76.26081 -211.6062 72.21306 -72.70999 -204.0059 68.65171 -74.49964 -204.0058 70.40843 -74.44525 -204.0059 70.35511 -53.79248 -160.8256 58.50889 -57.67369 -135.8236 53.71173 -53.3345 -135.8236 58.05091 -53.66659 -135.8236 58.38299 -60.66167 -135.8195 56.69972 -56.32249 -135.8211 61.03889 -55.78447 -160.8256 60.50087 -59.57473 -135.7875 55.61278 -59.54269 -135.7886 55.58073 -78.00788 -211.7151 74.03178 -85.38196 -203.9537 81.42002 -79.28817 -121.1255 75.32228 -79.1068 -133.9591 75.13946 -81.04278 -203.9537 85.7592 -74.54682 -134.7442 79.26323 -72.68267 -160.9026 68.65959 -72.76292 -135.973 68.7602 -68.40335 -135.973 73.11976 -68.90135 -135.973 73.61776 -68.70774 -160.9026 73.42415 -68.32262 -160.9026 73.03903 -71.81224 -203.9834 76.52867 -71.80861 -203.9834 76.52503 -73.66162 -211.7365 78.37804 -76.18764 -203.9674 72.14305 -75.92401 -203.9771 71.87165 -74.71681 -204.0054 70.62886 -74.60654 -204.0056 70.51533 -75.69834 -203.9771 71.63932 -74.93904 -204.0054 70.85763 -75.43122 -203.9942 71.36431 -75.20758 -203.9942 71.13408 -74.50201 -204.0058 70.4108 -53.87853 -135.8233 58.59494 -54.0498 -160.8256 58.7662 -57.89381 -135.8236 53.93186 -53.8325 -135.8233 58.54891 -56.1582 -135.8088 60.8746 -60.38651 -135.7989 56.42456 -60.17186 -135.7989 56.20991 -59.62565 -160.8256 55.6637 -55.28647 -160.8256 60.00288 -55.82448 -135.8088 60.54089 -55.83267 -135.8088 60.54908 -59.39104 -135.7941 55.42909 -59.66567 -135.7842 55.70372 -55.16252 -135.806 59.87892 -78.12002 -203.7796 74.14482 -78.30381 -203.691 74.33007 -78.80918 -202.7771 74.83947 -78.71395 -161.7565 74.74346 -78.81708 -161.889 74.84743 -79.20777 -163.8314 75.24124 -79.20779 -201.3365 75.24125 -78.88874 -134.7442 74.92131 -74.5289 -162.1606 79.24533 -74.03943 -135.6582 78.75585 -74.86631 -163.8314 79.58271 -74.86631 -180.4296 79.58272 -72.7433 -160.9026 68.7202 -72.69237 -160.9026 68.66928 -73.26091 -135.973 69.2582 -69.39934 -135.973 74.11576 -69.89734 -135.973 74.61376 -69.376 -160.9026 74.09243 -68.82062 -160.9026 73.53704 -69.31861 -160.9026 74.03503 -71.86331 -203.9834 76.57975 -73.47885 -203.9213 78.19528 -71.87873 -203.9834 76.59514 -72.15005 -203.9834 76.86647 -73.30261 -204.0059 78.01903 -72.30661 -203.9918 77.02304 -73.14382 -204.0036 77.86024 -72.64712 -203.9918 77.36354 -72.80461 -204.0036 77.52103 -74.60128 -204.0056 70.51007 -76.23215 -203.9674 72.18886 -76.1891 -203.9674 72.14454 -74.52947 -204.0058 70.43827 -54.04978 -135.8233 58.76619 -58.38898 -160.8256 54.42702 -54.29048 -160.8256 59.00688 -58.38897 -135.823 54.42701 -58.17169 -135.823 54.20973 -60.16367 -135.7989 56.20172 -59.12766 -160.8256 55.1657 -54.78847 -160.8256 59.50488 -55.46931 -135.8001 60.18571 -55.66117 -135.8001 60.37757 -59.21156 -135.7941 55.24961 -59.89013 -135.7842 55.92818 -55.32649 -135.8001 60.0429 -54.82849 -135.806 59.5449 -73.66162 -203.8336 78.37804 -73.95874 -203.691 78.67515 -74.86631 -201.3365 79.58274 -74.46611 -202.7771 79.18254 -78.09858 -203.7899 74.12339 -78.58155 -161.5872 74.61109 -78.3814 -135.6582 74.41387 -73.66159 -135.8395 78.37802 -73.95285 -161.2223 78.66928 -73.6616 -161.0791 78.37802 -74.47406 -161.889 79.19046 -73.40255 -160.9026 69.37947 -73.74649 -135.973 69.74376 -73.19037 -160.9026 69.16728 -73.75904 -135.973 69.75608 -74.26192 -135.973 70.24919 -69.81661 -160.9026 74.53302 -70.0958 -135.973 74.81222 -70.09581 -160.9026 74.81224 -73.5298 -203.8969 78.24621 -76.40929 -203.9674 72.36851 -78.00743 -203.8336 74.03222 -77.65565 -204.0059 73.666 -76.41727 -203.9674 72.37683 -77.39003 -204.0019 73.38948 -76.67967 -203.9817 72.64998 -77.16765 -204.0019 73.15798 -76.90396 -203.9818 72.88348 -74.55159 -204.0057 70.46038 -76.25819 -203.9674 72.21567 -54.16462 -135.8233 58.88103 -58.39186 -135.823 54.42991 -58.62966 -160.8256 54.66771 -59.16768 -135.7941 55.20572 -73.63264 -203.8475 78.34906 -78.04668 -203.8148 74.07147 -78.29627 -161.2223 74.32585 -78.25595 -161.2024 74.28554 -73.38331 -135.973 78.09973 -73.4752 -160.9875 78.19161 -73.69117 -160.9026 69.66247 -74.00476 -160.9026 69.96997 -74.19406 -160.9026 70.15557 -74.47602 -160.9026 70.43203 -74.46234 -135.973 70.44569 -70.2322 -135.973 74.94863 -70.77398 -160.9026 75.4904 -70.31462 -160.9026 75.03102 -73.58104 -203.8723 78.29747 -76.36668 -203.9674 72.32416 -76.35987 -203.9674 72.31734 -54.66337 -135.8164 59.37978 -54.3305 -135.8164 59.0469 -58.54914 -135.8166 54.58718 -58.89112 -135.8116 54.92917 -54.80658 -135.8074 59.52298 -78.00358 -135.8395 74.03602 -78.00502 -161.0791 74.03461 -73.14076 -160.9026 77.85718 -72.88533 -135.9706 77.60173 -73.22045 -135.9706 77.93687 -73.30259 -160.9026 78.01902 -74.48606 -135.973 70.46942 -74.49192 -160.9026 70.44793 -70.39533 -135.9727 75.11175 -70.73023 -135.9727 75.44665 -71.10814 -160.9026 75.82456 -70.8126 -160.9026 75.52902 -58.66968 -135.8116 54.70773 -77.73091 -135.973 73.75214 -77.24633 -160.9026 73.24485 -77.6532 -160.9026 73.66841 -77.46142 -135.969 73.47161 -72.8068 -160.9026 77.5232 -72.38732 -135.9585 77.10374 -72.72378 -135.9585 77.4402 -74.67671 -160.9026 70.63273 -74.76187 -135.9725 70.74522 -74.98413 -135.9725 70.96747 -70.89334 -135.966 75.60975 -71.22898 -135.966 75.94539 -71.44281 -160.9026 76.15924 -71.3106 -160.9026 76.02703 -77.30912 -135.969 73.31307 -76.96356 -160.9026 72.95046 -77.16521 -160.9026 73.1604 -77.24155 -135.969 73.2455 -72.47285 -160.9026 77.18927 -71.88933 -135.9499 76.60575 -72.22673 -135.9499 76.94316 -72.80459 -160.9026 77.52101 -76.96872 -135.9485 72.97268 -76.74356 -135.9485 72.74752 -74.82563 -160.9026 70.78165 -74.6948 -160.9026 70.65084 -75.25986 -135.9611 71.24324 -75.48336 -135.9611 71.46673 -71.72811 -135.9557 76.44451 -71.77768 -160.9026 76.49411 -71.39133 -135.9557 76.10774 -76.91825 -160.9026 72.90516 -72.30661 -160.9026 77.02301 -71.8787 -160.9026 76.59513 -71.8787 -135.9503 76.59511 -76.47232 -135.934 72.47628 -76.24555 -135.934 72.24952 -75.16004 -160.9026 71.11606 -75.53624 -135.9578 71.51961 -75.75463 -135.9438 71.74443 -75.97694 -135.9438 71.97332 -71.8086 -160.9026 76.52501 -76.23492 -135.9344 72.23889 -76.24346 -160.9026 72.23036 -76.67135 -160.9026 72.65826 -75.19544 -160.9026 71.15146 -75.19281 -160.9026 71.14882 -75.77516 -160.9026 71.74827 -76.07057 -160.9026 72.05239 -76.17437 -160.9026 72.15924 -75.6836 -160.9026 71.65402 83.94159 -94.36551 79.72142 79.60241 -94.3655 84.0606 79.60247 -203.2174 84.06068 83.94165 -203.2174 79.7215 83.11334 -88.92147 78.89315 78.77416 -88.92147 83.23233 78.86753 -207.7765 83.32573 83.20671 -207.7765 78.98655 81.26123 -86.51295 77.04106 76.92205 -86.51295 81.38024 76.9386 -210.7681 81.39682 81.27778 -210.7681 77.05764 78.84251 -86.01739 74.62232 74.50334 -86.01738 78.96151 75.31826 -163.6385 79.77646 75.31829 -200.9738 79.77649 74.50341 -211.6862 78.96161 78.8426 -211.6862 74.62244 79.65747 -200.9738 75.43731 79.65744 -163.6385 75.43728 78.8687 -92.8399 74.64852 78.84252 -92.83329 74.62233 72.72045 -86.01739 77.17861 77.05963 -86.01739 72.83943 74.52952 -92.83989 78.9877 74.50335 -92.83329 78.96152 75.11299 -202.5375 79.57119 75.08692 -161.7713 79.54512 77.0597 -211.6862 72.83954 72.72052 -211.6862 77.17872 78.91339 -203.5636 74.69323 78.84259 -203.5964 74.62243 74.57421 -203.5636 79.03241 74.50341 -203.5964 78.9616 79.4261 -161.7713 75.20594 79.45217 -202.5375 75.23201 78.78707 -92.81936 74.56689 79.38603 -93.66597 75.16584 78.1931 -92.66991 73.97291 78.68094 -92.79265 74.46075 70.93756 -86.01739 75.39572 75.27674 -86.01739 71.05654 73.85392 -92.66991 78.31209 74.34176 -92.79264 78.79993 74.44789 -92.81935 78.90607 75.04685 -93.66596 79.50502 74.56958 -160.9452 79.02778 75.27681 -211.6862 71.05665 70.93763 -211.6862 75.39583 77.0597 -203.8785 72.83954 72.72052 -203.8785 77.17872 78.2332 -203.8785 74.01305 73.89402 -203.8785 78.35223 78.90876 -160.9452 74.6886 78.74195 -92.80799 74.52175 79.61738 -95.53324 75.39719 74.40277 -92.80799 78.86093 77.69511 -92.66991 73.47492 76.90098 -92.66991 72.6808 73.49385 -86.01741 69.27365 69.15467 -86.01739 73.61283 71.09622 -92.66991 75.55438 73.35593 -92.66991 77.8141 75.2782 -95.53324 79.73637 75.27822 -132.8685 79.7364 74.50337 -160.9285 78.96157 69.15474 -211.6862 73.61294 73.49392 -211.6862 69.27376 70.93762 -203.8785 75.39583 77.2372 -203.8785 73.01705 77.7352 -203.8785 73.51506 73.39602 -203.8785 77.85424 72.89802 -203.8785 77.35623 72.40003 -203.8785 76.85823 71.90203 -203.8785 76.36024 78.84255 -160.9285 74.62239 79.6174 -132.8685 75.39722 77.19712 -92.66991 72.97692 77.05963 -92.66991 72.83944 76.69911 -92.66991 72.47892 76.20112 -92.66991 71.98093 76.9868 -92.66991 72.7666 76.94248 -92.66991 72.72229 75.14099 -92.66991 70.92079 67.37178 -86.01741 71.82994 71.71096 -86.01741 67.49076 69.31333 -92.66991 73.77149 71.36396 -92.66991 75.82212 71.86194 -92.66991 76.32011 71.02339 -92.66991 75.48155 72.85794 -92.66991 77.3161 72.72045 -92.66991 77.17862 75.07293 -134.4322 79.53112 71.71103 -211.6862 67.49087 67.37185 -211.6862 71.83005 75.24522 -203.8785 71.02507 75.2768 -203.8785 71.05665 70.90604 -203.8785 75.36425 76.24121 -203.8785 72.02106 76.73921 -203.8785 72.51905 71.40404 -203.8785 75.86225 73.894 -160.7752 78.35219 79.41211 -134.4322 75.19194 75.70312 -92.66991 71.48294 72.35993 -92.66991 76.8181 74.70713 -92.66991 70.48694 74.20914 -92.66992 69.98894 75.20513 -92.66991 70.98493 75.22962 -92.66991 71.00942 73.21315 -92.66992 68.99295 73.3352 -92.66992 69.11502 69.92807 -86.01741 65.70787 65.58889 -86.01741 70.04705 67.50902 -92.66992 71.96718 69.37197 -92.66991 73.83012 69.86996 -92.66991 74.32812 69.31052 -92.66991 73.76869 75.27674 -92.66991 71.05655 70.93756 -92.66991 75.39573 74.53415 -135.4583 78.99234 65.58896 -211.6862 70.04716 69.92814 -211.6862 65.70798 71.71102 -203.854 67.49087 73.49391 -203.8765 69.27376 69.07688 -203.8782 73.53507 69.15473 -203.8782 73.61294 75.74322 -203.8785 71.52307 74.24922 -203.8785 70.02907 74.74723 -203.8785 70.52706 70.40805 -203.8785 74.86624 69.91004 -203.8785 74.36825 74.50336 -135.4726 78.96155 74.0987 -135.6599 78.5569 78.23318 -160.7752 74.01301 78.87333 -135.4583 74.65316 73.71115 -92.66992 69.49094 73.49385 -92.66992 69.27366 70.36795 -92.66991 74.82612 70.86595 -92.66991 75.32411 73.3395 -92.66992 69.1193 69.15467 -92.66991 73.61284 69.17757 -92.66991 73.63574 72.71515 -92.66992 68.49495 72.21715 -92.66992 67.99695 70.72316 -92.66992 66.50296 70.0941 -92.97912 65.8739 63.80599 -86.01741 68.26416 68.14517 -86.01741 63.92498 66.38398 -92.66992 70.84214 65.75492 -92.97912 70.21308 67.87797 -92.66992 72.33613 68.37597 -92.66992 72.83413 67.42039 -92.66992 71.87855 73.47245 -92.66992 69.25225 69.26622 -92.66991 73.72438 68.14525 -211.6862 63.92509 63.80606 -211.6862 68.26426 67.37184 -203.864 71.83005 73.02874 -203.8666 68.80858 71.75925 -203.854 67.5391 73.52799 -203.8779 69.30783 69.5749 -203.8785 74.0331 69.41205 -203.8782 73.87025 74.02604 -203.8785 69.80588 73.85395 -135.7732 78.31214 78.43788 -135.6599 74.21772 78.19313 -135.7732 73.97296 77.73519 -160.7752 73.51502 73.39601 -160.7752 77.8542 78.84254 -135.4726 74.62237 73.38381 -92.66992 69.16361 68.87397 -92.66992 73.33213 71.71916 -92.66992 67.49897 70.0729 -92.98957 65.8527 71.71096 -92.66992 67.49077 71.22116 -92.66992 67.00096 69.5517 -93.65629 65.3315 69.92807 -93.17481 65.70788 66.36228 -86.01741 62.14208 62.0231 -86.01741 66.48126 65.21252 -93.65629 69.67068 65.58889 -93.17481 70.04706 65.73372 -92.98957 70.19188 66.88198 -92.66992 71.34014 67.37178 -92.66992 71.82995 67.37998 -92.66992 71.83815 62.02317 -211.6862 66.48137 66.36236 -211.6862 62.1422 69.59975 -202.6497 65.37958 69.92813 -203.2412 65.70797 65.26057 -202.6497 69.71876 65.58895 -203.2412 70.04715 71.26126 -203.8744 67.04109 71.53337 -203.854 67.31321 66.92208 -203.876 71.38027 67.08332 -203.864 71.54152 72.02977 -203.8395 67.80961 72.52884 -203.8493 68.30868 73.25325 -203.8666 69.03308 73.75123 -203.8779 69.53107 68.57814 -203.8714 73.03633 67.42007 -203.864 71.87828 73.76633 -135.7732 78.22451 78.10551 -135.7732 73.88533 77.23719 -160.7752 73.01702 72.89801 -160.7752 77.3562 70.0069 -93.07397 65.78672 69.94564 -93.15233 65.72544 69.15945 -95.59867 64.93925 64.57939 -86.01741 60.35919 60.24021 -86.01741 64.69837 65.60646 -93.15233 70.06462 64.82027 -95.59867 69.27843 65.71368 -93.0152 70.17184 60.24028 -211.6862 64.69848 64.57947 -211.6862 60.35931 70.10713 -203.5636 65.88697 69.19954 -201.209 64.97937 65.76795 -203.5636 70.22615 64.86036 -201.209 69.31855 70.76325 -203.8785 66.54309 71.03762 -203.8744 66.81745 66.42407 -203.8785 70.88227 66.58665 -203.876 71.04486 72.25724 -203.8395 68.03708 72.75524 -203.8493 68.53508 67.58037 -203.8554 72.03857 68.91407 -203.8714 73.37226 68.41606 -203.8612 72.87426 68.07901 -203.8612 72.5372 77.69513 -135.7732 73.47496 73.35595 -135.7732 77.81414 72.72049 -160.7752 77.17868 69.15947 -133.1038 64.93928 62.79651 -86.01741 58.5763 58.45733 -86.01741 62.91548 64.86034 -163.7039 69.31852 69.19952 -163.7039 64.97934 65.66773 -93.07397 70.1259 64.82029 -133.1038 69.27846 58.4574 -211.6862 62.91559 67.91806 -203.8554 72.37626 77.65592 -135.7732 73.43576 73.31674 -135.7732 77.77494 72.4 -160.7752 76.8582 77.05967 -160.7752 72.8395 69.59177 -161.7616 65.37159 63.05456 -104.2056 58.83436 62.918 -94.58061 58.6978 61.01362 -86.01741 56.79341 56.67444 -86.01741 61.13259 58.48402 -93.81549 62.94218 58.45733 -93.77285 62.91549 58.71537 -95.68275 63.17353 58.71539 -133.018 63.17356 65.25259 -161.7616 69.71077 58.45739 -202.8688 62.91558 58.59088 -202.6146 63.04907 58.51011 -134.5817 62.96828 58.45735 -134.6822 62.91552 58.45737 -161.6768 62.91555 58.5648 -161.8484 63.02297 58.79616 -201.0509 63.25435 58.79614 -163.7156 63.25432 62.79748 -211.6835 58.57551 77.19715 -135.7732 72.97696 72.85797 -135.7732 77.31614 72.72048 -135.7732 77.17866 72.12421 -135.7732 76.58239 71.86196 -135.7732 76.32015 76.73918 -160.7752 72.51902 65.2205 -134.5444 69.67868 69.55968 -134.5444 65.3395 63.05478 -133.018 58.83418 63.05455 -95.68276 58.83435 62.82325 -93.81549 58.60296 61.11017 -92.81943 56.88987 54.89155 -86.01741 59.3497 59.23073 -86.01741 55.01052 56.67444 -92.81943 61.13259 57.96669 -92.98938 62.42485 62.84961 -134.5817 58.62878 57.97132 -135.6078 62.42949 58.13459 -161.1614 62.59276 58.40174 -202.9748 62.85993 56.67451 -211.6862 61.1327 62.79741 -202.8688 58.57557 62.93083 -202.6146 58.70913 62.79689 -134.6822 58.576 62.90446 -161.8484 58.68331 62.79709 -161.6768 58.57583 63.13599 -201.0509 58.91452 63.13571 -163.7156 58.91476 77.05966 -135.7732 72.83948 72.35997 -135.7732 76.81814 71.90201 -160.7752 76.3602 71.57946 -135.7732 76.03765 76.51491 -135.7732 72.29473 76.69915 -135.7732 72.47896 76.24119 -160.7752 72.02102 65.58892 -135.208 70.0471 69.92811 -161.3313 65.70794 69.9281 -135.208 65.70792 62.79657 -93.77285 58.57625 61.01475 -92.81943 56.79229 61.63033 -92.81943 57.41003 61.13233 -92.81943 56.91203 59.32841 -92.81943 55.10595 57.44784 -86.01742 53.22763 53.10866 -86.01741 57.56681 56.7931 -92.81943 61.25126 57.2911 -92.81943 61.74925 62.30593 -92.98938 58.08562 65.58893 -161.3313 70.04712 57.29112 -135.9227 61.74929 57.67606 -160.9288 62.13423 58.04747 -161.0223 62.50564 58.32553 -203.1199 62.78372 56.6745 -203.9556 61.13269 56.8739 -203.9556 61.33209 58.2588 -203.247 62.71699 58.0521 -203.6407 62.51029 57.3719 -203.9556 61.83009 61.0344 -211.6233 56.77281 62.74177 -202.9748 58.51993 62.31086 -135.6078 58.08996 62.47431 -161.1614 58.25305 71.40402 -160.7752 75.86222 71.36396 -135.7732 75.82215 76.18346 -135.7732 71.96328 76.20114 -135.7732 71.98097 75.7432 -160.7752 71.52304 65.71057 -135.4271 70.16875 70.11297 -161.0948 65.89279 70.04975 -135.4271 65.82957 60.63541 -92.81943 56.41296 60.13742 -92.81943 55.91497 59.23351 -92.81943 55.00775 59.63942 -92.81943 55.41697 57.54724 -92.81945 53.32147 51.32577 -86.01742 55.78392 55.66495 -86.01742 51.44474 54.89155 -92.81943 59.3497 55.79711 -92.81943 60.25526 56.2951 -92.81943 60.75326 65.77379 -161.0948 70.23197 61.72144 -135.8807 57.50053 56.79313 -135.9227 61.2513 57.37187 -160.8523 61.83005 56.67446 -135.9227 61.13263 57.26113 -160.8523 61.71931 56.58498 -203.9556 61.04317 54.89162 -211.6862 59.34981 61.0949 -203.9556 56.83723 62.39536 -203.6407 58.16703 62.67565 -203.1007 58.45381 61.23031 -203.9556 56.97568 61.72277 -203.9556 57.47922 62.38719 -161.0223 58.16593 62.07722 -160.9443 57.85597 70.9376 -160.7752 75.39579 70.93759 -135.7732 75.39577 75.70315 -135.7732 71.48297 75.87304 -135.7732 71.65287 65.72789 -135.4583 70.18608 70.76323 -160.7752 66.54306 70.06707 -135.4583 65.8469 59.14308 -92.81943 54.91731 58.64508 -92.81943 54.41932 55.29912 -92.81943 59.75727 57.45157 -92.81945 53.22391 57.64909 -92.81945 53.42332 55.76535 -92.81945 51.53768 53.88206 -86.01742 49.66184 49.54288 -86.01742 54.00102 53.10866 -92.81943 57.56681 54.80112 -92.81943 59.25926 66.42405 -160.7752 70.88224 61.63167 -135.9227 57.40874 61.13922 -135.9227 56.90521 56.67448 -160.8523 61.13265 56.87387 -160.8523 61.33205 56.53417 -203.9556 60.99235 56.49258 -203.9556 60.95077 55.37991 -203.9556 59.8381 54.89161 -203.9556 59.3498 56.3759 -203.9556 60.83409 55.87791 -203.9556 60.3361 59.28207 -211.5304 54.95936 61.03313 -203.9556 56.77407 61.71564 -160.8523 57.48629 61.43498 -160.8523 57.19932 70.86597 -135.7732 75.32415 70.36798 -135.7732 74.82616 75.27677 -135.7732 71.05659 75.20515 -135.7732 70.98497 75.27678 -160.7752 71.05661 70.90602 -160.7752 75.36421 70.48262 -135.6578 66.26245 58.14709 -92.81945 53.92132 54.30312 -92.81943 58.76127 57.15205 -92.81945 52.92438 53.30713 -92.81943 57.76528 55.66728 -92.81945 51.44242 56.15605 -92.81945 51.92838 52.09917 -86.01744 47.87895 47.75998 -86.01742 52.21813 51.32577 -92.81945 55.78392 53.98228 -92.90811 49.75736 52.31113 -92.81945 56.76928 52.80913 -92.81945 57.26728 66.14344 -135.6578 70.60163 61.22318 -160.8523 56.98275 61.026 -160.8523 56.78113 61.02188 -135.9227 56.78522 60.64254 -135.9227 56.40589 56.29513 -135.9227 60.75329 55.79713 -135.9227 60.2553 56.08583 -160.8523 60.544 56.37588 -160.8523 60.83406 54.88191 -203.9556 59.3401 54.83157 -203.9556 59.28976 53.10873 -211.6862 57.56692 60.92429 -203.9556 56.66523 59.3191 -203.9556 55.00398 59.75888 -203.9556 55.45912 60.73779 -203.9556 56.47222 60.24834 -203.9556 55.96567 60.94426 -203.9556 56.68521 70.34132 -135.7732 74.7995 74.9243 -135.7732 70.70412 74.70716 -135.7732 70.48698 75.2452 -160.7752 71.02503 70.3203 -135.7732 74.77848 66.38401 -135.7732 70.84218 70.72319 -135.7732 66.503 71.26123 -160.7752 67.04106 66.92205 -160.7752 71.38024 53.80513 -92.81943 58.26328 56.65404 -92.81945 52.42638 55.65665 -92.81945 51.43178 55.15865 -92.81945 50.93379 49.77115 -86.94931 45.55093 45.43197 -86.94931 49.89012 49.17089 -93.13906 53.62904 49.54288 -92.95621 54.00102 53.51048 -93.13906 49.28946 53.88245 -92.95621 49.66146 51.31514 -92.81945 55.77329 51.81314 -92.81945 56.27129 54.16266 -92.81945 49.9378 60.43759 -160.8523 56.19273 60.14455 -135.9227 55.9079 60.7274 -160.8523 56.48254 55.29914 -135.9227 59.7573 55.7517 -160.8523 60.20987 55.87789 -160.8523 60.33606 54.72994 -203.9556 59.18813 54.38391 -203.9556 58.8421 53.38793 -203.9556 57.84611 53.10872 -203.9556 57.56691 53.88592 -203.9556 58.34411 57.51666 -211.4773 53.15898 59.27897 -203.9556 54.96245 74.26142 -135.7732 70.04122 74.7472 -160.7752 70.52703 74.2492 -160.7752 70.02903 70.40802 -160.7752 74.86621 69.98886 -135.7732 74.44703 71.11462 -135.7691 66.89444 71.00061 -135.7691 66.78044 71.711 -160.7752 67.49083 66.47616 -135.7718 70.93434 54.66066 -92.81945 50.4358 50.81715 -92.81945 55.27529 52.09923 -211.6862 47.87906 49.75026 -210.7682 45.53008 43.566 -88.89319 48.02415 47.90519 -88.89319 43.68497 45.41107 -210.7682 49.86926 47.76005 -211.6862 52.21824 49.82115 -92.81945 54.2793 48.64969 -93.80577 53.10784 52.98931 -93.80578 48.76823 60.30534 -160.8523 56.06048 59.94736 -135.9227 55.71071 54.89157 -135.9227 59.34974 55.47824 -160.8523 59.93641 51.49425 -203.9366 55.95243 51.32583 -211.6862 55.78403 51.55313 -203.9387 56.01131 53.04897 -203.9556 57.50716 51.89393 -203.9387 56.35212 52.88993 -203.9553 57.34811 52.05222 -203.9487 56.51041 52.55094 -203.9553 57.00913 52.39193 -203.9487 56.85012 59.17137 -203.9556 54.85485 58.7752 -203.9556 54.45083 57.58119 -203.9556 53.23311 57.789 -203.9556 53.44505 58.2821 -203.9556 53.94794 59.26991 -203.9556 54.95339 73.75122 -160.7752 69.53103 69.91002 -160.7752 74.36821 66.54965 -135.7707 71.00782 66.77548 -135.7707 71.23366 67.37182 -160.7752 71.83001 71.75923 -160.7752 67.53905 50.31915 -92.81945 54.7773 47.93375 -208.1035 43.71357 52.59862 -133.2533 48.37448 46.5009 -94.55623 42.28068 42.16172 -94.55623 46.61986 43.59457 -208.1035 48.05275 48.25747 -133.2533 52.71563 48.25745 -95.74816 52.71559 52.59717 -95.74816 48.37587 59.52983 -160.8523 55.25789 59.65171 -135.9227 55.40474 59.74126 -160.8523 55.47669 60.23071 -160.8523 55.98324 59.25114 -135.9227 54.99018 54.89159 -160.8523 59.34976 55.37989 -160.8523 59.83806 51.44333 -203.9348 55.90152 55.70792 -211.5559 51.40195 59.26927 -203.9556 54.95275 57.51254 -203.9555 53.1631 57.56587 -203.9556 53.2175 69.41204 -160.7752 73.87021 74.20916 -135.7732 69.98899 69.86998 -135.7732 74.32817 69.53789 -135.7732 73.99607 71.22119 -135.7691 67.00099 66.88201 -135.7707 71.34017 67.42005 -160.7752 71.87823 72.30812 -135.7371 68.08793 72.34016 -135.7382 68.11998 53.8892 -211.6647 49.65488 46.50096 -203.9034 42.28078 52.59862 -121.0752 48.37446 52.78145 -133.9088 48.55586 42.16178 -203.9034 46.61995 48.65768 -134.6939 53.11583 59.26134 -160.8523 54.98002 59.1607 -135.9227 54.89974 54.80114 -135.9227 59.2593 54.30315 -135.9227 58.76131 54.49678 -160.8523 58.95495 54.88189 -160.8523 59.34006 51.39231 -203.9331 55.8505 51.39594 -203.9331 55.85412 49.54294 -211.6862 54.00113 55.77794 -203.9171 51.4751 56.04933 -203.9267 51.73873 57.29212 -203.9551 52.94593 57.40565 -203.9553 53.05621 56.28166 -203.9267 51.9644 57.06334 -203.9551 52.7237 56.55666 -203.9438 52.23153 56.78689 -203.9438 52.45516 57.51018 -203.9555 53.16074 69.32595 -135.7729 73.78414 69.15471 -160.7752 73.6129 73.98903 -135.7732 69.76885 69.37198 -135.7729 73.83016 67.04628 -135.7584 71.50447 71.49633 -135.7485 67.27616 71.71099 -135.7485 67.49081 72.25722 -160.7752 68.03704 67.91804 -160.7752 72.37622 67.38 -135.7584 71.83818 67.37181 -135.7584 71.82999 72.4918 -135.7437 68.27162 72.21717 -135.7338 67.99699 68.04196 -135.7556 72.50016 53.77616 -203.7292 49.54272 53.59091 -203.6407 49.35894 53.08151 -202.7268 48.85357 53.17747 -161.7062 48.94875 53.0735 -161.8387 48.84561 52.67969 -163.781 48.45492 52.67972 -201.2862 48.45495 52.9996 -134.6939 48.77391 48.67562 -162.1103 53.13378 49.16506 -135.6078 53.62322 48.33822 -163.781 52.79639 48.33823 -180.3792 52.7964 59.20072 -160.8523 54.9194 59.25164 -160.8523 54.97032 58.66271 -135.9227 54.40175 53.80515 -135.9227 58.26332 53.30715 -135.9227 57.76531 53.82851 -160.8523 58.28668 54.38389 -160.8523 58.84207 53.8859 -160.8523 58.34407 51.34124 -203.9331 55.79943 49.7257 -203.871 54.18388 51.32583 -203.9331 55.78402 51.05451 -203.9331 55.51269 49.90195 -203.9556 54.36013 50.89794 -203.9414 55.35613 50.06073 -203.9532 54.51892 50.55744 -203.9414 55.01562 50.39994 -203.9532 54.85813 57.4109 -203.9553 53.06147 55.73212 -203.917 51.4306 55.77643 -203.917 51.47364 57.48272 -203.9554 53.13328 69.1547 -135.7729 73.61288 73.49389 -160.7752 69.27372 68.91403 -160.7752 73.37223 73.49388 -135.7727 69.2737 73.71116 -135.7727 69.49098 71.71918 -135.7485 67.499 72.75521 -160.7752 68.53504 68.41603 -160.7752 72.87422 67.73519 -135.7497 72.19335 67.54331 -135.7497 72.00151 72.67128 -135.7437 68.45111 71.99272 -135.7338 67.77254 67.87799 -135.7497 72.33617 68.37599 -135.7556 72.83417 49.54294 -203.7833 54.00112 49.24583 -203.6407 53.70402 48.33824 -201.2862 52.79642 48.73844 -202.7268 53.19663 53.79761 -203.7395 49.56417 53.30984 -161.5368 49.08115 53.50704 -135.6078 49.28125 49.5429 -135.7891 54.00106 49.25167 -161.1719 53.70983 49.54292 -161.0288 54.00109 48.73047 -161.8387 53.18864 58.54146 -160.8523 54.26014 58.17714 -135.9227 53.91618 58.75364 -160.8523 54.47232 58.16484 -135.9227 53.90363 57.67173 -135.9227 53.40074 53.3879 -160.8523 57.84608 53.10868 -135.9227 57.56685 53.1087 -160.8523 57.56687 49.67477 -203.8466 54.13295 55.55247 -203.9171 51.25346 53.88876 -203.7833 49.65531 54.25499 -203.9556 50.0071 55.54415 -203.9171 51.24547 54.5315 -203.9516 50.27272 55.271 -203.9314 50.98308 54.76299 -203.9516 50.49509 55.0375 -203.9314 50.75878 57.46059 -203.9554 53.11116 55.7053 -203.9171 51.40455 69.03987 -135.7729 73.49804 73.49098 -135.7727 69.2708 73.25321 -160.7752 69.03305 72.71517 -135.7437 68.49499 49.57192 -203.7972 54.0301 53.84951 -203.7644 49.61606 53.59508 -161.1719 49.36642 53.63539 -161.1521 49.40673 49.82117 -135.9227 54.27933 49.72931 -160.9371 54.18748 58.25846 -160.8523 53.97152 57.95097 -160.8523 53.65793 57.76535 -160.8523 53.46863 57.48889 -160.8523 53.18668 57.47521 -135.9227 53.20032 52.97229 -135.9227 57.43045 52.43053 -160.8523 56.8887 52.8899 -160.8523 57.34807 49.62351 -203.822 54.08169 55.59682 -203.9171 51.29606 55.60364 -203.9171 51.30289 68.54111 -135.766 72.99929 68.874 -135.766 73.33216 73.33371 -135.7662 69.11354 72.99172 -135.7612 68.77156 68.39791 -135.757 72.85608 53.88489 -135.7891 49.65908 53.88632 -161.0288 49.65768 50.06375 -160.8523 54.52191 50.31917 -135.9203 54.77733 49.98404 -135.9203 54.4422 49.90193 -160.8523 54.36009 57.45149 -135.9227 53.1766 57.47299 -160.8523 53.17078 52.80916 -135.9224 57.26732 52.47425 -135.9224 56.93242 52.09637 -160.8523 56.55454 52.39191 -160.8523 56.85008 73.21318 -135.7612 68.99298 54.16876 -135.9227 49.93175 54.67609 -160.8523 50.41635 54.25254 -160.8523 50.00949 54.44929 -135.9186 50.20123 50.39773 -160.8523 54.8559 50.81717 -135.9082 55.27533 50.48071 -135.9082 54.93887 57.2882 -160.8523 52.98598 57.17569 -135.9222 52.9008 56.95343 -135.9222 52.67854 52.31116 -135.9157 56.76932 51.97552 -135.9157 56.43368 51.7617 -160.8523 56.21987 51.89391 -160.8523 56.35208 54.60783 -135.9186 50.35353 54.97047 -160.8523 50.69914 54.76054 -160.8523 50.49747 54.67541 -135.9186 50.42111 50.73166 -160.8523 55.18983 51.31516 -135.8996 55.77333 50.97776 -135.8996 55.43592 50.39992 -160.8523 54.85809 54.94824 -135.8982 50.69395 55.1734 -135.8982 50.9191 57.13928 -160.8523 52.83707 57.27009 -160.8523 52.96789 56.67768 -135.9108 52.4028 56.45417 -135.9108 52.17929 51.47639 -135.9054 55.93456 51.42683 -160.8523 55.885 51.81316 -135.9054 56.27132 55.01577 -160.8523 50.74444 50.89792 -160.8523 55.35609 51.32581 -160.8523 55.78398 51.32579 -135.9 55.78396 55.44462 -135.8837 51.19035 55.67139 -135.8837 51.41711 56.80486 -160.8523 52.50265 56.4013 -135.9075 52.12642 56.17647 -135.8935 51.90803 55.94761 -135.8935 51.68572 51.39591 -160.8523 55.85408 55.68202 -135.8841 51.42774 55.69057 -160.8523 51.41923 55.26268 -160.8523 50.99134 56.76947 -160.8523 52.46726 56.7721 -160.8523 52.46989 56.17266 -160.8523 51.88753 55.86854 -160.8523 51.59211 55.76169 -160.8523 51.48831 56.26691 -160.8523 51.97908</float_array> + <technique_common> + <accessor source="#Kinton-mesh-positions-array" count="15336" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Kinton-mesh-normals"> + <float_array id="Kinton-mesh-normals-array" count="94986">0.7071068 0 0.7071068 0 -1 0 0.7071078 0 0.7071058 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071078 -1.59541e-7 0.7071059 0.7071051 0 0.7071086 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071051 0 0.7071086 0 -1 0 0.7071068 0 -0.7071068 0.7071068 -1.75137e-6 0.7071068 0 1 0 0.7071071 -2.50967e-6 0.7071064 0.7071079 -8.75875e-7 0.7071056 -0.7071064 0 0.7071071 0 1 0 0.7071068 0 0.7071068 0 -1 0 0.7071061 0 0.7071074 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071051 0 0.7071086 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071051 0 0.7071086 0 -1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071064 0 0.7071071 0 1 0 0.7071068 0 0.7071068 0 -1 0 0.7071061 0 0.7071074 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071051 0 0.7071086 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071051 0 0.7071086 0 -1 0 0.7071057 5.31746e-6 -0.7071078 0 1 0 -0.7071064 0 0.7071071 0 1 0 0.7071068 0 0.7071068 0 -1 0 0.7071061 0 0.7071074 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071051 0 0.7071086 0.7071057 0 -0.7071078 0.7071073 -8.99132e-7 0.7071063 0.7071085 -8.99131e-7 0.7071051 0 -1 0 0.7071057 0 -0.7071078 0 1 0 -0.7071064 0 0.7071071 0 1 0 0.7071073 0 0.7071064 0 -1 0 0.7071061 0 0.7071074 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071064 0 0.7071071 0 1 0 0.7071073 0 0.7071064 0 -1 0 0.7071061 0 0.7071074 -0.7071064 0 0.7071071 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071064 0 0.7071071 0 1 0 0.7071073 0 0.7071064 0 -1 0 0.7071061 0 0.7071074 -0.7071057 0 0.7071078 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071073 0 0.7071063 0 -1 0 0.7071061 0 0.7071074 -0.7071057 0 0.7071078 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071063 0.7071043 0 0.7071092 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071073 0 0.7071064 0 -1 0 0.7071061 0 0.7071074 -0.7071057 0 0.7071078 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071073 0 0.7071064 0 -1 0 0.7071061 0 0.7071074 -0.7071057 0 0.7071078 0.7071061 0 0.7071074 0.7071044 0 0.7071093 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0 -1 0 0.7071064 0 -0.7071071 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071073 -1.03379e-6 0.7071063 0 -1 0 0.7071061 0 0.7071074 -0.7071057 0 0.7071078 0.7071044 0 0.7071093 0.7071055 0 -0.7071082 0.7071073 0 0.7071064 0.7071044 0 0.7071093 0.7071036 7.06432e-6 0.70711 0 -1 0 0.7071055 0 -0.7071082 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071065 3.10137e-6 0.707107 0 -1 0 0.7071081 -5.39479e-6 0.7071055 -0.7071068 -5.3948e-6 0.7071068 0.7071044 0 0.7071093 0.7071055 0 -0.7071082 0.7071053 0 0.7071082 0.7071064 5.72204e-6 0.7071073 0 -1 0 0.7071055 0 -0.7071082 0 1 0 -0.7071057 0 0.7071078 0 1 0 0.7071066 1.36461e-6 0.7071071 0 -1 -2.04847e-7 0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071058 0 0.7071078 0.7071064 0 -0.7071071 0.7071065 1.56826e-6 0.7071071 0.7071077 -3.8147e-7 0.7071059 0.7071067 0 0.7071068 0.7071068 0 0.7071068 0 -1 -2.04847e-7 0.7071065 0 -0.7071071 0.7071065 0 0.707107 0 1 0 0.7071058 0 0.7071077 0.7071065 0 0.707107 0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 0 -1 0 0.7071064 0 -0.7071071 0.7071065 0 0.707107 0 1 0 0.7071058 0 0.7071077 0.7071065 0 0.707107 0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 0 -1 0 0.7071064 0 -0.7071071 0.7071065 0 0.707107 0 1 0 0.7071058 0 0.7071077 0.7071073 -1.3487e-6 0.7071064 0.7071116 -1.34869e-6 0.7071019 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071057 0 0.7071078 0.7071058 0 0.7071077 0.7071065 0 -0.7071071 0 -1 0 0.7071065 0 -0.7071071 0.7071073 0 0.7071064 0 1 0 0.7071058 0 0.7071078 0.7071073 0 0.7071064 0.7071068 0 0.7071068 -0.7071057 0 0.7071078 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 0 -1 0 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0 1 0 0.7071058 0 0.7071077 0.7071073 0 0.7071064 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 0 -1 0 0.7071064 0 -0.7071071 0.7071073 0 0.7071064 0 1 0 0.7071058 0 0.7071077 0.7071073 0 0.7071064 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 0 -1 0 0.7071064 0 -0.7071071 0.7071073 -8.5288e-7 0.7071064 0 1 0 0.7071078 -8.99132e-7 0.7071059 0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0.7071065 0 0.7071071 0.7071057 0 -0.7071078 0 -1 0 0.7071057 0 -0.7071078 0.7071068 0 0.7071068 0 1 0 0.7071064 0 0.7071071 0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0.7071065 0 0.7071071 0.7071068 0 -0.7071068 0 -1 0 0.7071068 0 -0.7071068 0.7071068 -9.3041e-7 0.7071068 0 1 0 0.7071068 0 0.7071068 0.7071067 -1.73002e-7 0.707107 -0.7071068 0 0.7071068 0 1 0 0.7071062 0 0.7071074 -0.7071068 0 0.7071068 0.7071065 -5.51396e-7 0.7071071 0 1 2.35e-7 0 1 0 -0.7071068 0 0.7071068 0.7071088 -8.55488e-6 0.7071048 -0.7036654 0.09853899 0.7036654 0.7071076 -3.21821e-6 0.707106 -0.6765076 0.290985 0.6765096 -0.703665 0.09853106 0.7036671 0.7071083 -7.40037e-6 0.7071053 -0.6237423 0.4710533 0.6237424 -0.676507 0.2909922 0.676507 0.707106 1.1568e-5 0.7071075 -0.5468073 0.6340373 0.5468075 -0.6237422 0.4710533 0.6237424 0.7071071 -4.86973e-6 0.7071065 -0.4483374 0.773297 0.4483363 -0.5468053 0.6340422 0.5468038 0.707107 5.42749e-6 0.7071067 -0.3330871 0.8821035 0.3330863 -0.4483373 0.773297 0.4483363 0.7071184 -8.2444e-5 0.7070952 -0.2057565 0.9567281 0.2057561 0.7071068 0 0.7071068 -0.333087 0.8821035 0.3330863 -0.06967514 0.9951335 0.06967544 -0.2057582 0.9567272 0.2057587 0.09229618 0.9914449 -0.09229606 0.092296 0.9914448 -0.09229606 -0.06967544 0.9951335 0.06967586 0.7071058 0 0.7071077 0.7071064 0 -0.7071071 -1.22609e-7 -1 -1.22609e-7 -1.22609e-7 -1 -1.22609e-7 0.7071064 0 -0.7071071 0.7071068 0 -0.7071068 0.707107 -1.04632e-6 0.7071066 0 1 0 0.7071067 -6.53444e-7 0.7071069 0.7071068 0 -0.7071068 0.7071068 0 0.7071067 0.7071061 0 -0.7071075 0 1 0 0 -1 0 0.7071076 1.07505e-6 -0.7071061 -0.5000007 -0.707107 0.4999992 0 -1 0 -0.7071071 0 0.7071064 -0.5 -0.7071072 0.4999995 0.7071063 8.90097e-7 0.7071073 0 -1 -1.98473e-7 0.7071067 0 0.7071067 -0.7071071 0 0.7071064 -0.7071067 0 0.707107 0 -1 -2.0537e-7 0.7071084 -5.17709e-6 0.7071052 -0.5000002 0.7071067 0.4999999 0.7071064 1.63487e-7 0.7071073 -0.707107 0 0.7071067 0 1 0 -0.5 0.7071065 0.5000005 0.4999998 0.707107 -0.4999998 0 1 0 0.7071065 1.59542e-7 -0.7071071 0.4999997 0.7071068 -0.5000002 0.6123724 -0.5000014 -0.6123715 0.612372 -0.499999 -0.6123738 0.7071058 0 -0.7071078 0.7071076 0 -0.7071061 0.7071076 0 -0.7071061 -0.7071071 0 -0.7071065 -0.7071065 0 -0.707107 -0.7071072 -1.23032e-6 -0.7071064 -0.7071065 5.58249e-7 -0.707107 -0.7071071 -5.66743e-7 -0.7071065 -0.7071078 0 -0.7071058 -0.7071067 0 -0.707107 -0.7071061 1.12197e-6 -0.7071075 -0.7071073 0 -0.7071064 -0.7071074 2.24394e-7 -0.7071062 -0.7071077 0 -0.7071058 -0.7071071 0 -0.7071065 -0.7071065 0 -0.707107 -0.7071065 0 -0.707107 -0.7071071 0 -0.7071065 -0.7071066 7.11773e-7 -0.707107 -0.7071077 0 -0.7071058 -0.7071077 0 -0.7071058 -0.7071071 0 -0.7071065 -0.7071073 0 -0.7071064 -0.7071073 0 -0.7071064 -0.7071071 0 -0.7071065 -0.7070621 5.39514e-6 -0.7071514 -0.7071068 0 -0.7071068 -0.7071071 0 -0.7071065 -0.7071073 0 -0.7071063 -0.7071073 0 -0.7071063 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071071 0 -0.7071065 -0.7071073 0 -0.7071064 -0.7071073 0 -0.7071064 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071071 0 -0.7071065 -0.7071073 0 -0.7071064 -0.7071068 8.99133e-7 -0.7071068 -0.707103 8.99138e-7 -0.7071105 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 1.31809e-6 -0.7071068 -0.7071075 0 -0.7071061 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071041 1.3487e-6 -0.7071095 -0.7071077 0 -0.7071058 -0.7071075 -1.55069e-6 -0.7071061 -0.7071075 0 -0.7071061 -0.7071077 0 -0.7071058 -0.707102 1.05964e-5 -0.7071115 -0.7071058 0 -0.7071078 -0.7071077 0 -0.7071058 -0.7071075 -9.30414e-6 -0.7071061 -0.7071068 0 -0.7071067 -0.7071068 0 -0.7071068 -0.7071058 0 -0.7071078 -0.7071078 0 -0.7071059 -0.7071068 0 -0.7071068 -0.7071061 1.90735e-6 -0.7071076 -0.7071071 7.13269e-7 -0.7071065 -0.7071012 8.11627e-7 -0.7071125 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 1.31809e-6 -0.7071068 -0.7071009 1.34871e-6 -0.7071127 -0.7071068 0 -0.7071068 -0.7071076 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071075 0 -0.7071061 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 1.3487e-6 -0.7071068 -0.7070968 1.34872e-6 -0.7071167 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 -0.7071058 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 1.13533e-6 -0.7071068 -0.7071068 1.17166e-6 -0.7071068 -0.7071069 0 -0.7071067 -0.7071068 9.39e-7 -0.7071068 -0.7071067 1.07896e-6 -0.7071069 -0.7071065 2.18708e-7 -0.7071072 -0.7071083 -7.39099e-6 -0.7071054 -0.7071064 0 -0.7071071 -0.7071076 0 -0.7071061 -0.7071059 2.85693e-6 -0.7071076 -0.7071071 3.60379e-7 -0.7071065 -0.7071053 5.11838e-6 -0.7071083 -0.7071083 -5.13442e-6 -0.7071053 -0.7071071 0 -0.7071064 -0.7071083 -7.39156e-6 -0.7071053 -0.707107 1.07222e-5 -0.7071065 -0.7071075 -4.10542e-6 -0.7071062 0.7071063 0 -0.7071073 0 -1 0 0.7071077 0 -0.7071058 0.7071068 0 0.7071068 0.7071062 0 -0.7071075 0.7071077 1.59541e-7 -0.7071058 0.7071073 0 -0.7071063 -0.7071061 0 -0.7071076 0.7071064 0 -0.7071073 0.7071073 0 -0.7071063 0 -1 0 -0.7071061 0 -0.7071076 0.7071063 -9.30414e-7 -0.7071073 0 1 0 0.7071068 0 -0.7071068 0.7071076 -1.70023e-6 -0.707106 0.7071068 0 0.7071068 0 1 0 0.7071064 0 -0.7071073 0 -1 0 0.7071061 0 -0.7071074 0.7071068 0 0.7071068 0.7071061 0 -0.7071074 0.7071073 0 -0.7071063 -0.7071068 0 -0.7071068 0.7071064 0 -0.7071073 0.7071073 0 -0.7071063 0 -1 0 -0.7071068 0 -0.7071068 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071064 0 -0.7071073 0 -1 0 0.7071061 0 -0.7071074 0.7071068 0 0.7071068 0.7071061 0 -0.7071074 0.7071073 0 -0.7071063 -0.7071068 0 -0.7071068 0.7071064 0 -0.7071073 0.7071073 0 -0.7071063 0 -1 0 -0.7071068 0 -0.7071068 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071063 0 -0.7071073 0 -1 0 0.7071061 0 -0.7071074 0.7071068 0 0.7071068 0.7071061 0 -0.7071074 0.7071073 0 -0.7071063 -0.7071068 0 -0.7071068 0.7071063 0 -0.7071073 0.7071073 0 -0.7071063 0 -1 0 -0.7071068 0 -0.7071068 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071064 0 -0.7071073 0 -1 0 0.7071061 0 -0.7071074 0.7071068 0 0.7071068 0.7071061 0 -0.7071074 0.7071073 0 -0.7071063 -0.7071068 0 -0.7071068 0.707107 1.3487e-6 -0.7071066 0.7071138 1.34869e-6 -0.7070999 0 -1 0 -0.7071068 0 -0.7071068 0 1 0 0.7071068 0 0.7071068 0 1 0 0.707107 0 -0.7071066 0 -1 0 0.7071061 0 -0.7071074 0.7071078 0 0.7071057 0.7071061 0 -0.7071074 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.707107 0 -0.7071066 0.7071063 0 -0.7071073 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071078 0 0.7071057 0 1 0 0.707107 0 -0.7071066 0 -1 0 0.7071061 0 -0.7071074 0.7071078 0 0.7071057 0.7071061 0 -0.7071074 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.707107 0 -0.7071066 0.7071063 0 -0.7071073 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071078 0 0.7071057 0 1 0 0.707107 0 -0.7071066 0 -1 0 0.7071061 0 -0.7071074 0.7071078 0 0.7071057 0.7071061 0 -0.7071074 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.707107 0 -0.7071066 0.7071063 0 -0.7071073 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071078 0 0.7071057 0 1 0 0.707107 1.39562e-6 -0.7071066 0 -1 0 0.7071061 0 -0.7071074 0.7071078 0 0.7071057 0.70711 1.34869e-6 -0.7071036 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.7071064 0 -0.7071073 0.7071063 0 -0.7071073 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071078 0 0.7071057 0 1 0 0.7071064 0 -0.7071073 0 -1 0 0.7071071 0 -0.7071065 0.7071068 0 0.7071068 0.7071071 0 -0.7071065 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.7071064 0 -0.7071073 0.7071063 0 -0.7071073 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071064 -7.23655e-7 -0.7071073 0 -1 0 0.7071071 0 -0.7071065 0.7071068 0 0.7071068 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.7071064 0 -0.7071073 0.7071063 0 -0.7071073 0.7071089 4.94498e-6 -0.7071047 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071064 -4.34193e-6 -0.7071073 0 -1 0 0.7071071 0 -0.7071065 0.7071068 0 0.7071068 0.7071063 0 -0.7071073 -0.7071064 0 -0.7071071 0.7071065 0 -0.7071071 0.7071067 -7.62939e-7 -0.707107 0 -1 0 -0.7071064 0 -0.7071071 0 1 0 0.7071068 0 0.7071068 0 1 0 0.7071061 -8.06359e-7 -0.7071075 0 -1 0 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 0.7071068 1.05964e-6 -0.7071068 0.7071068 1.08083e-6 -0.7071068 0.7071071 0 -0.7071065 0.7071063 8.90096e-7 -0.7071073 0 -1 0 -0.7071068 0 -0.7071068 0.7071061 0 -0.7071075 0 1 0 0.7071068 0 -0.7071068 0.7071061 0 -0.7071075 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071057 0 -0.7071078 0 -1 0 -0.7071057 0 -0.7071078 0.7071061 0 -0.7071075 0 1 0 0.7071068 0 -0.7071068 0.7071061 0 -0.7071075 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071057 0 -0.7071078 0 -1 0 -0.7071057 0 -0.7071078 0.7071061 0 -0.7071075 0 1 0 0.7071068 0 -0.7071068 0.7071061 0 -0.7071075 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071057 0 -0.7071078 0 -1 0 -0.7071057 0 -0.7071078 0.7071061 0 -0.7071075 0 1 0 0.7071068 0 -0.7071068 0.7071061 0 -0.7071075 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071067 0 -0.7071067 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071057 0 -0.7071078 0 -1 0 -0.7071057 0 -0.7071078 0.7071061 -1.39562e-6 -0.7071075 0 1 0 0.7071015 -1.34869e-6 -0.7071121 0.7071075 1.3487e-6 -0.7071061 0.7071131 1.34869e-6 -0.7071005 0.7071068 0 0.7071068 0 1 0 0 -1 0 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0.7071058 0 -0.7071077 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0.7071075 0 -0.7071061 0 1 0 0.7071058 0 -0.7071077 0.7071075 0 -0.7071061 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0 1 0 0 -1 0 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0.7071058 0 -0.7071077 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0.7071075 0 -0.7071061 0 1 0 0.7071058 0 -0.7071077 0.7071075 0 -0.7071061 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0 1 0 0 -1 0 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0.7071058 0 -0.7071077 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0.7071075 0 -0.7071061 0 1 0 0.7071058 0 -0.7071077 0.7071075 0 -0.7071061 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0 1 0 0 -1 0 0.7071058 0 -0.7071077 0.7071078 0 0.7071057 0.7071058 0 -0.7071077 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0.7071075 4.65207e-6 -0.7071061 0 1 0 0.7071064 0 -0.7071071 0.7071067 -4.32506e-7 -0.7071069 0.7071078 0 0.7071057 0 1 0 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 0 1 0 -1.22609e-7 1 1.22609e-7 0.7071068 0 0.7071068 0.7071041 -8.63759e-6 -0.7071094 0.7036654 0.09853899 0.7036654 0.7071069 2.94524e-6 -0.7071066 0.6765086 0.290985 0.6765086 0.7036654 0.09853911 0.7036654 0.7071076 6.90258e-6 -0.7071059 0.6237423 0.4710533 0.6237423 0.6765086 0.2909848 0.6765086 0.7071067 0 -0.7071067 0.5468046 0.6340423 0.5468046 0.6237423 0.4710533 0.6237423 0.7071071 4.86973e-6 -0.7071065 0.4483369 0.7732968 0.4483369 0.5468046 0.6340423 0.5468046 0.7071069 -5.42748e-6 -0.7071066 0.3330874 0.882103 0.3330871 0.4483381 0.7732958 0.4483376 0.7071068 0 -0.7071068 0.2057573 0.9567276 0.2057573 0.7071068 0 -0.7071068 0.3330864 0.8821036 0.3330864 0.06967484 0.9951336 0.06967484 0.2057573 0.9567276 0.2057573 -0.09229564 0.991445 -0.0922954 -0.09229564 0.991445 -0.09229594 0.06967413 0.9951336 0.06967437 0.7071068 0 -0.7071068 -0.7071078 0 -0.7071058 -1.68587e-7 -1 -1.68587e-7 -1.68588e-7 -1 -1.68587e-7 -0.7071078 0 -0.7071058 -0.7071068 0 -0.7071068 0.7071067 -1.74386e-7 -0.7071069 1.54137e-7 1 1.54137e-7 0.7071067 0 -0.7071068 -0.7071061 1.45277e-7 -0.7071074 0.7071066 0 -0.7071068 -0.7071075 0 -0.7071061 1.54137e-7 1 1.54137e-7 -1.25461e-7 -1 -1.2546e-7 -0.7071075 0 -0.7071061 0.5000005 -0.7071068 0.4999995 -1.25461e-7 -1 -1.2546e-7 0.7071078 -1.87319e-7 0.7071057 0.5000007 -0.7071068 0.4999992 0.7071071 1.39872e-6 -0.7071065 0 -1 0 0.7071063 0 -0.7071073 0.7071068 0 0.7071068 0.7071068 -1.57826e-7 0.7071068 0 -1 -2.81235e-7 0.7071068 0 -0.7071068 0.4999992 0.7071069 0.5000007 0.7071066 -5.17709e-7 -0.707107 0.7071057 0 0.7071079 0 1 0 0.5000009 0.7071062 0.4999999 -0.5000008 0.7071067 -0.4999994 0 1 0 -0.7071068 1.59542e-7 -0.7071068 -0.4999998 0.707107 -0.4999998 -0.6123725 -0.5 -0.6123724 -0.6123724 -0.5 -0.6123724 -0.7071068 1.57938e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071058 0 0.7071077 -0.7071068 -8.52881e-7 0.7071068 -0.7071056 -3.19884e-6 0.707108 -0.7071068 0 0.7071068 -0.707106 -1.70023e-6 0.7071076 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071073 9.53674e-7 0.7071064 -0.707107 0 0.7071065 -0.7071065 4.26349e-7 0.7071071 -0.7070987 -8.99144e-7 0.7071149 -0.7071058 0 0.7071077 -0.7071073 0 0.7071064 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071073 1.77943e-6 0.7071063 -0.7071071 0 0.7071065 -0.7071071 0 0.7071065 -0.7071058 0 0.7071077 -0.7071073 0 0.7071064 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071071 0 0.7071065 -0.7071071 0 0.7071065 -0.7071058 0 0.7071077 -0.7071073 0 0.7071063 -0.7071073 0 0.7071063 -0.7071058 0 0.7071078 -0.7071071 0 0.7071065 -0.7071071 0 0.7071065 -0.7071058 0 0.7071077 -0.7071073 9.30414e-7 0.7071064 -0.7071061 -1.3487e-6 0.7071075 -0.7071009 -1.34871e-6 0.7071127 -0.7071071 0 0.7071065 -0.707113 8.99141e-7 0.7071006 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 -1.55069e-6 0.7071075 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.7071115 1.04198e-5 0.707102 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071061 -9.30414e-6 0.7071075 -0.7071071 0 0.7071065 -0.7071069 1.27157e-6 0.7071067 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 -0.7071075 1.1165e-6 0.7071061 -0.7071073 5.72204e-7 0.7071063 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071075 0 0.7071061 -0.7071068 0 0.7071068 -0.7071065 0 0.7071071 -0.7071068 -1.3487e-6 0.7071068 -0.707105 -1.3487e-6 0.7071086 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071075 0 0.7071062 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071074 0 0.7071061 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071065 -8.62848e-7 0.7071071 -0.7071069 2.45231e-7 0.7071067 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071067 0 0.7071067 -0.7071053 -5.96047e-6 0.7071082 -0.7071068 0 0.7071068 -0.7071061 0 0.7071075 -0.7071064 6.2652e-7 0.7071071 -0.7071062 5.28556e-7 0.7071072 -0.7071081 5.25991e-6 0.7071055 -0.7071074 2.64394e-6 0.7071063 -0.7071051 -8.0281e-6 0.7071086 -0.7071034 -3.59021e-5 0.7071101 -0.7071061 3.4311e-6 0.7071075 -0.707106 2.01791e-6 0.7071076 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 -0.7071068 1.59542e-7 -0.7071067 -0.7071067 0 -0.707107 -0.7071075 0 0.7071061 -0.7071068 0 -0.7071068 -0.7071066 0 -0.7071069 0 -1 0 -0.7071075 0 0.7071061 -0.7071068 -1.64191e-7 -0.7071068 0 1 0 -0.7071075 -1.75677e-6 -0.7071061 -0.7071071 -2.57611e-6 -0.7071065 0.7071068 0 -0.7071068 0 1 0 -0.7071068 0 -0.7071068 0 -1 0 -0.7071084 0 -0.7071052 0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 -0.7071067 0 -0.707107 -0.7071076 0 0.7071061 -0.7071068 0 -0.7071068 -0.7071066 0 -0.707107 0 -1 0 -0.7071076 0 0.7071061 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071064 0 -0.7071073 0 -1 0 -0.7071084 0 -0.7071052 0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 -0.7070965 3.59658e-6 -0.707117 -0.7071076 -3.59653e-6 0.7071061 -0.7071064 0 -0.7071073 -0.7071073 0 -0.7071063 0 -1 0 -0.7071068 0 0.7071068 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071064 0 -0.7071073 0 -1 0 -0.7071084 0 -0.7071052 0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 -0.7071073 0 -0.7071063 -0.7071068 0 0.7071068 -0.7071064 0 -0.7071073 -0.7071073 0 -0.7071063 0 -1 0 -0.7071068 0 0.7071068 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071064 0 -0.7071073 0 -1 0 -0.7071084 0 -0.7071052 0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.7071064 0 -0.7071073 -0.7071073 0 -0.7071063 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071064 1.39562e-6 -0.7071073 0 -1 0 -0.7071084 0 -0.7071052 0.7071068 0 -0.7071068 -0.7071008 1.34871e-6 -0.7071126 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.707107 0 -0.7071066 -0.7071073 0 -0.7071063 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.707107 0 -0.7071066 0 -1 0 -0.7071074 0 -0.7071061 0.7071057 0 -0.7071078 -0.7071074 0 -0.7071061 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.707107 0 -0.7071066 -0.7071073 0 -0.7071063 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071057 0 -0.7071078 0 1 0 -0.707107 0 -0.7071066 0 -1 0 -0.7071074 0 -0.7071061 0.7071057 0 -0.7071078 -0.7071074 0 -0.7071061 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.707107 0 -0.7071066 -0.7071073 0 -0.7071063 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071057 0 -0.7071078 0 1 0 -0.707107 0 -0.7071066 0 -1 0 -0.7071074 0 -0.7071061 0.7071057 0 -0.7071078 -0.7071074 0 -0.7071061 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.707107 0 -0.7071066 -0.7071073 0 -0.7071063 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071057 0 -0.7071078 0 1 0 -0.707107 1.39562e-6 -0.7071066 0 -1 0 -0.7071074 0 -0.7071061 0.7071057 0 -0.7071078 -0.7071048 1.3487e-6 -0.7071088 -0.7071073 0 -0.7071063 -0.7071078 0 0.7071057 -0.707107 1.3487e-6 -0.7071065 -0.7070947 1.34872e-6 -0.7071188 0 -1 0 -0.7071078 0 0.7071057 0 1 0 0.7071057 0 -0.7071078 0 1 0 -0.707107 -5.16897e-7 -0.7071065 0 -1 0 -0.7071065 0 -0.7071071 0.7071068 0 -0.7071068 -0.7071082 0 -0.7071053 -0.7071068 0 0.7071068 -0.707107 0 -0.7071065 -0.7071082 0 -0.7071053 -0.7071052 3.53212e-6 -0.7071083 0 -1 0 -0.7071068 0 0.7071068 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.707107 -3.10138e-6 -0.7071065 0 -1 0 -0.7071065 0 -0.7071071 0.7071068 0 -0.7071068 -0.7071082 0 -0.7071053 -0.7071068 0 0.7071068 -0.7071074 0 -0.7071061 -0.707107 -2.54313e-6 -0.7071067 0 -1 0 -0.7071057 5.43306e-6 0.7071078 0 1 0 0.7071068 0 -0.7071068 0 1 0 -0.7071063 2.29502e-6 -0.7071073 -1.22609e-7 -1 -1.22609e-7 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 -0.7071078 0 -0.7071058 -0.7071068 0 0.7071068 -0.7071071 2.54313e-7 -0.7071065 -0.7071065 1.20799e-6 -0.7071071 -0.7071068 0 -0.7071067 -0.7071075 7.94728e-7 -0.7071061 -1.22609e-7 -1 -1.22609e-7 -0.7071068 0 0.7071068 -0.7071064 0 -0.7071073 0 1 0 -0.7071078 0 -0.7071058 -0.7071064 0 -0.7071073 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 -0.7071078 0 -0.7071058 -0.7071068 0 0.7071068 0 -1 0 -0.7071068 0 0.7071068 -0.7071064 0 -0.7071073 0 1 0 -0.7071077 0 -0.7071058 -0.7071064 0 -0.7071073 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 -0.7071077 0 -0.7071058 -0.7071068 0 0.7071068 0 -1 0 -0.7071068 0 0.7071068 -0.7071064 0 -0.7071073 0 1 0 -0.7071077 0 -0.7071058 -0.7071064 0 -0.7071073 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 -0.7071077 0 -0.7071058 -0.7071057 0 0.7071078 0 -1 0 -0.7071057 0 0.7071078 -0.7071064 9.30414e-7 -0.7071073 0 1 0 -0.7071034 8.99137e-7 -0.7071102 -0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071065 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 -0.7071071 0 -0.7071065 -0.7071064 0 0.7071071 0 -1 0 -0.7071064 0 0.7071071 -0.7071068 0 -0.7071068 0 1 0 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 -0.7071071 0 -0.7071065 -0.7071064 0 0.7071071 0 -1 0 -0.7071064 0 0.7071071 -0.7071068 0 -0.7071068 0 1 0 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071071 0 -0.7071064 -0.7071071 0 -0.7071065 -0.7071064 0 0.7071071 0 -1 0 -0.7071064 0 0.7071071 -0.7071068 0 -0.7071068 0 1 0 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 0.7071061 5.43306e-6 -0.7071076 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071061 0 -0.7071076 -0.7071071 0 -0.7071065 -0.7071064 0 0.7071071 0 -1 0 -0.7071064 0 0.7071071 -0.7071068 0 -0.7071068 0 1 0 -0.7071071 0 -0.7071065 -0.7071068 0 -0.7071068 -0.7071084 0 -0.7071052 0.7071061 0 -0.7071076 0 1 0 0 -1 0 -0.7071084 0 -0.7071052 0.7071061 0 -0.7071076 -0.7071071 0 -0.7071065 -0.7071064 0 0.7071071 0 -1 0 -0.7071064 0 0.7071071 -0.7071068 9.30413e-7 -0.7071068 0 1 0 -0.7071065 2.18708e-7 -0.707107 -0.7071068 6.05507e-7 -0.7071068 0.7071061 0 -0.7071076 0 1 0 -0.707107 0 -0.7071065 0.7071068 0 -0.7071068 -0.7071071 -3.00761e-7 -0.7071065 0 1 0 0 1 2.35001e-7 0.7071068 0 -0.7071068 -0.7071088 -5.78702e-6 -0.7071049 0.7036656 0.09853631 -0.7036656 -0.7071075 -2.72973e-7 -0.7071062 0.676509 0.2909875 -0.6765069 0.7036661 0.09854447 -0.703664 -0.7071055 1.03207e-5 -0.7071081 0.623744 0.4710511 -0.6237422 0.6765092 0.2909872 -0.6765071 -0.7071073 -4.10863e-6 -0.7071062 0.5468049 0.6340433 -0.546803 0.623744 0.4710515 -0.623742 -0.7071074 -5.37701e-6 -0.7071062 0.4483353 0.7732995 -0.4483338 0.5468048 0.6340433 -0.5468031 -0.7071071 4.73166e-6 -0.7071064 0.3330887 0.882102 -0.3330884 0.4483374 0.7732965 -0.448337 -0.7071145 -5.49643e-5 -0.707099 0.2057557 0.9567284 -0.2057555 -0.707107 -1.65729e-6 -0.7071066 0.333089 0.8821018 -0.3330888 0.06967633 0.9951333 -0.0696761 0.2057557 0.9567284 -0.2057555 -0.09229552 0.9914449 0.09229594 -0.092296 0.991445 0.092296 0.06967586 0.9951335 -0.06967544 -0.7071068 0 -0.7071068 -0.7071061 0 0.7071075 0 -1 0 0 -1 0 -0.7071061 0 0.7071075 -0.7071068 0 0.7071068 -0.707107 -1.74386e-7 -0.7071067 0 1 0 -0.7071068 0 -0.7071068 -0.7071068 0 0.7071068 -0.7071068 5.3948e-7 -0.7071068 -0.7071067 -5.3948e-7 0.7071067 0 1 0 0 -1 0 -0.7071075 0 0.7071061 0.5000001 -0.7071067 -0.5000001 0 -1 0 0.7071078 0 -0.7071057 0.500001 -0.7071064 -0.4999995 -0.7071067 1.52588e-6 -0.7071068 -1.22609e-7 -1 -1.22609e-7 -0.7071075 0 -0.7071061 0.7071075 0 -0.7071061 0.7071077 0 -0.7071059 0 -1 0 -0.7071068 0 -0.7071068 0.4999998 0.7071068 -0.5 -0.707107 -5.17709e-7 -0.7071066 0.7071067 0 -0.707107 0 1 0 0.5 0.7071071 -0.4999995 -0.4999999 0.7071067 0.5000004 0 1 0 -0.7071078 0 0.7071058 -0.5000005 0.7071072 0.499999 -0.6123725 -0.5 0.6123724 -0.6123726 -0.5000004 0.6123719 -0.7071071 0 0.7071065 -0.7071068 0 0.7071068 -0.7071067 0 0.7071067 0.7071065 0 0.7071071 0.7071077 0 0.7071059 0.7071063 2.76823e-6 0.7071073 0.7071077 -5.3964e-6 0.7071058 0.7071062 -2.00936e-6 0.7071073 0.7071051 0 0.7071086 0.707107 0 0.7071067 0.7071071 -1.68296e-7 0.7071066 0.7071064 -1.29131e-7 0.7071073 0.7071066 1.34636e-7 0.707107 0.707105 0 0.7071086 0.7071065 0 0.7071071 0.7071077 0 0.7071058 0.7071077 0 0.7071058 0.7071064 0 0.7071071 0.7071077 -1.63708e-6 0.7071058 0.7071051 0 0.7071086 0.707105 0 0.7071086 0.7071065 0 0.7071071 0.7071077 0 0.7071059 0.7071077 0 0.7071059 0.7071065 0 0.7071071 0.7071051 0 0.7071086 0.7071051 0 0.7071086 0.7071065 0 0.7071071 0.7071077 -1.31809e-6 0.7071059 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071051 0 0.7071086 0.7071149 -1.34868e-6 0.7070986 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 0 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071059 0 0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 0.707107 -9.30415e-7 0.7071065 0.707107 0 0.7071065 0.7071065 0 0.7071071 0.7071036 6.71099e-6 0.7071099 0.7071059 0 0.7071076 0.7071768 -7.19306e-6 0.7070368 0.7071073 -1.86083e-6 0.7071064 0.7071061 0 0.7071074 0.7071069 3.94185e-6 0.7071068 0.7071079 -5.3948e-6 0.7071056 0.7071067 0 0.7071067 0.7071061 2.23299e-6 0.7071076 0.707107 -2.86102e-7 0.7071065 0.7071065 3.65575e-7 0.7071071 0.7071036 4.56547e-7 0.7071101 0.7071061 0 0.7071075 0.7071067 0 0.7071067 0.707108 0 0.7071055 0.7071061 0 0.7071075 0.7071081 0 0.7071055 0.7071068 0 0.7071068 0.7071061 0 0.7071075 0.7071068 0 0.7071068 0.707108 0 0.7071055 0.7071061 0 0.7071075 0.707108 0 0.7071055 0.7071068 0 0.7071068 0.7071061 0 0.7071075 0.7071068 0 0.7071068 0.707108 0 0.7071055 0.7071068 -1.3487e-6 0.7071068 0.707112 -1.34869e-6 0.7071016 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071071 0 0.7071065 0.7071068 0 0.7071068 0.7071071 0 0.7071064 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071071 0 0.7071064 0.7071068 0 0.7071068 0.7071071 0 0.7071064 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071071 0 0.7071064 0.7071068 0 0.7071068 0.7071071 0 0.7071064 0.7071207 -5.39469e-6 0.7070929 0.7071061 0 0.7071075 0.7071077 0 0.7071058 0.7071071 0 0.7071064 0.7071061 0 0.7071075 0.7071071 0 0.7071064 0.7071077 0 0.7071058 0.7071061 0 0.7071075 0.7071077 0 0.7071058 0.7071071 0 0.7071064 0.7071061 0 0.7071075 0.7071071 0 0.7071064 0.7071077 0 0.7071058 0.7071061 2.79124e-6 0.7071075 0.7071071 0 0.7071064 0.7071077 0 0.7071058 0.7071071 -1.59389e-6 0.7071064 0.7071068 0 0.7071068 0.7071068 -1.36239e-7 0.7071067 0.7071073 -1.24199e-6 0.7071064 0.7071072 -9.39002e-7 0.7071065 0.707107 0 0.7071067 0.7071072 0 0.7071065 0.7071078 -2.62261e-6 0.7071059 0.7071071 0 0.7071065 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071056 2.33045e-6 0.7071078 0.7071094 -7.45352e-6 0.7071043 0.7071071 1.53443e-7 0.7071065 0.7071077 -2.62428e-6 0.7071058 0.7071057 1.20377e-5 0.7071079 0.7071084 -3.02366e-5 0.7071051 0.7071071 1.837e-5 0.7071064 -0.7071065 0 0.707107 0 -1 0 -0.7071068 0 0.7071068 -0.7071078 0 -0.7071057 -0.7071078 0 0.7071058 -0.7071068 0 0.7071068 -0.7071071 0 0.7071065 0.7071057 0 0.7071078 -0.7071061 -8.99134e-7 0.7071075 -0.7071061 -8.99134e-7 0.7071076 0 -1 0 0.7071057 0 0.7071078 -0.7071065 -5.47302e-7 0.707107 0 1 0 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071078 0 -0.7071057 0 1 0 -0.7071061 0 0.7071075 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071078 0 0.7071058 -0.7071077 0 0.7071058 0.7071064 0 0.7071071 -0.7071061 0 0.7071075 -0.7071078 0 0.7071058 0 -1 0 0.7071064 0 0.7071071 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071061 0 0.7071075 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 0.7071064 0 0.7071071 -0.7071061 0 0.7071075 -0.7071077 0 0.7071058 0 -1 0 0.7071064 0 0.7071071 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071061 0 0.7071075 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 0.7071064 0 0.7071071 -0.7071061 0 0.7071075 -0.7071077 0 0.7071058 0 -1 0 0.7071064 0 0.7071071 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071061 0 0.7071075 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071077 0 0.7071058 0.7071064 0 0.7071071 -0.7071068 1.3487e-6 0.7071068 -0.7071142 1.34871e-6 0.7070994 0 -1 0 0.7071064 0 0.7071071 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071068 -1.31809e-6 0.7071068 0 -1 0 -0.7071077 0 0.7071058 -0.7071068 0 -0.7071068 -0.7071039 -1.3487e-6 0.7071097 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 -1.3487e-6 0.7071068 -0.7070955 -1.34872e-6 0.7071181 0 -1 0 0.7071068 0 0.7071068 0 1 0 -0.7071068 0 -0.7071068 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071068 0 0.7071068 -0.7071078 0 -0.7071057 -0.7071068 0 0.7071068 -0.7071078 0 0.7071058 0.7071078 0 0.7071057 -0.7071068 0 0.7071068 -0.7071078 0 0.7071058 0 -1 0 0.7071078 0 0.7071057 0 1 0 -0.7071078 0 -0.7071057 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071068 0 0.7071068 -0.7071078 0 -0.7071057 -0.7071078 0 0.7071058 0.7071078 0 0.7071057 -0.7071068 0 0.7071068 -0.7071078 0 0.7071058 -0.7071068 0 0.7071068 0 -1 0 0.7071078 0 0.7071057 0 1 0 -0.7071078 0 -0.7071057 0 1 0 -0.7071068 0 0.7071068 0 -1 0 -0.7071068 0 0.7071068 -0.7071078 0 -0.7071057 -0.7071078 0 0.7071058 0.7071078 0 0.7071057 -0.7071076 0 0.707106 -0.707107 3.17891e-6 0.7071066 0 -1 0 0.7071078 0 0.7071057 0 1 0 -0.7071078 0 -0.7071057 0 1 0 -0.7071068 1.05447e-6 0.7071068 0 -1 0 -0.7071058 0 0.7071077 -0.7071062 0 -0.7071076 -0.7071074 0 0.7071061 0.7071076 0 0.7071061 -0.7071065 2.54313e-7 0.7071071 -0.7071061 -2.54313e-7 0.7071074 -0.7071066 0 0.707107 -0.7071066 0 0.707107 0 -1 0 0.7071076 0 0.7071061 -0.7071068 -8.5288e-7 0.7071068 0 1 0 -0.7071007 -8.99141e-7 0.707113 -0.7071073 0 0.7071064 -0.7071058 0 0.7071078 -0.7071062 0 -0.7071076 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071063 0 1 0 -0.7071068 0 0.7071068 -0.7071073 0 0.7071063 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071061 0 -0.7071076 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 0 0.7071064 0 1 0 -0.7071067 0 0.7071067 -0.7071073 0 0.7071064 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 0 1 0 0 -1 0 -0.7071058 0 0.7071077 -0.7071078 0 -0.7071057 -0.7071067 0 0.7071067 0.7071068 0 0.7071068 0 -1 0 0.7071068 0 0.7071068 -0.7071073 1.39562e-6 0.7071064 0 1 0 -0.7071061 0 0.7071074 -0.7071069 -1.21102e-6 0.7071067 -0.7071078 0 -0.7071057 0 1 0 -0.7071072 0 0.7071064 -0.7071068 0 -0.7071068 -0.7071065 -1.55393e-6 0.7071072 0 1 0 0 1 0 -0.7071068 0 -0.7071068 -0.7071055 -5.70113e-6 0.7071081 -0.7036656 0.09853631 -0.7036656 -0.7071068 0 0.7071068 -0.676509 0.2909875 -0.6765071 -0.7036672 0.0985282 -0.7036651 -0.7071081 7.20124e-6 0.7071055 -0.6237425 0.4710527 -0.6237425 -0.6765065 0.2909948 -0.6765065 -0.7071073 5.98347e-7 0.7071063 -0.5468043 0.6340428 -0.5468043 -0.6237424 0.471053 -0.6237424 -0.7071063 -1.37976e-5 0.7071073 -0.4483349 0.7732992 -0.4483349 -0.5468043 0.6340428 -0.5468043 -0.7071065 -6.95832e-7 0.7071071 -0.3330918 0.8820999 -0.3330908 -0.4483385 0.7732959 -0.4483371 -0.707102 -1.27085e-5 0.7071116 -0.2057537 0.9567291 -0.2057543 -0.7071061 1.59702e-5 0.7071075 -0.333086 0.8821036 -0.333087 -0.06967598 0.9951334 -0.0696758 -0.2057576 0.9567278 -0.205757 0.09229594 0.9914448 0.092296 0.09229594 0.9914449 0.09229594 -0.06967532 0.9951335 -0.06967532 -0.7071082 0 0.7071053 0.7071064 0 0.7071071 1.2261e-7 -1 -1.22609e-7 -1.68587e-7 -1 -1.68588e-7 0.7071064 0 0.7071071 0.7071068 -1.82257e-7 0.7071068 -0.7071067 -5.23158e-7 0.707107 1.54137e-7 1 1.54137e-7 -0.7071068 -2.47249e-7 0.7071068 0.7071058 0 0.7071079 -0.7071067 0 0.7071068 0.7071054 0 0.7071082 1.54137e-7 1 1.54137e-7 -1.2546e-7 -1 -1.25461e-7 0.7071054 0 0.7071082 -0.5000005 -0.7071068 -0.4999995 -1.2546e-7 -1 -1.2546e-7 -0.7071068 0 -0.7071068 -0.5000001 -0.7071067 -0.5000001 -0.7071069 7.62939e-7 0.7071065 0 -1 0 -0.7071066 0 0.7071071 -0.7071068 0 -0.7071068 -0.707107 1.57827e-7 -0.7071067 0 -1 0 -0.7071068 -9.53674e-7 0.7071068 -0.5000003 0.7071065 -0.5 -0.7071071 -3.54222e-7 0.7071065 -0.707107 1.58639e-7 -0.7071066 0 1 0 -0.4999991 0.7071071 -0.5000006 0.4999995 0.7071069 0.5000004 0 1 0 0.7071067 0 0.7071067 0.5000001 0.7071066 0.5000001 0.6123712 -0.5000015 0.6123725 0.6123733 -0.4999995 0.6123721 0.7071074 -1.59989e-7 0.7071061 0.7071061 0 0.7071074 0.7071061 0 0.7071074 0.7071071 0 -0.7071065 0.7071065 0 -0.707107 0.7071073 1.23032e-6 -0.7071064 0.7071066 -1.48866e-6 -0.7071071 0.7071071 -2.96252e-7 -0.7071064 0.7071058 0 -0.7071077 0.7071067 0 -0.7071067 0.7071061 -1.43051e-6 -0.7071076 0.7071074 1.57826e-7 -0.7071061 0.7071079 -2.24394e-7 -0.7071058 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071073 0 -0.7071063 0.7071073 0 -0.7071063 0.7071061 0 -0.7071074 0.7071072 1.42354e-6 -0.7071062 0.7071058 0 -0.7071077 0.7071058 0 -0.7071078 0.7071061 0 -0.7071074 0.7071073 0 -0.7071064 0.7071073 0 -0.7071064 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071073 0 -0.7071064 0.7071073 0 -0.7071064 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071073 8.5288e-7 -0.7071064 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071117 8.99127e-7 -0.707102 0.7071061 0 -0.7071074 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071065 0 -0.7071071 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071065 0 -0.7071071 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071065 0 -0.7071071 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071065 0 -0.7071071 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071065 0 -0.7071071 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 3.10138e-7 -0.7071068 0.7071068 0 -0.7071068 0.7071061 0 -0.7071074 0.7071058 -2.11927e-6 -0.7071079 0.7071065 0 -0.7071071 0.7071061 0 -0.7071074 0.7071068 1.86083e-6 -0.7071068 0.7071059 0 -0.7071077 0.7071064 -3.30607e-6 -0.7071072 0.7071065 0 -0.7071071 0.7071058 0 -0.7071077 0.7071068 1.05447e-6 -0.7071068 0.7071061 -8.26518e-7 -0.7071075 0.7071068 0 -0.7071068 0.7071056 0 -0.707108 0.7071068 0 -0.7071068 0.7071059 0 -0.7071078 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071059 0 -0.7071078 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071058 0 -0.7071077 0.7071058 0 -0.7071077 0.7071068 3.87672e-7 -0.7071068 0.7071077 4.49563e-7 -0.7071058 0.7071058 0 -0.7071077 0.7071065 0 -0.707107 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071065 0 -0.707107 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071065 0 -0.707107 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071065 0 -0.707107 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071065 0 -0.707107 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071065 0 -0.707107 0.7071061 0 -0.7071074 0.7071058 0 -0.7071077 0.7071065 0 -0.707107 0.7071058 0 -0.7071077 0.7071061 0 -0.7071074 0.7071065 6.5129e-7 -0.707107 0.7071058 0 -0.7071077 0.7071068 0 -0.7071068 0.7071065 6.90683e-7 -0.707107 0.7071071 1.99818e-6 -0.7071065 0.7071064 1.63487e-7 -0.7071072 0.7071067 5.32283e-7 -0.7071069 0.7071064 -1.4085e-6 -0.7071071 0.7071067 0 -0.7071069 0.7071065 0 -0.7071072 0.7071058 -2.62261e-6 -0.7071077 0.7071065 0 -0.7071071 0.7071061 0 -0.7071075 0.7071064 6.2652e-7 -0.7071071 0.7071064 5.28557e-7 -0.7071073 0.7071045 -4.52871e-6 -0.7071091 0.7071081 8.08522e-6 -0.7071055 0.7071059 -2.62429e-6 -0.7071078 0.7071074 1.90069e-5 -0.7071062 0.7071058 -5.03944e-6 -0.7071078 0.707106 2.01791e-6 -0.7071076 0 -1 -1.60835e-7 0.4530754 0 0.8914722 1.18421e-6 -1 6.01849e-7 0.8914738 0 0.4530723 0 -1 0 0 -1 0 0.8914738 0 0.4530723 0 -1 0 -0.1557841 0 0.9877911 0.4530754 0 0.8914722 0 -1 0 -0.7071028 0 0.7071108 -0.1557841 0 0.9877911 -2.9143e-7 -1 0 -0.9877948 0 0.1557608 0 -1 -2.27467e-7 0 -1 -1.63254e-7 -1.56409e-7 -1 -2.21533e-7 0 -1 0 0 -1 0 -0.7071028 0 0.7071108 7.40047e-7 -1 -7.40048e-7 -0.8914689 0 -0.4530818 0 -1 -1.62757e-7 -0.9877948 0 0.1557608 0 -1 0 -0.453085 0 -0.8914673 0 -1 0 -0.891469 0 -0.4530818 -1.1638e-6 -1 9.72211e-7 0.1557686 0 -0.9877936 0 -1 0 -0.453085 0 -0.8914673 2.01619e-7 -1 -2.01622e-7 0.7071028 0 -0.7071108 0 -1 -1.45102e-7 0.1557686 0 -0.9877936 2.91957e-6 -1 -4.60417e-7 0.9877926 0 -0.1557751 5.15482e-7 -1 -2.97313e-7 2.1918e-7 -1 -2.19182e-7 0.7071028 0 -0.7071108 -2.74919e-7 -1 -2.74919e-7 -1.24384e-7 -1 -2.1565e-7 0 -1 -1.83213e-7 0 -1 -1.76946e-7 0.9877926 0 -0.1557751 0 -1 0 0.4530439 0 0.8914882 3.16418e-7 -1 1.608e-7 0.8914882 0 0.4530439 2.01739e-7 -1 0 0.8914882 0 0.4530439 0 -1 0 -0.1557325 0 0.9877992 0.4530439 0 0.8914882 0 -1 0 -0.7071108 0 0.7071028 -0.1557325 0 0.9877992 1.34973e-6 -1 -1.34972e-6 -0.9877819 0 0.1558428 0 -1 -2.55891e-7 0 -1 -1.7537e-7 0 -1 0 0 -1 0 -0.7071108 0 0.7071028 0 -1 0 -0.8914431 0 -0.4531325 0 -1 0 -0.9877819 0 0.1558429 0 -1 0 -0.4531325 0 -0.8914431 0 -1 0 -0.8914431 0 -0.4531325 0 -1 -2.27455e-7 0.1557403 0 -0.987798 1.19958e-6 -1 -1.19958e-6 -0.4531325 0 -0.8914431 2.14491e-7 -1 -2.1446e-7 0.7071585 0 -0.7070552 0 -1 -1.48239e-7 0.1557403 0 -0.987798 -3.23802e-5 -1 3.96817e-6 0.9877992 0 -0.1557325 -3.7756e-6 -1 1.11254e-6 0 -1 0 0.7071585 0 -0.7070552 -2.03452e-7 -1 -2.69242e-7 -1.41851e-7 -1 -2.45935e-7 0 -1 -2.11869e-7 1.19771e-7 -1 -2.07652e-7 0.9877992 0 -0.1557325 0.4531325 0 0.8914433 0.8914448 0 0.4531294 0.8914448 0 0.4531294 -0.1557562 0 0.9877955 0.4531325 0 0.8914432 2.76417e-7 -1 -2.76417e-7 -0.7071068 0 0.7071068 -0.1557562 0 0.9877955 -5.97255e-6 -1 0 -0.9877979 0 0.1557415 0 -1 0 0 -1 0 -5.56459e-6 -1 2.01127e-6 -0.7071068 0 0.7071068 1.05635e-6 -1 5.36837e-7 -0.891485 0 -0.4530503 0 -1 -1.7495e-7 -1.29648e-7 -1 -2.24778e-7 0 -1 -1.99472e-7 -0.9877979 0 0.1557415 0 -1 -1.64752e-7 -0.4530503 0 -0.8914849 0 -1 0 0 -1 -2.29219e-7 -0.8914849 0 -0.4530503 0 -1 0 0.1557415 0 -0.9877979 -0.4530503 0 -0.8914849 0 -1 0 0.7070512 0 -0.7071624 0.1557415 0 -0.9877979 0.9877992 0 -0.1557325 -1.83025e-7 -1 -2.464e-7 0 -1 0 0 -1 0 0.7070512 0 -0.7071624 0.9877992 0 -0.1557325 0.4530786 0 0.8914706 0.8914706 0 0.4530786 0.8914706 0 0.4530786 -0.1557829 0 0.9877912 0.4530786 0 0.8914706 2.75852e-7 -1 -2.75852e-7 -0.7071068 0 0.7071068 -0.1557829 0 0.9877912 0 -1 0 -0.9877923 0 0.1557764 -1.13407e-6 -1 2.91143e-7 0 -1 0 1.12648e-6 -1 -6.49716e-7 -0.7071068 0 0.7071068 -3.83648e-6 -1 -3.20553e-6 -0.8914706 0 -0.4530786 0 -1 0 0 -1 0 0 -1 0 -0.9877923 0 0.1557764 0 -1 0 -0.4530786 1.25952e-6 -0.8914707 1.28711e-7 -1 0 -0.8914722 6.40128e-7 -0.4530754 0 -1 0 0.1557764 0 -0.9877924 -0.4530723 0 -0.8914738 -1.00116e-6 -1 -5.78364e-7 0.7071068 0 -0.7071068 0.1557764 0 -0.9877924 0.9877912 0 -0.1557829 2.7386e-7 -1 0 -3.31252e-7 -1 -1.03386e-6 0.7071068 0 -0.7071068 0.9877912 0 -0.1557829 6.09023e-7 -1 -7.64353e-7 0.6332195 0 0.7739723 -1.19788e-7 -1 0 0.7739723 0 0.6332195 0.7739723 0 0.6332195 0 -1 0 0.4709546 0 0.8821574 0 -1 0 0.6332195 0 0.7739723 0 -1 0 0.2907091 0 0.9568115 0.4709546 0 0.8821574 0 -1 0 0.09688943 0 0.9952952 0.2907091 0 0.9568115 -1.0555e-6 -1 8.77548e-7 -0.09689092 0 0.995295 0.09688943 0 0.9952952 0 -1 -3.08628e-7 -0.2907091 0 0.9568114 1.52885e-7 -1 -3.45889e-7 -0.09689092 0 0.9952951 2.20637e-7 -1 -4.12334e-7 -0.4717952 0 0.8817082 -0.2907091 0 0.9568114 7.0165e-7 -1 -8.56936e-7 -0.6335194 0 0.7737268 -0.4717952 0 0.8817082 -2.08514e-6 -1 1.70704e-6 -0.7737721 0 0.633464 -4.02554e-7 -1 1.72232e-7 -5.88717e-7 -1 3.67383e-7 4.59829e-6 -1 -4.59829e-6 -0.6335194 0 0.7737268 -4.65447e-7 -1 2.49049e-7 -0.8817147 0 0.4717832 -0.7737721 0 0.633464 -2.93299e-7 -1 0 -0.9567816 1.89251e-5 0.2908075 -0.8816695 1.74393e-5 0.4718674 -2.25219e-7 -1 0 -0.9953041 0 0.09679764 -0.9568115 0 0.2907091 1.24384e-6 -1 -9.70454e-7 -0.9953032 0 -0.09680807 -1.20391e-7 -1 0 -0.9953041 0 0.09679764 0 -1 0 -0.9568114 0 -0.2907091 -0.995303 0 -0.09680801 0 -1 0 -0.8821393 0 -0.4709885 -0.9568114 0 -0.2907091 0 -1 0 -0.7740172 0 -0.6331645 -0.8821393 0 -0.4709885 0 -1 0 -0.6331645 0 -0.7740172 0 -1 0 -0.7740172 0 -0.6331645 0 -1 0 -0.4709547 0 -0.8821574 -0.6331645 0 -0.7740172 0 -1 0 -0.2906793 0 -0.9568206 -0.4709547 0 -0.8821574 0 -1 0 -0.09690135 0 -0.995294 -0.2906793 0 -0.9568206 0 -1 -1.95797e-7 0.09678232 0 -0.9953056 1.77711e-7 -1 -2.95449e-7 -0.09690135 0 -0.995294 0 -1 0 0.2908074 0 -0.9567816 -2.25767e-6 -1 1.42307e-6 0.09678232 0 -0.9953056 0 -1 0 0.4717953 0 -0.8817082 0.2908074 0 -0.9567816 -5.74814e-6 -1 5.31291e-6 0.633464 0 -0.7737721 0.4717953 0 -0.8817082 0 -1 0 0.7737659 0 -0.6334717 2.52557e-6 -1 -2.64751e-6 5.17308e-6 -1 -5.17308e-6 0.6334641 0 -0.7737721 -5.88027e-7 -1 3.14711e-7 0.8816695 0 -0.4718675 4.77433e-7 -1 -5.24313e-7 0.7737659 0 -0.6334717 -3.16956e-7 -1 0 0.9568205 0 -0.2906792 0.8816695 0 -0.4718674 -2.29909e-7 -1 0 0.9952942 1.64286e-6 -0.09689986 0.9568128 4.92867e-6 -0.2907049 -1.86018e-7 -1 0 0.9952952 0 0.09688943 0.9952951 0 -0.09689092 -1.79945e-7 -1 0 0.9568114 0 0.2907091 0 -1 0 0.9952952 0 0.09688943 -1.45707e-7 -1 0 0.8821575 0 0.4709546 0.9568114 0 0.2907091 0.8821575 0 0.4709546 0 -1 -2.22909e-7 0.4530217 0 0.8914995 -2.27497e-7 -1 0 0.8914995 0 0.4530217 0.8914995 0 0.4530217 0 -1 -2.46021e-7 -0.1557393 0 0.9877983 -2.04924e-7 -1 0 0.4530217 0 0.8914995 6.19471e-7 -1 -6.19471e-7 -0.7071068 0 0.7071068 -0.1557393 0 0.9877983 -1.66041e-7 -1 0 -0.9877983 0 0.1557393 0 -1 -1.44758e-7 -0.7071068 0 0.7071068 0 -1 0 -0.8914995 0 -0.4530217 0 -1 0 -0.9877983 0 0.1557393 0 -1 0 -0.4530217 0 -0.8914995 0 -1 0 -0.8914995 0 -0.4530217 0 -1 -1.44758e-7 0.1557393 0 -0.9877982 -1.66041e-7 -1 0 -0.4530217 0 -0.8914995 1.55445e-6 -1 -1.55445e-6 0.7071068 0 -0.7071068 5.93108e-7 -1 -7.15044e-7 0.1557393 0 -0.9877983 -4.84038e-7 -1 0 0.9877983 0 -0.1557393 0 -1 -1.34078e-7 0 -1 -2.69382e-7 0.7071068 0 -0.7071068 0.9877983 0 -0.1557393 0.4530217 0 0.8914995 0.8914995 0 0.4530217 0.8914995 0 0.4530217 -0.1557393 0 0.9877982 0.4530217 0 0.8914995 -0.7071068 0 0.7071068 -0.1557393 0 0.9877982 -4.66228e-7 -1 0 -0.9877982 0 0.1557393 -0.7071068 0 0.7071068 5.62215e-7 -1 -7.95648e-7 -0.8914805 0 -0.4530591 -0.9877982 0 0.1557393 0 -1 -1.38986e-7 -0.4530952 0 -0.891462 0 -1 -1.4781e-7 -0.8914805 0 -0.4530591 0 -1 -1.9318e-7 0.1557393 0 -0.9877982 -0.4530952 0 -0.891462 -3.70468e-6 -1 2.34463e-6 0.7071068 0 -0.7071068 0.1557393 0 -0.9877982 0.9877982 0 -0.1557393 0.7071068 0 -0.7071068 0.9877982 0 -0.1557393 0 -1 0 0.4530217 0 0.8914995 0 -1 0 0.8914995 0 0.4530217 0 -1 0 0.8914995 0 0.4530217 0 -1 -1.28674e-7 -0.1557393 0 0.9877982 -1.47592e-7 -1 0 0.4530217 0 0.8914995 -6.84625e-6 -1 5.31619e-6 -0.7071068 0 0.7071068 0 -1 -1.64306e-7 -0.1557393 0 0.9877982 -2.11416e-7 -1 0 -0.9877982 0 0.1557393 9.47836e-7 -1 -9.40289e-7 -0.7071068 0 0.7071068 0 -1 0 -0.8914805 0 -0.4530591 -0.9877982 0 0.1557393 0 -1 0 -0.4530952 0 -0.891462 0 -1 0 -0.8914805 0 -0.4530591 0 -1 -1.41811e-7 0.1557393 0 -0.9877982 -0.4530952 0 -0.891462 6.2044e-7 -1 -6.2044e-7 0.7071068 0 -0.7071068 0.1557393 0 -0.9877982 1.15984e-6 -1 -1.28416e-6 0.9877982 0 -0.1557393 0 -1 -2.73432e-7 0.7071068 0 -0.7071068 0 -1 0 0.9877982 0 -0.1557393 0 -1 0 0.4530217 0 0.8914995 -1.23409e-7 -1 0 0.8914995 0 0.4530217 0.8914995 0 0.4530217 0 -1 -1.61268e-7 -0.1557393 0 0.9877982 0 -1 -1.4061e-7 0.4530217 0 0.8914995 2.91066e-7 -1 -2.91066e-7 -0.7071068 0 0.7071068 -0.1557393 0 0.9877982 -0.9877982 0 0.1557393 -0.7071068 0 0.7071068 -0.8914995 0 -0.4530217 -0.9877982 0 0.1557393 -0.4530217 0 -0.8914995 -0.8914995 0 -0.4530217 0.1557393 0 -0.9877982 -0.4530217 0 -0.8914995 0.7071068 0 -0.7071068 0.1557393 0 -0.9877982 -2.93736e-7 -1 0 0.9877982 0 -0.1557393 0 -1 0 0.7071068 0 -0.7071068 0.9877982 0 -0.1557393 0 -1 0 0.5555064 0 0.8315122 0 -1 0 0.8315122 0 0.5555064 0.8315122 0 0.5555064 0 -1 -1.77177e-7 0.1951017 0 0.9807831 0 -1 -1.93794e-7 0.5555064 0 0.8315122 0 -1 -2.28978e-7 -0.1950868 0 0.980786 0.1951017 0 0.9807831 2.66517e-7 -1 -3.98933e-7 -0.5555109 0 0.8315092 -0.1950868 0 0.980786 -3.98871e-7 -1 2.66444e-7 -0.8315393 0 0.5554658 0 -1 0 -0.5555109 0 0.8315092 -5.55058e-7 -1 0 -0.9807848 0 0.1950923 0 -1 -1.84555e-7 -0.8315393 0 0.5554658 -2.98444e-7 -1 0 -0.9807878 0 -0.1950774 -0.9807848 0 0.1950923 2.71397e-7 -1 -5.54511e-7 -0.8315363 0 -0.5554703 -0.9807878 0 -0.1950774 0 -1 -1.29156e-7 -0.5555178 0 -0.8315048 0 -1 -1.35417e-7 -0.8315364 0 -0.5554704 0 -1 -1.55901e-7 -0.1950117 0 -0.9808009 -0.5555178 0 -0.8315048 -6.91945e-7 -1 3.49693e-7 0.1950923 0 -0.9807848 -0.1950117 0 -0.9808009 6.14702e-7 -1 -9.20217e-7 0.5554658 0 -0.8315393 0.1950923 0 -0.9807848 -4.87306e-7 -1 3.25557e-7 0.8315092 0 -0.5555109 0 -1 -1.71088e-7 0 -1 -2.34123e-7 0.5554658 0 -0.8315393 -5.21229e-7 -1 0 0.9807859 0 -0.1950868 0 -1 0 0.8315092 0 -0.5555109 -1.87359e-7 -1 0 0.9807831 0 0.1951017 0.980786 0 -0.1950868 0.9807831 0 0.1951017 0 -1 -1.97997e-7 0.4530833 0 0.8914681 -1.99437e-7 -1 0 0.8914666 0 0.4530866 0.8914666 0 0.4530866 0 -1 -1.38852e-7 -0.1557728 0 0.9877929 0 -1 -1.99445e-7 0.4530833 0 0.8914681 0 -1 0 -0.7071028 0 0.7071107 -0.1557728 0 0.9877929 0 -1 0 -0.987795 0 0.1557596 0 -1 -1.51806e-7 -0.7071028 0 0.7071107 -4.38025e-7 -1 -2.22616e-7 -0.8914747 0 -0.4530707 0 -1 0 -0.987795 0 0.1557596 0 -1 -1.23198e-7 -0.4530707 0 -0.8914747 -0.8914747 0 -0.4530707 0 -1 0 0.1557593 0 -0.9877951 -0.4530707 0 -0.8914747 0 -1 0 0.7071118 0 -0.7071018 0.1557593 0 -0.9877951 -3.38922e-7 -1 0 0.9877932 0 -0.1557713 -1.6571e-7 -1 0 -1.55479e-7 -1 0 0.7071118 0 -0.7071018 -1.57621e-7 -1 -1.29219e-7 0.9877932 0 -0.1557713 0 -1 -1.27173e-7 0.4530802 0 0.8914698 -7.24021e-7 -1 -3.67973e-7 0.8914714 0 0.4530771 0.8914714 0 0.4530771 0 -1 0 -0.1557713 0 0.9877932 0.4530802 0 0.8914698 0 -1 0 -0.7071028 0 0.7071107 -0.1557713 0 0.9877932 -4.43118e-7 -1 0 -0.987795 0 0.1557596 -1.30313e-7 -1 0 -0.7071028 0 0.7071107 -1.98e-7 -1 0 -0.8914726 0 -0.4530747 -0.987795 0 0.1557596 0 -1 -1.90021e-7 -0.4530707 0 -0.8914746 -1.35166e-7 -1 -1.64875e-7 -0.8914726 0 -0.4530747 0 -1 -3.38916e-7 0.1557608 0 -0.9877948 -0.4530707 0 -0.8914746 1.72951e-6 -1 -1.72953e-6 0.7071018 0 -0.7071118 0 -1 -1.65711e-7 0.1557608 0 -0.9877948 0 -1 0 0.9877932 0 -0.1557713 -2.21098e-7 -1 0 0 -1 -1.82741e-7 0 -1 -1.62675e-7 0.7071018 0 -0.7071118 0 -1 0 -7.14752e-7 -1 -3.64487e-7 0.9877932 0 -0.1557713 0 -1 -2.1958e-7 0.4530707 0 0.8914747 -2.27679e-7 -1 0 0.8914698 0 0.4530802 0.8914698 0 0.4530802 0 -1 -2.24873e-7 -0.1557725 0 0.987793 -1.42919e-7 -1 -1.78242e-7 0.4530707 0 0.8914747 3.72475e-7 -1 -3.72475e-7 -0.7071068 0 0.7071068 -0.1557725 0 0.987793 -3.96504e-7 -1 0 -0.9877932 0 0.1557713 0 -1 -1.51897e-7 -0.7071068 0 0.7071068 -1.88994e-7 -1 0 -0.891473 0 -0.4530739 -0.9877932 0 0.1557713 0 -1 0 -0.4530739 0 -0.891473 -1.2003e-7 -1 0 -1.1043e-6 -1 9.23271e-7 -0.891473 0 -0.4530739 0 -1 -1.87941e-7 0.1557713 0 -0.9877932 -2.06684e-7 -1 0 -0.4530739 0 -0.891473 3.8243e-7 -1 -3.8243e-7 0.7071068 1.49855e-6 -0.7071068 0 -1 -2.07524e-7 0.1557596 2.09341e-6 -0.987795 -5.62732e-7 -1 0 0.9877932 0 -0.1557706 -3.47523e-7 -1 0 -1.57307e-7 -1 0 0.7071127 0 -0.7071009 0.9877932 0 -0.1557706 0 -1 -1.88994e-7 0.4530707 0 0.8914747 0.8914698 0 0.4530802 2.6974e-6 -1 -2.6974e-6 0.8914698 0 0.4530802 0 -1 0 -0.1557731 0 0.9877929 -1.36312e-7 -1 -1.36312e-7 0.4530707 0 0.8914747 0 -1 0 -0.7071008 0 0.7071127 -0.1557731 0 0.9877929 -4.63268e-7 -1 0 -0.9877943 0 0.1557635 -1.54933e-7 -1 -1.24229e-7 -1.61256e-7 -1 0 -0.7071008 0 0.7071127 -2.19579e-7 -1 0 -0.8914729 0 -0.4530738 -0.9877943 0 0.1557635 0 -1 -2.02701e-7 -0.4530738 0 -0.8914729 -1.26687e-7 -1 -2.15417e-7 -0.8914729 0 -0.4530738 0 -1 -1.41228e-7 0.1557725 0 -0.9877929 -0.4530738 0 -0.8914729 0 -1 0 0.7071028 0 -0.7071108 0.1557725 0 -0.9877929 0.9877932 0 -0.1557706 0 -1 -1.32351e-7 0.7071028 0 -0.7071108 0.9877932 0 -0.1557706 0 -1 -1.21996e-7 0.5867193 0 0.8097903 -1.37728e-7 -1 0 0.8097898 0 0.5867201 0.8097898 0 0.5867201 0 -1 -1.45214e-7 0.30667 0 0.9518159 0.5867193 0 0.8097903 0 -1 -1.7671e-7 1.83549e-5 0 1 0.30667 0 0.9518159 0 -1 -2.35842e-7 -0.3074647 0 0.9515594 1.83549e-5 0 1 3.21507e-7 -1 -4.43619e-7 -0.5868275 0 0.809712 -0.3074647 0 0.9515594 -3.94304e-7 -1 2.85758e-7 -0.8097206 0 0.5868155 0 -1 -1.54264e-7 -0.5868275 0 0.809712 -5.7089e-7 -1 1.84479e-7 -0.9515523 0 0.3074869 0 -1 0 -0.8097206 0 0.5868155 -2.37245e-7 -1 0 -1 0 -1.83548e-5 -0.9515523 0 0.3074869 -1.5479e-7 -1 0 -0.9518141 0 -0.3066756 -1 0 -1.83548e-5 0 -1 0 -0.8097883 0 -0.5867223 -0.9518141 0 -0.3066756 0 -1 0 -0.5867201 0 -0.8097898 -0.8097882 0 -0.5867223 0 -1 -1.3995e-7 -0.3066813 0 -0.9518123 -0.5867201 0 -0.8097898 0 -1 -1.20308e-7 0 0 -1 0 -1 0 -0.3066813 0 -0.9518123 0 -1 -1.50024e-7 0.307463 0 -0.95156 0 0 -1 1.65882e-7 -1 -2.28889e-7 0.5868225 1.14401e-6 -0.8097157 0.3074519 1.34442e-6 -0.9515636 -6.14126e-6 -1 4.45073e-6 0.8097162 0 -0.5868217 -7.07731e-7 -1 3.8478e-7 0.5868304 0 -0.8097099 -3.64202e-7 -1 0 0.9515577 0 -0.3074703 0.8097162 0 -0.5868217 -2.1529e-7 -1 0 1 0 0 0.9515577 0 -0.3074703 -1.57444e-7 -1 0 0.9518123 0 0.3066813 1 0 0 0 -1 0 0.9518123 0 0.3066813 0 -1 0 -0.6339947 0 0.7733374 0 -1 0 -0.7071065 0 0.707107 0 -1 0 -0.4707518 0 0.8822656 -0.6339947 0 0.7733374 0 -1 0 -0.2909795 0 0.9567294 -0.4707518 0 0.8822656 -0.09853333 0 0.9951338 -0.2909795 0 0.9567294 0 0 1 0 0 1 -0.09853333 0 0.9951338 0.09853333 0 0.9951338 0.2909902 0 0.9567261 0.09853333 0 0.9951338 0.4707459 0 0.8822688 0.2909902 0 0.9567261 0.6339909 0 0.7733405 0.4707459 0 0.8822688 0.7071065 0 0.7071071 0.6339909 0 0.7733405 0.7801732 0 0.6255636 0.7071065 0 0.7071071 2.81424e-7 -1 -2.2619e-7 0.8974846 0 0.441046 0.7801732 0 0.6255636 -1.27829e-7 -1 0 0.9718871 0 0.2354471 0.8974845 0 0.4410459 1.27938e-7 -1 -2.68193e-7 0.9718863 0 0.2354506 1.75465e-6 -1 -1.52968e-6 0.9718872 0 0.2354471 0.8974846 0 0.441046 0 -1 0 0.9718863 0 0.2354506 0.7801709 0 0.6255664 0.8974846 0 0.4410459 0.7071067 0 0.707107 -1.45607e-7 -1 0 -1.67508e-7 -1 -2.33299e-7 0 -1 -1.85721e-7 0 -1 0 1.76188e-6 -1 1.2174e-6 -2.20036e-7 -1 -1.26914e-7 0 -1 0 0 -1 -1.22448e-7 0 -1 -1.50843e-7 1.29192e-7 -1 -2.23991e-7 4.03464e-7 -1 -4.03464e-7 0.7801709 0 0.6255664 0 -1 0 0.6534922 0 0.7569332 0 -1 0 -2.58728e-7 -1 0 -3.49627e-7 -1 2.01662e-7 -1.92677e-7 -1 0 -1.43638e-7 -1 0 0.7071067 0 0.707107 0.5363547 0 0.8439927 0 -1 -2.13247e-7 0.6534922 0 0.7569332 0.4084264 0 0.9127913 0.5363547 0 0.8439927 0.2712104 0 0.96252 0.4084264 0 0.9127913 0.2994166 0 0.9541224 0.2712104 0 0.96252 0.4876542 0 0.8730369 0.2994166 0 0.9541224 0.6553302 0 0.7553426 0.4876542 0 0.8730369 0.795529 0 0.6059156 0.6553302 0 0.7553426 0.9023184 0 0.4310703 0.7955291 0 0.6059156 0 -1 -2.49714e-7 0.9712202 0 0.2381833 0.9023184 0 0.4310703 -1.7678e-7 -1 0 0.9993771 0 0.03529018 0 -1 -1.45832e-7 0.9712202 0 0.2381833 1.77013e-7 -1 -3.34065e-7 0.9856045 0 -0.1690673 0 -1 -2.20919e-7 0.9993771 0 0.03529018 -4.19638e-7 -1 1.65213e-7 0.9304833 0 -0.3663344 0 -1 -2.59034e-7 0.9856045 0 -0.1690673 9.23669e-7 -1 -9.23636e-7 0.8363297 0 -0.5482267 -4.39415e-7 -1 1.8499e-7 0.9304832 0 -0.3663344 0.7071195 0 -0.707094 0.8363298 0 -0.5482267 0.5482089 0 -0.8363415 0.7071195 0 -0.707094 0.3663322 0 -0.9304841 0.5482089 0 -0.8363415 0.1690714 0 -0.9856038 0.3663322 0 -0.9304841 -0.03529006 0 -0.9993771 0.1690714 0 -0.9856037 -0.2381552 0 -0.9712271 -0.03529006 0 -0.9993771 -0.4310881 0 -0.9023098 -0.2381552 0 -0.9712271 -0.6059251 0 -0.7955217 -0.4310881 0 -0.9023098 -0.7553316 0 -0.6553428 -0.6059251 0 -0.7955217 -0.873043 0 -0.4876434 -0.7553316 0 -0.6553428 -0.9541152 0 -0.2994398 -0.873043 0 -0.4876434 -0.9625242 0 -0.2711958 -0.9541152 0 -0.2994398 -0.9127943 0 -0.4084197 -0.9625241 0 -0.2711958 -0.8439929 0 -0.5363544 -0.9127943 0 -0.4084197 -0.7569319 0 -0.6534937 -0.8439928 0 -0.5363544 -0.7071068 0 -0.7071068 -2.71226e-7 -1 -1.56441e-7 0 -1 0 0 -1 -1.27678e-7 0 -1 -1.71269e-7 1.79255e-7 -1 -3.10779e-7 1.11449e-6 -1 -1.11449e-6 2.24916e-6 -1 1.61756e-6 0 -1 -1.71228e-7 0 -1 -1.73517e-7 0 -1 0 -0.7569319 0 -0.6534937 -0.6255636 0 -0.7801732 1.00748e-6 -1 -1.77939e-6 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 -0.4410459 0 -0.8974846 -0.6255636 0 -0.7801732 0 -1 -1.43807e-7 -0.2354517 2.74626e-6 -0.9718861 -1.96664e-7 -1 0 -0.4410497 2.53602e-6 -0.8974827 0 -1 -1.56785e-7 -0.2354441 0 -0.971888 0 -1 -1.56756e-7 -0.2354473 0 -0.9718871 0 -1 -1.47783e-7 -0.4410488 1.90201e-6 -0.8974832 -0.2354474 2.0597e-6 -0.9718871 -0.625564 1.6534e-6 -0.7801728 -0.4410488 1.90201e-6 -0.8974832 -0.7071068 0 -0.7071068 -0.6255619 0 -0.7801746 -0.7733421 0 -0.633989 -0.7071068 0 -0.7071068 -0.8822665 0 -0.4707503 -0.7733421 0 -0.633989 -2.40659e-7 -1 0 -0.9567288 0 -0.2909812 -0.8822665 0 -0.4707503 -3.46442e-7 -1 0 -0.9951336 0 -0.09853446 -0.9567288 0 -0.2909812 0 -1 -2.21098e-7 -1 0 0 -1 0 0 -0.9951338 2.08819e-7 -0.09853333 -2.51617e-7 -1 0 -0.9951338 0 0.09853333 -3.59002e-7 -1 0 -0.9567248 0 0.2909945 -0.9951338 0 0.09853333 -5.94923e-7 -1 3.17425e-7 -0.8822714 0 0.4707411 -0.9567248 0 0.2909945 -1.78202e-6 -1 1.4609e-6 -0.773342 0 0.633989 -0.8822714 0 0.4707411 -0.7071052 -1.47172e-6 0.7071084 -0.7071065 0 0.707107 -0.773342 0 0.633989 0.7071068 -1.49855e-6 0.7071067 -0.7071068 -1.49855e-6 0.7071068 0.7071069 -1.49855e-6 0.7071067 -0.7071068 0 -0.7071068 -0.7071058 0 0.7071079 -0.7071065 0 0.707107 -0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.4996319 0 -0.8662378 0.4996319 0 -0.8662378 0.7071068 0 -0.7071068 0.8662346 0 -0.4996374 1 0 0 0.8662346 0 -0.4996374 0.8662346 0 0.4996374 1 0 0 0.7071068 0 0.7071068 0.8662346 0 0.4996374 0.4996374 0 0.8662346 0.7071068 0 0.7071068 0 0 1 0.4996374 0 0.8662346 -0.4996374 0 0.8662346 0 0 1 -0.7071067 0 0.7071067 -0.7071067 0 0.7071067 -0.4996374 0 0.8662346 -0.8662346 0 0.4996374 -1 0 0 -0.8662346 0 0.4996374 -0.8662328 0 -0.4996407 -1 0 0 -0.7071078 0 -0.7071059 -0.8662328 0 -0.4996407 -0.4996319 0 -0.8662378 -0.7071078 0 -0.7071059 0 0 -1 -0.4996319 0 -0.8662378 0 0 -1 -0.8662346 0 0.4996374 -0.7071068 0 0.7071068 -1 0 0 -0.8662347 0 0.4996374 -0.8662585 0 -0.4995959 -1 0 0 -0.7071062 0 -0.7071073 -0.8662585 0 -0.4995959 -0.4996334 0 -0.8662369 -0.7071062 0 -0.7071073 -1.47035e-5 0 -1 -0.4996334 0 -0.8662369 0 -1 0 0.4996334 0 -0.8662369 -1.47035e-5 0 -1 0 -1 0 0.7071068 0 -0.7071068 6.53406e-6 -1 3.76873e-6 0.7071068 0 -0.7071068 0.4996334 0 -0.8662369 -9.21637e-7 -1 -5.3358e-7 0.8662388 -5.17963e-7 -0.4996302 0 -1 0 -2.49786e-6 -1 -1.03386e-6 3.6753e-7 -1 0 1 0 7.35181e-6 0.8662356 7.05911e-7 -0.4996358 5.80778e-6 -1 3.34982e-6 0.8662388 0 0.4996303 0 -1 0 1 0 7.35175e-6 0.707107 0 0.7071066 0 -1 0 0.8662388 0 0.4996303 0.4996319 0 0.8662378 0.707107 0 0.7071066 0 0 1 0.4996319 0 0.8662378 -0.4996351 0 0.8662359 0 0 1 -0.7071068 0 0.7071068 -0.4996351 0 0.8662359 0.7071045 -9.93401e-7 -0.7071092 0.4996271 0 -0.8662407 0.4996271 0 -0.8662407 0.7071068 0 -0.7071068 0.8662452 -1.74186e-6 -0.4996191 1 0 0 0.8662407 0 -0.4996271 0.8662388 0 0.4996303 1 0 0 0.7071068 0 0.7071068 0.8662388 0 0.4996303 0.4996334 0 0.8662369 0.7071068 0 0.7071068 0 0 1 0.4996334 0 0.8662369 -0.4996247 0 0.8662421 0 0 1 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.4996271 -5.1797e-7 0.8662407 -0.8662407 0 0.4996271 -1 0 0 -0.8662407 0 0.4996271 -0.8662388 0 -0.4996303 -1 0 0 -0.7071066 0 -0.707107 -0.8662388 0 -0.4996303 -0.4996334 0 -0.8662369 -0.7071066 0 -0.707107 -1.47037e-5 0 -1 -0.4996334 0 -0.8662369 -1.47037e-5 0 -1 -0.8662438 0 0.4996215 -0.7071044 0 0.7071092 -1 0 0 -0.8662438 0 0.4996215 -0.8662374 0 -0.4996325 -1 0 0 -0.7071086 0 -0.707105 -0.7071086 0 -0.707105 -0.8662374 0 -0.4996325 -0.4996251 0 -0.8662417 0 0 -1 -0.4996251 0 -0.8662417 0.4996258 0 -0.8662413 0 0 -1 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.4996258 0 -0.8662413 0.8662407 0 -0.4996271 1 0 0 0.8662389 7.05903e-7 -0.4996302 0.8662388 0 0.4996303 1 0 0 0.7071064 0 0.7071072 0.7071064 0 0.7071072 0.8662388 0 0.4996303 0.4996325 0 0.8662374 -7.35186e-6 0 1 0.4996325 0 0.8662374 -0.4996279 0 0.8662402 -7.35186e-6 0 1 -0.7071068 9.99036e-7 0.7071068 -0.4996271 1.87928e-7 0.8662407 -0.7071062 0 -0.7071074 -0.7071058 0 0.7071079 -0.7071058 0 0.7071079 0.7071064 0 -0.7071071 -0.7071062 0 -0.7071074 0.707107 -9.99036e-7 0.7071065 0.7071057 9.99038e-7 -0.7071078 0.7071074 0 0.7071062 0 1 0 1.57357e-7 1 3.09617e-7 3.32395e-7 1 5.25796e-7 0 1 0 0 1 0 0 1 2.91433e-7 2.27467e-7 1 0 1.45102e-7 1 0 0 1 0 0 1 0 0 1 1.82493e-7 1.62757e-7 1 0 1.62757e-7 1 0 0 1 1.82494e-7 2.2746e-7 1 0 0 1 2.91439e-7 0 1 0 0 1 3.04191e-7 0 1 0 0 1 0 0 1 0 0 1 0 -2.44264e-7 1 -1.78474e-7 -2.29635e-7 1 -1.32449e-7 0 1 9.18976e-7 -1.33369e-7 1 0 2.52611e-7 1 4.97081e-7 1.41685e-7 1 2.31381e-7 0 1 1.49135e-7 0 1 0 0 1 0 0 1 2.91423e-7 2.27452e-7 1 0 1.48239e-7 1 0 -1.99467e-7 1 -1.48163e-7 0 1 0 0 1 0 0 1 1.82481e-7 1.62749e-7 1 0 0 1 0 -6.47269e-7 1 9.22506e-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 2.5745e-7 0 1 0 0 1 0 2.1446e-7 1 -2.14494e-7 9.23498e-7 1 -5.85733e-6 2.34416e-7 1 -2.34416e-7 3.38033e-7 1 -5.8606e-7 0 1 1.86134e-7 1.8458e-7 1 0 0 1 1.32293e-7 0 1 0 2.20687e-7 1 9.1903e-7 1.03518e-6 1 1.64226e-6 -1.20675e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.01623e-7 1 -2.01623e-7 4.60413e-7 1 -2.91952e-6 2.19182e-7 1 -2.19182e-7 2.97308e-7 1 -5.15465e-7 0 1 0 1.76946e-7 1 0 0 1 0 0 1 0 2.39653e-7 1 9.18989e-7 -1.60835e-7 1 0 0 1 0 0 1 1.2204e-7 0 1 0 0 1 0 4.05859e-7 1 5.61994e-7 0 1 3.23737e-7 2.68018e-7 1 4.64675e-7 0 1 0 0 1 1.3356e-7 0 1 2.94359e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -8.3708e-7 1 1.32801e-6 -1.59446e-6 1 1.95054e-6 8.56539e-7 1 -7.01237e-7 -7.9156e-7 1 9.66885e-7 4.59829e-6 1 -4.59829e-6 0 1 0 -3.14512e-7 1 5.87772e-7 -1.60656e-7 1 3.92394e-7 0 1 3.17041e-7 0 1 2.29873e-7 0 1 1.86014e-7 0 1 1.79949e-7 0 1 0 0 1 1.45706e-7 0 1 1.19796e-7 0 1 0 0 1 0 0 1 2.7751e-7 0 1 0 0 1 0 0 1 0 0 1 0 -1.57614e-7 1 2.50053e-7 -1.59445e-6 1 1.95053e-6 8.56477e-7 1 -7.01172e-7 -1.81071e-6 1 2.21144e-6 4.59829e-6 1 -4.59829e-6 -4.52851e-7 1 6.96722e-7 -4.65358e-7 1 7.08652e-7 -2.6373e-7 1 4.92867e-7 0 1 3.10503e-7 0 1 2.38494e-7 0 1 2.4168e-7 0 1 1.27472e-7 0 1 1.9248e-7 0 1 1.59448e-7 1.54434e-7 1 0 0 1 1.39318e-7 1.64232e-7 1 0 2.14641e-7 1 0 5.97839e-7 1 -5.97839e-7 1.13889e-6 1 -1.01457e-6 2.57348e-7 1 0 0 1 1.54606e-7 0 1 0 0 1 0 -6.34507e-7 1 7.58829e-7 -6.72541e-7 1 8.04314e-7 2.57348e-7 1 0 1.13889e-6 1 -1.01457e-6 0 1 2.74252e-7 1.55438e-6 1 -1.55438e-6 0 1 2.42019e-7 1.34074e-7 1 0 0 1 1.26376e-7 0 1 0 0 1 0 1.23012e-7 1 0 0 1 0 3.09745e-7 1 -3.09745e-7 0 1 0 0 1 0 0 1 0 2.89517e-7 1 0 1.42943e-6 1 -1.30511e-6 0 1 2.93734e-7 0 1 0 0 1 1.23399e-7 0 1 0 1.61268e-7 1 0 1.40609e-7 1 0 2.91066e-7 1 -2.91066e-7 0 1 1.47592e-7 -1.16319e-6 1 1.40706e-6 0 1 2.38015e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.41809e-7 1 0 6.20397e-7 1 -6.20397e-7 9.45964e-7 1 -9.45964e-7 0 1 2.11411e-7 1.10216e-6 1 -1.14055e-6 0 1 0 0 1 0 1.20371e-7 1 0 1.38573e-7 1 0 -3.73179e-7 1 6.96565e-7 8.66321e-7 1 -5.78768e-7 -2.89272e-7 1 4.33043e-7 0 1 2.36087e-7 0 1 0 0 1 4.633e-7 0 1 0 0 1 1.66563e-7 0 1 0 0 1 0 0 1 0 0 1 1.20473e-7 -3.49635e-7 1 6.91934e-7 3.75408e-7 1 -2.50771e-7 -2.82195e-7 1 4.224e-7 0 1 1.58287e-7 0 1 2.612e-7 0 1 2.32269e-7 0 1 1.40441e-7 1.90019e-7 1 0 0 1 1.97997e-7 1.64875e-7 1 1.35165e-7 3.38922e-7 1 0 1.7295e-6 1 -1.72948e-6 1.6571e-7 1 0 0 1 0 0 1 2.21098e-7 1.82741e-7 1 0 1.62676e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.4313e-7 0 1 2.69987e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.19799e-6 1 -1.18903e-6 0 1 2.44213e-7 0 1 1.65711e-7 0 1 0 0 1 0 0 1 0 4.01784e-7 1 9.4713e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.95182e-7 0 1 1.91756e-7 0 1 0 0 1 0 0 1 2.32516e-7 2.11434e-7 1 0 0 1 1.35842e-7 0 1 1.34765e-7 0 1 1.35034e-7 1.29855e-7 1 0 1.88994e-7 1 0 1.99589e-6 1 -1.79223e-6 0 1 2.52887e-7 0 1 0 0 1 1.93588e-7 0 1 0 0 1 4.11802e-7 0 1 1.37718e-7 0 1 1.7485e-7 0 1 0 2.39021e-7 1 -2.39024e-7 1.36264e-6 1 -2.23303e-6 -1.34604e-7 1 4.35654e-7 -2.6158e-7 1 8.46621e-7 0 1 0 0 1 0 -2.75512e-7 1 1.05393e-6 0 1 0 3.31095e-7 1 -3.31101e-7 0 1 0 7.39618e-7 1 -1.14207e-6 0 1 0 0 1 0 1.3995e-7 1 0 1.20308e-7 1 0 0 1 0 1.50025e-7 1 0 2.28888e-7 1 -1.65881e-7 -3.9591e-6 1 5.46277e-6 -1.38292e-7 1 3.56833e-7 0 1 3.2372e-7 0 1 1.91369e-7 0 1 1.3995e-7 7.16893e-7 1 -1.59271e-6 0 1 0 -6.34996e-7 1 1.41076e-6 1.29078e-7 1 0 1.57075e-7 1 0 2.09642e-7 1 0 3.94304e-7 1 -2.85758e-7 -2.85784e-7 1 3.94328e-7 0 1 0 -1.84443e-7 1 5.70825e-7 0 1 0 0 1 2.37245e-7 0 1 1.54791e-7 -1.46106e-6 1 1.78218e-6 0 1 1.20328e-7 0 1 1.73221e-7 0 1 2.15067e-7 0 1 2.51617e-7 0 1 3.5899e-7 -3.17446e-7 1 5.94946e-7 0 1 0 0 1 0 0 1 0 4.7715e-7 1 1.13072e-6 0 1 0 0 1 1.27829e-7 0 1 1.72675e-7 1.79011e-6 1 -2.08176e-6 -1.27718e-7 1 3.42225e-7 0 1 0 -1.20909e-7 1 0 -1.42021e-7 1 0 8.12344e-7 1 1.14872e-6 -1.09307e-6 1 -1.39446e-6 0 1 0 0 1 0 0 1 0 -3.69476e-7 1 9.18976e-7 2.23992e-7 1 -1.29194e-7 4.03461e-7 1 -4.03461e-7 0 1 0 0 1 0 -1.13918e-6 1 1.29244e-6 -3.5851e-7 1 6.21558e-7 9.18942e-7 1 -3.72657e-7 0 1 1.27678e-7 0 1 0 0 1 1.64899e-7 0 1 1.83851e-7 0 1 2.64149e-7 2.89269e-7 1 0 2.29755e-7 1 0 0 1 2.62272e-7 -1.80234e-7 1 3.56918e-7 0 1 0 -6.92862e-7 1 8.51877e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.7992e-6 1 -2.29528e-6 0 1 0 -1.36709e-7 1 0 6.47937e-7 1 9.18982e-7 -1.29192e-7 1 2.23991e-7 0 1 1.50843e-7 0 1 1.22448e-7 1.59786e-7 1 0 0 1 1.48887e-7 0 1 2.99343e-7 0 1 1.65638e-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 -3.21676e-7 -1 1.63489e-7 0.8914689 0 -0.4530818 6.01846e-7 -1 -1.1842e-6 0.4530723 0 -0.8914738 0 -1 -1.29519e-7 0 -1 -1.58345e-7 0.4530723 0 -0.8914738 -1.50598e-7 -1 0 0.9877914 0 0.1557829 0.891469 0 -0.4530818 0 -1 0 0.7071068 0 0.7071068 0.9877914 0 0.1557829 0 -1 -3.27863e-7 0.1557698 0 0.9877934 2.55897e-7 -1 0 -1.26672e-7 -1 -3.42214e-7 2.62761e-7 -1 -4.95398e-7 0 -1 -3.64203e-7 3.01524e-7 -1 -5.22765e-7 0.7071068 0 0.7071068 0 -1 -2.05306e-7 -0.4530786 0 0.8914707 1.83101e-7 -1 0 0.1557698 0 0.9877934 0 -1 0 -0.891469 0 0.4530818 -7.28213e-7 -1 -1.03786e-6 -0.4530786 0 0.8914707 0 -1 0 -0.9877936 0 -0.1557686 0 -1 0 -0.891469 0 0.4530818 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 -0.9877936 0 -0.1557686 0 -1 0 -0.1557673 0 -0.9877938 0 -1 0 0 -1 0 -0.7071067 0 -0.7071067 2.08541e-7 -1 -5.29661e-7 0 -1 0 0 -1 0 0 -1 0 -0.1557673 0 -0.9877938 -2.1975e-7 -1 0 0.8914464 0 -0.4531262 2.36624e-7 -1 -4.65508e-7 0.4531325 0 -0.8914431 -1.55663e-7 -1 0 0.4531325 0 -0.8914431 -1.35833e-7 -1 0 0.987783 0 0.155835 0.8914464 0 -0.4531262 0 -1 0 0.7071068 0 0.7071068 0.987783 0 0.155835 0 -1 0 0.1558416 0 0.9877821 -1.09382e-6 -1 -1.30936e-6 0 -1 -3.16586e-7 0 -1 -3.57104e-7 0 -1 -3.39735e-7 0.7071068 0 0.7071068 0 -1 0 -0.4531325 0 0.8914431 0 -1 0 0.1558416 0 0.9877821 0 -1 0 -0.8914415 0 0.4531357 0 -1 0 -0.4531325 0 0.8914431 0 -1 0 -0.9877821 0 -0.1558416 0 -1 0 -0.8914415 0 0.4531357 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 -0.9877821 0 -0.1558416 0 -1 0 -0.1558416 0 -0.9877821 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 -1.89832e-7 -1 0 -2.18612e-7 -1 1.26095e-7 0 -1 -9.18935e-7 0 -1 0 -0.1558416 0 -0.9877821 0.8914882 0 -0.4530439 0.4531325 0 -0.8914431 0.4531325 0 -0.8914431 0.9877965 0 0.1557497 0.8914882 0 -0.4530439 0 -1 0 0.7071108 0 0.7071028 0.9877965 0 0.1557497 0 -1 0 0.1557485 0 0.9877968 0 -1 0 0 -1 0 0 -1 0 0.7071108 0 0.7071028 2.5249e-7 -1 -4.969e-7 -0.4530022 0 0.8915095 0 -1 -2.57447e-7 0 -1 0 0 -1 0 0.1557485 0 0.9877968 1.83763e-6 -1 -2.18959e-6 -0.8914849 0 0.4530503 -1.31615e-7 -1 0 0 -1 -1.49135e-7 -0.4530022 0 0.8915095 -1.38094e-7 -1 0 -0.9877981 0 -0.1557403 -0.891485 0 0.4530503 0 -1 0 -0.7071068 0 -0.7071068 -0.987798 0 -0.1557403 -0.1557403 0 -0.987798 -4.39999e-7 -1 3.2683e-7 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 -0.1557403 0 -0.987798 0.8914689 0 -0.4530817 0.453085 0 -0.8914673 0.453085 0 -0.8914673 0.9877926 0 0.1557751 0.8914689 0 -0.4530817 0 -1 0 0.7071147 0 0.7070988 0.9877926 0 0.1557751 0 -1 0 0.1557608 0 0.9877949 0 -1 0 0 -1 0 0 -1 0 0.7071147 0 0.7070989 2.45865e-7 -1 -4.83768e-7 -0.4530722 0 0.8914738 0 -1 -3.01393e-7 0 -1 0 0 -1 0 0.1557608 0 0.9877949 -2.38959e-7 -1 1.21449e-7 -0.8914689 0 0.4530817 -2.20391e-7 -1 0 -0.4530723 0 0.8914738 -1.5385e-7 -1 0 -0.9877924 0 -0.1557764 -0.8914689 0 0.4530817 4.15603e-7 -1 -1.16389e-6 -0.7071147 0 -0.7070988 -0.9877924 0 -0.1557764 -0.1557739 0 -0.9877927 0 -1 0 0 -1 0 -0.7071147 0 -0.7070989 -0.1557739 0 -0.9877927 0 -1 0 0.7739648 0 -0.6332287 -6.77799e-7 -1 -8.6901e-7 0.6331645 0 -0.7740172 0.6331645 0 -0.7740172 0 -1 0 0.8821604 0 -0.4709489 0 -1 0 0.7739648 0 -0.6332287 0 -1 0 0.9568086 0 -0.2907189 0.8821604 0 -0.4709489 0 -1 0 0.9952951 0 -0.09689092 0.9568086 0 -0.2907189 1.19247e-7 -1 0 0.9952952 0 0.09688943 0.9952951 0 -0.09689092 0 -1 0 0.9568072 0 0.2907232 -1.77313e-7 -1 -2.81303e-7 0.9952952 0 0.09688943 0 -1 0 0.8817146 0 0.4717832 0.9568072 0 0.2907232 -4.72554e-6 -1 -5.11253e-6 0.7737193 0 0.6335286 0.8817146 0 0.4717832 0 -1 0 0.6334624 0 0.7737735 2.35325e-6 -1 2.24487e-6 0 -1 0 4.59589e-6 -1 4.59579e-6 0.7737193 0 0.6335286 0 -1 0 0.4717952 0 0.8817081 0.6334624 0 0.7737735 0 -1 0 0.2908032 0 0.9567828 0.4717952 0 0.8817081 0 -1 0 0.09689092 0 0.9952951 0.2908032 0 0.9567828 -8.42782e-7 -1 -1.3084e-6 -0.09689986 0 0.9952942 0 -1 0 0.09689092 0 0.9952951 0 -1 0 -0.2907049 0 0.9568128 -0.09689986 0 0.9952942 0 -1 0 -0.4710006 0 0.8821328 -0.2907049 0 0.9568128 0 -1 0 -0.6331554 0 0.7740247 -0.4710006 0 0.8821328 0 -1 0 -0.7740247 0 0.6331554 0 -1 0 -0.6331554 0 0.7740247 0 -1 0 -0.8821574 0 0.4709547 -0.7740247 0 0.6331554 0 -1 0 -0.9568163 0 0.2906934 -0.8821574 0 0.4709547 0 -1 0 -0.9952957 0 0.09688454 -0.9568163 0 0.2906934 -7.29983e-7 -1 -1.16232e-6 -0.9953054 0 -0.09678381 -1.41644e-7 -1 -2.25534e-7 -0.9952957 0 0.09688454 3.47247e-7 -1 0 -0.9567829 0 -0.2908032 1.71948e-6 -1 2.28251e-6 -0.9953054 0 -0.09678381 4.63877e-7 -1 2.48217e-7 -0.8817082 0 -0.4717953 -0.9567829 0 -0.2908032 9.63613e-7 -1 7.88878e-7 -0.7737735 0 -0.6334624 -0.8817082 0 -0.4717953 0 -1 0 -0.633464 0 -0.7737721 2.64817e-6 -1 2.52627e-6 5.15681e-6 -1 5.15602e-6 -0.7737735 0 -0.6334624 -1.57355e-7 -1 -2.94014e-7 -0.4718675 0 -0.8816695 2.62174e-7 -1 2.38738e-7 -0.633464 0 -0.7737721 0 -1 -1.58483e-7 -0.2906934 0 -0.9568163 -0.4718675 0 -0.8816695 0 -1 0 -0.09688454 0 -0.9952957 -0.2906934 0 -0.9568163 0 -1 0 0.0968756 0 -0.9952965 -0.09688454 0 -0.9952957 0 -1 0 0.2907189 0 -0.9568085 -1.43405e-7 -1 -2.40586e-7 0.0968756 0 -0.9952965 0 -1 0 0.4710338 0 -0.8821151 0.2907189 0 -0.9568085 0.4710338 0 -0.8821151 0 -1 0 0.8914933 0 -0.4530339 -6.43897e-7 -1 -8.60704e-7 0.4530279 0 -0.8914963 0.4530279 0 -0.8914963 1.23012e-7 -1 0 0.9877958 0 0.1557544 0 -1 0 0.8914933 0 -0.4530339 3.09649e-7 -1 3.09602e-7 0.7071607 0 0.707053 0.9877958 0 0.1557544 0 -1 0 0.1557226 0 0.9878009 -1.16268e-6 -1 -1.28463e-6 0.7071607 0 0.707053 0 -1 0 -0.4530653 0 0.8914773 0 -1 0 0.1557226 0 0.9878009 0 -1 0 -0.8914559 0 0.4531075 0 -1 0 -0.4530653 0 0.8914773 0 -1 0 -0.9877958 0 -0.1557544 0 -1 0 -0.8914559 0 0.4531075 -8.8233e-6 -1 -1.01832e-5 -0.7071145 0 -0.7070991 5.38086e-7 -1 5.38087e-7 -0.9877958 0 -0.1557544 0 -1 0 -0.1557369 0 -0.9877986 3.0618e-7 -1 2.08029e-7 0 -1 0 -0.7071145 0 -0.7070991 -0.1557369 0 -0.9877986 0.8914933 0 -0.453034 0.4530279 0 -0.8914963 0.4530279 0 -0.8914963 0.9877958 0 0.1557544 0.8914933 0 -0.453034 0.7071607 0 0.707053 0.9877958 0 0.1557544 0 -1 0 0.1557226 0 0.9878009 0.7071607 0 0.707053 0 -1 0 -0.4530653 0 0.8914773 0.1557226 0 0.9878009 -3.73461e-7 -1 -1.02659e-6 -0.8914559 0 0.4531075 0 -1 0 -0.4530653 0 0.8914773 1.93183e-7 -1 0 -0.9877958 0 -0.1557544 -0.891456 0 0.4531075 5.38055e-7 -1 5.38043e-7 -0.7071145 0 -0.7070991 -0.9877958 0 -0.1557544 -0.1557369 0 -0.9877986 -0.7071145 0 -0.7070991 -0.1557369 0 -0.9877986 0 -1 0 0.8914933 0 -0.453034 0 -1 0 0.4530279 0 -0.8914963 0 -1 0 0.4530279 0 -0.8914963 0 -1 0 0.9877958 0 0.1557544 -1.18528e-6 -1 -1.3096e-6 0.8914933 0 -0.453034 2.90895e-7 -1 2.90851e-7 0.7071607 0 0.707053 2.9108e-7 -1 2.91083e-7 0.9877958 0 0.1557544 0 -1 -2.11406e-7 0.1557226 0 0.9878008 -1.8184e-6 -1 -2.33681e-6 0.7071607 0 0.707053 0 -1 0 -0.4530653 0 0.8914773 0.1557226 0 0.9878008 0 -1 0 -0.891456 0 0.4531075 -1.56221e-7 -1 -2.90125e-7 -0.4530653 0 0.8914773 0 -1 0 -0.9877958 0 -0.1557544 -0.891456 0 0.4531075 0 -1 0 -0.7071145 0 -0.7070991 -0.9877958 0 -0.1557544 0 -1 -1.47591e-7 -0.1557369 0 -0.9877986 1.28676e-7 -1 0 -0.7071145 0 -0.7070991 0 -1 0 -0.1557369 0 -0.9877986 0 -1 0 0.8914933 0 -0.453034 0 -1 0 0.4530279 0 -0.8914963 0.4530279 0 -0.8914963 0 -1 0 0.9877958 0 0.1557544 0 -1 0 0.8914933 0 -0.453034 -1.29935e-6 -1 -2.65921e-6 0.7071607 0 0.707053 0.9877958 0 0.1557544 0.1557226 0 0.9878009 0.7071607 0 0.707053 -0.4530653 0 0.8914773 0.1557226 0 0.9878008 -0.891456 0 0.4531075 -0.4530653 0 0.8914773 -0.9877958 0 -0.1557544 -0.891456 0 0.4531075 -0.7071145 0 -0.7070991 -0.9877958 0 -0.1557544 0 -1 0 -0.1557369 0 -0.9877986 -1.50446e-7 -1 -2.59802e-7 -0.7071145 0 -0.7070991 -0.1557369 0 -0.9877986 0 -1 0 0.8315047 0 -0.5555177 0 -1 0 0.5555177 0 -0.8315047 0.5555177 0 -0.8315047 0 -1 0 0.9807852 0 -0.1950905 -1.36869e-7 -1 -2.87645e-7 0.8315047 0 -0.5555177 0 -1 0 0.9807874 0 0.1950793 0.9807852 0 -0.1950905 -1.16405e-6 -1 -1.51347e-6 0.8315077 0 0.5555132 0.9807874 0 0.1950793 -1.41062e-7 -1 -2.11169e-7 0.5554703 0 0.8315363 0 -1 0 0.8315077 0 0.5555132 0 -1 0 0.1950905 0 0.9807852 0 -1 -1.87013e-7 0.5554703 0 0.8315363 -4.78486e-7 -1 -7.23256e-7 -0.1950793 0 0.9807875 0.1950905 0 0.9807852 0 -1 0 -0.5554704 0 0.8315364 -0.1950793 0 0.9807874 0 -1 0 -0.8315393 0 0.5554658 0 -1 -1.84905e-7 -0.5554704 0 0.8315364 0 -1 0 -0.9807857 0 0.1950887 -0.8315394 0 0.5554658 0 -1 0 -0.9807834 0 -0.1950999 -0.9807857 0 0.1950887 0 -1 0 -0.8315364 0 -0.5554703 -0.9807834 0 -0.1950999 2.36046e-6 -1 2.29414e-6 -0.5555177 0 -0.8315047 -1.55823e-7 -1 -1.50477e-7 -2.30633e-7 -1 -3.89008e-7 -0.8315364 0 -0.5554703 0 -1 0 -0.1950793 0 -0.9807874 0 -1 0 -0.5555178 0 -0.8315048 -4.75931e-7 -1 -1.12736e-6 0.1950905 0 -0.9807852 -0.1950793 0 -0.9807874 0.1950905 0 -0.9807852 0 -1 0 0.8914747 0 -0.4530707 0 -1 0 0.4530707 0 -0.8914746 0.4530707 0 -0.8914746 0 -1 0 0.9877948 0 0.1557608 0 -1 0 0.8914747 0 -0.4530707 0 -1 0 0.7071068 0 0.7071068 0.9877948 0 0.1557608 0 -1 -1.95112e-7 0.1557589 0 0.9877952 0 -1 -2.02312e-7 0.7071068 0 0.7071068 -2.50441e-7 -1 4.92776e-7 -0.4530707 0 0.8914747 0 -1 -1.87728e-7 0.1557589 0 0.9877952 -1.38597e-7 -1 0 -0.891475 0 0.4530699 -0.4530707 0 0.8914747 -1.22623e-7 -1 0 -0.9877929 0 -0.1557728 -0.891475 0 0.4530699 0 -1 0 -0.7071127 0 -0.7071009 -0.9877929 0 -0.1557728 0 -1 -3.81283e-7 -0.1557615 0 -0.9877946 0 -1 -1.86423e-7 -1.19243e-7 -1 -3.74567e-7 -0.7071127 0 -0.7071009 -6.32296e-7 -1 -9.49182e-7 -0.1557615 0 -0.9877946 -1.27172e-7 -1 0 0.8914722 0 -0.4530755 -3.67964e-7 -1 7.23998e-7 0.4530802 0 -0.8914698 0.4530802 0 -0.8914698 0 -1 0 0.9877952 0 0.1557589 0.8914722 0 -0.4530755 0 -1 0 0.7071068 0 0.7071068 0.9877952 0 0.1557589 0 -1 0 0.1557593 0 0.9877951 0 -1 -1.39675e-7 0.7071068 0 0.7071068 0 -1 0 -0.4530779 0 0.891471 0.1557593 0 0.9877951 0 -1 0 -0.8914698 0 0.4530802 0 -1 0 -0.4530779 0 0.891471 0 -1 0 -0.9877944 0 -0.1557633 -0.8914698 0 0.4530802 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 -0.9877944 0 -0.1557633 0 -1 -3.24009e-7 -0.155771 0 -0.9877932 0 -1 -2.21098e-7 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 -1.55138e-7 -1 0 0 -1 -5.02713e-7 -0.155771 0 -0.9877932 2.19579e-7 -1 0 0.8914747 0 -0.4530707 0 -1 -2.27679e-7 0.4530802 0 -0.8914698 0.4530802 0 -0.8914698 0 -1 0 0.9877935 0 0.1557692 0 -1 -3.46637e-7 0.8914747 0 -0.4530707 0 -1 0 0.7071068 0 0.7071068 0.9877935 0 0.1557692 0 -1 0 0.1557731 0 0.9877929 0 -1 0 0.7071068 0 0.7071068 0 -1 0 -0.4530739 0 0.8914731 0.1557731 0 0.9877929 0 -1 0 -0.8914698 0 0.4530802 0 -1 0 8.87073e-7 -1 7.96556e-7 -0.4530739 0 0.8914731 0 -1 0 -0.9877938 0 -0.1557673 0 -1 0 -0.8914698 0 0.4530802 0 -1 0 -0.7071048 0 -0.7071088 0 -1 -1.66605e-7 -0.9877938 0 -0.1557673 0 -1 -5.62733e-7 -0.1557713 0 -0.9877932 -2.94277e-7 -1 -9.52447e-7 0 -1 0 -0.7071048 0 -0.7071088 -0.1557713 0 -0.9877932 0 -1 0 0.891473 0 -0.4530739 0.4530833 0 -0.8914681 -2.1194e-6 -1 -2.36024e-6 0.4530833 0 -0.8914681 0 -1 0 0.9877929 0 0.1557731 0 -1 0 0.891473 0 -0.4530739 0 -1 0 0.7071107 0 0.7071028 0.9877929 0 0.1557731 0 -1 0 0.1557614 0 0.9877947 -1.65413e-7 -1 -2.58528e-7 0 -1 -2.103e-7 0.7071107 0 0.7071028 0 -1 0 -0.4530707 0 0.8914747 0.1557614 0 0.9877947 -2.02702e-7 -1 0 -0.8914698 0 0.4530802 0 -1 0 -0.4530707 0 0.8914747 -1.41228e-7 -1 0 -0.987793 0 -0.1557725 -0.8914698 0 0.4530802 0 -1 0 -0.7071127 0 -0.7071009 -0.987793 0 -0.1557725 -0.1557713 0 -0.9877932 0 -1 -1.66156e-7 -0.7071127 0 -0.7071009 -0.1557713 0 -0.9877932 0 -1 0 0.8097969 0 -0.5867104 0 -1 0 0.5867114 0 -0.809796 0.5867114 0 -0.809796 0 -1 0 0.9518111 0 -0.3066849 0.8097969 0 -0.5867104 0 -1 0 1 0 0 0.9518111 0 -0.3066849 -1.86948e-6 -1 -2.40935e-6 0.9515594 0 0.3074647 1 0 0 4.43618e-7 -1 3.21506e-7 0.809712 0 0.5868275 0.9515595 0 0.3074648 0 -1 0 0.5868275 0 0.809712 6.9869e-7 -1 6.12481e-7 0.809712 0 0.5868275 0 -1 0 0.3074648 0 0.9515595 0 -1 0 0.5868275 0 0.809712 0 -1 0 -1.22368e-5 0 1 0.3074648 0 0.9515595 0 -1 0 -0.306672 0 0.9518153 -1.22368e-5 0 1 -1.03089e-6 -1 -1.48208e-6 -0.586728 0 0.8097841 -0.306672 0 0.9518153 1.21063e-7 -1 0 -0.8097811 0 0.586732 -0.586728 0 0.809784 1.57444e-7 -1 0 -0.9518123 0 0.3066813 -0.8097811 0 0.586732 1.35346e-7 -1 0 -1 0 0 0 -1 -1.31942e-7 -0.9518123 0 0.3066813 1.68778e-7 -1 0 -0.9515577 0 -0.3074703 -1 0 0 2.57504e-7 -1 1.86624e-7 -0.8097099 0 -0.5868304 -0.9515577 0 -0.3074703 0 -1 0 -0.5868304 0 -0.8097099 2.06265e-6 -1 2.75642e-6 -0.8097099 0 -0.5868304 0 -1 0 -0.3074703 0 -0.9515577 -0.5868304 0 -0.8097099 0 -1 0 0 0 -1 -0.3074703 0 -0.9515577 0 -1 0 0.3066813 0 -0.9518123 0 0 -1 0 -1 0 0.3066813 0 -0.9518123 0 -1 0 0.7733389 0 0.6339928 0 -1 0 0.7071065 0 0.707107 0 -1 0 0.8822656 0 0.4707518 0.7733389 0 0.6339928 0 -1 0 0.956729 0 0.2909805 0.8822656 0 0.4707518 0.9951338 0 0.09853333 0.956729 0 0.2909805 1 0 2.21098e-6 1 0 2.21098e-6 0.9951338 0 0.09853333 0.9951328 0 -0.09854292 0.9567261 0 -0.2909902 0.9951328 0 -0.09854292 0.8822688 0 -0.4707459 0.9567261 0 -0.2909902 0.7733405 0 -0.6339909 0.8822688 0 -0.4707459 0.7071071 0 -0.7071064 0.7733405 0 -0.6339909 0.6255619 0 -0.7801746 0.7071071 0 -0.7071064 0 -1 0 0.441047 0 -0.8974841 0.6255619 0 -0.7801746 0 -1 0 0.2354473 0 -0.9718871 0.441047 0 -0.8974841 -2.43595e-7 -1 -3.8385e-7 0.2354473 0 -0.9718871 2.08437e-6 -1 2.61812e-6 0.2354473 0 -0.9718871 0.4410497 0 -0.8974827 -1.23195e-7 -1 -2.6345e-7 0.2354474 0 -0.9718871 0.6255636 0 -0.7801732 0.4410497 0 -0.8974827 0.7071071 0 -0.7071065 -2.04474e-7 -1 -2.90684e-7 0 -1 -2.66784e-7 -2.73116e-7 -1 1.57527e-7 -1.50954e-7 -1 0 -2.68982e-7 -1 1.57535e-7 -1.26914e-7 -1 2.20037e-7 0 -1 -2.58806e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.6255636 0 -0.7801732 0 -1 0 0.7569313 0 -0.6534945 0 -1 0 -5.69592e-7 -1 -6.46223e-7 -1.79255e-7 -1 -3.1078e-7 0 -1 -1.71269e-7 0 -1 -1.27681e-7 0.7071071 0 -0.7071064 0.8439936 0 -0.5363533 0 -1 -1.80548e-7 0.7569312 0 -0.6534945 0.9127908 0 -0.4084275 0.8439936 0 -0.5363533 0.9625203 0 -0.2712097 0.9127908 0 -0.4084275 0.9541225 0 -0.2994166 0.9625203 0 -0.2712097 0.8730447 0 -0.4876401 0.9541224 0 -0.2994166 0.7553316 0 -0.6553428 0.8730448 0 -0.4876402 0.6059128 0 -0.7955311 0.7553316 0 -0.6553428 0.4310981 0 -0.9023051 0.6059128 0 -0.7955311 0 -1 0 0.2381542 0 -0.9712273 0.4310981 0 -0.9023051 0 -1 0 0.03529018 0 -0.9993771 -1.63813e-7 -1 -2.60441e-7 0.2381542 0 -0.9712273 0 -1 0 -0.1690714 0 -0.9856037 0 -1 0 0.03529018 0 -0.9993771 0 -1 0 -0.3663322 0 -0.9304841 -3.42113e-7 -1 -4.20639e-7 -0.1690714 0 -0.9856037 0 -1 0 -0.5482248 0 -0.836331 0 -1 0 -0.3663322 0 -0.9304841 -0.707094 0 -0.7071195 -0.5482248 0 -0.836331 -0.8363298 0 -0.5482267 -0.707094 0 -0.7071195 -0.9304934 0 -0.3663086 -0.8363297 0 -0.5482268 -0.9856037 0 -0.1690714 -0.9304934 0 -0.3663086 -0.999377 0 0.03529441 -0.9856037 0 -0.1690714 -0.9712271 0 0.2381552 -0.999377 0 0.03529441 -0.9023123 0 0.431083 -0.9712271 0 0.2381552 -0.7955182 0 0.6059299 -0.9023123 0 0.431083 -0.6553449 0 0.7553297 -0.7955182 0 0.6059299 -0.4876433 0 0.8730429 -0.6553449 0 0.7553297 -0.2994398 0 0.9541152 -0.4876433 0 0.8730429 -0.2711986 0 0.9625234 -0.2994398 0 0.9541152 -0.4084185 0 0.9127948 -0.2711986 0 0.9625234 -0.5363547 0 0.8439927 -0.4084185 0 0.9127948 -0.6534937 0 0.7569319 -0.5363547 0 0.8439927 -0.7071068 0 0.7071068 -1.56462e-7 -1 2.71296e-7 0 -1 -1.20891e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -3.0909e-7 -1 1.77509e-7 1.46149e-6 -1 -2.04127e-6 -1.43663e-7 -1 0 -0.6534937 0 0.7569319 -0.7801746 0 0.6255619 -1.45343e-7 -1 -2.51991e-7 0 -1 -1.69698e-7 0 -1 -1.37754e-7 -0.7071068 0 0.7071068 -0.8974846 0 0.4410459 -0.7801746 0 0.6255619 0 -1 0 -0.9718864 0 0.2354506 -3.8583e-7 -1 -6.26669e-7 -0.8974846 0 0.4410459 0 -1 -2.81469e-7 -0.9718876 0 0.2354452 0 -1 0 -0.9718863 0 0.2354506 0 -1 0 -0.8974832 0 0.4410488 -0.9718877 0 0.2354452 -0.7801746 0 0.6255619 -0.8974832 0 0.4410488 -0.7071064 0 0.7071071 -0.7801746 0 0.6255619 -0.6339852 0 0.7733453 -0.7071064 0 0.7071071 -0.4707551 0 0.882264 -0.6339851 0 0.7733453 0 -1 0 -0.2909862 0 0.9567272 -0.4707551 0 0.882264 0 -1 0 -0.0985341 0 0.9951336 -0.2909862 0 0.9567272 0 -1 0 0 0 1 0 0 1 -0.0985341 0 0.9951336 0 -1 0 0.09853333 0 0.9951338 0 -1 0 0.2909895 0 0.9567263 0.09853333 0 0.9951338 0 -1 0 0.4707518 0 0.8822656 0.2909895 0 0.9567263 0 -1 0 0.633989 0 0.7733421 0.4707518 0 0.8822656 0.7071079 0 0.7071056 0.7071079 0 0.7071056 0.633989 0 0.7733421 0.7071065 0 -0.7071071 0.7071068 0 0.7071068 0.7071065 0 -0.7071071 -0.7071068 0 0.7071067 0.7071068 0 0.7071068 0.7071065 0 0.707107 -0.7071068 0 0.7071067 -0.7071402 0 -0.7070735 -0.8662346 0 -0.4996374 -0.8662346 0 -0.4996374 -0.7071402 0 -0.7070735 -0.4995903 0 -0.8662618 0 0 -1 -0.4995903 0 -0.8662618 0.4995903 0 -0.8662618 0 0 -1 0.7071134 0 -0.7071001 0.4995903 0 -0.8662618 0.8662328 0 -0.4996407 0.7071135 0 -0.7071001 1 0 0 0.8662328 0 -0.4996407 0.8662346 0 0.4996374 1 0 0 0.7071043 0 0.7071091 0.7071043 0 0.7071091 0.8662346 0 0.4996374 0.4996374 0 0.8662346 0 0 1 0.4996374 0 0.8662346 -0.4995959 0 0.8662585 0 0 1 -0.707113 0 0.7071006 -0.4995959 0 0.8662586 -0.8662346 0 0.4996374 -0.707113 0 0.7071006 -1 0 0 -0.8662346 0 0.4996374 -1 0 0 0.4995903 0 0.8662618 0.7071068 0 0.7071068 0 0 1 0.4995903 0 0.8662618 -0.499632 0 0.8662378 0 0 1 -0.7071057 0 0.7071079 -0.499632 0 0.8662378 -0.8662407 0 0.4996271 -0.7071056 0 0.7071079 -1 0 7.35186e-6 -0.8662407 0 0.4996271 0 -1 0 -0.8662438 0 -0.4996215 -1 0 7.35186e-6 0 -1 0 -0.707102 0 -0.7071115 3.34901e-6 -1 -5.80647e-6 -0.707102 0 -0.7071115 -0.8662438 0 -0.4996215 0 -1 -1.53547e-7 -0.499639 0 -0.8662338 0 -1 -1.5355e-7 0 -1 -3.67524e-7 0 -1 -3.67533e-7 7.35175e-6 0 -1 -0.499639 0 -0.8662338 3.35071e-6 -1 -5.80928e-6 0.4996334 0 -0.8662369 0 -1 0 7.35175e-6 0 -1 0.7071053 0 -0.7071083 0 -1 0 0.4996334 0 -0.8662369 0.8662328 0 -0.4996407 0.7071053 0 -0.7071083 1 0 0 0.8662328 0 -0.4996407 0.8662346 0 0.4996374 1 0 0 0.7071068 0 0.7071068 0.8662346 0 0.4996374 -0.707102 0 -0.7071116 -0.8662438 0 -0.4996215 -0.8662438 0 -0.4996215 -0.707102 0 -0.7071116 -0.4996334 0 -0.866237 0 0 -1 -0.4996334 0 -0.866237 0.4996334 0 -0.8662369 0 0 -1 0.707107 0 -0.7071066 0.4996334 0 -0.8662369 0.8662388 0 -0.4996303 0.707107 0 -0.7071066 1 0 0 0.8662389 0 -0.4996302 0.8662402 0 0.4996279 1 0 0 0.7071092 0 0.7071044 0.7071092 0 0.7071044 0.8662402 0 0.4996279 0.4996215 0 0.8662438 0 0 1 0.4996215 0 0.8662438 -0.4996247 0 0.8662421 0 0 1 -0.707107 0 0.7071066 -0.4996247 0 0.8662421 -0.8662407 0 0.4996271 -0.707107 0 0.7071066 -1 0 7.35186e-6 -0.8662407 0 0.4996271 -1 0 7.35186e-6 0.4996271 0 0.8662407 0.7071068 0 0.7071068 0 0 1 0.4996271 0 0.8662407 -0.4996325 0 0.8662374 0 0 1 -0.7071054 0 0.7071081 -0.7071054 0 0.7071082 -0.4996325 0 0.8662374 -0.8662454 0 0.4996187 -1 0 1.10278e-5 -0.8662455 0 0.4996187 -0.8662407 0 -0.4996271 -1 0 1.10278e-5 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.8662407 0 -0.4996271 -0.4996286 0 -0.8662397 0 0 -1 -0.4996286 0 -0.8662397 0.4996302 0 -0.8662389 0 0 -1 0.7071059 0 -0.7071077 0.7071058 0 -0.7071077 0.4996303 0 -0.8662388 0.8662374 0 -0.4996325 1 0 7.35186e-6 0.8662374 0 -0.4996325 0.8662438 0 0.4996215 1 0 7.35186e-6 0.7071068 0 0.7071068 0.8662438 0 0.4996215 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071067 0 -0.7071067 -0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0 1 0 -3.04477e-6 1 2.66365e-6 6.8737e-7 1 -3.58217e-7 0 1 0 -8.84121e-7 1 5.19884e-7 0 1 0 0 1 0 2.01623e-7 1 2.01623e-7 2.36685e-7 1 0 2.66222e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.05945e-7 -1.32451e-7 1 2.29636e-7 9.18969e-7 1 0 -1.67525e-7 1 3.2957e-7 4.97434e-7 1 -2.52848e-7 -1.30337e-7 1 2.95378e-7 0 1 0 9.07832e-7 1 -6.50496e-7 -6.57638e-7 1 7.46478e-7 0 1 0 0 1 0 0 1 0 3.15168e-7 1 0 -2.68754e-7 1 9.18935e-7 4.21651e-7 1 -2.43207e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.45697e-7 1 2.45697e-7 2.45697e-7 1 2.45697e-7 1.46795e-6 1 2.31588e-7 8.07304e-7 1 4.65647e-7 2.72316e-7 1 2.72291e-7 1.42386e-7 1 2.4689e-7 -2.7493e-7 1 2.74925e-7 -1.2963e-7 1 2.24772e-7 0 1 1.99472e-7 0 1 0 -2.87934e-5 1 -3.52922e-6 0 1 0 0 1 0 6.32858e-7 1 -3.21617e-7 0 1 1.8458e-7 -3.11704e-7 1 4.59733e-7 -2.52176e-7 1 4.37211e-7 9.1903e-7 1 1.55969e-7 0 1 0 8.81752e-7 1 -5.24263e-7 0 1 0 -8.58293e-7 1 5.45612e-7 3.11815e-7 1 0 3.01987e-7 1 0 2.01629e-7 1 2.01624e-7 2.91951e-6 1 4.60411e-7 2.19181e-7 1 2.19181e-7 5.15478e-7 1 2.97311e-7 1.18438e-6 1 -6.01949e-7 0 1 1.76946e-7 -2.74917e-7 1 2.74919e-7 -1.24384e-7 1 2.1565e-7 0 1 1.83214e-7 1.93588e-6 1 -1.6129e-6 0 1 2.41203e-7 0 1 0 0 1 1.36257e-7 -6.58793e-7 1 7.45211e-7 4.05591e-7 1 -1.84331e-7 -1.59523e-7 1 9.18984e-7 4.64671e-7 1 -2.68011e-7 0 1 0 0 1 0 1.80683e-7 1 1.9762e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.08622e-7 2.02795e-6 1 1.52774e-6 2.20714e-7 1 4.12397e-7 7.01172e-7 1 8.56477e-7 0 1 0 4.61594e-6 1 4.61523e-6 2.24552e-6 1 2.35393e-6 -2.9389e-7 1 -1.57258e-7 2.38714e-7 1 2.62155e-7 -1.5852e-7 1 0 0 1 0 8.58229e-7 1 8.86623e-7 0 1 0 1.85269e-7 1 1.91399e-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 3.08653e-7 4.02937e-7 1 5.03501e-7 2.20626e-7 1 4.12315e-7 7.01149e-7 1 8.56453e-7 -9.83116e-7 1 -8.04985e-7 4.60046e-6 1 4.60036e-6 2.24487e-6 1 2.35326e-6 4.90909e-7 1 5.14612e-7 -2.19042e-7 1 0 -1.38005e-7 1 0 0 1 0 1.20088e-6 1 8.5317e-7 0 1 0 0 1 0 0 1 0 0 1 1.54433e-7 0 1 0 2.6114e-7 1 2.77982e-7 0 1 2.14641e-7 5.97884e-7 1 5.97871e-7 -1.47595e-7 1 0 0 1 1.28674e-7 2.21615e-7 1 3.30002e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.28672e-7 -1.47595e-7 1 0 0 1 0 1.0763e-6 1 1.07628e-6 -2.42026e-7 1 0 2.20269e-7 1 3.24191e-7 1.56084e-7 1 2.29724e-7 0 1 0 0 1 0 0 1 1.23009e-7 0 1 0 3.09879e-7 1 3.09831e-7 0 1 0 0 1 0 0 1 0 0 1 1.28674e-7 -1.47595e-7 1 0 -2.93745e-7 1 0 1.84616e-7 1 2.30692e-7 -1.23396e-7 1 0 0 1 0 0 1 1.61267e-7 0 1 1.4061e-7 2.91161e-7 1 2.91116e-7 -1.47595e-7 1 0 0 1 1.28672e-7 0 1 1.64305e-7 0 1 0 0 1 0 0 1 0 1.72677e-7 1 2.12328e-7 0 1 1.41808e-7 6.20464e-7 1 6.20451e-7 5.82579e-7 1 5.8249e-7 0 1 0 3.08993e-6 1 2.59519e-6 0 1 0 4.76438e-7 1 6.01454e-7 0 1 0 0 1 0 0 1 0 0 1 0 -5.41318e-7 1 -3.61603e-7 1.33758e-7 1 1.38509e-7 0 1 0 -1.04247e-6 1 -2.07371e-7 0 1 2.02128e-7 -3.74719e-7 1 0 5.27705e-7 1 5.6724e-7 0 1 0 0 1 0 -1.20474e-7 1 0 0 1 0 1.25389e-7 1 1.87706e-7 -2.34667e-7 1 -1.56776e-7 0 1 0 -3.26493e-7 1 0 0 1 0 -1.75553e-7 1 0 0 1 1.90022e-7 -1.98e-7 1 0 -1.35165e-7 1 1.64876e-7 0 1 3.38918e-7 1.72992e-6 1 1.72989e-6 0 1 1.65709e-7 3.24008e-7 1 0 0 1 1.90547e-7 0 1 1.82741e-7 0 1 1.62675e-7 -1.28725e-6 1 6.54211e-7 0 1 1.90103e-7 0 1 1.55138e-7 0 1 2.26084e-7 0 1 1.83634e-7 1.58174e-7 1 1.58174e-7 -4.4312e-7 1 0 0 1 1.80011e-7 -1.25228e-7 1 2.46396e-7 -8.76023e-7 1 4.45223e-7 0 1 2.17996e-7 2.06645e-7 1 2.06645e-7 0 1 0 1.77469e-7 1 2.06305e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.47021e-7 0 1 0 0 1 0 0 1 0 0 1 1.24399e-7 0 1 1.82565e-7 -1.45442e-7 1 2.86168e-7 -1.95182e-7 1 0 0 1 2.43515e-7 0 1 1.99381e-7 1.50114e-7 1 1.50115e-7 -1.29177e-7 1 0 0 1 0 0 1 1.29702e-7 0 1 1.86848e-7 0 1 0 0 1 0 0 1 0 -2.37609e-6 1 -2.26294e-6 0 1 0 0 1 1.99512e-7 1.28871e-7 1 1.68636e-7 1.69026e-7 1 1.69026e-7 -4.11798e-7 1 0 1.20809e-7 1 2.75839e-7 0 1 1.82118e-7 -2.36242e-7 1 1.20065e-7 2.39027e-7 1 2.39023e-7 0 1 0 2.39018e-7 1 2.39018e-7 7.5615e-7 1 3.98796e-7 0 1 0 0 1 0 0 1 1.99886e-7 1.81083e-7 1 2.38984e-7 3.31096e-7 1 3.31092e-7 -4.95632e-7 1 0 -5.4572e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 1.20308e-7 1.98562e-7 1 2.26413e-7 0 1 1.50025e-7 1.65888e-7 1 2.28893e-7 0 1 0 2.45024e-6 1 1.83353e-6 0 1 0 0 1 0 0 1 0 -1.22423e-7 1 0 2.0533e-7 1 2.08746e-7 0 1 0 0 1 1.29078e-7 0 1 1.57076e-7 0 1 2.09637e-7 2.85783e-7 1 3.94328e-7 0 1 0 5.44427e-7 1 6.21058e-7 0 1 0 0 1 0 0 1 0 0 1 0 -1.78213e-6 1 -1.46101e-6 -2.40655e-7 1 0 -3.46435e-7 1 0 0 1 2.21098e-7 -2.51617e-7 1 0 -3.58991e-7 1 0 -5.94946e-7 1 -3.17446e-7 0 1 0 0 1 1.20731e-7 0 1 1.35451e-7 0 1 1.48581e-7 -2.13615e-7 1 0 -2.87616e-7 1 0 2.4792e-7 1 3.13923e-7 -8.56983e-6 1 -6.52409e-6 0 1 0 -2.58385e-7 1 -1.81755e-7 0 1 2.6502e-7 -1.82737e-7 1 3.16819e-7 9.18973e-7 1 -5.37566e-7 -1.57521e-7 1 2.68972e-7 -2.20038e-7 1 1.26914e-7 0 1 0 8.64652e-7 1 3.47636e-7 0 1 0 0 1 0 0 1 0 0 1 1.71637e-7 0 1 1.67694e-7 -6.46227e-7 1 -5.69597e-7 -3.1078e-7 1 -1.79255e-7 -1.71269e-7 1 0 3.42351e-7 1 8.67741e-7 1.24561e-7 1 1.98066e-7 0 1 0 2.00575e-7 1 2.59142e-7 0 1 0 0 1 0 0 1 0 -2.09803e-7 1 0 0 1 1.29517e-7 9.23476e-7 1 9.23509e-7 2.42074e-7 1 3.6929e-7 -2.71218e-7 1 1.56436e-7 0 1 0 7.94019e-7 1 4.69998e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.30065e-7 -1.75894e-7 1 3.04963e-7 9.18982e-7 1 -5.55992e-7 -2.23991e-7 1 -1.29192e-7 -1.50842e-7 1 0 2.25186e-7 1 9.35274e-7 0 1 0 0 1 0 0 1 1.66007e-7 1.3187e-7 1 1.65637e-7 0 1 1.56476e-7 0 1 0 0 1 0 5.80806e-6 1 -3.34998e-6 0 1 0 0 1 0 -2.22032e-6 1 9.18982e-7 -2.22037e-6 1 9.18999e-7 5.80699e-6 1 -3.34933e-6 0 1 0 0 1 0 0 -1 -1.60838e-7 -0.4530818 2.51903e-6 -0.891469 1.18438e-6 -1 6.01952e-7 -0.891469 0 -0.4530818 -1.29494e-7 -1 -2.0484e-7 0 -1 -1.59749e-7 -0.8914722 1.28026e-6 -0.4530754 0 -1 0 0.1557673 0 -0.9877937 -0.4530692 0 -0.8914754 0 -1 0 0.7071107 0 -0.7071028 0.1557673 0 -0.9877937 -2.91437e-7 -1 0 0.9877924 0 -0.1557764 0 -1 -2.27467e-7 0 -1 -1.63254e-7 -1.56409e-7 -1 -2.21533e-7 0 -1 0 0 -1 0 0.7071107 0 -0.7071028 -1.82492e-7 -1 0 0.8914641 0 0.4530913 0 -1 -1.62756e-7 0.9877924 0 -0.1557764 0 -1 -1.62756e-7 0.4530818 0 0.891469 -1.82494e-7 -1 0 0.8914641 0 0.4530913 0 -1 -2.2746e-7 -0.1557608 0 0.9877948 -2.91433e-7 -1 0 0.4530818 0 0.891469 2.01626e-7 -1 -2.01623e-7 -0.7071107 0 0.7071028 0 -1 -1.45102e-7 -0.1557608 0 0.9877948 2.91958e-6 -1 -4.60422e-7 -0.9877924 0 0.1557764 5.15464e-7 -1 -2.97308e-7 2.19183e-7 -1 -2.19182e-7 -0.7071107 0 0.7071028 -2.7492e-7 -1 -2.7492e-7 -1.24384e-7 -1 -2.1565e-7 0 -1 -1.83214e-7 0 -1 -1.76946e-7 -0.9877924 0 0.1557764 0 -1 0 -0.4531325 0 -0.8914431 3.16431e-7 -1 1.60811e-7 -0.8914833 0 -0.4530535 2.01739e-7 -1 0 -0.8914833 0 -0.4530535 0 -1 0 0.1558416 0 -0.9877821 -0.4531325 0 -0.8914431 0 -1 0 0.7070552 0 -0.7071585 0.1558416 0 -0.9877821 -3.27848e-7 -1 0 0.9877991 0 -0.1557337 0 -1 -2.55886e-7 0 -1 -1.75365e-7 0 -1 0 0 -1 0 0.7070552 0 -0.7071585 -2.05314e-7 -1 0 0.8914882 0 0.4530439 0 -1 -1.83106e-7 0.9877991 0 -0.1557337 0 -1 -1.83103e-7 0.4530907 0 0.8914645 -2.05297e-7 -1 0 0.8914882 0 0.4530439 0 -1 -2.55918e-7 -0.1558416 0 0.9877821 -3.2785e-7 -1 0 0.4530907 0 0.8914645 2.41249e-7 -1 -2.41249e-7 -0.7071068 0 0.7071068 0 -1 -1.66765e-7 -0.1558416 0 0.9877821 6.59443e-6 -1 -1.03971e-6 -0.987798 0 0.1557403 6.59504e-7 -1 -3.80349e-7 2.63757e-7 -1 -2.63734e-7 -0.7071068 0 0.7071068 -2.03462e-7 -1 -2.69251e-7 -1.41834e-7 -1 -2.45932e-7 0 -1 -2.11873e-7 1.19759e-7 -1 -2.07656e-7 -0.987798 0 0.1557403 -0.4530503 0 -0.8914849 -0.8914431 0 -0.4531325 -0.8914431 0 -0.4531325 0.1557403 0 -0.987798 -0.4530503 0 -0.8914849 2.76476e-7 -1 -2.76436e-7 0.7071585 0 -0.7070552 0.1557403 0 -0.987798 0 -1 0 0.9877808 0 -0.1558498 3.0628e-7 -1 -3.06305e-7 -1.19029e-6 -1 0 9.08563e-7 -1 -5.23994e-7 0.7071585 0 -0.7070552 5.59411e-7 -1 2.84318e-7 0.8914677 0 0.4530844 2.89621e-7 -1 0 0 -1 0 0 -1 0 0.9877808 0 -0.1558498 0 -1 -1.96131e-7 0.4530439 0 0.8914882 -1.83603e-7 -1 -2.733e-7 0 -1 -1.65357e-7 0.8914677 0 0.4530844 0 -1 0 -0.1557325 0 0.9877992 0.4530439 0 0.8914882 0 -1 0 -0.7071108 0 0.7071028 -0.1557325 0 0.9877992 -0.9877979 0 0.1557415 -2.17887e-7 -1 -2.93332e-7 0 -1 0 0 -1 0 -0.7071108 0 0.7071028 -0.9877979 0 0.1557415 -0.453085 0 -0.8914673 -0.8914707 0 -0.4530786 -0.8914707 0 -0.4530786 0.1557829 0 -0.9877914 -0.453085 0 -0.8914673 2.75852e-7 -1 -2.75852e-7 0.7071068 0 -0.7071068 0.1557829 0 -0.9877914 0 -1 0 0.9877936 0 -0.1557686 3.09809e-7 -1 -3.09809e-7 -1.09439e-6 -1 0 1.12642e-6 -1 -6.49688e-7 0.7071068 0 -0.7071068 3.28967e-7 -1 1.67192e-7 0.8914721 0 0.4530755 2.04947e-7 -1 0 0 -1 0 0 -1 0 0.9877936 0 -0.1557686 -1.21449e-7 -1 -2.38959e-7 0.4530818 0 0.891469 -3.54972e-7 -1 -3.86586e-7 0.8914721 0 0.4530755 0 -1 -1.5385e-7 -0.1557673 0 0.9877937 0.4530818 0 0.891469 0 -1 0 -0.7071068 0 0.7071068 -0.1557673 0 0.9877937 -0.9877937 0 0.1557673 -1.29039e-7 -1 -2.11507e-7 0 -1 0 -0.7071068 0 0.7071068 -0.9877937 0 0.1557673 0 -1 0 -0.6332194 0 -0.7739723 0 -1 0 -0.7740247 0 -0.6331554 -0.7740247 0 -0.6331554 0 -1 -1.43655e-7 -0.4709547 0 -0.8821574 1.60364e-7 -1 -2.83351e-7 -0.6332194 0 -0.7739723 0 -1 -1.6273e-7 -0.2906793 0 -0.9568206 -0.4709547 0 -0.8821574 0 -1 -1.88109e-7 -0.09689986 0 -0.9952942 -0.2906793 0 -0.9568206 0 -1 -2.25244e-7 0.09689092 0 -0.9952951 -0.09689986 0 -0.9952942 0 -1 0 0.2907049 0 -0.9568128 -5.31343e-7 -1 3.34916e-7 0.09689092 0 -0.9952951 0 -1 0 0.4717953 0 -0.8817082 0.2907049 0 -0.9568128 0 -1 0 0.6335269 0 -0.7737206 0.4717953 0 -0.8817082 1.51992e-5 -1 -1.38418e-5 0.7737721 0 -0.633464 -2.64741e-6 -1 2.52548e-6 0 -1 -1.47271e-7 0 -1 0 0.6335269 0 -0.7737206 -4.38089e-7 -1 2.34418e-7 0.8817081 0 -0.4717952 0.7737721 0 -0.6334641 -2.76047e-7 -1 0 0.9567817 0 -0.2908075 0.8817082 0 -0.4717952 -2.11994e-7 -1 0 0.9952952 0 -0.09688943 0.9567817 0 -0.2908075 -2.14824e-7 -1 0 0.9952942 0 0.09689986 0 -1 0 0.9952952 0 -0.09688943 -1.7109e-7 -1 0 0.9568073 0 0.2907232 0.9952942 0 0.09689986 -1.41726e-7 -1 0 0.8821393 0 0.4709885 0.9568073 0 0.2907232 0 -1 0 0.7740173 0 0.6331645 0.8821393 0 0.4709885 0 -1 0 0.6331645 0 0.7740173 0 -1 0 0.7740173 0 0.6331645 7.25795e-7 -1 -7.08753e-7 0.4709611 0 0.882154 0.6331645 0 0.7740173 0 -1 0 0.2906792 0 0.9568206 0.4709611 0 0.882154 -8.95666e-7 -1 7.65211e-7 0.09689986 0 0.9952942 0.2906792 0 0.9568206 0 -1 -1.8428e-7 -0.09678232 0 0.9953056 0 -1 -1.28092e-7 0.09689986 0 0.9952942 0 -1 -3.08656e-7 -0.2908075 -1.89251e-5 0.9567817 9.65992e-7 -1 -8.58413e-7 -0.09688943 -1.96869e-5 0.9952952 2.20628e-7 -1 -4.12317e-7 -0.4717952 0 0.8817082 -0.2907091 0 0.9568114 7.01172e-7 -1 -8.56477e-7 -0.633464 0 0.7737721 -0.4717952 0 0.8817082 -1.08773e-6 -1 8.90487e-7 -0.7737735 0 0.6334624 -4.02548e-7 -1 1.72226e-7 4.59579e-6 -1 -4.59589e-6 -0.633464 0 0.7737721 -6.24515e-7 -1 3.34173e-7 -0.8817082 0 0.4717952 -4.71276e-7 -1 2.13501e-7 -0.7737735 0 0.6334624 -3.36835e-7 -1 0 -0.9567907 1.31737e-5 0.2907776 -0.8816872 8.10685e-6 0.4718344 -2.44278e-7 -1 0 -0.9952942 0 0.09689986 -0.9568115 0 0.2907091 8.72388e-7 -1 -1.00639e-6 -0.9952952 0 -0.09688943 -0.9952942 0 0.09689986 0 -1 0 -0.9568114 0 -0.2907091 0 -1 0 -0.9952952 0 -0.09688943 0 -1 0 -0.8821121 0 -0.4710395 -0.9568114 0 -0.2907091 -0.8821121 0 -0.4710395 0 -1 0 -0.4530217 0 -0.8914995 0 -1 0 -0.8914995 0 -0.4530217 -0.8914995 0 -0.4530217 0 -1 -1.23012e-7 0.1557544 0 -0.9877958 0 -1 0 -0.4530217 0 -0.8914995 3.09715e-7 -1 -3.09722e-7 0.7070991 0 -0.7071145 0.1557544 0 -0.9877958 -3.13638e-7 -1 0 0.9877962 0 -0.155752 0 -1 -2.73437e-7 0.7070991 0 -0.7071145 7.19185e-7 -1 -8.50959e-7 0.8914901 0 0.4530402 0 -1 -1.75171e-7 0.9877962 0 -0.155752 0 -1 0 0.4530403 0 0.8914902 0 -1 0 0.8914902 0 0.4530403 0 -1 -1.28676e-7 -0.155752 0 0.9877962 -1.47595e-7 -1 0 0.4530403 0 0.8914902 -1.11085e-5 -1 9.5782e-6 -0.7071144 0 0.7070991 0 -1 -2.10445e-7 -0.155752 0 0.9877962 -2.42026e-7 -1 0 -0.9877958 0 0.1557544 3.0592e-7 -1 -4.5026e-7 1.56079e-7 -1 -2.29721e-7 -0.7071145 0 0.7070991 -0.9877958 0 0.1557544 -0.4530217 0 -0.8914995 -0.8914995 0 -0.4530217 -0.8914995 0 -0.4530217 0.1557544 0 -0.9877958 -0.4530217 0 -0.8914995 0.7070991 0 -0.7071145 0.1557544 0 -0.9877958 -2.19406e-7 -1 0 0.9877962 0 -0.155752 0.7070991 0 -0.7071145 0 -1 0 0.8914711 0 0.4530776 0.9877962 0 -0.155752 0 -1 -1.23542e-7 0.4531137 0 0.8914527 0 -1 -1.31386e-7 0.8914711 0 0.4530776 0 -1 -1.71718e-7 -0.155752 0 0.9877962 0.4531137 0 0.8914527 4.78329e-7 -1 -4.78319e-7 -0.7071145 0 0.7070991 -0.155752 0 0.9877962 -0.9877958 0 0.1557544 -0.7071145 0 0.7070991 -0.9877958 0 0.1557544 0 -1 0 -0.4530217 0 -0.8914995 0 -1 0 -0.8914995 0 -0.4530217 0 -1 0 -0.8914995 0 -0.4530217 0 -1 -1.44761e-7 0.1557544 0 -0.9877958 -1.66044e-7 -1 0 -0.4530217 0 -0.8914995 9.45855e-7 -1 -9.45876e-7 0.7070991 0 -0.7071145 3.53975e-7 -1 -4.75909e-7 0.1557544 0 -0.9877958 -2.11415e-7 -1 0 0.9877962 0 -0.155752 1.14059e-6 -1 -1.10219e-6 0.7070991 0 -0.7071145 0 -1 0 0.8914712 0 0.4530776 0.9877962 0 -0.155752 0 -1 -1.87405e-7 0.4531137 0 0.8914528 0 -1 -2.68443e-7 0.8914712 0 0.4530776 0 -1 -2.83625e-7 -0.155752 0 0.9877962 0.4531137 0 0.8914528 1.24102e-6 -1 -1.24099e-6 -0.7071145 0 0.7070991 -0.155752 0 0.9877962 -1.66044e-7 -1 0 -0.9877958 0 0.1557544 0 -1 -1.44761e-7 -0.7071145 0 0.7070991 0 -1 0 -0.9877958 0 0.1557544 0 -1 -1.29812e-7 -0.4530217 0 -0.8914995 6.79425e-7 -1 -7.36004e-7 -0.8914995 0 -0.4530217 -0.8914995 0 -0.4530217 0 -1 -1.81427e-7 0.1557544 0 -0.9877958 0 -1 -1.58187e-7 -0.4530217 0 -0.8914995 -2.33209e-6 -1 9.72057e-7 0.7070991 0 -0.7071145 0.1557544 0 -0.9877958 0.9877962 0 -0.155752 0.7070991 0 -0.7071145 0.8914901 0 0.4530402 0.9877962 0 -0.155752 0.4530402 0 0.8914901 0.8914901 0 0.4530402 -0.155752 0 0.9877962 0.4530402 0 0.8914901 -0.7071145 0 0.7070991 -0.155752 0 0.9877962 -6.24208e-7 -1 0 -0.9877958 0 0.1557544 0 -1 -2.06039e-7 -0.7071145 0 0.7070991 -0.9877958 0 0.1557544 0 -1 0 -0.5555109 0 -0.8315092 0 -1 0 -0.8315077 0 -0.5555132 -0.8315077 0 -0.5555132 0 -1 0 -0.1950998 0 -0.9807834 -1.35534e-7 -1 0 -0.5555109 0 -0.8315092 0 -1 -1.21224e-7 0.1950887 0 -0.9807857 -0.1950998 0 -0.9807834 -1.37239e-6 -1 9.52862e-7 0.5555109 0 -0.8315092 0.1950887 0 -0.9807857 -1.87732e-7 -1 1.2542e-7 0.8315078 0 -0.5555132 1.98452e-7 -1 -3.42792e-7 0.5555109 0 -0.8315092 -2.61163e-7 -1 0 0.9807961 0 -0.195036 0 -1 0 0.8315078 0 -0.5555132 -1.40452e-7 -1 0 0.9807991 0 0.195021 0.9807961 0 -0.195036 0 -1 0 0.8315048 0 0.5555178 0.9807991 0 0.195021 0 -1 0 0.5554704 0 0.8315364 0 -1 -1.20371e-7 0.8315048 0 0.5555178 0 -1 -1.38572e-7 0.1950793 0 0.9807874 0.5554704 0 0.8315364 0 -1 -1.88309e-7 -0.1950905 0 0.9807852 0.1950793 0 0.9807874 2.89281e-7 -1 -4.33053e-7 -0.5554704 0 0.8315364 -0.1950905 0 0.9807852 -4.33055e-7 -1 2.89283e-7 -0.8315364 0 0.5554704 0 -1 0 0 -1 0 -0.5554704 0 0.8315364 -9.84801e-7 -1 1.95944e-7 -0.9807748 0 0.1951432 0 -1 -2.08147e-7 -0.8315364 0 0.5554704 6.48201e-7 -1 -4.93449e-7 -0.9807848 0 -0.1950923 -0.9807747 0 0.1951432 -0.9807848 0 -0.1950923 0 -1 0 -0.4530707 0 -0.8914747 0 -1 0 -0.8914738 0 -0.4530723 -0.8914738 0 -0.4530723 0 -1 0 0.1557611 0 -0.9877948 0 -1 0 -0.4530707 0 -0.8914747 0 -1 0 0.7071068 0 -0.7071068 0.1557611 0 -0.9877948 0 -1 0 0.987795 0 -0.1557596 0 -1 0 0.7071068 0 -0.7071068 4.14764e-6 -1 9.91772e-7 0.8914747 0 0.4530707 -1.67676e-7 -1 -2.42604e-7 0.987795 0 -0.1557596 0 -1 -1.23198e-7 0.4530738 0 0.8914729 0.8914746 0 0.4530707 0 -1 0 -0.1557611 0 0.9877947 0.4530738 0 0.8914729 -1.21387e-6 -1 -1.9012e-7 -0.7071068 0 0.7071068 -0.1557611 0 0.9877947 0 -1 0 -0.9877948 0 0.1557609 0 -1 0 1.77469e-7 -1 -2.06305e-7 -0.7071068 0 0.7071068 0 -1 0 -0.9877948 0 0.1557609 0 -1 0 -0.4530707 0 -0.8914747 8.13506e-6 -1 2.87876e-6 -0.8914746 0 -0.4530707 -0.8914747 0 -0.4530707 0 -1 0 0.1557589 0 -0.9877952 -0.4530707 0 -0.8914747 -1.24044e-6 -1 -3.39073e-7 0.7071127 0 -0.7071009 0.1557589 0 -0.9877952 0 -1 0 0.9877932 0 -0.1557713 2.63831e-7 -1 -1.56432e-7 0.7071127 0 -0.7071008 0 -1 0 0.8914702 0 0.4530794 0.9877932 0 -0.1557713 0 -1 0 0.4530707 0 0.8914747 0 -1 0 0.8914702 0 0.4530794 0 -1 0 -0.1557608 0 0.9877949 0.4530707 0 0.8914747 0 -1 0 -0.7071068 0 0.7071068 0 -1 0 -0.1557608 0 0.9877948 0 -1 0 -0.987795 0 0.1557593 0 -1 0 0 -1 0 0 -1 0 -0.7071068 0 0.7071068 0 -1 0 -1.35007e-6 -1 -6.88467e-7 -0.987795 0 0.1557593 0 -1 0 -0.4530739 0 -0.891473 0 -1 0 -0.8914698 0 -0.4530802 -0.8914698 0 -0.4530802 0 -1 0 0.1557725 0 -0.987793 0 -1 0 -0.4530739 0 -0.891473 0 -1 0 0.7071028 0 -0.7071107 0.1557725 0 -0.987793 1.87438e-6 -1 -1.4324e-6 0.9877929 0 -0.1557731 -1.51906e-6 -1 7.65217e-7 0.7071028 0 -0.7071107 0 -1 0 0.8914697 0 0.4530801 0.9877929 0 -0.1557731 0 -1 0 0.4530801 0 0.8914697 6.80031e-7 -1 -7.70547e-7 7.96562e-7 -1 -8.87079e-7 0.8914697 0 0.4530801 0 -1 -1.87942e-7 -0.1557725 0 0.987793 -2.06684e-7 -1 0 0.4530801 0 0.8914697 -3.13335e-6 -1 1.55389e-6 -0.7071009 0 0.7071128 -1.41995e-7 -1 0 -0.1557725 0 0.987793 0 -1 0 -0.9877932 0 0.1557713 1.28548e-6 -1 -6.77961e-7 4.06332e-7 -1 -4.06332e-7 -0.7071009 0 0.7071127 -0.9877932 0 0.1557713 0 -1 0 -0.4530739 0 -0.891473 -0.8914697 0 -0.4530801 -2.36024e-6 -1 2.1194e-6 -0.8914698 0 -0.4530802 0 -1 0 0.1557725 0 -0.987793 0 -1 0 -0.4530739 0 -0.891473 -1.07417e-6 -1 -3.29826e-7 0.7071009 9.99045e-7 -0.7071127 0.1557647 1.39561e-6 -0.9877942 0 -1 0 0.9877936 0 -0.1557686 0 -1 0 0 -1 -1.61883e-7 0.7071048 0 -0.7071088 0 -1 0 0.8914698 0 0.4530802 0.9877936 0 -0.1557686 0 -1 0 0.4530802 0 0.8914698 0 -1 0 0.8914698 0 0.4530802 0 -1 0 -0.1557731 0 0.9877929 0.4530802 0 0.8914698 0 -1 0 -0.7071009 0 0.7071128 -0.1557731 0 0.9877929 -0.9877932 -3.30122e-7 0.1557713 0 -1 0 -0.7071068 -1.49855e-6 0.7071068 -0.9877929 0 0.1557731 0 -1 0 -0.5867161 0 -0.8097927 -1.22425e-7 -1 0 -0.8097903 0 -0.5867193 -0.8097903 0 -0.5867193 0 -1 -1.29078e-7 -0.3066868 0 -0.9518104 -0.5867161 0 -0.8097927 0 -1 -1.57078e-7 0 0 -1 -0.3066868 0 -0.9518104 0 -1 -2.09638e-7 0.3074685 0 -0.9515582 0 0 -1 2.85772e-7 -1 -3.94317e-7 0.5868217 0 -0.8097162 0.3074685 0 -0.9515582 4.23677e-6 -1 -5.18171e-6 0.8097206 0 -0.5868155 -7.75328e-7 -1 5.35857e-7 0.5868217 0 -0.8097162 -5.70841e-7 -1 1.84452e-7 0.9515578 0 -0.3074703 0 -1 0 0.8097206 0 -0.5868155 -2.37252e-7 -1 0 1 0 0 0.9515578 0 -0.3074703 -1.54789e-7 -1 0 0.9518123 0 0.3066813 1 0 0 0 -1 0 0.8097898 0 0.5867201 0.9518123 0 0.3066813 0 -1 0 0.5867234 0 0.8097875 0.8097898 0 0.5867201 0 -1 -1.3995e-7 0.3066813 0 0.9518123 0.5867233 0 0.8097875 0 -1 -1.20308e-7 0 0 1 0 -1 0 0.3066813 0 0.9518123 0 -1 -1.50025e-7 -0.3074703 0 0.9515578 0 0 1 1.65886e-7 -1 -2.28891e-7 -0.5868275 0 0.809712 -0.3074703 0 0.9515578 -6.14565e-6 -1 4.45401e-6 -0.8097098 0 0.5868304 -7.07706e-7 -1 3.84761e-7 -0.5868275 0 0.809712 -3.64201e-7 -1 0 -0.9515583 0 0.3074685 -0.8097098 0 0.5868304 1.96218e-6 -1 -1.7208e-6 -1 0 0 -0.9515583 0 0.3074685 0 -1 0 -0.9518104 0 -0.3066868 -1 0 0 2.0533e-7 -1 -2.08746e-7 -0.9518104 0 -0.3066868 0 -1 0 0.633989 0 -0.7733421 -1.43165e-7 -1 -2.18093e-7 0.707107 0 -0.7071066 0 -1 0 0.4707503 0 -0.8822665 0.633989 0 -0.7733421 0 -1 0 0.2909934 0 -0.9567251 0.4707503 0 -0.8822665 0.09853333 0 -0.9951338 0.2909934 0 -0.9567251 0 0 -1 0 0 -1 0.09853333 0 -0.9951338 -0.09853333 0 -0.9951338 -0.2909913 0 -0.9567257 -0.09853333 0 -0.9951338 -0.4707487 0 -0.8822674 -0.2909913 0 -0.9567257 -0.6339947 0 -0.7733374 -0.4707487 0 -0.8822674 -0.7071066 0 -0.707107 -0.6339947 0 -0.7733374 -0.7801746 0 -0.6255619 -0.7071065 0 -0.707107 -1.8988e-7 -1 0 -0.8974827 0 -0.4410497 -0.7801746 0 -0.6255619 1.60296e-7 -1 -2.60354e-7 -0.9718871 0 -0.2354473 -0.8974827 0 -0.4410497 0 -1 0 -0.971888 0 -0.2354441 -8.63272e-7 -1 5.54546e-7 -0.9718871 0 -0.2354473 -0.8974827 0 -0.4410497 0 -1 0 -0.971888 0 -0.2354441 -0.7801736 0 -0.625563 -0.8974827 0 -0.4410497 -0.7071066 0 -0.707107 0 -1 -2.89373e-7 1.42644e-7 -1 0 0 -1 -1.8572e-7 0 -1 0 -2.96323e-6 -1 -2.32278e-6 -4.67588e-7 -1 -2.69694e-7 1.78765e-7 -1 -1.82494e-7 0 -1 -1.22448e-7 -1.03384e-6 -1 2.64817e-7 2.74538e-7 -1 -4.75983e-7 8.57357e-7 -1 -8.57357e-7 -0.7801736 0 -0.625563 0 -1 -2.27608e-7 -0.6534937 0 -0.7569319 0 -1 -2.07637e-7 -2.58729e-7 -1 0 -3.49629e-7 -1 2.01665e-7 -1.92677e-7 -1 0 -1.43641e-7 -1 0 -0.7071066 0 -0.707107 -0.5363547 0 -0.8439927 0 -1 0 -0.6534937 0 -0.7569319 -0.4084185 0 -0.9127948 -0.5363547 0 -0.8439927 -0.2712152 0 -0.9625188 -0.4084185 0 -0.9127948 -0.2994166 0 -0.9541224 -0.2712152 0 -0.9625188 -0.4876433 0 -0.8730429 -0.2994166 0 -0.9541224 -0.6553449 0 -0.7553297 -0.4876433 0 -0.8730429 -0.7955291 0 -0.6059156 -0.6553449 0 -0.7553297 -0.902306 0 -0.4310962 -0.795529 0 -0.6059156 -1.649e-7 -1 0 -0.9712273 0 -0.2381542 -0.902306 0 -0.4310962 1.36934e-7 -1 -2.6139e-7 -0.999377 0 -0.03529441 -2.96292e-7 -1 0 -0.9712273 0 -0.2381542 -2.01419e-7 -1 0 -0.9856038 0 0.1690714 0 -1 -1.50225e-7 -0.9993769 0 -0.03529441 3.20784e-7 -1 -4.47997e-7 -0.9304832 0 0.3663344 0 -1 -2.75225e-7 -0.9856038 0 0.1690714 0 -1 0 -0.8363298 0 0.5482267 -6.81437e-7 -1 5.54225e-7 -0.9304833 0 0.3663344 -0.7071217 0 0.7070919 -0.8363297 0 0.5482268 -0.5482039 0 0.8363447 -0.7071217 0 0.7070919 -0.3663359 0 0.9304828 -0.548204 0 0.8363447 -0.1690714 0 0.9856037 -0.3663359 0 0.9304828 0.03529018 -1.97676e-5 0.9993771 -0.1691004 -1.94951e-5 0.9855989 0.2381542 -1.64664e-5 0.9712273 0.03529441 -1.69436e-5 0.999377 0.4310881 0 0.9023098 0.2381783 0 0.9712213 0.6059278 0 0.7955197 0.4310881 0 0.9023098 0.7553298 0 0.6553449 0.6059279 0 0.7955197 0.8730447 0 0.4876401 0.7553297 0 0.6553449 0.954114 0 0.2994437 0.8730447 0 0.4876401 0.9625243 0 0.2711958 0.954114 0 0.2994437 0.9127943 0 0.4084196 0.9625242 0 0.2711958 0.8439936 0 0.5363534 0.9127943 0 0.4084197 0.7569313 0 0.6534945 0.8439935 0 0.5363533 0.707107 0 0.7071067 -2.7118e-7 -1 -1.56427e-7 1.20893e-7 -1 0 0 -1 0 0 -1 0 -1.93288e-6 -1 1.50433e-6 1.1145e-6 -1 -1.1145e-6 2.2493e-6 -1 1.61766e-6 0 -1 -1.71229e-7 1.8734e-6 -1 1.40131e-6 -9.18982e-7 -1 -7.94473e-7 0.7569313 0 0.6534947 0.6255611 0 0.7801752 -2.23991e-7 -1 1.29193e-7 -1.50843e-7 -1 0 -1.22448e-7 -1 0 0.7071069 0 0.7071067 0.4410492 0 0.8974829 0.6255611 0 0.7801752 0 -1 -1.43807e-7 0.2354495 0 0.9718866 4.30007e-7 -1 -4.30006e-7 0.4410492 0 0.8974829 0 -1 0 0.2354452 0 0.9718876 0 -1 0 0.2354495 0 0.9718866 0 -1 0 0.4410488 0 0.8974831 0.2354452 0 0.9718876 0.6255636 0 0.7801732 0.4410488 0 0.8974831 0.7071068 0 0.7071067 0.6255636 0 0.7801732 0.7733453 0 0.6339852 0.7071068 0 0.7071067 0.8822639 0 0.4707551 0.7733453 0 0.6339852 -2.40657e-7 -1 0 0.9567273 0 0.2909862 0.8822639 0 0.4707551 -3.46442e-7 -1 0 0.9951336 -1.39214e-7 0.0985341 0.9567266 -4.11123e-7 0.2909883 0 -1 -2.21098e-7 1 0 0 1 0 0 0.9951338 0 0.09853333 -2.51617e-7 -1 0 0.9951338 0 -0.09853333 -3.58998e-7 -1 0 0.9567266 0 -0.2909884 0.9951338 0 -0.09853333 -5.9495e-7 -1 3.17448e-7 0.8822656 0 -0.4707518 0.9567266 0 -0.2909884 -1.78207e-6 -1 1.46094e-6 0.7733421 0 -0.633989 0.8822656 0 -0.4707518 0.707107 0 -0.7071066 0.7071083 1.49855e-6 -0.7071052 0.7733374 1.34361e-6 -0.6339947 -0.7071067 0 -0.7071069 0.7071071 0 -0.7071064 -0.7071067 0 -0.7071069 0.7071068 0 0.7071067 0.7071072 0 -0.7071065 0.707107 0 -0.7071065 0.7071068 0 0.7071067 -0.7070782 0 0.7071354 -0.4995904 0 0.8662618 -0.4995903 0 0.8662618 -0.7070782 0 0.7071354 -0.8662585 0 0.4995959 -1 0 0 -0.8662585 0 0.4995959 -0.866217 0 -0.4996679 -1 0 0 -0.7071068 0 -0.7071068 -0.866217 0 -0.4996679 -0.4996374 0 -0.8662346 -0.7071068 0 -0.7071068 0 0 -1 -0.4996374 0 -0.8662346 0.4996374 0 -0.8662347 0 0 -1 0.7071068 1.39902e-5 -0.7071068 0.7070735 0 -0.7071402 0.4996374 0 -0.8662346 0.8662328 9.88285e-6 -0.4996407 1 0 0 0.8662585 0 -0.4995959 0.8662585 0 0.4995959 1 0 0 0.7071006 0 0.707113 0.8662585 0 0.4995959 0.4996319 0 0.8662378 0.7071006 0 0.707113 0 0 1 0.4996319 0 0.8662378 0 0 1 0.8662618 0 -0.4995903 0.7071377 0 -0.7070757 1 0 0 0.8662378 9.17376e-6 -0.4996319 0.8662359 0 0.4996351 1 0 0 0.7071086 0 0.7071049 0.8662359 0 0.4996351 0.4996302 0 0.8662389 0.7071086 0 0.7071049 7.3518e-6 0 1 0.4996302 0 0.8662389 -7.33523e-7 -1 -5.74984e-7 -0.4996302 -1.22387e-6 0.8662389 0 -1.41285e-6 1 0 -1 0 -0.7071068 0 0.7071068 5.80859e-6 -1 3.35029e-6 -0.7071068 0 0.7071068 -0.4996271 -5.1797e-7 0.8662406 1.53549e-7 -1 0 -0.8662388 0 0.4996303 1.53549e-7 -1 0 3.67526e-7 -1 0 3.67533e-7 -1 0 -1 0 -7.35181e-6 -0.8662388 0 0.4996303 5.80832e-6 -1 3.35013e-6 -0.8662389 0 -0.4996302 0 -1 0 -1 0 -7.3518e-6 -0.707109 0 -0.7071046 0 -1 0 -0.8662389 0 -0.4996302 -0.4995904 0 -0.8662618 -0.707109 0 -0.7071046 0 0 -1 -0.4995904 0 -0.8662618 0.4995903 0 -0.8662618 0 0 -1 0.7071377 0 -0.7070757 0.4995903 0 -0.8662618 -0.7071068 0 0.7071068 -0.4996271 0 0.8662407 -0.4996294 -5.17965e-7 0.8662393 -0.7071068 0 0.7071068 -0.866242 0 0.4996247 -1 0 0 -0.866242 0 0.4996247 -0.8662388 0 -0.4996302 -1 0 0 -0.707107 0 -0.7071066 -0.8662388 0 -0.4996302 -0.4996271 0 -0.8662407 -0.707107 0 -0.7071066 0 0 -1 -0.4996271 0 -0.8662407 0.4996302 0 -0.8662389 0 0 -1 0.7071068 -1.0072e-6 -0.7071068 0.7071092 0 -0.7071045 0.4996302 0 -0.8662389 0.8662407 -1.74184e-6 -0.4996271 1 0 0 0.8662343 7.05914e-7 -0.4996381 0.8662388 0 0.4996303 1 0 0 0.7071068 0 0.7071068 0.8662388 0 0.4996303 0.4996271 0 0.8662407 0.7071068 0 0.7071068 7.35186e-6 0 1 0.4996271 0 0.8662407 7.35186e-6 0 1 0.8662407 7.05899e-7 -0.4996271 0.7071092 1.00721e-6 -0.7071044 1 0 0 0.8662407 7.10164e-7 -0.4996271 0.8662407 0 0.4996271 1 0 0 0.7071077 0 0.7071058 0.7071077 0 0.7071058 0.8662407 0 0.4996271 0.4996187 0 0.8662455 1.10277e-5 0 1 0.4996187 0 0.8662455 -0.4996303 0 0.8662388 1.10277e-5 0 1 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.4996303 0 0.8662388 -0.8662407 0 0.4996271 -1 0 0 -0.8662407 0 0.4996271 -0.8662407 0 -0.4996271 -1 0 0 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.8662407 0 -0.4996271 -0.4996325 0 -0.8662374 0 0 -1 -0.4996325 0 -0.8662374 0.4996271 0 -0.8662407 0 0 -1 0.7071068 0 -0.7071068 0.4996271 0 -0.8662407 0.7071062 -1.49856e-6 0.7071074 0.7071078 0 -0.7071058 0.7071068 1.49855e-6 -0.7071068 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 0.7071068 -0.7071067 0 -0.7071067 0 1 0 1.77019e-7 1 3.48308e-7 3.73946e-7 1 5.91522e-7 0 1 0 0 1 0 0 1 2.9143e-7 2.27462e-7 1 0 1.45102e-7 1 0 0 1 0 0 1 0 0 1 1.82493e-7 1.62757e-7 1 0 1.62756e-7 1 0 0 1 1.82493e-7 2.27465e-7 1 0 0 1 2.91439e-7 0 1 0 0 1 3.04191e-7 0 1 0 0 1 0 0 1 0 0 1 0 -3.12994e-7 1 -2.47204e-7 -2.87044e-7 1 -1.65562e-7 0 1 1.14872e-6 -1.33372e-7 1 0 2.52866e-7 1 4.97462e-7 1.82625e-7 1 2.7591e-7 0 1 1.8012e-7 0 1 0 0 1 0 0 1 2.91468e-7 2.27455e-7 1 0 0 1 2.57802e-7 -1.99467e-7 1 -1.48164e-7 9.1903e-7 1 5.45947e-7 0 1 0 0 1 1.82493e-7 1.6275e-7 1 0 1.62762e-7 1 0 0 1 1.825e-7 2.27453e-7 1 0 0 1 2.91423e-7 0 1 0 0 1 2.8141e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.57452e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.48903e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.7442e-7 1 -1.58263e-7 0 1 0 0 1 0 0 1 0 9.19023e-7 1 5.12533e-7 2.01623e-7 1 -2.01623e-7 4.60468e-7 1 -2.92004e-6 2.19182e-7 1 -2.19182e-7 2.97309e-7 1 -5.15468e-7 0 1 0 1.76946e-7 1 0 0 1 0 0 1 0 2.39651e-7 1 9.18982e-7 -1.60835e-7 1 0 0 1 0 0 1 1.2204e-7 0 1 0 0 1 0 4.05866e-7 1 5.62001e-7 0 1 3.23736e-7 2.68012e-7 1 4.64673e-7 0 1 0 0 1 0 0 1 2.81729e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -6.69463e-7 1 1.06214e-6 -1.59405e-6 1 1.95011e-6 8.56453e-7 1 -7.01149e-7 -9.89435e-7 1 1.20859e-6 4.60036e-6 1 -4.60046e-6 -4.52826e-7 1 6.96696e-7 -3.53832e-7 1 6.61255e-7 -2.66347e-7 1 5.50158e-7 0 1 3.56594e-7 0 1 2.58641e-7 0 1 2.09266e-7 0 1 2.02443e-7 0 1 1.2446e-7 0 1 1.63918e-7 0 1 1.34771e-7 1.33569e-7 1 0 0 1 0 0 1 2.8919e-7 0 1 0 0 1 0 1.32496e-7 1 0 0 1 0 -1.9702e-7 1 3.12567e-7 -1.59414e-6 1 1.9502e-6 8.56477e-7 1 -7.01172e-7 -1.60989e-6 1 1.96615e-6 4.59589e-6 1 -4.59579e-6 0 1 0 -2.69362e-7 1 4.68738e-7 -2.34427e-7 1 4.38105e-7 0 1 2.76e-7 0 1 2.11994e-7 0 1 2.14824e-7 0 1 0 0 1 1.71099e-7 0 1 1.41732e-7 1.23547e-7 1 0 0 1 0 1.31385e-7 1 0 1.71715e-7 1 0 4.78245e-7 1 -4.78235e-7 1.13307e-6 1 -9.77671e-7 2.89521e-7 1 0 -1.2436e-7 1 3.68231e-7 0 1 0 0 1 0 -6.34509e-7 1 7.58831e-7 -8.40676e-7 1 1.00539e-6 2.89521e-7 1 0 1.42946e-6 1 -1.30514e-6 0 1 2.19406e-7 1.55414e-6 1 -1.5541e-6 0 1 2.42025e-7 1.34075e-7 1 0 0 1 1.26376e-7 0 1 0 0 1 0 1.23011e-7 1 0 0 1 0 3.09746e-7 1 -3.09753e-7 0 1 0 0 1 0 0 1 0 2.57352e-7 1 0 1.13889e-6 1 -1.01457e-6 0 1 3.67179e-7 1.21199e-7 1 0 0 1 1.54244e-7 1.44228e-7 1 0 2.01586e-7 1 0 1.75763e-7 1 0 3.6384e-7 1 -3.63848e-7 0 1 1.47595e-7 -9.04814e-7 1 1.12159e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.41811e-7 1 0 6.20336e-7 1 -6.20323e-7 9.46044e-7 1 -9.46064e-7 0 1 2.11415e-7 1.10208e-6 1 -1.14045e-6 0 1 0 0 1 0 1.20371e-7 1 0 1.38573e-7 1 0 -5.13578e-7 1 8.80106e-7 9.74373e-7 1 -6.50886e-7 -2.89281e-7 1 4.33053e-7 0 1 2.48878e-7 0 1 0 0 1 4.633e-7 0 1 0 0 1 1.66544e-7 0 1 0 0 1 0 0 1 0 0 1 1.20473e-7 -4.63962e-7 1 8.70244e-7 4.22396e-7 1 -2.82194e-7 -2.5084e-7 1 3.75466e-7 1.5829e-7 1 0 0 1 2.61201e-7 0 1 1.90709e-7 0 1 1.40441e-7 1.90022e-7 1 0 0 1 1.98e-7 1.64876e-7 1 1.35165e-7 3.38918e-7 1 0 1.72971e-6 1 -1.72971e-6 1.65709e-7 1 0 0 1 0 0 1 2.21098e-7 1.82741e-7 1 0 1.62675e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.4312e-7 0 1 2.69988e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.19799e-6 1 -1.18904e-6 0 1 2.44214e-7 0 1 1.65711e-7 0 1 0 0 1 0 0 1 0 4.01782e-7 1 9.47125e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.95181e-7 0 1 1.91756e-7 0 1 0 0 1 0 0 1 2.06684e-7 1.87942e-7 1 0 0 1 1.41995e-7 0 1 1.34765e-7 0 1 1.2003e-7 0 1 0 1.88993e-7 1 0 1.77415e-6 1 -1.59312e-6 5.78027e-7 1 -3.37188e-7 0 1 0 0 1 1.93588e-7 0 1 0 0 1 4.118e-7 0 1 1.37718e-7 0 1 1.7485e-7 0 1 0 1.91214e-7 1 -1.91214e-7 1.36264e-6 1 -2.23304e-6 0 1 3.48521e-7 -2.61578e-7 1 8.46615e-7 0 1 0 0 1 0 -2.75515e-7 1 1.05394e-6 0 1 0 3.31092e-7 1 -3.31094e-7 0 1 0 7.39631e-7 1 -1.1421e-6 0 1 0 0 1 0 1.3995e-7 1 0 1.20308e-7 1 0 0 1 0 1.50025e-7 1 0 2.28893e-7 1 -1.65888e-7 -3.95796e-6 1 5.46124e-6 -1.38285e-7 1 3.56823e-7 0 1 3.23735e-7 0 1 1.91369e-7 0 1 1.3995e-7 7.16876e-7 1 -1.59266e-6 0 1 0 -6.35009e-7 1 1.41078e-6 1.29078e-7 1 0 1.57078e-7 1 0 2.09639e-7 1 0 3.94308e-7 1 -2.8576e-7 -2.85772e-7 1 3.94317e-7 0 1 0 -1.84448e-7 1 5.70832e-7 0 1 0 0 1 2.37252e-7 0 1 1.54788e-7 -1.46093e-6 1 1.78205e-6 0 1 1.20327e-7 0 1 1.73221e-7 0 1 2.15067e-7 0 1 2.51617e-7 0 1 3.59e-7 -3.17444e-7 1 5.94944e-7 0 1 0 0 1 0 0 1 0 3.81714e-7 1 9.0456e-7 0 1 0 0 1 1.27829e-7 0 1 1.59392e-7 1.26925e-6 1 -1.42754e-6 0 1 2.82479e-7 0 1 0 -1.20907e-7 1 0 -1.42021e-7 1 0 6.34181e-7 1 9.1898e-7 -1.22972e-6 1 -1.56879e-6 0 1 0 0 1 0 0 1 0 -3.6948e-7 1 9.18982e-7 2.23991e-7 1 -1.29193e-7 4.03463e-7 1 -4.03463e-7 0 1 0 0 1 0 -1.28158e-6 1 1.454e-6 -4.03324e-7 1 6.99254e-7 9.18942e-7 1 -3.29841e-7 0 1 1.59598e-7 0 1 0 0 1 1.64895e-7 0 1 1.69707e-7 -1.23102e-7 1 3.28435e-7 2.93339e-7 1 -1.36287e-7 2.12083e-7 1 0 0 1 2.0982e-7 -2.12613e-7 1 3.69665e-7 0 1 0 -5.54285e-7 1 6.81499e-7 -1.56439e-7 1 -2.71226e-7 0 1 1.20892e-7 0 1 0 0 1 0 0 1 0 0 1 0 -1.59935e-6 1 -2.04033e-6 0 1 0 -1.26193e-7 1 0 6.53677e-7 1 9.18976e-7 -1.29194e-7 1 2.23992e-7 0 1 1.50842e-7 0 1 1.22448e-7 1.27829e-7 1 0 0 1 2.44444e-7 0 1 2.99343e-7 0 1 1.3251e-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 1.61292e-6 -1 -1.93591e-6 -0.8914707 0 0.4530786 6.01844e-7 -1 -1.1842e-6 -0.4530723 0 0.8914738 0 -1 -1.29519e-7 0 -1 -1.58345e-7 -0.4530723 0 0.8914738 -1.36257e-7 -1 0 -0.9877938 0 -0.1557673 -0.8914706 0 0.4530786 0 -1 0 -0.7071068 0 -0.7071068 -0.9877938 0 -0.1557673 0 -1 0 -0.1557608 0 -0.9877949 0 -1 0 0 -1 0 -4.00871e-7 -1 2.83028e-7 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 0.453085 0 -0.8914673 0 -1 0 -0.1557608 0 -0.9877949 -5.77294e-7 -1 -8.22773e-7 0.8914673 0 -0.453085 0 -1 0 0.453085 0 -0.8914673 2.2746e-7 -1 0 0.9877951 0 0.1557596 0 -1 -2.91439e-7 0.8914673 0 -0.453085 0 -1 0 0.7071028 0 0.7071108 0 -1 -2.48114e-7 0.9877951 0 0.1557596 0 -1 0 0.1557673 0 0.9877937 0 -1 0 0 -1 0 0.7071028 0 0.7071107 2.08538e-7 -1 -5.29657e-7 0 -1 0 0 -1 0 0 -1 0 0.1557673 0 0.9877937 -2.19726e-7 -1 0 -0.8914849 0 0.4530503 2.36471e-7 -1 -4.65321e-7 -0.4530439 0 0.8914882 -1.55664e-7 -1 0 -0.4530439 0 0.8914882 -1.3584e-7 -1 0 -0.987798 0 -0.1557403 -0.8914849 0 0.4530503 4.68523e-7 -1 -1.11094e-6 -0.7071585 0 -0.7070552 -0.987798 0 -0.1557403 0 -1 0 -0.1557403 0 -0.987798 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.7071585 0 -0.7070552 -7.28247e-7 -1 -1.03792e-6 0.4530503 0 -0.8914849 0 -1 0 -0.1557403 0 -0.987798 1.831e-7 -1 0 0.8914677 0 -0.4530844 0 -1 -2.05295e-7 0.4530502 0 -0.891485 2.55889e-7 -1 0 0.9877965 0 0.1557497 0 -1 -3.27892e-7 0.8914677 0 -0.4530844 0 -1 0 0.7071068 0 0.7071068 0 -1 -2.90021e-7 0.9877965 0 0.1557497 0 -1 0 0.1557337 0 0.9877991 0 -1 0 0 -1 0 0.7071068 0 0.7071068 1.25138e-7 -1 -3.30733e-7 0 -1 0 0 -1 0 0 -1 0 0.1557337 0 0.9877991 -0.8914431 0 0.4531325 -0.4531325 0 0.8914431 -0.4531325 0 0.8914431 -0.9877979 0 -0.1557415 -0.8914431 0 0.4531325 0 -1 0 -0.7070552 0 -0.7071585 -0.9877979 0 -0.1557415 0 -1 0 -0.1558416 0 -0.9877821 0 -1 0 0 -1 0 0 -1 0 -0.7070552 0 -0.7071585 2.52866e-7 -1 -4.97462e-7 0.4531325 0 -0.8914431 -2.74913e-7 -1 2.74913e-7 2.34264e-7 -1 -1.20032e-6 0 -1 0 -0.1558416 0 -0.9877821 -3.29502e-7 -1 1.67451e-7 0.8914865 0 -0.4530472 -1.31615e-7 -1 0 0 -1 -1.49135e-7 0.4531325 0 -0.8914431 -1.54667e-7 -1 0 0.9877992 0 0.1557325 0.8914865 0 -0.4530472 0 -1 0 0.7071068 0 0.7071068 0.9877992 0 0.1557325 0.1558416 0 0.9877821 1.73908e-7 -1 -4.0029e-7 0 -1 -3.11803e-7 2.73538e-7 -1 -4.74293e-7 0.7071068 0 0.7071068 0.1558416 0 0.9877821 -0.8914706 0 0.4530786 -0.4530818 0 0.891469 -0.4530818 0 0.891469 -0.9877926 0 -0.1557751 -0.8914706 0 0.4530786 0 -1 0 -0.7071068 0 -0.7071068 -0.9877926 0 -0.1557751 0 -1 0 -0.1557608 0 -0.9877948 0 -1 0 0 -1 0 0 -1 0 -0.7071068 0 -0.7071068 2.55706e-7 -1 -5.03127e-7 0.4530755 0 -0.8914722 -2.44142e-7 -1 0 -2.5834e-7 -1 1.49006e-7 0 -1 -1.03385e-6 -0.1557608 0 -0.9877948 -2.24901e-7 -1 0 0.8914706 0 -0.4530786 -1.56101e-7 -1 0 0.4530754 0 -0.8914721 -1.448e-7 -1 0 0.9877933 0 0.1557698 0.8914706 0 -0.4530786 0 -1 0 0.7071068 0 0.7071068 0.9877933 0 0.1557698 0.1557829 0 0.9877912 0 -1 -2.36684e-7 0 -1 -2.66223e-7 0.7071068 0 0.7071068 0.1557829 0 0.9877912 0 -1 0 -0.7739723 0 0.6332194 0 -1 0 -0.6331645 0 0.7740172 -0.6331645 0 0.7740172 0 -1 0 -0.882154 0 0.4709611 -1.53008e-7 -1 -2.59645e-7 -0.7739723 0 0.6332194 0 -1 0 -0.9568128 0 0.2907049 -0.882154 0 0.4709611 0 -1 0 -0.9952951 0 0.09689092 -0.9568128 0 0.2907049 -9.83527e-7 -1 -1.0658e-6 -0.9952952 0 -0.09688943 -0.9952951 0 0.09689092 3.08628e-7 -1 0 -0.9568114 0 -0.2907091 5.035e-7 -1 4.02932e-7 -0.9952952 0 -0.09688943 4.12397e-7 -1 2.20714e-7 -0.8816695 0 -0.4718675 -0.9568114 0 -0.2907091 8.56477e-7 -1 7.01172e-7 -0.7737721 0 -0.633464 -0.8816695 0 -0.4718675 -8.03097e-7 -1 -9.81001e-7 -0.6334548 0 -0.7737796 2.35334e-6 -1 2.24495e-6 5.14648e-7 -1 4.90945e-7 4.59829e-6 -1 4.59829e-6 -0.7737721 0 -0.633464 0 -1 -2.19044e-7 -0.4717953 0 -0.8817082 -0.6334548 0 -0.7737796 0 -1 -1.38023e-7 -0.2908074 0 -0.9567816 -0.4717953 0 -0.8817082 0 -1 0 -0.09689092 0 -0.9952951 -0.2908074 0 -0.9567816 0 -1 0 0.09689986 0 -0.9952942 -1.53212e-7 -1 -2.37858e-7 -0.09689092 0 -0.9952951 0 -1 0 0.2906793 0 -0.9568206 0.09689986 0 -0.9952942 0 -1 0 0.4710395 0 -0.8821121 0.2906793 0 -0.9568206 0 -1 0 0.6331554 0 -0.7740247 0.4710395 0 -0.8821121 -4.98388e-7 -1 -8.2668e-7 0.7740172 0 -0.6331645 0 -1 0 0.6331554 0 -0.7740247 0 -1 0 0.882164 0 -0.4709424 0.7740172 0 -0.6331645 0 -1 0 0.9567907 0 -0.2907776 0.882164 0 -0.4709424 0 -1 0 0.995303 0 -0.09680801 0.9567907 0 -0.2907776 0 -1 0 0.9953039 0 0.09679913 -1.41644e-7 -1 -2.25533e-7 0.995303 0 -0.09680801 0 -1 0 0.9567829 0 0.2908032 0 -1 0 0.9953039 0 0.09679913 0 -1 0 0.8817146 0 0.4717832 0.9567829 0 0.2908032 0 -1 0 0.7737661 0 0.6334716 0.8817146 0 0.4717832 -8.90491e-7 -1 -1.08773e-6 0.633464 0 0.7737721 -2.52548e-6 -1 -2.64741e-6 0 -1 0 0.7737661 0 0.6334716 3.67589e-6 -1 4.56197e-6 0.4718675 0 0.8816695 -4.7565e-7 -1 -7.09983e-7 0.633464 0 0.7737721 -1.80986e-6 -1 -2.24612e-6 0.2906934 0 0.9568163 0.4718675 0 0.8816695 0 -1 -1.29324e-7 0.09689986 0 0.9952942 0.2906934 0 0.9568163 0 -1 0 -0.09689092 0 0.9952951 0.09689986 0 0.9952942 0 -1 0 -0.2907232 0 0.9568072 0 -1 0 -0.09689092 0 0.9952951 0 -1 0 -0.4710274 0 0.8821187 -0.2907232 0 0.9568072 -0.4710274 0 0.8821187 0 -1 0 -0.8914963 0 0.4530279 0 -1 0 -0.453034 0 0.8914933 -0.453034 0 0.8914933 0 -1 0 -0.9877986 0 -0.1557369 -1.49725e-7 -1 -2.77365e-7 -0.8914963 0 0.4530279 0 -1 0 -0.7070991 0 -0.7071145 -0.9877986 0 -0.1557369 0 -1 -1.66044e-7 -0.1557544 0 -0.9877958 1.44758e-7 -1 0 -0.7070991 0 -0.7071145 0 -1 0 0.4530217 0 -0.8914995 0 -1 0 -0.1557544 0 -0.9877958 0 -1 0 0.8914995 0 -0.4530217 0 -1 0 0.4530217 0 -0.8914995 1.44758e-7 -1 0 0.9877982 0 0.1557393 0 -1 -1.66044e-7 0.8914995 0 -0.4530217 5.38084e-7 -1 5.38084e-7 0.7071068 0 0.7071068 -3.01331e-7 -1 -4.23267e-7 0.9877982 0 0.1557393 0 -1 -2.42026e-7 0.1557544 0 0.9877958 -1.721e-7 -1 -2.70249e-7 0 -1 -1.26372e-7 0.7071068 0 0.7071068 0.1557544 0 0.9877958 -0.8914963 0 0.4530279 -0.453034 0 0.8914933 -0.453034 0 0.8914933 -0.9877986 0 -0.1557369 -0.8914963 0 0.4530279 -0.7070991 0 -0.7071145 -0.9877986 0 -0.1557369 0 -1 0 -0.1557544 0 -0.9877958 -0.7070991 0 -0.7071145 0 -1 0 0.4530653 0 -0.8914773 -0.1557544 0 -0.9877958 0 -1 0 0.891456 0 -0.4531075 0 -1 0 0.4530653 0 -0.8914773 0 -1 0 0.9877982 0 0.1557393 0.891456 0 -0.4531075 0 -1 0 0.7071068 0 0.7071068 0.9877982 0 0.1557393 0.1557544 0 0.9877958 0.7071068 0 0.7071068 0.1557544 0 0.9877958 0 -1 0 -0.8914963 0 0.4530279 0 -1 0 -0.4530339 0 0.8914932 0 -1 0 -0.4530339 0 0.8914932 -1.03347e-6 -1 -1.14186e-6 -0.9877986 0 -0.1557369 0 -1 0 -0.8914963 0 0.4530279 2.9109e-7 -1 2.91097e-7 -0.7070991 0 -0.7071145 -1.26759e-7 -1 -2.35145e-7 -0.9877986 0 -0.1557369 0 -1 0 -0.1557544 0 -0.9877958 1.29752e-6 -1 1.54487e-6 -0.7070991 0 -0.7071145 0 -1 0 0.4530653 0 -0.8914773 -0.1557544 0 -0.9877958 -4.5711e-7 -1 -8.48919e-7 0.891456 0 -0.4531075 0 -1 0 0.4530653 0 -0.8914773 1.41811e-7 -1 0 0.9877982 0 0.1557393 0.8914559 0 -0.4531075 6.20434e-7 -1 6.20434e-7 0.7071068 0 0.7071068 0.9877982 0 0.1557393 0 -1 0 0.1557544 0 0.9877958 -1.03349e-6 -1 -1.14188e-6 0.7071068 0 0.7071068 0 -1 0 0.1557544 0 0.9877958 0 -1 0 -0.8914963 0 0.4530279 -6.02734e-7 -1 -9.41655e-7 -0.4530339 0 0.8914933 -0.453034 0 0.8914933 0 -1 0 -0.9877986 0 -0.1557369 0 -1 -2.52569e-7 -0.8914963 0 0.4530279 0 -1 0 -0.7070991 0 -0.7071145 -0.9877986 0 -0.1557369 -0.1557544 0 -0.9877958 -0.7070991 0 -0.7071145 0.4530217 0 -0.8914995 -0.1557544 0 -0.9877958 0.8914995 0 -0.4530217 0.4530217 0 -0.8914995 0.9877982 0 0.1557393 0.8914995 0 -0.4530217 0.7071068 0 0.7071068 0.9877982 0 0.1557393 0 -1 0 0.1557544 0 0.9877958 0 -1 0 0.7071068 0 0.7071068 0.1557544 0 0.9877958 0 -1 0 -0.8315048 0 0.5555178 0 -1 0 -0.5555178 0 0.8315048 -0.5555178 0 0.8315048 0 -1 0 -0.9807852 0 0.1950905 0 -1 0 -0.8315047 0 0.5555177 -4.57357e-7 -1 -7.13311e-7 -0.9807875 0 -0.1950793 -0.9807852 0 0.1950905 1.87735e-7 -1 1.25422e-7 -0.8315077 0 -0.5555132 -0.9807874 0 -0.1950793 -1.41062e-7 -1 -2.11169e-7 -0.5554704 0 -0.8315364 0 -1 0 -0.8315077 0 -0.5555132 0 -1 0 -0.1950905 0 -0.9807852 0 -1 -1.87016e-7 -0.5554704 0 -0.8315364 0 -1 0 0.1950793 0 -0.9807874 -0.1950905 0 -0.9807852 0 -1 0 0.5554658 0 -0.8315393 0.1950793 0 -0.9807874 -2.69e-7 -1 -5.56086e-7 0.8315122 0 -0.5555064 -1.65427e-7 -1 -1.31042e-7 0.5554658 0 -0.8315393 0 -1 0 0.9807988 0 -0.195023 0.8315122 0 -0.5555064 0 -1 0 0.9807852 0 0.1950905 0.9807988 0 -0.195023 0 -1 0 0.8315364 0 0.5554704 0.9807852 0 0.1950905 -3.25431e-7 -1 -4.87174e-7 0.5554658 0 0.8315393 0 -1 0 0 -1 -2.22416e-7 0.8315364 0 0.5554704 0 -1 0 0.195145 0 0.9807744 0 -1 -2.75358e-7 0.5554658 0 0.8315393 0 -1 0 -0.1950905 0 0.9807852 0.195145 0 0.9807744 -0.1950905 0 0.9807852 0 -1 0 -0.8914697 0 0.4530801 0 -1 0 -0.4530755 0 0.8914722 -0.4530755 0 0.8914722 -1.38852e-7 -1 0 -0.9877932 0 -0.1557713 0 -1 0 -0.8914697 0 0.4530801 0 -1 0 -0.7071108 0 -0.7071028 -0.9877932 0 -0.1557713 0 -1 -1.95111e-7 -0.1557635 0 -0.9877943 0 -1 -1.86477e-7 -0.7071108 0 -0.7071028 0 -1 0 0.4530738 0 -0.8914729 0 -1 -2.23014e-7 -0.1557635 0 -0.9877943 0 -1 0 0.8914746 0 -0.4530707 0.4530738 0 -0.8914729 0 -1 0 0.987795 0 0.1557596 0.8914746 0 -0.4530707 0 -1 0 0.7071019 0 0.7071118 0.987795 0 0.1557596 0 -1 0 0.1557713 0 0.9877932 0 -1 0 0 -1 0 0.7071019 0 0.7071118 0 -1 0 0.1557713 0 0.9877932 -1.27173e-7 -1 0 -0.8914698 0 0.4530802 -3.67954e-7 -1 7.23972e-7 -0.4530834 0 0.8914682 -0.4530834 0 0.8914682 2.17233e-7 -1 -1.10254e-6 -0.9877932 0 -0.1557713 -0.8914698 0 0.4530802 0 -1 0 -0.7071068 0 -0.7071068 -0.9877932 0 -0.1557713 0 -1 0 -0.1557593 0 -0.9877951 0 -1 0 -0.7071068 0 -0.7071068 -7.25563e-7 -1 -1.04309e-6 0.4530707 0 -0.8914747 -0.1557593 0 -0.9877951 2.13774e-7 -1 0 0.8914738 0 -0.4530723 1.85484e-7 -1 -1.52063e-7 0.4530707 0 -0.8914746 3.81282e-7 -1 0 0.9877948 0 0.1557608 0.8914738 0 -0.4530723 1.94589e-6 -1 1.94589e-6 0.7071068 0 0.7071068 1.86424e-7 -1 0 0.9877948 0 0.1557608 0 -1 0 0.1557673 0 0.9877938 0 -1 0 0 -1 0 -6.14643e-7 -1 -9.61307e-7 0.7071068 0 0.7071068 0 -1 0 -3.64485e-7 -1 7.14748e-7 0.1557673 0 0.9877938 0 -1 0 -0.8914746 0 0.4530707 0 -1 0 -0.4530801 0 0.8914697 -0.4530801 0 0.8914697 0 -1 0 -0.987793 0 -0.1557725 0 -1 0 -0.8914746 0 0.4530707 0 -1 0 -0.7071128 0 -0.7071009 -0.987793 0 -0.1557725 0 -1 -3.96505e-7 -0.1557713 0 -0.9877932 -6.80189e-7 -1 -1.35026e-6 -0.7071128 0 -0.7071009 0 -1 -1.88993e-7 0.4530801 0 -0.8914697 -0.1557713 0 -0.9877932 0 -1 0 0.8914729 0 -0.4530738 0 -1 0 -1.81031e-6 -1 -1.90082e-6 0.4530801 0 -0.8914697 0 -1 0 0.9877933 0 0.1557706 0 -1 0 0.8914729 0 -0.4530738 0 -1 0 0.7071068 0 0.7071068 0 -1 -1.66605e-7 0.9877933 0 0.1557706 0 -1 0 0.1557706 0 0.9877933 0 -1 0 0 -1 0 0.7071068 0 0.7071068 0.1557706 0 0.9877933 0 -1 0 -0.8914746 0 0.4530707 -0.4530801 0 0.8914697 0 -1 0 -0.4530801 0 0.8914697 0 -1 0 -0.987793 0 -0.1557725 0 -1 0 -0.8914746 0 0.4530707 0 -1 0 -0.7071128 0 -0.7071009 -0.987793 0 -0.1557725 0 -1 -4.11801e-7 -0.1557713 0 -0.9877932 0 -1 -1.37718e-7 0 -1 -2.103e-7 -0.7071128 0 -0.7071009 0 -1 -1.9518e-7 0.4530801 0 -0.8914697 -0.1557713 0 -0.9877932 0 -1 0 0.8914729 0 -0.4530738 0 -1 -2.33656e-7 0.4530801 0 -0.8914697 0 -1 0 0.987793 0 0.1557725 0.8914729 0 -0.4530738 0 -1 0 0.7071108 0 0.7071028 0.987793 0 0.1557725 0.1557713 0 0.9877932 0 -1 -1.49537e-7 0.7071108 0 0.7071028 0.1557713 0 0.9877932 1.21996e-7 -1 0 -0.8097883 0 0.5867223 0 -1 -1.37728e-7 -0.5867201 0 0.8097898 -0.5867201 0 0.8097898 1.45213e-7 -1 0 -0.9518141 0 0.3066756 -0.8097883 0 0.5867223 1.7671e-7 -1 0 -1 0 1.22365e-5 -0.9518141 0 0.3066756 2.35841e-7 -1 0 -0.9515594 0 -0.3074647 -1 0 1.22365e-5 4.43621e-7 -1 3.21511e-7 -0.8097099 0 -0.5868304 -0.9515594 0 -0.3074647 0 -1 0 -0.5868275 0 -0.809712 6.98679e-7 -1 6.12471e-7 -0.8097099 0 -0.5868304 0 -1 0 -0.3074703 0 -0.9515577 0 -1 0 -0.5868275 0 -0.809712 0 -1 0 0 0 -1 -0.3074703 0 -0.9515577 0 -1 0 0.3066849 0 -0.9518111 0 0 -1 0 -1 0 0.5867263 0 -0.8097853 0.3066849 0 -0.9518111 0 -1 0 0.8097791 0 -0.5867349 0.5867263 0 -0.8097853 0 -1 0 0.9518176 0 -0.3066647 0.8097791 0 -0.5867349 0 -1 0 1 0 0 0 -1 0 0.9518176 0 -0.3066647 0 -1 0 0.9515594 0 0.3074647 1 0 0 -2.76347e-6 -1 -4.11401e-6 0.8097177 0 0.5868195 0.9515594 0 0.3074647 0 -1 0 0.5868304 0 0.8097098 2.06283e-6 -1 2.75667e-6 0.8097178 0 0.5868196 0 -1 0 0.3074594 0 0.9515612 0.5868304 0 0.8097098 0 -1 0 0 0 1 0.3074594 0 0.9515612 -1.32375e-6 -1 -1.50943e-6 -0.3066813 0 0.9518123 0 0 1 0 -1 0 -0.3066813 0 0.9518123 0 -1 0 -0.773342 0 -0.633989 0 -1 0 -0.7071065 0 -0.707107 0 -1 0 -0.8822639 0 -0.4707552 -0.773342 0 -0.633989 3.25998e-7 -1 -9.21509e-7 -0.9567294 0 -0.2909795 -0.8822639 0 -0.4707552 -0.9951338 0 -0.09853333 -0.9567293 0 -0.2909795 -1 0 -2.65318e-6 -1 0 -2.65318e-6 -0.9951338 0 -0.09853333 -0.9951326 0 0.09854483 -0.9567289 0 0.2909805 -0.9951326 0 0.09854483 -0.8822674 0 0.4707487 -0.956729 0 0.2909805 -0.7733374 0 0.6339947 -0.8822674 0 0.4707487 -0.707107 0 0.7071066 -0.7733374 0 0.6339947 -0.6255643 0 0.7801726 -0.707107 0 0.7071066 0 -1 0 -0.4410474 0 0.8974839 -0.6255643 0 0.7801726 -2.23222e-7 -1 -4.67948e-7 -0.2354474 0 0.9718871 -0.4410474 0 0.8974838 0 -1 0 -0.2354452 0 0.9718877 -3.26162e-6 -1 -4.28438e-6 -0.2354473 0 0.9718871 -0.4410479 0 0.8974837 0 -1 0 -0.2354452 0 0.9718877 -0.6255664 0 0.7801709 -0.4410479 0 0.8974837 -0.7071067 0 0.7071068 -2.04476e-7 -1 -2.90686e-7 0 -1 -2.66786e-7 -2.73118e-7 -1 1.57529e-7 -1.50954e-7 -1 0 -2.68971e-7 -1 1.57521e-7 -1.26913e-7 -1 2.20032e-7 0 -1 0 -3.47637e-7 -1 -8.64656e-7 0 -1 0 0 -1 0 0 -1 0 -0.6255664 0 0.7801709 0 -1 -1.87027e-7 -0.7569319 0 0.6534937 0 -1 -1.73314e-7 5.44902e-7 -1 4.68271e-7 0 -1 0 0 -1 0 -7.94091e-7 -1 -4.70026e-7 -0.7071067 0 0.7071069 -0.8439928 0 0.5363544 0 -1 0 -0.7569319 0 0.6534937 -0.9127942 0 0.4084196 -0.8439928 0 0.5363544 -0.9625188 0 0.2712152 -0.9127942 0 0.4084196 -0.9541236 0 0.2994127 -0.9625188 0 0.2712152 -0.873043 0 0.4876434 -0.9541237 0 0.2994127 -0.7553297 0 0.6553449 -0.8730429 0 0.4876433 -0.6059155 0 0.795529 -0.7553297 0 0.6553449 -0.4310981 0 0.9023051 -0.6059155 0 0.795529 0 -1 0 -0.2381552 0 0.9712271 -0.4310981 0 0.9023051 -2.85043e-7 -1 -4.09498e-7 -0.03529006 0 0.9993771 0 -1 0 -0.2381552 0 0.9712271 0 -1 0 0.1690714 0 0.9856037 -1.75628e-7 -1 -3.00083e-7 -0.03529006 0 0.9993771 0 -1 -2.36048e-7 0.3663359 0 0.9304828 1.45707e-7 -1 0 0.1690714 0 0.9856037 1.03909e-6 -1 1.03913e-6 0.5482238 0 0.8363317 4.15399e-7 -1 2.72285e-7 0.3663359 0 0.9304828 0.7070919 0 0.7071217 0.5482238 0 0.8363317 0.8363434 0 0.5482059 0.7070919 0 0.7071217 0.9304832 0 0.3663344 0.8363434 0 0.5482059 0.9856045 0 0.1690673 0.9304832 0 0.3663344 0.9993771 0 -0.03529018 0.9856045 0 0.1690673 0.9712273 0 -0.2381542 0.9993771 0 -0.03529018 0.9023115 0 -0.4310846 0.9712274 0 -0.2381542 0.7955182 0 -0.6059299 0.9023115 0 -0.4310846 0.6553428 0 -0.7553316 0.7955181 0 -0.6059299 0.4876433 0 -0.8730429 0.6553428 0 -0.7553316 0.2994398 0 -0.9541152 0.4876434 0 -0.873043 0.2711986 0 -0.9625234 0.2994398 0 -0.9541152 0.4084196 0 -0.9127943 0.2711986 0 -0.9625234 0.5363547 0 -0.8439927 0.4084197 0 -0.9127943 0.6534922 0 -0.7569332 0.5363547 0 -0.8439927 0.7071065 0 -0.707107 -1.56411e-7 -1 2.71126e-7 0 -1 -1.20893e-7 0 -1 0 0 -1 0 0 -1 0 -5.15062e-6 -1 -5.9935e-6 0 -1 0 1.42223e-7 -1 -3.56042e-7 -2.62904e-7 -1 1.5164e-7 -1.43663e-7 -1 0 0.6534922 0 -0.7569332 0.7801745 0 -0.6255618 -1.4534e-7 -1 -2.51989e-7 0 -1 -1.69698e-7 0 -1 -1.37754e-7 0.7071066 0 -0.707107 0.8974827 0 -0.4410497 0.7801746 0 -0.6255619 -1.60295e-7 -1 -2.60354e-7 0.9718866 0 -0.2354493 0 -1 0 0.8974827 0 -0.4410497 0 -1 0 0.9718877 0 -0.2354452 0 -1 -1.3251e-7 0.9718866 0 -0.2354493 0 -1 -2.87304e-7 0.8974832 0 -0.4410488 0.9718877 0 -0.2354452 0.7801728 0 -0.625564 0.8974831 0 -0.4410488 0.7071067 0 -0.7071068 0.7801728 0 -0.625564 0.633989 0 -0.7733421 0.7071067 0 -0.7071068 0.4707518 0 -0.8822656 0.633989 0 -0.7733421 0 -1 0 0.2909795 0 -0.9567293 0.4707518 0 -0.8822656 0 -1 0 0.09853333 0 -0.9951338 0.2909795 0 -0.9567293 -2.48734e-7 -1 -6.06856e-7 2.21098e-6 0 -1 2.21098e-6 0 -1 0.09853333 0 -0.9951338 0 -1 -2.83069e-7 -0.09853333 0 -0.9951338 -1.2284e-7 -1 -4.03873e-7 -0.2909917 0 -0.9567257 -0.09853333 0 -0.9951338 -3.57123e-7 -1 -6.6931e-7 -0.4707502 0 -0.8822665 -0.2909917 0 -0.9567257 -1.64357e-6 -1 -2.00483e-6 -0.6339909 0 -0.7733405 -0.4707502 0 -0.8822665 -0.7071079 0 -0.7071056 -0.7071079 0 -0.7071056 -0.6339909 0 -0.7733405 -0.7071068 0 0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 0.7071068 0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071065 0 -0.707107 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.8662585 0 0.4995959 0.8662585 0 0.4995959 0.7071068 0 0.7071068 0.4995903 0 0.8662618 0 0 1 0.4995903 0 0.8662618 -0.499704 0 0.8661963 0 0 1 -0.7071011 0 0.7071125 -0.499704 0 0.8661963 -0.8662346 0 0.4996374 -0.7071011 0 0.7071125 -1 0 0 -0.8662346 0 0.4996374 -0.8662328 0 -0.4996407 -1 0 0 -0.7071092 0 -0.7071044 -0.7071092 0 -0.7071043 -0.8662328 0 -0.4996407 -0.4996374 0 -0.8662346 0 0 -1 -0.4996374 0 -0.8662346 0.4996374 0 -0.8662346 0 0 -1 0.7071068 0 -0.7071068 0.4996374 0 -0.8662346 0.8662347 0 -0.4996374 0.7071068 0 -0.7071068 1 0 0 0.8662346 0 -0.4996374 1 0 0 -0.4996407 0 -0.8662328 -0.7070735 0 -0.7071402 0 0 -1 -0.4996407 0 -0.8662328 0.4995959 0 -0.8662585 0 0 -1 0.7071064 0 -0.7071071 0.4995959 0 -0.8662585 0.8662388 0 -0.4996302 0.7071064 0 -0.7071071 1 0 -7.35181e-6 0.8662388 0 -0.4996302 0 -1 0 0.8662388 0 0.4996303 1 0 -7.35181e-6 0 -1 0 0.7071068 0 0.7071068 3.34924e-6 -1 -5.80683e-6 0.7071068 0 0.7071068 0.8662388 0 0.4996303 0 -1 -1.53548e-7 0.4996303 0 0.8662388 0 -1 -1.53549e-7 0 -1 -3.67524e-7 0 -1 -3.67524e-7 0 0 1 0.4996303 0 0.8662388 3.34998e-6 -1 -5.80806e-6 -0.4996302 0 0.8662388 0 -1 0 0 0 1 -0.7071064 0 0.7071071 0 -1 0 -0.4996302 0 0.8662388 -0.8662568 0 0.4995991 -0.7071064 0 0.7071072 -1 0 0 -0.8662568 0 0.4995991 -0.8662585 0 -0.4995959 -1 0 0 -0.7070735 0 -0.7071402 -0.8662585 0 -0.4995959 0.7071068 0 0.7071068 0.8662407 0 0.4996271 0.8662407 0 0.4996271 0.7071068 0 0.7071068 0.4996302 0 0.8662388 0 0 1 0.4996302 0 0.8662388 -0.4996326 0 0.8662375 0 0 1 -0.7071068 0 0.7071068 -0.4996326 0 0.8662375 -0.8662369 0 0.4996334 -0.7071068 0 0.7071068 -1 0 0 -0.8662369 0 0.4996334 -0.8662389 0 -0.4996302 -1 0 0 -0.7071092 0 -0.7071044 -0.7071092 0 -0.7071044 -0.8662389 0 -0.4996302 -0.4996271 0 -0.8662407 0 0 -1 -0.4996271 0 -0.8662407 0.4996271 0 -0.8662407 0 0 -1 0.7071066 0 -0.707107 0.4996271 0 -0.8662407 0.8662388 0 -0.4996303 0.7071066 0 -0.707107 1 0 -7.35186e-6 0.8662388 0 -0.4996303 1 0 -7.35186e-6 -0.4996271 0 -0.8662407 -0.7071092 0 -0.7071045 0 0 -1 -0.4996271 0 -0.8662407 0.4996381 0 -0.8662343 0 0 -1 0.7071036 0 -0.7071099 0.7071036 0 -0.7071099 0.4996381 0 -0.8662343 0.8662436 0 -0.4996219 1 0 0 0.8662436 0 -0.4996219 0.8662416 0 0.4996255 1 0 0 0.707108 0 0.7071056 0.707108 0 0.7071056 0.8662416 0 0.4996255 0.4996227 0 0.8662431 0 0 1 0.4996227 0 0.8662431 -0.4996274 0 0.8662404 0 0 1 -0.7071073 0 0.7071064 -0.7071073 0 0.7071063 -0.4996274 0 0.8662404 -0.8662407 0 0.4996271 -1 0 0 -0.8662407 0 0.4996271 -0.8662388 0 -0.4996303 -1 0 0 -0.7071092 0 -0.7071045 -0.8662388 0 -0.4996303 0.7071074 0 -0.7071062 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 0.7071065 0 0.7071072 0.7071073 0 -0.7071062 -0.7071072 0 0.7071064 0.7071065 0 0.7071072 -0.7071072 0 0.7071064 0 1 0 -3.97034e-6 1 3.41308e-6 6.87364e-7 1 -3.58213e-7 0 1 0 -1.11816e-6 1 6.3683e-7 0 1 0 0 1 0 2.52029e-7 1 2.52029e-7 3.11037e-7 1 0 3.3278e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.13609e-7 -1.3245e-7 1 2.29636e-7 9.18976e-7 1 0 -1.51501e-7 1 2.98119e-7 9.94216e-7 1 -5.05258e-7 0 1 0 0 1 1.27725e-7 0 1 1.39936e-7 0 1 0 1.19974e-6 1 1.19974e-6 1.19974e-6 1 1.19974e-6 0 1 0 -3.31219e-7 1 4.45892e-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 -2.06254e-6 1 -6.58331e-7 0 1 0 1.46879e-6 1 2.31575e-7 8.07612e-7 1 4.65773e-7 2.72284e-7 1 2.72284e-7 1.42386e-7 1 2.4689e-7 0 1 1.8605e-7 -1.29676e-7 1 2.24783e-7 0 1 1.99471e-7 -1.88933e-6 1 -4.85216e-7 5.85889e-6 1 9.23689e-7 2.3439e-7 1 2.34413e-7 5.86208e-7 1 3.38083e-7 4.46713e-7 1 -2.27017e-7 0 1 1.84579e-7 0 1 1.94832e-7 -1.26074e-7 1 2.18602e-7 0 1 1.88328e-7 0 1 2.32678e-7 0 1 2.31209e-7 0 1 1.43823e-7 0 1 0 0 1 2.03722e-7 0 1 0 2.52029e-7 1 2.52029e-7 3.64992e-6 1 5.75573e-7 2.7398e-7 1 2.73978e-7 6.44323e-7 1 3.71633e-7 1.48036e-6 1 -7.52375e-7 1.27573e-7 1 2.21183e-7 -3.43645e-7 1 3.43648e-7 -1.55483e-7 1 2.69564e-7 0 1 2.29017e-7 1.93592e-6 1 -1.61293e-6 0 1 1.99084e-7 0 1 0 0 1 1.36257e-7 -6.58793e-7 1 7.45212e-7 4.05593e-7 1 -1.84333e-7 -1.59524e-7 1 9.18984e-7 4.64674e-7 1 -2.68016e-7 0 1 0 0 1 0 1.80683e-7 1 1.9762e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.08622e-7 2.02798e-6 1 1.52776e-6 2.20714e-7 1 4.12397e-7 7.01172e-7 1 8.56477e-7 0 1 0 4.59579e-6 1 4.59589e-6 2.24487e-6 1 2.35325e-6 -2.93871e-7 1 -1.57243e-7 2.38717e-7 1 2.62157e-7 -1.5852e-7 1 0 0 1 0 8.58296e-7 1 8.86683e-7 0 1 0 2.31588e-7 1 2.39248e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.32496e-7 0 1 3.85819e-7 5.03677e-7 1 6.29382e-7 2.75783e-7 1 5.15393e-7 8.76365e-7 1 1.0705e-6 -9.81329e-7 1 -8.03384e-7 5.74786e-6 1 5.74786e-6 2.80619e-6 1 2.94168e-6 4.9092e-7 1 5.14622e-7 -2.1911e-7 1 0 -1.38001e-7 1 0 0 1 0 1.20088e-6 1 8.53171e-7 0 1 0 0 1 0 0 1 0 0 1 1.23546e-7 0 1 0 2.08912e-7 1 2.22385e-7 0 1 1.71715e-7 4.78271e-7 1 4.78271e-7 -1.47592e-7 1 0 0 1 1.28676e-7 0 1 2.10436e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.28676e-7 -1.47591e-7 1 0 0 1 0 9.56542e-7 1 9.56542e-7 -2.42019e-7 1 0 1.95796e-7 1 2.88171e-7 1.56085e-7 1 2.29725e-7 0 1 0 0 1 0 0 1 1.23012e-7 0 1 0 3.09715e-7 1 3.09722e-7 0 1 0 0 1 0 0 1 0 0 1 1.60846e-7 -1.8449e-7 1 0 -2.93736e-7 1 0 1.84616e-7 1 2.30692e-7 -1.23396e-7 1 0 0 1 0 0 1 1.61269e-7 0 1 1.4061e-7 2.91052e-7 1 2.91058e-7 -1.84489e-7 1 0 0 1 1.60845e-7 0 1 1.32616e-7 0 1 0 0 1 0 0 1 0 1.72678e-7 1 2.12329e-7 0 1 1.41811e-7 6.20397e-7 1 6.20397e-7 6.54826e-7 1 6.54841e-7 0 1 0 3.47644e-6 1 2.91981e-6 0 1 0 3.81151e-7 1 4.81162e-7 0 1 0 0 1 0 0 1 0 0 1 0 -4.33058e-7 1 -2.89285e-7 1.33758e-7 1 1.38509e-7 0 1 0 -9.26608e-7 1 -1.84314e-7 0 1 1.90282e-7 -3.3312e-7 1 0 4.01713e-7 1 4.67425e-7 0 1 0 0 1 0 -1.20473e-7 1 0 0 1 0 1.25389e-7 1 1.87706e-7 -1.87735e-7 1 -1.25422e-7 0 1 0 -2.61196e-7 1 0 0 1 0 -1.40443e-7 1 0 0 1 1.90021e-7 -1.97998e-7 1 0 -1.35166e-7 1 1.64876e-7 0 1 3.38922e-7 1.72947e-6 1 1.72949e-6 0 1 1.6571e-7 3.24016e-7 1 0 0 1 1.90547e-7 0 1 1.82741e-7 0 1 1.62676e-7 -1.44814e-6 1 7.35983e-7 -2.12037e-7 1 2.711e-7 0 1 1.55138e-7 -1.29266e-7 1 2.54345e-7 0 1 2.06588e-7 1.77948e-7 1 1.77946e-7 -4.43128e-7 1 0 0 1 1.98415e-7 -1.40883e-7 1 2.77196e-7 -9.85494e-7 1 5.00867e-7 0 1 2.45246e-7 2.32475e-7 1 2.32475e-7 0 1 0 1.99652e-7 1 2.32093e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.30685e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.09137e-7 -1.57562e-7 1 3.10015e-7 -1.95182e-7 1 0 0 1 2.55222e-7 0 1 2.15997e-7 1.62625e-7 1 1.62625e-7 0 1 0 0 1 0 0 1 0 0 1 2.02419e-7 0 1 0 0 1 0 0 1 0 -1.90085e-6 1 -1.81034e-6 0 1 0 0 1 0 0 1 0 0 1 0 -4.11802e-7 1 0 1.20809e-7 1 2.75838e-7 0 1 0 -1.88994e-7 1 0 1.91219e-7 1 1.91217e-7 0 1 0 1.91215e-7 1 1.91215e-7 6.04922e-7 1 3.19038e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -3.96505e-7 1 0 -1.35024e-6 1 -6.80175e-7 0 1 0 0 1 0 0 1 1.3995e-7 0 1 1.20308e-7 0 1 0 0 1 1.50023e-7 1.65889e-7 1 2.28894e-7 0 1 0 2.45037e-6 1 1.83363e-6 0 1 0 0 1 0 0 1 0 -1.22422e-7 1 0 2.05329e-7 1 2.08746e-7 0 1 0 0 1 1.29077e-7 0 1 1.57078e-7 0 1 2.09638e-7 2.85782e-7 1 3.94326e-7 0 1 0 5.44417e-7 1 6.21048e-7 -5.70821e-7 1 -1.84442e-7 1.88005e-7 1 2.2196e-7 -2.37246e-7 1 0 -1.5479e-7 1 0 -1.78205e-6 1 -1.46093e-6 -2.70742e-7 1 0 -3.89738e-7 1 0 1.90388e-7 1 2.76373e-7 -2.51617e-7 1 0 -3.5899e-7 1 0 -5.94954e-7 1 -3.17453e-7 1.21758e-7 1 1.21757e-7 0 1 1.30792e-7 0 1 1.46739e-7 0 1 1.60963e-7 0 1 0 -1.27829e-7 1 0 1.8771e-7 1 2.53712e-7 -1.19054e-6 1 -8.15097e-7 0 1 0 -2.58386e-7 1 -1.81756e-7 -2.22627e-7 1 3.54208e-7 -1.89035e-7 1 3.27742e-7 1.14872e-6 1 -7.09698e-7 -1.57533e-7 1 2.68981e-7 -2.20042e-7 1 1.26915e-7 0 1 0 8.64654e-7 1 3.47637e-7 0 1 0 0 1 0 0 1 0 1.31178e-7 1 2.04684e-7 0 1 1.7657e-7 -8.07772e-7 1 -7.11983e-7 -3.88477e-7 1 -2.24073e-7 -2.14086e-7 1 0 4.27934e-7 1 1.08467e-6 0 1 1.64165e-7 0 1 0 2.64863e-7 1 3.2343e-7 0 1 0 0 1 0 0 1 0 -2.09819e-7 1 0 0 1 1.29518e-7 9.23364e-7 1 9.23403e-7 2.42067e-7 1 3.6928e-7 -6.10258e-7 1 3.51992e-7 0 1 1.88184e-7 9.92614e-7 1 5.87532e-7 0 1 0 0 1 0 0 1 0 1.44082e-6 1 -9.47544e-7 -1.91557e-7 1 3.23138e-7 -1.81962e-7 1 3.15481e-7 9.18982e-7 1 -5.50246e-7 -2.2399e-7 1 -1.29192e-7 -1.50843e-7 1 0 2.25189e-7 1 9.3528e-7 0 1 1.27829e-7 3.82224e-7 1 3.82224e-7 0 1 1.47562e-7 0 1 1.47518e-7 2.18951e-7 1 2.13743e-7 0 1 0 0 1 0 5.80983e-6 1 -3.35103e-6 0 1 0 0 1 0 -2.22034e-6 1 9.18982e-7 -2.77545e-6 1 1.14874e-6 7.26113e-6 1 -4.18808e-6 1.2039e-7 1 1.20389e-7 0 1 1.25244e-7 0 -1 0 -0.4705901 0 -0.882352 0 -1 0 -0.7071071 0 -0.7071065 0 -1 0 -0.7071071 0 -0.7071065 0 -1 0 0.09711259 0 -0.9952734 0 -1 0 -0.4705901 0 -0.882352 0 -1 0 0.6350921 0 -0.7724364 0 -1 0 0.09711259 0 -0.9952734 0 -1 0 0.9566788 0 -0.2911453 0 -1 0 0 -1 0 0 -1 0 0.6350921 0 -0.7724364 6.11393e-7 -1 -5.43814e-7 1 0 -4.0786e-7 0.9566788 0 -0.2911453 0 -1 0 0.956676 0 0.2911545 9.51645e-7 -1 -3.73123e-7 1 0 -4.0786e-7 0 -1 0 0.6350966 0 0.7724327 0.956676 0 0.2911545 0 -1 0 0.09711182 0 0.9952734 0.6350966 0 0.7724327 0 -1 0 -0.4705971 0 0.8823482 0.09711182 0 0.9952734 -2.56715e-6 -1 1.47952e-6 -0.707107 0 0.7071067 -0.4705971 0 0.8823482 0 -1 0 -0.8662403 0 0.4996275 0 -1 0 1.67202e-6 -1 -1.67202e-6 -0.7071069 0 0.7071067 0 -1 0 -1 0 0 0 -1 0 -0.8662403 0 0.4996275 0 -1 0 -0.8662406 0 -0.4996271 0 -1 0 -1 0 0 0 -1 0 -0.8662406 0 -0.4996271 -6.26406e-6 -1 5.17643e-6 0.7071069 0 -0.7071067 0 -1 0 0.4996195 0 -0.8662449 0 -1 0 0.4996195 0 -0.8662449 0 -1 0 0.8823482 0 -0.4705971 4.86343e-7 -1 -6.48926e-7 0 -1 0 0.7071069 0 -0.7071067 0 -1 0 0.9952734 0 0.09711277 0.8823482 0 -0.4705971 0 -1 0 0.772432 0 0.6350975 0 -1 0 0.9952734 0 0.09711277 0 -1 0 0.2911575 0 0.9566751 0 -1 0 0.772432 0 0.6350975 -5.43813e-7 -1 -6.11394e-7 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2911575 0 0.9566751 0 -1 0 -0.2911485 0 0.9566779 -3.73123e-7 -1 -9.51645e-7 0 0 1 0 -1 0 -0.772436 0 0.6350926 0 -1 0 0 -1 0 -0.2911485 0 0.9566779 0 -1 0 -0.9952725 0 0.09712171 0 -1 0 -0.772436 0 0.6350926 0 -1 0 -0.8823478 0 -0.4705977 0 -1 0 -0.9952725 0 0.09712171 0 -1 0 -0.7071069 0 -0.7071067 0 -1 0 -0.8823478 0 -0.4705977 0 -1 0 -0.4996193 0 -0.866245 0 -1 0 -0.7071069 0 -0.7071067 0 -1 0 0 0 -1 0 -1 0 -0.4996193 0 -0.866245 0 -1 0 0 0 -1 0.8662407 0 -0.4996269 0 -1 0 0.7071068 0 -0.7071067 0.7071068 0 -0.7071067 1 0 0 0.8662407 0 -0.4996269 0.8662405 0 0.4996273 1 0 0 0.707107 0 0.7071066 0.8662405 0 0.4996273 0.4705907 0 0.8823516 0.707107 0 0.7071066 -0.09711277 0 0.9952735 0.4705907 0 0.8823516 -0.6350926 0 0.772436 -0.09711277 0 0.9952735 0 -1 0 -0.9566788 0 0.2911455 0 -1 0 0 -1 0 -0.6350926 0 0.772436 0 -1 0 -1 0 0 -0.9566788 0 0.2911455 0 -1 0 -0.9566789 0 -0.2911453 0 -1 0 -1 0 0 0 -1 0 -0.6350961 0 -0.7724331 -0.9566789 0 -0.2911453 0 -1 0 -0.09711199 0 -0.9952735 -0.6350961 0 -0.7724331 0 -1 0 0.470597 0 -0.8823482 -0.09711199 0 -0.9952735 0.470597 0 -0.8823482 1.67202e-6 -1 -1.67202e-6 -0.7071067 0 0.7071069 -0.4996272 0 0.8662405 -0.4996272 0 0.8662405 0 -1 0 -0.8823479 0 0.4705978 0 -1 0 4.86259e-7 -1 -6.48814e-7 -0.7071067 0 0.7071069 0 -1 0 -0.9952735 0 -0.09711265 -0.8823479 0 0.4705978 0 -1 0 -0.7724314 0 -0.6350983 -0.9952735 0 -0.09711265 0 -1 0 -0.2911576 0 -0.9566752 0 -1 0 -0.7724314 0 -0.6350983 0 -1 0 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2911576 0 -0.9566752 0 -1 0 0.2911485 0 -0.9566779 0 -1 0 0 0 -1 0.7724354 0 -0.6350935 0.2911485 0 -0.9566779 0.9952734 0 -0.09711259 0.7724354 0 -0.6350935 0.8823482 0 0.4705971 0.9952734 0 -0.09711259 0.707107 0 0.7071065 0.8823482 0 0.4705971 0.4996201 0 0.8662446 0.707107 0 0.7071065 9.18982e-6 0 1 0.4996201 0 0.8662446 9.18982e-6 0 1 0 -1 0 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0 -1 0 0.7071077 0 0.7071059 0 -1 0 0 -1 0 0.7071068 0 -0.7071068 0 -1 0 -0.7071065 0 0.707107 0 -1 0 0.7071077 0 0.7071058 0 -1 0 0 0 1 0 -1 0 0 -1 0 0 -1 0 -0.7071065 0 0.707107 -0.04203075 0 0.9991164 0 0 1 -0.1252124 0 0.99213 -0.04203075 0 0.9991164 -0.2077741 0 0.9781768 -0.1252124 0 0.9921301 -0.2887698 0 0.9573986 -0.2077741 0 0.9781768 -0.3677471 0 0.9299259 -0.2887698 0 0.9573986 -0.4442519 0 0.8959019 -0.3677471 0 0.9299259 -0.5174264 0 0.8557278 -0.4442519 0 0.8959019 0.6195275 0 0.7849748 -0.5174264 0 0.8557278 0 -1 0 0.6978424 0 0.7162513 0 -1 0 -1.3695e-6 -1 1.17738e-6 0.6195275 0 0.7849748 0 -1 0 0.7685841 0 0.6397488 0 -1 0 0.6978424 0 0.7162513 0.7071068 0 -0.7071068 0.7685841 0 0.6397488 -0.7069538 0 -0.7072596 0.7071068 0 -0.7071068 0.7071071 0 -0.7071065 -0.7069538 0 -0.7072596 0 -1 0 0.7071068 0 0.7071068 0 -1 0 0.7071071 0 -0.7071065 1 0 -2.7987e-7 -1.36878e-6 -1 1.17672e-6 0.7071068 0 0.7071068 0.9984005 0 0.05653625 1 0 -2.7987e-7 0 -1 0 0.9858725 0 0.1674976 0.9984005 0 0.05653625 0 -1 0 0.9608811 0 0.276961 0.9858725 0 0.1674976 0 -1 0 0.9238792 0 0.3826845 0.9608811 0 0.276961 0 -1 0 0.8752869 0 0.4836038 0 -1 0 0.9238792 0 0.3826845 1.63623e-6 -1 -2.0841e-6 0.8155558 0 0.5786785 1.4164e-6 -1 -2.0077e-6 0.8752869 0 0.4836038 0 -1 0 0.7459524 0 0.6659992 0 -1 0 0.8155558 0 0.5786785 0 -1 0 0.7849755 0 -0.6195268 0.7459524 0 0.6659992 0 -1 0 0.7162506 0 -0.6978431 0.7849755 0 -0.6195268 0.6397492 0 -0.7685838 0.7162506 0 -0.6978431 0 -1 0 -0.7071068 0 -0.7071068 0.6397492 0 -0.7685838 -0.7071068 0 0.7071068 -0.7071068 0 -0.7071068 -0.7071071 0 -0.7071065 -0.7071068 0 0.7071068 0.707107 0 -0.7071065 -0.7071071 0 -0.7071065 0 0 -1 0.707107 0 -0.7071065 0.05653429 0 -0.9984007 0 0 -1 0.1674991 0 -0.9858723 0.05653429 0 -0.9984007 0.2769606 0 -0.9608814 0.1674991 0 -0.9858723 0.3826828 0 -0.9238798 0.2769606 0 -0.9608814 0.4836039 0 -0.8752869 0.3826828 0 -0.9238798 0.5786788 0 -0.8155555 0.4836039 0 -0.8752869 0.6659992 0 -0.7459524 0.5786788 0 -0.8155555 -0.6195273 0 -0.7849751 0.6659992 0 -0.7459524 0 -1 0 -0.6978424 0 -0.7162514 0 -1 0 -0.6195273 0 -0.7849751 0 -1 0 -0.7685841 0 -0.6397488 0 -1 0 -0.6978424 0 -0.7162514 -0.7071065 0 0.7071071 -0.7685841 0 -0.6397488 0.7071067 0 0.707107 -0.7071065 0 0.7071071 -0.7071068 0 0.7071068 0.7071067 0 0.707107 -0.7071068 0 -0.7071068 -0.7071068 0 0.7071068 -1 0 0 -0.7071068 0 -0.7071068 -0.9984006 0 -0.05653429 -1 0 0 -0.9858726 0 -0.167497 -0.9984006 0 -0.05653429 -0.960881 0 -0.2769616 -0.9858726 0 -0.167497 -0.9238792 0 -0.3826845 -0.960881 0 -0.2769616 -0.8752878 0 -0.4836024 -0.9238792 0 -0.3826845 -0.815556 0 -0.5786782 -0.8752878 0 -0.4836024 0 -1 0 -0.7459527 0 -0.6659989 -0.8155561 0 -0.5786781 0 -1 0 -0.7849756 0 0.6195266 -0.7459527 0 -0.6659989 0 -1 0 -0.7162508 0 0.6978429 -0.7849756 0 0.6195266 -0.6397498 0 0.7685833 -0.7162508 0 0.6978429 -0.6397498 0 0.7685833 0 1 0 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.83449e-6 1 2.3783e-6 1.98208e-6 1 -1.98208e-6 0 1 0 6.26514e-7 1 -3.61078e-7 0 1 0 0 1 0 -2.15519e-6 1 -6.55909e-7 -4.36414e-7 1 1.86561e-7 -3.05697e-7 1 2.71907e-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.62673e-6 1 2.17054e-6 0 1 0 9.91036e-7 1 -9.91036e-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 -6.55871e-7 1 2.15511e-6 0 1 0 -1.60932e-6 1 4.1003e-6 0 1 0 0 1 0 2.71907e-7 1 -1.58797e-7 -1.21411e-6 1 4.21222e-6 -2.44844e-7 1 1.44111e-6 0 1 9.5557e-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 -6.64208e-6 1 7.72971e-6 0 1 0 6.26642e-7 1 -3.61221e-7 0 1 0 0 1 0 -4.31014e-6 1 -1.3117e-6 -8.72751e-7 1 3.73161e-7 -6.11394e-7 1 5.43813e-7 0 1 0 0 1 0 -3.25348e-6 1 4.3411e-6 0 1 0 0 1 0 0 1 0 5.43813e-7 1 -4.2392e-7 -1.10273e-5 1 2.78849e-5 -1.22786e-6 1 4.0709e-6 -5.27556e-7 1 2.48367e-6 2.42163e-6 1 -3.09319e-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 -1.63623e-6 1 2.0841e-6 0 1 0 -1.4164e-6 1 2.00769e-6 0 1 0 0 1 0 0 1 0 0 1 0 1.44895e-7 1 1.44895e-7 2.05426e-6 1 -1.76608e-6 0 1 0 2.05316e-6 1 -1.76508e-6 1.44895e-7 1 1.44895e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.86561e-7 1 -1.86561e-7 1.75474e-7 1 0 1.32639e-7 1 0 -7.08198e-7 1 1.00385e-6 0 1 0 0 1 0 -8.18115e-7 1 1.04205e-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.4705965 0 -0.8823486 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 -0.7071068 0 -0.7071068 0 -1 0 0.09711259 0 -0.9952734 0 -1 0 -0.4705965 0 -0.8823486 0 -1 0 0.6350921 0 -0.7724364 0 -1 0 0.09711259 0 -0.9952734 0 -1 0 0.9566788 0 -0.2911455 0 -1 0 0 -1 0 0 -1 0 0.6350921 0 -0.7724364 0 -1 0 1 0 -4.0786e-7 0.9566788 0 -0.2911455 -7.15885e-7 -1 -2.17872e-7 0.9566761 0 0.2911545 -5.57832e-7 -1 -2.79842e-7 1 0 -4.0786e-7 -3.18726e-7 -1 -3.87653e-7 0.6350926 0 0.772436 0.9566761 0 0.2911545 0 -1 -5.17709e-7 0.09711182 0 0.9952735 0.6350926 0 0.772436 4.09107e-7 -1 -7.67071e-7 -0.4705901 0 0.882352 0.09711182 0 0.9952735 1.25402e-6 -1 -1.25402e-6 -0.7071068 0 0.7071068 -0.4705901 0 0.882352 0 -1 0 -0.8662446 0 0.4996203 0 -1 0 1.25402e-6 -1 -1.25402e-6 -0.7071068 0 0.7071068 0 -1 0 -1 0 0 0 -1 0 -0.8662446 -1.98531e-7 0.49962 0 -1 0 -0.8662446 1.48898e-7 -0.4996201 0 -1 0 -1 0 0 0 -1 0 -0.8662446 0 -0.4996203 8.36385e-7 -1 -8.36386e-7 0.7071065 0 -0.7071071 0 -1 0 0.4996274 0 -0.8662404 8.36389e-7 -1 -8.36389e-7 0.4996274 0 -0.8662404 -1.11006e-6 -1 5.92046e-7 0.8823482 0 -0.4705971 -8.11182e-7 -1 5.85406e-7 -1.91036e-7 -1 -2.42053e-7 0.7071065 0 -0.7071071 -4.23173e-7 -1 0 0.9952726 0 0.09712153 0.8823482 0 -0.4705971 -3.01947e-7 -1 -2.48256e-7 0.7724398 0 0.635088 2.97642e-6 -1 -3.33374e-6 0.9952726 0 0.09712153 -1.5681e-7 -1 -5.15257e-7 0.2911485 0 0.9566779 1.41951e-6 -1 -2.00057e-6 0.7724398 0 0.635088 0 -1 -1.27157e-6 0 0 1 0 -1 -1.19546e-6 1.93247e-7 -1 -1.13744e-6 3.33232e-7 -1 -1.15611e-6 5.25349e-7 -1 -1.2683e-6 8.63438e-7 -1 -1.56276e-6 0.2911485 0 0.9566779 0 -1 0 -0.2911485 0 0.9566779 -2.79842e-7 -1 -7.13733e-7 0 0 1 0 -1 0 -0.772432 0 0.6350975 0 -1 0 0 -1 0 -0.2911485 0 0.9566779 0 -1 0 -0.9952734 0 0.09711259 0 -1 0 -0.772432 0 0.6350975 0 -1 0 -0.8823456 0 -0.4706018 0 -1 0 -0.9952734 0 0.09711259 0 -1 0 -0.707107 0 -0.7071066 0 -1 0 -0.8823456 0 -0.4706018 0 -1 0 -0.4996272 0 -0.8662406 0 -1 0 -0.707107 0 -0.7071066 0 -1 0 0 0 -1 0 -1 0 -0.4996272 0 -0.8662406 0 -1 0 0 0 -1 0.8662407 0 -0.4996269 8.36388e-7 -1 -8.36388e-7 0.7071067 0 -0.7071069 0.7071067 0 -0.7071069 1 0 0 0.8662406 2.16253e-7 -0.4996271 0.8662404 -2.10942e-7 0.4996274 1 0 0 0.7071069 0 0.7071067 0.8662406 0 0.4996272 0.4705971 0 0.8823482 0.7071069 0 0.7071067 -0.09711199 0 0.9952735 0.4705971 0 0.8823482 -0.6350966 0 0.7724328 -0.09711199 0 0.9952735 0 -1 0 -0.9566788 0 0.2911455 0 -1 0 0 -1 0 -0.6350966 0 0.7724328 0 -1 0 -1 0 0 -0.9566788 0 0.2911455 -4.77301e-7 -1 -1.45257e-7 -0.9566789 0 -0.2911453 -3.71925e-7 -1 -1.8658e-7 -1 0 0 -2.12515e-7 -1 -2.58471e-7 -0.6350961 0 -0.7724332 -0.9566789 0 -0.2911453 0 -1 -3.45204e-7 -0.09711199 0 -0.9952735 -0.6350961 0 -0.7724332 2.72817e-7 -1 -5.11524e-7 0.4705935 0 -0.8823502 -0.09711199 0 -0.9952735 0.4705935 0 -0.8823502 1.25402e-6 -1 -1.25402e-6 -0.7071067 0 0.7071069 -0.4996269 0 0.8662406 -0.4996269 0 0.8662406 -7.40042e-7 -1 3.94699e-7 -0.8823479 0 0.4705977 -1.27357e-7 -1 -1.61369e-7 -3.38129e-7 -1 1.19863e-7 -0.7071067 0 0.7071069 -2.82118e-7 -1 0 -0.9952734 0 -0.09711343 -0.8823479 0 0.4705977 -1.67955e-7 -1 -1.38092e-7 -0.7724354 0 -0.6350934 -0.9952734 0 -0.09711343 0 -1 -2.90602e-7 -0.2911545 0 -0.9566761 5.03083e-7 -1 -8.32009e-7 -0.7724354 0 -0.6350934 0 -1 0 0 0 -1 0 -1 0 -8.70537e-7 -1 -7.32733e-7 1.88445e-7 -1 -6.24779e-7 2.59128e-7 -1 -6.55259e-7 3.66386e-7 -1 -7.3887e-7 -0.2911545 0 -0.9566761 0 -1 0 0.2911545 0 -0.9566761 0 -1 0 0 0 -1 0.7724354 0 -0.6350934 0.2911545 0 -0.9566761 0.9952734 0 -0.09711259 0.7724354 0 -0.6350934 0.8823482 0 0.4705971 0.9952734 0 -0.09711259 0.7071067 0 0.7071069 0.8823482 0 0.4705971 0.4996273 0 0.8662405 0.7071067 0 0.7071069 0 0 1 0.4996273 0 0.8662405 0 0 1 0 -1 0 0.7071068 0 -0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0 -1 0 0.7071071 0 0.7071065 0 -1 0 0 -1 0 0.7071068 0 -0.7071068 0 -1 0 -0.7071065 0 0.7071071 0 -1 0 0.7071071 0 0.7071065 0 -1 0 0 0 1 0 -1 0 0 -1 0 0 -1 0 -0.7071065 0 0.7071071 -0.04202973 0 0.9991164 0 0 1 -0.1252139 0 0.9921298 -0.04202973 0 0.9991164 -0.2077728 0 0.9781771 -0.1252139 0 0.9921298 -0.2887698 0 0.9573986 -0.2077728 0 0.9781771 -0.3677471 0 0.9299258 -0.2887698 0 0.9573986 -0.4442531 0 0.8959012 -0.3677471 0 0.9299258 -0.5174253 0 0.8557284 -0.4442531 0 0.8959012 0.6195271 0 0.7849753 -0.5174253 0 0.8557284 0 -1 0 0.6978428 0 0.7162508 0 -1 0 -1.71188e-6 -1 1.47173e-6 0.6195271 0 0.7849753 0 -1 0 0.7685833 0 0.6397498 0 -1 0 0.6978428 0 0.7162508 0.7071068 0 -0.7071068 0.7685833 0 0.6397498 -0.7069537 0 -0.7072597 0.7071068 0 -0.7071068 0.7071077 0 -0.7071059 -0.7069537 0 -0.7072597 -1.20746e-7 -1 -1.20746e-7 0.7071068 0 0.7071068 -1.20746e-7 -1 -1.20746e-7 0.7071077 0 -0.7071059 1 0 -2.7987e-7 -1.71096e-6 -1 1.47089e-6 0.7071068 0 0.7071068 0.9984006 0 0.05653625 1 0 -2.7987e-7 0 -1 0 0.9858726 0 0.1674975 0.9984006 0 0.05653625 0 -1 0 0.9608808 0 0.2769622 0.9858726 0 0.1674975 0 -1 0 0.9238795 0 0.3826833 0.9608808 0 0.2769622 0 -1 0 0.8752869 0 0.4836038 0 -1 0 0.9238795 0 0.3826833 0 -1 0 0.8155558 0 0.5786785 0 -1 0 0.8752869 0 0.4836038 -3.9251e-7 -1 -3.50441e-7 0.7459515 0 0.6660001 8.13016e-7 -1 -1.03556e-6 0.8155558 0 0.5786785 -3.95994e-6 -1 3.12531e-6 0.7849756 0 -0.6195269 0.7459515 0 0.6660001 -1.08005e-5 -1 1.05229e-5 0.7162508 0 -0.6978428 0.7849756 0 -0.6195269 0.6397498 0 -0.7685833 0.7162508 0 -0.6978428 -5.99422e-7 -1 -5.99422e-7 -0.7071068 0 -0.7071068 0.6397498 0 -0.7685833 -0.7071068 0 0.7071068 -0.7071068 0 -0.7071068 -0.7071071 0 -0.7071065 -0.7071068 0 0.7071068 0.7071071 0 -0.7071065 -0.7071071 0 -0.7071065 -2.79842e-7 0 -1 0.7071071 0 -0.7071065 0.05653625 0 -0.9984005 -2.79842e-7 0 -1 0.167497 0 -0.9858726 0.05653625 0 -0.9984005 0.276961 0 -0.9608812 0.167497 0 -0.9858726 0.3826833 0 -0.9238795 0.276961 0 -0.9608812 0.4836038 0 -0.8752869 0.3826833 0 -0.9238795 0.5786776 0 -0.8155564 0.4836038 0 -0.8752869 0.6659992 0 -0.7459525 0.5786776 0 -0.8155564 -0.6195264 0 -0.7849758 0.6659992 0 -0.7459525 0 -1 0 -0.6978431 0 -0.7162507 0 -1 0 -0.6195264 0 -0.7849758 0 -1 0 -0.7685833 0 -0.6397498 0 -1 0 -0.6978431 0 -0.7162507 -0.7071064 0 0.707107 -0.7685833 0 -0.6397498 0.7071067 0 0.7071069 -0.7071064 0 0.707107 -0.7071077 0 0.7071059 0.7071067 0 0.7071069 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071059 -1 0 0 -0.7071068 0 -0.7071068 -0.9984007 0 -0.05653297 -1 0 0 -0.9858723 0 -0.1674982 -0.9984007 0 -0.05653297 -0.9608809 0 -0.276962 -0.9858723 0 -0.1674982 -0.9238798 0 -0.3826828 -0.9608809 0 -0.276962 -0.8752873 0 -0.4836032 -0.9238798 0 -0.3826828 -0.8155555 0 -0.5786789 -0.8752873 0 -0.4836032 0 -1 0 -0.7459527 0 -0.6659988 -0.8155555 0 -0.5786789 0 -1 0 -0.7849763 0 0.6195259 -0.7459527 0 -0.6659988 0 -1 0 -0.7162507 0 0.6978431 -0.7849763 0 0.6195259 -0.6397491 0 0.7685838 -0.7162507 0 0.6978431 -0.6397491 0 0.7685838 0 1 0 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.91037e-7 1 -9.91037e-7 9.91034e-7 1 -9.91034e-7 -4.09107e-7 1 7.67071e-7 -7.80925e-7 1 9.81361e-7 0 1 5.17709e-7 3.18726e-7 1 3.87653e-7 0 1 0 5.70922e-7 1 2.79842e-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 1.48656e-6 1 -1.48656e-6 0 1 0 1.48655e-6 1 -1.48655e-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 -9.83807e-7 1 3.23267e-6 0 1 0 -2.41397e-6 1 6.15043e-6 0 1 0 0 1 0 0 1 9.61494e-7 -1.82119e-6 1 6.31838e-6 -3.67257e-7 1 2.16164e-6 0 1 1.43336e-6 1.5681e-7 1 5.15257e-7 -8.63438e-7 1 1.56276e-6 -5.25349e-7 1 1.2683e-6 2.51934e-7 1 2.07136e-7 -5.44078e-6 1 6.09395e-6 -1.41951e-6 1 2.00057e-6 3.54e-7 1 0 2.01799e-7 1 2.55691e-7 6.20452e-7 1 -3.30916e-7 1.48655e-6 1 -1.48655e-6 -2.72817e-7 1 5.11524e-7 -3.46782e-7 1 5.5416e-7 0 1 3.45204e-7 2.12515e-7 1 2.58471e-7 0 1 0 3.80654e-7 1 1.8658e-7 0 1 0 0 1 0 0 1 0 9.91036e-7 1 -9.91036e-7 0 1 0 0 1 0 0 1 0 0 1 4.53261e-7 -5.51374e-6 1 1.39427e-5 -6.13931e-7 1 2.03545e-6 1.71504e-6 1 -3.24311e-6 0 1 0 0 1 2.37141e-7 -5.65317e-7 1 9.34932e-7 -3.66386e-7 1 7.3887e-7 1.67955e-7 1 1.38092e-7 2.36001e-7 1 0 1.34533e-7 1 1.70461e-7 4.13635e-7 1 -2.20611e-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 1.20746e-7 1 1.20746e-7 1.71189e-6 1 -1.47173e-6 0 1 0 1.71095e-6 1 -1.47088e-6 1.20746e-7 1 1.20746e-7 0 1 0 0 1 0 0 1 0 0 1 0 2.79842e-7 1 -2.79842e-7 2.63211e-7 1 -1.26718e-7 1.98959e-7 1 0 0 1 0 0 1 0 -4.37977e-6 1 5.57861e-6 0 1 0 3.71201e-7 1 3.71201e-7 3.85368e-7 1 3.44064e-7 1.08005e-5 1 -1.05229e-5 3.95994e-6 1 -3.12531e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.3814378 0 -0.9243944 0 -1 0 -0.9243942 7.15333e-4 -0.381438 -0.9238904 0 -0.3826574 0 -1 0 0.383801 -3.11128e-5 -0.9234158 0 -1 0 -0.3826583 7.17074e-4 -0.9238896 0 -1 0 0.9234147 6.1123e-4 -0.3838031 0.3827068 6.10715e-4 -0.9238696 0 -1 0 0.9243942 7.13753e-4 0.381438 0 -1 0 0.9238689 -2.97633e-5 -0.382709 0 -1 0 0.3814336 0 0.9243962 0.9238915 0 0.3826547 0 -1 0 -0.3838089 -3.62301e-5 0.9234126 0.3826428 7.10424e-4 0.9238961 0 -1 0 -0.9234134 6.10864e-4 0.3838062 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3827063 6.10563e-4 0.9238699 -0.923868 -3.06154e-5 0.3827112 0 -1 0 -0.3814384 0 -0.9243943 0 -1 0 -0.9243934 7.146e-4 -0.3814398 -0.9238901 0 -0.382658 0 -1 0 0.3838021 -3.1114e-5 -0.9234154 -0.3826588 7.17075e-4 -0.9238895 0 -1 0 0.9234123 6.12332e-4 -0.3838087 0 -1 0 0 -1 0 0.3827071 6.11172e-4 -0.9238695 0 -1 0 0.9243942 7.17758e-4 0.381438 0.9238697 -3.30438e-5 -0.3827071 0 -1 0 0.3814326 0 0.9243966 0 -1 0 0.9238887 0 0.3826615 0 -1 0 -0.383797 -2.81728e-5 0.9234175 0 -1 0 0 -1 0 0.3826581 7.20008e-4 0.9238898 0 -1 0 -0.9234123 6.14167e-4 0.3838087 0 -1 0 -0.3827058 6.11932e-4 0.9238701 0 -1 0 -0.9238699 -3.13446e-5 0.3827068 0 -1 0 0.8314614 0 -0.5555825 0 -1 0 0.5555753 6.10612e-5 -0.8314663 -1.93668e-6 -1 1.79019e-6 -3.18311e-7 -1 1.60181e-7 0.5557006 0 -0.8313826 0 -1 0 0.9807889 -3.5454e-4 -0.1950721 0.8313922 5.06187e-5 -0.5556861 0 -1 0 0.9807862 1.37413e-4 0.1950857 0.980622 -6.77875e-6 -0.1959092 0 -1 0 0.8314658 -9.05322e-4 0.5555751 0.9804429 -5.73627e-4 0.1968026 0 -1 0 0.5555753 1.49916e-4 0.8314663 0.8329033 1.49838e-4 0.5534185 0 -1 0 0.1950871 -5.7752e-4 0.9807857 0 -1 0 0 -1 0 0.553411 -9.07058e-4 0.8329078 0 -1 0 -0.1950902 -7.70617e-6 0.9807853 0 -1 0 0.1968207 1.39281e-4 0.9804395 0 -1 0 -0.5555825 6.37135e-5 0.8314614 -0.1958972 -3.42489e-4 0.9806243 0 -1 0 -0.831459 0 0.5555861 0 -1 0 0 -1 0 0 -1 0 -0.5557132 0 0.8313741 0 -1 0 -0.9807832 -3.48275e-4 0.1951007 -0.8313826 5.59202e-5 0.5557006 0 -1 0 -0.980782 1.30565e-4 -0.1951068 0 -1 0 -0.980622 -1.23906e-5 0.1959092 0 -1 0 -0.8314756 -8.98246e-4 -0.5555607 -0.9804432 -5.71123e-4 -0.1968011 0 -1 0 -0.5555753 1.49916e-4 -0.8314663 -0.8329033 1.49838e-4 -0.5534185 0 -1 0 -0.1950901 -5.77523e-4 -0.9807851 -0.553411 -9.07058e-4 -0.8329078 0 -1 0 0.1950872 -6.46468e-6 -0.9807859 -0.1968208 1.3803e-4 -0.9804395 0.1959047 -3.45598e-4 -0.9806229 0 -1 0 0.8314759 0 -0.5555609 0 -1 0 0.555559 5.57424e-5 -0.8314771 0.5556734 0 -0.8314006 0 -1 0 0.9807859 -3.48289e-4 -0.1950872 0 -1 0 0.8313994 5.58888e-5 -0.5556752 0 -1 0 0.980785 1.36795e-4 0.1950917 0 -1 0 0.9806218 -6.15654e-6 -0.1959107 0 -1 0 0.8314756 -9.08831e-4 0.5555607 0.9804393 -5.79253e-4 0.1968207 0 -1 0 0.5555483 1.49915e-4 0.8314843 0.8329177 1.49837e-4 0.5533969 0 -1 0 0.1951142 -5.66333e-4 0.9807804 0.5534111 -8.93837e-4 0.8329078 0 -1 0 -0.1951128 -1.52076e-5 0.9807808 0.1967936 1.28044e-4 0.9804449 0 -1 0 -0.555559 6.10406e-5 0.8314771 -0.1959092 -3.45594e-4 0.9806219 0 -1 0 -0.8314759 0 0.5555609 0 -1 0 -0.5556843 0 0.8313934 0 -1 0 -0.980782 -3.37055e-4 0.1951068 -0.8313813 6.91507e-5 0.5557023 0 -1 0 -0.9807859 1.31178e-4 -0.1950872 -0.9806265 -1.30048e-5 0.1958867 0 -1 0 -0.8314611 -9.08849e-4 -0.5555823 0 -1 0 -0.980443 -5.79235e-4 -0.1968026 0 -1 0 -0.5555753 1.49916e-4 -0.8314663 -0.8329033 1.49838e-4 -0.5534185 0 -1 0 -0.1950901 -5.66929e-4 -0.9807851 -0.5534344 -8.95616e-4 -0.8328922 0 -1 0 0.1950872 -6.46468e-6 -0.9807859 -0.1967951 1.38021e-4 -0.9804446 0.1959092 -3.47462e-4 -0.9806221 0 -1 0 0.5555753 0 0.8314663 0 -1 0 0.8314663 6.10612e-5 0.5555753 0.8313826 0 0.5557006 0 -1 0 0.1950902 -3.47046e-4 0.9807853 0.5556969 5.94503e-5 0.831385 0 -1 0 -0.1950872 1.30558e-4 0.9807859 0.1958957 -1.23855e-5 0.9806247 0 -1 0 -0.5555714 -9.0884e-4 0.8314683 -0.1968011 -5.79233e-4 0.9804432 0 -1 0 -0.8314771 1.41985e-4 0.555559 0 -1 0 0 -1 0 0 -1 0 -0.5534185 1.4456e-4 0.8329033 0 -1 0 -0.9807851 -5.76283e-4 0.1950901 0 -1 0 -0.832903 -9.03546e-4 0.5534182 0 -1 0 -0.9807859 -6.46468e-6 -0.1950872 0 -1 0 -0.9804401 1.38029e-4 0.1968178 0 -1 0 -0.8314722 6.10498e-5 -0.5555663 0 -1 0 -0.9806229 -3.45598e-4 -0.1959047 0 -1 0 -0.5555717 0 -0.8314687 0 -1 0 -0.8313886 0 -0.5556915 0 -1 0 -0.1950872 -3.48289e-4 -0.9807859 0 -1 0 -0.5556861 5.5902e-5 -0.8313923 0 -1 0 0.1950902 1.36795e-4 -0.9807853 0 -1 0 -0.1959107 -6.15654e-6 -0.9806218 0 -1 0 0.555575 -9.0531e-4 -0.8314659 0 -1 0 0.1968162 -5.77997e-4 -0.9804403 0 -1 0 0.8314614 1.49916e-4 -0.5555825 0 -1 0 0 -1 0 0.5534185 1.49838e-4 -0.8329033 0 -1 0 0.9807857 -5.7752e-4 -0.1950871 0.832903 -9.07064e-4 -0.5534182 0 -1 0 0.9807853 -7.70617e-6 0.1950902 0.9804395 1.39281e-4 -0.1968207 0 -1 0 0.9806229 -3.45598e-4 0.1959047 0.5555753 0 0.8314663 0.8314771 5.83856e-5 0.555559 0.831397 0 0.5556788 0.1950706 -3.53301e-4 0.9807892 0.5556861 5.41541e-5 0.8313922 -0.1950917 1.36795e-4 0.980785 0.1959062 -6.15483e-6 0.9806227 -0.5555642 -9.03547e-4 0.8314731 -0.1968057 -5.73004e-4 0.9804424 0 -1 0 -0.8314626 1.52559e-4 0.5555806 0 -1 0 -0.5534077 1.51597e-4 0.8329105 0 -1 0 -0.9807857 -5.7752e-4 0.1950871 -0.8329078 -9.07058e-4 0.553411 0 -1 0 -0.9807808 -1.52076e-5 -0.1951128 0 -1 0 -0.980445 1.28044e-4 0.1967936 0 -1 0 -0.8314687 6.10566e-5 -0.5555717 -0.9806219 -3.45594e-4 -0.1959092 0 -1 0 -0.5555753 0 -0.8314663 -0.8313849 0 -0.5556969 0 -1 0 -0.1951067 -3.46409e-4 -0.9807819 -0.5557006 6.12197e-5 -0.8313826 0 -1 0 0.1951007 1.32423e-4 -0.9807832 -0.1959062 -1.42578e-5 -0.9806227 0 -1 0 0.5555642 -9.05313e-4 -0.8314731 0.1968057 -5.7363e-4 -0.9804424 0.8314771 1.49915e-4 -0.555559 0 -1 0 0.5534077 1.49837e-4 -0.8329105 0.9807851 -5.77523e-4 -0.1950901 0.8329187 -9.07045e-4 -0.5533949 0.9807859 -6.46468e-6 0.1950872 0.9804395 1.3803e-4 -0.1968208 0.9806236 -3.44352e-4 0.1959018 -6.35805e-7 -1 4.24954e-7 -0.8313953 0 0.5556814 0 -1 0 -0.5556741 1.28617e-5 0.8314002 4.81076e-7 -1 -6.44921e-7 -3.18337e-7 -1 1.60194e-7 -0.5557006 0 0.8313826 -2.43625e-7 -1 0 -0.980727 -1.63651e-4 0.1953833 -0.831385 7.59426e-6 0.5556969 -1.60381e-7 -1 0 -0.9808375 4.55702e-4 -0.1948274 -0.980625 4.82475e-5 0.1958943 0 -1 0 -0.8315292 -5.06384e-4 -0.5554808 -0.980451 -3.45086e-4 -0.1967634 0 -1 0 -0.5554772 4.98239e-4 -0.8315316 -0.8328973 4.97993e-4 -0.5534275 0 -1 -2.12533e-7 -0.1948139 -3.53462e-4 -0.9808401 6.67234e-5 -1 -6.67234e-5 1.78246e-7 -1 -4.30327e-7 -0.5534076 -5.13521e-4 -0.8329105 0 -1 -3.14795e-7 0.1953878 5.5658e-5 -0.980726 0 -1 -1.80117e-7 -0.1967861 4.63252e-4 -0.9804464 4.98541e-7 -1 -7.45924e-7 0.5556705 1.81591e-5 -0.8314026 0.1958957 -1.55331e-4 -0.9806247 0 -1 0 0.8314026 0 -0.5556705 -4.43558e-7 -1 1.83728e-7 0 -1 -2.98556e-7 -1.78643e-7 -1 0 0.5557077 0 -0.8313776 0 -1 0 0.9807231 -1.55544e-4 -0.1954029 0.8313776 1.81793e-5 -0.5557078 0 -1 0 0.9808381 4.5508e-4 0.1948244 0 -1 0 0.9806247 4.88686e-5 -0.1958957 0 -1 0 0.8315243 -5.11685e-4 0.5554881 0.980451 -3.46962e-4 0.1967634 0 -1 0 0.5554772 4.98239e-4 0.8315316 0.8328997 4.97993e-4 0.5534238 0 -1 0 0.1948289 -3.44115e-4 0.9808371 0.5534238 -5.05584e-4 0.8328997 0 -1 0 -0.1953983 4.94112e-5 0.980724 0.1967634 4.56996e-4 0.9804509 -0.1958957 -1.57199e-4 0.9806247 0 -1 0 -0.8314026 0 0.5556705 0 -1 0 -0.5556705 7.57386e-6 0.8314026 -0.5556861 0 0.8313922 0 -1 0 -0.9807236 -1.61781e-4 0.1953998 0 -1 0 -0.831385 1.28911e-5 0.5556969 0 -1 0 -0.9808329 4.55725e-4 -0.19485 0 -1 0 -0.9806227 4.82344e-5 0.1959062 0 -1 0 -0.8315351 -5.11678e-4 -0.5554718 -0.9804454 -3.46976e-4 -0.1967905 0 -1 0 -0.5554808 5.06169e-4 -0.8315292 -0.8329176 5.03267e-4 -0.5533968 0 -1 0 -0.1948274 -3.44734e-4 -0.9808375 -0.5534076 -5.07337e-4 -0.8329105 0 -1 0 0.1953833 5.81595e-5 -0.980727 -0.1967875 4.66996e-4 -0.980446 0 -1 0 0.5556814 7.57968e-6 -0.8313953 0.1959167 -1.63425e-4 -0.9806205 0 -1 0 0.8314002 0 -0.5556741 0 -1 0 0.5556969 0 -0.831385 0 -1 0 0.980724 -1.57409e-4 -0.1953983 0.8313826 1.28758e-5 -0.5557006 0 -1 0 0.9808371 4.64439e-4 0.1948289 0.9806203 5.8196e-5 -0.1959182 0 -1 0 0.8315267 -5.09918e-4 0.5554844 0 -1 0 0.9804458 -3.4635e-4 0.196789 0 -1 0 0.5554988 5.03528e-4 0.8315171 0.8329045 5.0151e-4 0.5534167 0 -1 0 0.1948018 -3.55314e-4 0.9808425 0.5534076 -5.18799e-4 0.8329105 0 -1 0 -0.1953803 5.87839e-5 0.9807276 0.1967861 4.66369e-4 0.9804464 -0.1959152 -1.63426e-4 0.9806208 0 -1 0 -0.5556851 0 -0.831393 0 -1 0 -0.8313918 7.58257e-6 -0.5556868 -0.8313813 0 -0.5557023 0 -1 0 -0.1953758 -1.63654e-4 -0.9807285 -0.5557006 7.58154e-6 -0.8313825 0 -1 0 0.1948274 4.65056e-4 -0.9808375 -0.1959093 5.75831e-5 -0.9806221 0 -1 0 0.5554718 -5.11678e-4 -0.8315352 0.1967905 -3.46976e-4 -0.9804454 0 -1 0 0.8315303 4.99127e-4 -0.555479 0 -1 0 0 -1 0 0 -1 0 0.5534004 5.01526e-4 -0.8329152 0 -1 0 0.9808371 -3.53469e-4 -0.1948289 0 -1 0 0.8329105 -5.13521e-4 -0.5534076 0 -1 0 0.9807285 5.87888e-5 0.1953758 0 -1 0 0.9804418 4.66391e-4 -0.1968086 0 -1 0 0.8313845 7.5884e-6 0.5556976 0 -1 0 0.9806218 -1.63428e-4 0.1959107 0 -1 0 0.5556814 0 0.8313953 0 -1 0 0.8313741 0 0.5557132 0 -1 0 0.1953998 -1.57409e-4 0.9807236 0 -1 0 0.5557078 1.28796e-5 0.8313776 0 -1 0 -0.1948229 4.65052e-4 0.9808383 0 -1 0 0.1959182 5.75732e-5 0.9806203 0 -1 0 -0.5554881 -5.11685e-4 0.8315243 0 -1 0 -0.1967861 -3.46974e-4 0.9804464 0 -1 0 -0.831528 4.9824e-4 0.5554827 0 -1 0 0 -1 0 -0.5534238 4.97993e-4 0.8328997 0 -1 0 -0.980836 -3.45976e-4 0.1948349 -0.8329032 -5.1086e-4 0.5534184 0 -1 0 -0.9807266 5.06682e-5 -0.1953848 -0.9804494 4.55752e-4 0.1967709 0 -1 0 -0.9806238 -1.63432e-4 -0.1959002 -0.5556705 0 -0.8314026 -0.8314062 1.54999e-5 -0.5556651 -0.831385 0 -0.5556969 -0.1953878 -1.61786e-4 -0.980726 -0.5556969 1.28911e-5 -0.831385 0.1948319 4.63182e-4 -0.9808366 -0.1959062 5.32235e-5 -0.9806227 0.5554827 -5.09917e-4 -0.831528 0.196789 -3.4635e-4 -0.9804458 0 -1 0 0.8315243 5.01772e-4 -0.5554881 0 -1 0 0.5534112 5.03287e-4 -0.832908 0 -1 0 0.9808375 -3.45973e-4 -0.1948274 0.8329045 -5.10859e-4 -0.5534167 0 -1 0 0.980727 5.81595e-5 0.1953833 0 -1 0 0.9804454 4.66999e-4 -0.1967905 0 -1 0 0.8314038 1.11057e-5 0.5556687 0.9806211 -1.62181e-4 0.1959137 0 -1 0 0.5556705 0 0.8314026 0.8313885 0 0.5556915 0 -1 0 0.1953833 -1.54298e-4 0.980727 0.5557023 1.55196e-5 0.8313813 0 -1 0 -0.1948139 4.63185e-4 0.9808401 0.1958987 5.94628e-5 0.9806241 0 -1 0 -0.5554881 -5.15206e-4 0.8315244 -0.1967861 -3.52582e-4 0.9804464 -0.831528 5.01771e-4 0.5554827 0 -1 0 -0.5534058 5.03286e-4 0.8329116 -0.9808405 -3.50343e-4 0.1948124 -0.832908 -5.10875e-4 0.5534112 -0.9807266 5.81578e-5 -0.1953848 -0.9804463 4.66994e-4 0.196786 -0.9806247 -1.54082e-4 -0.1958957 -1.45726e-7 -1 -2.86003e-7 -0.4539919 0 -0.8910058 -2.93639e-7 -1 -1.49616e-7 -0.8910079 0 -0.4539878 -0.8910079 0 -0.4539878 0 -1 -5.04229e-7 0.1564307 0 -0.987689 -0.4539919 0 -0.8910058 1.10227e-4 -1 -1.10227e-4 0.7071068 0 -0.7071068 0.1564307 0 -0.987689 0 -1 0 0.987687 0 -0.1564427 5.94571e-7 -1 -1.00693e-6 0.7071068 0 -0.7071068 0 -1 0 0.8910079 0 0.4539878 0 -1 0 0.987687 0 -0.1564427 0 -1 0 0.4539886 0 0.8910075 0.8910079 0 0.4539878 0 -1 0 -0.1564427 0 0.987687 0.4539886 0 0.8910075 0 -1 0 -0.7071068 0 0.7071068 -0.1564427 0 0.987687 -5.65451e-7 -1 0 -0.9876887 0 0.1564323 -2.12748e-7 -1 -2.12748e-7 -1.06515e-6 -1 6.42951e-7 -0.7071068 0 0.7071068 -0.9876887 0 0.1564323 0 -1 0 -0.5734222 0 -0.81926 0 -1 0 -0.8192592 0 -0.5734232 -0.8192592 0 -0.5734232 0 -1 0 -0.2589417 0 -0.965893 0 -1 0 -0.5734222 0 -0.81926 0 -1 0 0.08730185 0 -0.9961818 -0.2589417 0 -0.965893 0 -1 0 0.4225801 7.20282e-7 -0.9063256 0.08730137 7.91694e-7 -0.996182 0 -1 0 0.7071051 5.61959e-7 -0.7071086 0.4225801 7.20282e-7 -0.9063256 -4.05555e-7 -1 1.89092e-7 0.9063259 3.35836e-7 -0.4225795 -1.67832e-6 -1 1.50207e-6 0 -1 -2.26596e-7 0 -1 -1.47747e-7 0.7071051 5.61959e-7 -0.7071086 -2.91127e-7 -1 0 0.9961823 0 -0.08729779 4.14362e-5 -1 -4.14362e-5 3.42254e-7 -1 -5.59179e-7 0.9063259 3.35836e-7 -0.4225795 -2.30916e-7 -1 0 0.9658928 -2.05789e-7 0.2589424 0 -1 -1.79676e-7 0.9961823 0 -0.08729779 -1.69055e-7 -1 0 0.8192621 -4.52152e-7 0.5734192 0.9658928 -2.04181e-7 0.2589424 0 -1 -1.68464e-7 0.5734212 -6.5109e-7 0.8192608 0.8192621 -4.55712e-7 0.5734193 0 -1 -2.25755e-7 0.2589418 -7.67622e-7 0.965893 0 -1 -2.10725e-7 0.5734211 -6.5109e-7 0.8192608 0 -1 -3.07106e-7 -0.08730125 -9.89617e-7 0.996182 0.2589417 -9.59528e-7 0.965893 2.40499e-7 -1 -5.15811e-7 -0.422578 -7.20283e-7 0.9063266 -0.08730119 -7.91694e-7 0.996182 2.59618e-6 -1 -2.59618e-6 -0.7071074 -5.61957e-7 0.7071062 4.48764e-7 -1 -7.24465e-7 -0.4225781 -7.20283e-7 0.9063265 0 -1 0 -0.9063261 -3.35835e-7 0.4225789 6.45131e-7 -1 -8.85326e-7 0 -1 0 -0.7071074 -5.61957e-7 0.7071062 0 -1 0 -0.9961822 0 0.08729869 -0.9063261 -3.35835e-7 0.4225789 0 -1 0 -0.9658939 0 -0.2589381 -0.9961821 0 0.08729875 0 -1 0 -0.9658939 0 -0.2589381 0 -1 0 -0.5734227 0 -0.8192596 0 -1 0 -0.8192607 0 -0.5734213 0 -1 0 -0.8192607 0 -0.5734213 0 -1 0 -0.2589423 0 -0.9658928 -0.5734227 0 -0.8192596 0 -1 0 0.08730334 0 -0.9961817 0 -1 0 -0.2589423 0 -0.9658928 0 -1 0 0.4225797 0 -0.9063258 0.08730334 0 -0.9961817 0 -1 0 0.7071053 0 -0.7071083 0.4225797 0 -0.9063258 -5.62591e-7 -1 2.6231e-7 0.9063268 0 -0.4225777 -4.58368e-6 -1 3.99462e-6 0.7071053 0 -0.7071083 -3.15274e-7 -1 0 0.996182 0 -0.08730119 0.9063268 0 -0.4225777 -2.26377e-7 -1 0 0.9658931 0 0.2589411 0.996182 0 -0.08730119 -1.67242e-7 -1 0 0.8192591 0 0.5734238 -2.01655e-7 -1 0 0.9658931 0 0.2589411 0 -1 -1.65454e-7 0.573423 0 0.8192594 0.8192591 0 0.5734238 0 -1 -2.05427e-7 0.2589416 0 0.965893 -1.76389e-7 -1 0 0.573423 0 0.8192594 0 -1 -2.75883e-7 -0.08730232 0 0.9961819 0.2589416 0 0.965893 2.08806e-7 -1 -4.4784e-7 -0.422576 0 0.9063274 -0.08730232 0 0.9961819 5.47381e-6 -1 -5.47379e-6 -0.7071079 0 0.7071056 -0.422576 0 0.9063274 0 -1 0 -0.9063256 0 0.42258 0 -1 0 0 -1 0 2.82836e-6 -1 -2.94474e-6 -0.7071079 0 0.7071056 0 -1 0 -0.996182 -6.93802e-7 0.08730047 0 -1 0 0 -1 0 -0.9063264 -3.35835e-6 0.4225782 0 -1 0 -0.965893 0 -0.2589415 0 -1 0 -0.996182 0 0.08730089 -0.965893 0 -0.2589415 5.39485e-6 -1 -5.39485e-6 -0.7071068 0 0.7071068 0.7071069 -1.75612e-7 0.7071067 0.707107 0 0.7071067 0 -1 0 -0.7071067 1.22928e-7 -0.7071068 0 -1 0 2.69114e-6 -1 -2.857e-6 -0.7071068 -1.32455e-7 0.7071067 0 -1 0 0.7071067 4.91713e-7 -0.7071068 -0.7071069 6.32202e-7 -0.7071067 -3.05227e-6 -1 2.86502e-6 0.7071067 1.75612e-7 -0.7071068 0 -1 0 -0.3826811 0 -0.9238805 0 -1 0 -0.9238799 0 -0.3826826 -0.9238799 0 -0.3826826 0 -1 0 0.3826874 0 -0.9238778 -0.3826811 0 -0.9238805 0 -1 0 0.9238759 0 -0.3826921 0 -1 0 0.3826874 0 -0.9238778 0 -1 0 0.9238758 0 0.3826925 0 -1 0 0.9238759 0 -0.3826921 0 -1 0 0.3826876 0 0.9238778 0 -1 0 0.9238758 0 0.3826925 0 -1 0 -0.3826836 0 0.9238795 0.3826876 0 0.9238778 0 -1 0 -0.92388 0 0.3826821 0 -1 0 0 -1 0 0 -1 0 -0.3826836 0 0.9238795 -0.92388 0 0.3826821 0 -1 0 -0.3826816 0 -0.9238803 0 -1 0 -0.9238817 0 -0.382678 0 -1 0 -0.9238817 0 -0.382678 0 -1 0 0.3826757 0 -0.9238827 -0.3826816 0 -0.9238803 -8.69456e-7 -1 3.60148e-7 0.9238768 0 -0.3826899 -1.59533e-7 -1 -3.13108e-7 0 -1 0 0.3826757 0 -0.9238827 -3.46262e-7 -1 -1.43432e-7 0.9238747 0 0.3826953 0.9238768 0 -0.3826899 -1.40567e-7 -1 -3.39349e-7 0.3826937 0 0.9238753 -3.24403e-7 -1 -1.65292e-7 0.9238747 0 0.3826953 3.33923e-7 -1 -8.06147e-7 -0.3826897 0 0.923877 0.3826937 0 0.9238753 0 -1 0 -0.9238795 0 0.3826835 -5.6178e-7 -1 0 0 -1 0 -0.3826897 0 0.923877 -0.9238795 0 0.3826835 0 -1 0 -0.3826816 0 -0.9238803 0 -1 0 -0.9238768 0 -0.3826899 -0.9238768 0 -0.3826899 0 -1 0 0.3826757 0 -0.9238827 -0.3826816 0 -0.9238803 0 -1 0 0.9238827 0 -0.3826757 0 -1 0 0 -1 0 0.3826757 0 -0.9238827 0 -1 0 0.9238803 0 0.3826816 0 -1 0 0.9238827 0 -0.3826757 0 -1 0 0.3826899 0 0.9238768 0 -1 0 0.9238803 0 0.3826816 0 -1 0 -0.3826957 0 0.9238744 0 -1 0 0.3826899 0 0.9238768 0 -1 0 -0.9238744 0 0.3826957 0 -1 0 -0.3826957 0 0.9238744 -0.9238744 0 0.3826957 -0.3826867 0 -0.9238782 -0.9238811 0 -0.3826796 -0.9238811 0 -0.3826796 0.3826808 0 -0.9238806 -0.3826867 0 -0.9238782 0.9238794 0 -0.3826837 -1.76891e-6 -1 1.60684e-6 0.3826808 0 -0.9238806 0.9238792 0 0.3826844 0.9238794 0 -0.3826837 0.3826878 0 0.9238778 0.9238792 0 0.3826844 -0.3826815 0 0.9238803 0.3826878 0 0.9238778 -0.9238816 0 0.3826785 -0.3826815 0 0.9238803 -0.9238816 0 0.3826785 -0.3826899 0 -0.9238768 -0.9238793 0 -0.3826839 -0.9238793 0 -0.3826839 0.3826957 0 -0.9238744 -0.3826899 0 -0.9238768 0 -1 0 0.9238744 0 -0.3826957 0 -1 0 0.3826957 0 -0.9238744 0 -1 0 0.9238768 0 0.3826899 0 -1 0 0.9238744 0 -0.3826957 0 -1 0 0.3826839 0 0.9238793 0 -1 0 0.9238768 0 0.3826899 0 -1 0 -0.382678 0 0.9238817 0 -1 0 0.3826839 0 0.9238793 -0.9238817 0 0.382678 4.57104e-6 -1 -4.57104e-6 1.3884e-6 -1 -1.53346e-6 -0.382678 0 0.9238817 -0.9238817 0 0.382678 -0.3826836 0 -0.9238794 -0.9238795 0 -0.3826835 -0.9238795 0 -0.3826835 0.3826821 0 -0.92388 -0.3826836 0 -0.9238794 0 -1 0 0.9238795 0 -0.3826836 0.3826821 0 -0.92388 0 -1 0 0.9238805 0 0.3826811 0 -1 0 0.9238795 0 -0.3826836 0 -1 0 0.382682 0 0.9238801 0 -1 0 0.9238805 0 0.3826811 0 -1 0 -0.3826826 0 0.9238799 0.382682 0 0.9238801 0 -1 0 -0.9238795 0 0.3826835 0 -1 0 0 -1 0 -0.3826826 0 0.9238799 -0.9238795 0 0.3826835 0 -1 0 -0.382678 0 -0.9238817 0 -1 0 -0.9238818 0 -0.3826779 0 -1 0 -0.9238818 0 -0.3826779 0 -1 0 0.3826835 0 -0.9238795 -0.382678 0 -0.9238817 -8.69456e-7 -1 3.60147e-7 0.923877 0 -0.3826897 0 -1 0 -1.59535e-7 -1 -3.13107e-7 0.3826835 0 -0.9238795 -3.46264e-7 -1 -1.4343e-7 0.9238773 0 0.3826887 0.923877 0 -0.3826897 -1.40564e-7 -1 -3.39352e-7 0.3826835 0 0.9238795 -3.24403e-7 -1 -1.65292e-7 0.9238773 0 0.3826887 3.33924e-7 -1 -8.06147e-7 -0.3826899 0 0.9238768 0.3826835 0 0.9238795 0 -1 0 -0.9238802 0 0.3826818 0 -1 0 -5.61782e-7 -1 0 -0.3826899 0 0.9238768 -0.9238802 0 0.3826818 -0.3826915 0 -0.9238762 -0.9238776 0 -0.3826882 -0.9238776 0 -0.3826882 0.3826786 0 -0.9238816 -0.3826915 0 -0.9238762 -5.96808e-7 -1 2.47204e-7 0.9238807 0 -0.3826806 -1.67239e-7 -1 -1.29916e-7 0.3826786 0 -0.9238816 -2.16307e-7 -1 0 0.9238796 0 0.3826833 0.9238807 0 -0.3826806 0 -1 -2.07625e-7 0.3826855 0 0.9238786 0.9238796 0 0.3826833 1.93357e-7 -1 -4.66803e-7 -0.382685 0 0.9238789 0.3826855 0 0.9238786 -0.923879 0 0.3826848 -0.382685 0 0.9238789 -0.923879 0 0.3826848 -0.4539825 0 -0.8910107 -0.8910071 0 -0.4539893 -0.8910071 0 -0.4539893 0 -1 -3.69508e-7 0.1564263 0 -0.9876897 -7.17289e-6 -1 6.70478e-6 -0.4539825 0 -0.8910107 3.1486e-5 -1 -3.14858e-5 0.707109 0 -0.7071047 -7.85779e-6 -1 7.54681e-6 0.1564263 0 -0.9876897 0 -1 0 0.9876881 0 -0.1564358 0 -1 0 0.707109 0 -0.7071047 0 -1 0 0.891008 0 0.4539877 0.9876881 0 -0.1564358 0 -1 0 0.4539878 0 0.891008 0.891008 0 0.4539877 0 -1 0 -0.1564382 0 0.9876877 0 -1 0 0.4539878 0 0.891008 0 -1 0 -0.7071028 0 0.7071108 -0.1564382 0 0.9876877 1.35225e-5 -1 -1.3541e-5 -0.9876882 0 0.1564356 0 -1 -3.69512e-7 -5.13675e-7 -1 2.02688e-7 -0.7071028 0 0.7071108 -0.9876882 0 0.1564356 -0.4539877 0 -0.891008 -0.8910079 0 -0.4539879 -0.8910079 0 -0.4539879 0 -1 0 0.1564336 0 -0.9876885 -0.4539877 0 -0.891008 0 -1 0 0.7071089 0 -0.7071048 0.1564336 0 -0.9876885 0.9876878 0 -0.1564383 0.7071089 0 -0.7071048 0.891003 0 0.4539973 0.9876878 0 -0.1564383 0.453991 0 0.8910062 0.891003 0 0.4539973 -0.1564345 0 0.9876884 0.453991 0 0.8910062 2.42727e-6 -1 -2.42725e-6 -0.7071106 0 0.707103 -0.1564345 0 0.9876884 -0.9876878 0 0.1564383 4.66848e-7 -1 -6.7104e-7 -0.7071106 0 0.707103 -0.9876878 0 0.1564383 -0.4539911 0 -0.8910063 -0.8910055 0 -0.4539926 -0.8910055 0 -0.4539926 0.1564305 0 -0.987689 -0.4539911 0 -0.8910063 0.7071031 0 -0.7071106 0.1564305 0 -0.987689 -7.17274e-6 -1 6.70463e-6 0.9876881 0 -0.1564365 0 -1 -3.69512e-7 -3.5316e-6 -1 3.22061e-6 0.7071031 0 -0.7071106 0.8910071 0 0.4539893 0.9876881 0 -0.1564365 0.4539918 0 0.8910058 0.8910071 0 0.4539893 0 -1 -3.69513e-7 -0.1564379 0 0.9876877 1.35228e-5 -1 -1.35412e-5 0.4539918 0 0.8910058 3.18451e-5 -1 -3.18453e-5 -0.7071046 0 0.7071089 -7.9569e-6 -1 7.64591e-6 -0.1564379 0 0.9876877 0 -1 0 -0.9876885 0 0.1564335 8.47155e-5 -1 -8.43088e-5 -0.7071046 0 0.7071089 -0.9876885 0 0.1564335 -0.4539876 0 -0.891008 -0.8910062 0 -0.4539909 -0.8910062 0 -0.4539909 0.1564353 0 -0.9876882 -0.4539876 0 -0.891008 1.66143e-5 -1 -1.66144e-5 0.7071051 0 -0.7071085 0.1564353 0 -0.9876882 0 -1 0 0.9876877 0 -0.1564382 0 -1 0 5.56842e-7 -1 -8.01027e-7 0.7071051 0 -0.7071085 0 -1 0 0.891008 0 0.4539879 0.9876877 0 -0.1564382 0 -1 0 0.4539876 0 0.891008 0.891008 0 0.4539879 0 -1 0 -0.1564335 0 0.9876886 0.4539876 0 0.891008 0 -1 0 -0.707109 0 0.7071047 -0.1564335 0 0.9876886 -0.9876877 0 0.1564382 -0.707109 0 0.7071047 -0.9876877 0 0.1564382 1 0 0 -2.69273e-6 0 1 -2.69273e-6 0 1 0.9758968 0 0.2182323 1 0 0 0 -1 0 0.7905748 0 0.6123656 0.9758968 0 0.2182323 0 -1 -1.2996e-7 0.4552687 0 0.8903541 -1.60238e-7 -1 0 0.7905748 0 0.6123656 0.2966428 0 0.9549885 0.4552687 0 0.8903541 0.3877708 0 0.9217559 0.2966428 0 0.9549885 0.4753307 0 0.8798072 0.3877708 0 0.9217559 -0.7071064 0 0.7071072 0.4753307 0 0.8798072 -0.5220395 0 0.8529213 -0.7071064 0 0.7071072 -0.0778262 -6.82386e-4 0.9969667 -0.5222586 -1.99824e-4 0.8527871 0.3833646 -1.93959e-4 0.9235971 -0.07782286 -6.79796e-4 0.996967 0.6299826 0 0.7766093 0.3835945 0 0.9235016 0 -1 0 0.7071068 0 0.7071068 0 -1 0 -1.40523e-5 -1 1.38244e-5 0.6299826 0 0.7766093 0.7766098 0 0.6299818 0.7071068 0 0.7071068 0 -1 0 0.923596 0 0.3833673 0 -1 0 0.7766098 0 0.6299818 0 -1 0 0.996967 -6.78559e-4 -0.0778231 0 -1 0 0.9234975 -1.99766e-4 0.3836044 0 -1 0 0.8529227 -2.00112e-4 -0.522037 0 -1 0 0.9969673 -6.82393e-4 -0.07781821 0.7071068 0 -0.7071068 0.8527886 0 -0.5222561 0.4996271 0 -0.8662407 0.7071068 0 -0.7071068 0 -0.00102514 -0.9999994 0.4999206 -2.91944e-4 -0.8660712 -0.4996271 -2.85584e-4 -0.8662407 -9.21522e-6 -0.001017212 -0.9999995 -0.7071068 0 -0.7071068 -0.4999137 0 -0.8660752 0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 0.7057792 0 0.7084318 0.7071068 0 -0.7071068 0.7896847 0 0.613513 -1.40989e-5 -1 1.38701e-5 0.7057792 0 0.7084318 0.8609144 0 0.5087499 0.7896847 0 0.613513 0.9183278 0 0.395821 0.8609144 0 0.5087499 0.9610033 0 0.2765368 0.9183278 0 0.395821 0.9882548 0 0.152815 0.9610033 0 0.2765368 -2.34314e-7 -1 0 0.9996452 0 0.02663367 0.9882548 0 0.152815 -3.05972e-7 -1 0 0.9949898 0 -0.09997642 0 -1 -2.66073e-7 0.9996452 0 0.02663367 -4.26218e-7 -1 0 0.974361 0 -0.2249901 0 -1 -3.58205e-7 0.9949898 0 -0.09997642 -6.55751e-7 -1 2.42138e-7 0.9380899 0 -0.3463922 1.5018e-7 -1 -5.2204e-7 0.974361 0 -0.2249901 3.98736e-6 -1 -4.29242e-6 0.8867534 0 -0.4622427 3.72773e-7 -1 -8.65036e-7 0.9380899 0 -0.3463922 0.7071068 0 0.7071068 0 -1 0 0 -1 0 0 -1 0 0.8867534 0 -0.4622427 0 -1 0 0.8529246 0 0.5220341 0.7071068 0 0.7071068 0 -1 0 0.996967 -6.82638e-4 0.0778231 0 -1 0 0.8527894 -2.0149e-4 0.522255 0 -1 0 0.9236003 -1.99343e-4 -0.3833568 0 -1 0 0.996967 -6.82472e-4 0.07782286 0 -1 0 0.7766099 0 -0.6299818 0 -1 0 0.9235022 0 -0.3835932 0.7071058 0 -0.7071077 0.7766099 0 -0.6299818 0.6299818 0 -0.7766099 0.7071058 0 -0.7071077 0.3833715 0 -0.9235942 0.6299818 0 -0.7766099 -0.07782214 -6.82472e-4 -0.996967 0.3836078 -1.9904e-4 -0.9234961 -0.522037 -1.9469e-4 -0.8529227 -0.07783037 -6.76046e-4 -0.9969664 -0.7071082 0 -0.7071053 -0.5222502 0 -0.8527923 0 -1 0 -0.8662866 0 -0.4995473 -0.7071082 0 -0.7071053 0 -1 0 -1 -1.1762e-4 0 -0.8660702 -3.73623e-4 -0.4999221 0 -1 0 -0.8662847 -3.68682e-4 0.4995505 -1 -1.1762e-4 0 -0.7071067 0 0.7071068 -0.8660712 0 0.4999206 -0.7071057 0 -0.7071079 -0.7071067 0 0.7071068 0 -1 0 0.7084161 0 -0.7057951 -0.7071057 0 -0.7071079 0.6134701 0 -0.7897179 0.7084161 0 -0.7057951 0.5086919 0 -0.8609487 0.6134701 0 -0.7897179 0.3957509 0 -0.9183579 0.5086919 0 -0.8609487 0.2764669 0 -0.9610235 0.3957509 0 -0.9183579 0.1527505 0 -0.9882648 0.2764669 0 -0.9610235 0.02658385 0 -0.9996466 0.1527505 0 -0.9882648 -0.1000092 0 -0.9949865 0.02658385 0 -0.9996466 -0.2250083 0 -0.9743568 -0.1000092 0 -0.9949865 -0.3464026 0 -0.9380859 -0.2250083 0 -0.9743568 -0.4622455 0 -0.886752 -0.3464026 0 -0.9380859 0.7071068 0 -0.7071068 -0.4622455 0 -0.886752 0.5220425 0 -0.8529195 0.7071068 0 -0.7071068 0.07783025 -6.8189e-4 -0.9969664 0.522258 -1.96505e-4 -0.8527875 -0.3833672 -1.90522e-4 -0.923596 0.07781881 -6.72961e-4 -0.9969673 -0.6299825 0 -0.7766093 -0.3835932 0 -0.9235022 0 -1 0 -0.7071071 0 -0.7071065 0 -1 0 -0.6299825 0 -0.7766093 -0.7766099 0 -0.6299818 -0.7071071 0 -0.7071065 0 -1 0 -0.9235942 0 -0.3833715 0 -1 0 -0.7766099 0 -0.6299818 0 -1 0 -0.996967 -6.72964e-4 0.07782214 0 -1 0 -0.9235004 -1.90246e-4 -0.3835974 0 -1 0 -0.8529192 -1.94683e-4 0.5220431 0 -1 0 -0.9969673 -6.76057e-4 0.07781821 -0.7071053 0 0.7071082 -0.8527887 0 0.5222562 -0.4995436 0 0.8662888 -0.7071053 0 0.7071082 0 -1.23978e-4 1 -0.4999192 -3.7436e-4 0.8660721 0.4995452 -3.67303e-4 0.8662878 9.2153e-6 -1.16036e-4 1 0.7071067 0 0.7071069 0.4999139 0 0.8660751 -0.7071079 0 0.7071057 0.7071067 0 0.7071069 -0.7057941 0 -0.7084171 -0.7071079 0 0.7071057 -0.7897165 0 -0.613472 -0.7057941 0 -0.7084171 -0.8609501 0 -0.5086894 -0.7897165 0 -0.613472 -0.9183604 0 -0.3957452 -0.8609501 0 -0.5086894 -0.9610269 0 -0.276455 -0.9183604 0 -0.3957452 -0.9882674 0 -0.1527336 -0.9610269 0 -0.276455 2.10266e-6 -1 -1.90866e-6 -0.9996472 0 -0.0265609 0 -1 -2.28279e-7 -0.9882674 0 -0.1527336 0 -1 0 -0.994984 0 0.1000348 -0.9996472 0 -0.0265609 0 -1 0 -0.9743516 0 0.2250308 0 -1 0 -0.994984 0 0.1000348 0 -1 0 -0.93808 0 0.3464187 0 -1 0 -0.9743516 0 0.2250308 0 -1 0 -0.8867481 0 0.462253 0 -1 0 -0.93808 0 0.3464187 -0.7071068 0 -0.7071068 0 -1 0 0 -1 0 0 -1 0 -0.8867481 0 0.462253 0 -1 0 -0.8529206 0 -0.5220407 -0.7071068 0 -0.7071068 0 -1 0 -0.996967 -6.81895e-4 -0.07782214 0 -1 0 -0.8527886 -1.96507e-4 -0.5222561 0 -1 0 -0.9235983 -1.964e-4 0.3833616 0 -1 0 -0.9969673 -6.79297e-4 -0.07781881 0 -1 0 -0.7766095 0 0.6299822 0 -1 0 -0.9235016 0 0.3835945 -0.7071065 0 0.7071071 -0.7766095 0 0.6299822 -0.6299818 0 0.7766098 -0.7071065 0 0.7071071 -0.3833715 0 0.9235942 -0.6299818 0 0.7766098 0.07782119 -6.72961e-4 0.9969671 -0.3835974 -1.90245e-4 0.9235005 0.5220485 -1.86985e-4 0.8529158 0.07782226 -6.72139e-4 0.9969671 0.7071068 0 0.7071068 0.5222532 0 0.8527905 0 -1 0 0.8662887 0 0.4995436 0.7071068 0 0.7071068 0 -1 0 1 -1.1603e-4 0 0.866076 -3.67473e-4 0.4999123 0 -1 0 0.8662887 -3.67301e-4 -0.4995436 1 -1.1603e-4 0 0.7071064 0 -0.7071073 0.8660761 0 -0.4999123 0.7071058 0 0.7071077 0.7071064 0 -0.7071073 0 -1 0 -0.7109418 0 0.703251 0.7071058 0 0.7071077 -0.6219235 0 0.783078 -0.7109418 0 0.703251 -0.5240252 0 0.8517028 -0.6219235 0 0.783078 -0.4186434 0 0.9081507 -0.5240252 0 0.8517028 -0.3073554 0 0.9515948 -0.4186434 0 0.9081507 -0.4552691 0 0.8903539 -0.3073554 0 0.9515948 -0.790569 0 0.6123731 -0.4552691 0 0.8903539 -0.9758991 0 0.2182219 -0.790569 0 0.6123731 -1 0 0 -0.9758991 0 0.2182219 2.69273e-6 0 1 -1 0 0 1 0 -3.97365e-7 2.69273e-6 0 1 0 0 1 1 0 -3.97365e-7 -1 0 -3.17892e-7 0 0 1 -1 0 -3.17892e-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 2.10993e-7 1 3.15669e-7 0 1 2.12207e-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 -3.7464e-7 1 -2.50406e-7 -1.36869e-7 1 0 -1.39543e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.3289e-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 7.37254e-7 1 1.103e-6 0 1 2.63305e-7 3.53316e-7 1 7.02108e-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 -3.60652e-7 1 -2.41069e-7 -1.35381e-7 1 0 -1.37986e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.64863e-7 2.49337e-5 1 2.49337e-5 2.49355e-5 1 2.49355e-5 2.49349e-5 1 2.49349e-5 6.65018e-6 1 6.74679e-6 2.63511e-7 1 6.36152e-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 3.53244e-7 9.66609e-7 1 9.72072e-7 1.25172e-7 1 4.6691e-7 5.87624e-7 1 8.39553e-7 0 1 0 0 1 0 2.15793e-6 1 2.15792e-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 1.8465e-6 1 1.87115e-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 4.05668e-6 1 4.05668e-6 -1.21469e-7 1 1.21469e-7 0 1 0 0 1 0 1.77808e-6 1 1.90241e-6 0 1 0 -2.26067e-6 1 -2.16726e-6 -1.21716e-7 1 1.21266e-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 -5.87526e-7 1 -2.43357e-7 0 1 0 0 1 0 -3.06816e-6 1 -2.78484e-6 -2.34345e-7 1 0 -2.38405e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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.74193e-6 1 1.74193e-6 1.30524e-6 1 1.34384e-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 0 1 0 0 1 0 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.76769e-7 1 9.35719e-7 -3.12981e-6 1 -1.5947e-6 -9.93854e-7 1 0 -1.61217e-6 1 -1.53963e-6 -1.00344e-6 1 1.58933e-7 -5.72949e-7 1 5.72951e-7 0 1 5.99692e-7 -8.85412e-7 1 2.0449e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.02028e-6 1 -1.79899e-6 0 1 0 1.08666e-6 1 1.08667e-6 8.34207e-7 1 8.58719e-7 9.61156e-7 1 9.61159e-7 0 1 0 0 1 0 7.57379e-7 1 7.79633e-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 -3.06035e-6 1 -2.72514e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.27396e-6 1 1.34354e-6 0 1 1.56213e-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.6331958 -1.23023e-7 0.7739918 0 -1 0 0.7739916 0 0.633196 0 -1 0 0.7739916 0 0.633196 0 -1 0 0.4709631 -1.40214e-7 0.8821529 0.6331958 -1.25646e-7 0.7739918 0 -1 0 0.290719 -1.52081e-7 0.9568085 0.4709631 -1.40214e-7 0.8821529 0 -1 0 0.09687805 0 0.9952962 0.2907199 0 0.9568082 0 -1 0 -0.09687709 -1.58198e-7 0.9952964 0.09687709 -1.58198e-7 0.9952964 0 -1 0 -0.2907217 -1.52081e-7 0.9568077 -0.09687709 -1.58198e-7 0.9952964 0 -1 -1.36515e-7 -0.4717981 -1.40144e-7 0.8817066 -0.2907217 -1.52081e-7 0.9568077 1.44698e-7 -1 -1.76732e-7 -0.6334974 -1.22983e-7 0.7737448 -0.4717981 -1.40144e-7 0.8817066 4.11045e-7 -1 -3.36541e-7 -0.7737444 0 0.633498 -0.6334974 -1.22983e-7 0.7737448 9.65278e-6 -1 -6.27337e-6 -0.8817047 0 0.4718018 -2.95178e-6 -1 1.73031e-6 -0.7737444 0 0.633498 -2.56749e-7 -1 0 -0.9568086 0 0.2907189 2.945e-6 -1 -1.96748e-6 -0.8817047 0 0.4718017 -1.6416e-7 -1 0 -0.9952963 0 0.09687823 -0.9568085 0 0.2907189 -1.25568e-7 -1 0 -0.9952962 0 -0.09687823 -0.9952962 0 0.09687823 0 -1 0 -0.9568085 0 -0.2907191 -0.9952962 0 -0.09687823 0 -1 0 -0.8821493 0 -0.4709699 2.52415e-7 -1 -3.77826e-7 -0.9568083 0 -0.2907191 0 -1 0 -0.7739962 0 -0.6331902 0 -1 -2.22135e-7 -0.8821493 0 -0.4709699 0 -1 -1.20983e-7 -0.6331912 0 -0.7739955 0 -1 -1.7255e-7 -0.7739959 0 -0.6331906 0 -1 -1.41119e-7 -0.470968 1.40214e-7 -0.8821503 0 -1 -1.32506e-7 -0.6331917 1.23023e-7 -0.773995 0 -1 -1.64195e-7 -0.2907199 1.52081e-7 -0.9568082 -0.470968 1.40214e-7 -0.8821503 0 -1 -1.59669e-7 -0.09687805 1.58198e-7 -0.9952962 -1.20386e-7 -1 0 -0.2907199 1.52081e-7 -0.9568082 0 -1 -1.92089e-7 0.096879 1.58198e-7 -0.9952961 -0.09687805 1.58198e-7 -0.9952962 0 -1 -1.79283e-7 0.2907181 1.52081e-7 -0.9568088 -1.31392e-7 -1 0 0.096879 1.58198e-7 -0.9952961 1.36107e-7 -1 -2.54357e-7 0.4718021 0 -0.8817044 0.290719 0 -0.9568085 4.94301e-7 -1 -6.03731e-7 0.6334982 1.22983e-7 -0.7737442 0.4718014 1.40143e-7 -0.8817049 -9.9058e-7 -1 8.11032e-7 0.773744 0 -0.6334984 7.61451e-7 -1 -9.30039e-7 -8.53648e-6 -1 8.36789e-6 0.6334981 1.22983e-7 -0.7737442 -4.11817e-7 -1 2.20364e-7 0.8817049 0 -0.4718014 2.06661e-7 -1 -3.86209e-7 0.773744 0 -0.6334984 1.2343e-6 -1 -1.38732e-6 0.9568081 0 -0.2907204 0 -1 -2.75015e-7 0.8817048 0 -0.4718014 -1.79796e-7 -1 0 0.9952962 0 -0.0968784 0 -1 -1.69524e-7 0.9568081 0 -0.2907203 -1.55657e-7 -1 0 0.9952963 0 0.09687823 0 -1 -1.47899e-7 0.9952962 0 -0.0968784 0 -1 0 0.956808 0 0.2907207 0 -1 -1.31003e-7 4.78708e-7 -1 -6.1213e-7 -1.43253e-6 -1 1.09535e-6 0.9952963 0 0.09687823 -1.19291e-7 -1 0 0.8821533 0 0.4709622 2.03131e-7 -1 -3.52185e-7 0 -1 -1.57542e-7 0.956808 0 0.2907207 0 -1 0 0.8821533 0 0.4709622 0 -1 0 0.6331906 0 0.7739959 -1.20983e-7 -1 0 0.7739951 0 0.6331916 -1.7255e-7 -1 0 0.7739951 0 0.6331916 0 -1 0 0.4709623 0 0.8821533 -6.99189e-7 -1 4.67106e-7 -2.22135e-7 -1 0 0.6331906 0 0.7739959 0 -1 -2.56748e-7 0.2907189 0 0.9568085 1.96825e-6 -1 2.9462e-6 0 -1 -1.28822e-7 0.4709623 0 0.8821533 0 -1 -1.6416e-7 0.09687823 0 0.9952963 0.2907189 0 0.9568085 0 -1 -1.25568e-7 -0.09687823 0 0.9952963 0.09687823 0 0.9952963 0 -1 0 -0.2907191 0 0.9568083 -0.09687823 0 0.9952963 0 -1 0 -0.4718014 0 0.8817049 -0.2907191 0 0.9568083 0 -1 0 -0.6334927 0 0.7737486 -0.4718014 0 0.8817049 -4.41825e-7 -1 3.61737e-7 -0.7737483 0 0.6334933 5.27028e-6 -1 3.52091e-6 0 -1 0 -1.28282e-7 -1 -1.60834e-7 -9.75855e-7 -1 -8.16473e-7 -0.6334927 0 0.7737486 -3.41289e-7 -1 1.82625e-7 -0.8817046 0 0.4718017 -0.7737483 0 0.6334933 1.89595e-5 -1 -7.27912e-6 -0.9568083 0 0.2907195 -1.67099e-7 -1 -1.67099e-7 -0.8817046 0 0.4718017 -3.58459e-7 -1 0 -0.9952962 0 0.09687852 -0.9568083 0 0.2907195 -2.21149e-7 -1 0 -0.9952961 0 -0.09688043 -0.9952962 0 0.09687852 -1.62643e-7 -1 0 -0.9568089 0 -0.2907177 -0.9952961 0 -0.09688043 -1.29313e-7 -1 0 -0.8821524 0 -0.4709638 -0.9568089 0 -0.2907177 0 -1 0 -0.7739955 0 -0.6331912 -0.8821524 0 -0.4709638 0 -1 0 -0.6331914 0 -0.7739953 -1.22193e-7 -1 0 -0.7739955 0 -0.6331912 0 -1 0 -0.4709612 0 -0.8821539 -1.83459e-7 -1 0 -0.6331914 0 -0.7739953 -0.2907204 0 -0.9568081 -3.5219e-7 -1 2.03135e-7 -0.4709612 0 -0.8821539 -0.0968784 1.58198e-6 -0.9952962 -0.2907292 1.5208e-6 -0.9568054 0.09687823 0 -0.9952963 -0.09686875 0 -0.9952972 0.2907207 1.52081e-6 -0.956808 0.09686857 1.58198e-6 -0.9952971 0.4718014 0 -0.8817048 0.2907295 0 -0.9568053 0.6334921 1.47581e-6 -0.7737491 0.4717923 1.68173e-6 -0.8817098 -9.05537e-7 -1 7.41392e-7 0.7737486 0 -0.6334927 -1.99976e-6 -1 1.84283e-6 0.6334991 0 -0.7737435 -1.16079e-6 -1 6.21143e-7 0.8817045 8.99891e-7 -0.4718021 4.86049e-7 -1 -6.85328e-7 0.7737441 1.2083e-6 -0.6334984 2.2702e-6 -1 -2.20821e-6 0.9568085 0 -0.290719 0.8817071 0 -0.4717972 -1.92089e-7 -1 0 0.9952961 0 -0.096879 0.9568085 0 -0.290719 -2.00309e-7 -1 0 0.9952964 0 0.09687709 0 -1 0 0.9952961 0 -0.096879 -1.64195e-7 -1 0 0.9568085 0 0.290719 0.9952964 0 0.09687709 -1.44847e-7 -1 0 0.8821524 0 0.4709638 -1.30426e-7 -1 0 0.9568085 0 0.290719 0.8821524 0 0.4709638 0 -1 -1.20983e-7 0.6331912 -1.23023e-7 0.7739955 0 -1 0 0.7739962 0 0.6331902 0 -1 -1.7255e-7 0.7739962 0 0.6331902 0 -1 -1.41119e-7 0.4709631 -1.40214e-7 0.8821529 0 -1 -1.32506e-7 0.6331912 -1.20619e-7 0.7739955 0 -1 -1.64195e-7 0.2907204 -1.52081e-7 0.956808 0.4709631 -1.40214e-7 0.8821529 0 -1 -1.59669e-7 0.09687787 -1.58198e-7 0.9952962 -1.20386e-7 -1 0 0.2907204 -1.52081e-7 0.956808 0 -1 -1.92089e-7 -0.096879 -1.58198e-7 0.9952961 0.09687787 -1.58198e-7 0.9952962 0 -1 -1.79284e-7 -0.2907214 -1.52081e-7 0.9568078 -1.31392e-7 -1 0 -0.096879 -1.58198e-7 0.9952961 1.36103e-7 -1 -2.54354e-7 -0.4717972 -1.40144e-7 0.881707 -0.2907214 -1.52081e-7 0.9568078 4.94303e-7 -1 -6.03733e-7 -0.6334982 -1.84475e-7 0.7737442 -0.4717977 -2.10215e-7 0.8817069 -9.9058e-7 -1 8.11032e-7 -0.7737439 0 0.6334984 7.61446e-7 -1 -9.30034e-7 -8.53729e-6 -1 8.36871e-6 -0.6334973 0 0.773745 -4.11805e-7 -1 2.20352e-7 -0.8817098 0 0.4717923 2.06662e-7 -1 -3.8621e-7 -0.7737444 0 0.633498 1.23432e-6 -1 -1.38734e-6 -0.9568054 0 0.2907293 0 -1 -2.75015e-7 -0.8817098 0 0.4717923 -1.79796e-7 -1 0 -0.9952962 0 0.0968784 0 -1 -1.69524e-7 -0.9568054 0 0.2907293 -1.55657e-7 -1 0 -0.9952963 0 -0.09687823 0 -1 -1.47899e-7 -0.9952962 0 0.0968784 0 -1 0 -0.9568086 0 -0.2907188 0 -1 -1.31003e-7 4.78707e-7 -1 -6.12129e-7 -1.43252e-6 -1 1.09535e-6 -0.9952962 0 -0.09687823 -1.1929e-7 -1 0 -0.8821493 0 -0.4709699 0 -1 -1.57542e-7 2.03131e-7 -1 -3.52185e-7 -0.9568085 0 -0.2907189 0 -1 0 -0.7739962 0 -0.6331902 0 -1 0 -0.882149 0 -0.4709703 -1.55598e-7 -1 -1.902e-7 -0.6331901 1.23023e-7 -0.7739964 0 -1 -1.80629e-7 -0.7739967 0 -0.6331897 0 -1 -1.90512e-7 -0.4709631 1.40214e-7 -0.8821529 -0.6331901 1.23023e-7 -0.7739964 0 -1 -1.94594e-7 -0.2907231 1.5208e-7 -0.9568072 -0.4709631 1.40214e-7 -0.8821529 9.41311e-7 -1 -3.95493e-7 -0.09687709 0 -0.9952964 -0.2907223 0 -0.9568075 0 -1 0 0.09687691 1.58198e-7 -0.9952964 -0.09687805 1.58198e-7 -0.9952962 -1.1211e-6 -1 3.58139e-7 0.2907195 1.52081e-7 -0.9568083 0.09687691 1.58198e-7 -0.9952964 1.46099e-7 -1 -2.73032e-7 0.4718013 1.40143e-7 -0.8817049 0.2907195 1.52081e-7 -0.9568083 2.89389e-7 -1 -3.5346e-7 0.6334927 1.22984e-7 -0.7737486 0.4718013 1.40143e-7 -0.8817049 8.22137e-7 -1 -6.73109e-7 0.7737492 0 -0.6334921 0.6334927 1.22984e-7 -0.7737487 -1.44188e-6 -1 7.71549e-7 0.8817055 0 -0.4718002 1.16811e-6 -1 -8.8575e-7 0.7737492 0 -0.6334921 -5.135e-7 -1 1.56024e-7 0.956808 0 -0.2907207 5.89181e-6 -1 -3.93613e-6 0.8817055 0 -0.4718002 -3.2832e-7 -1 0 0.9952962 0 -0.09687823 0.956808 0 -0.2907207 9.32081e-7 -1 -8.89083e-7 0.9952962 0 0.09687823 0.9952962 0 -0.09687823 0 -1 0 0.9568079 0 0.2907209 0.9952962 0 0.09687823 0 -1 0 0.8821542 0 0.4709608 2.52417e-7 -1 -3.77828e-7 0.9568079 0 0.2907209 0 -1 -2.22134e-7 0.8821542 0 0.4709607 0 -1 0 0.6331914 0 0.7739953 0 -1 0 0.7739955 0 0.6331912 -1.22194e-7 -1 0 0.7739955 0 0.6331912 0 -1 0 0.4709608 0 0.8821542 -1.83459e-7 -1 0 0.6331908 0 0.7739956 0.2907205 0 0.956808 -3.52184e-7 -1 2.0313e-7 0.4709612 0 0.882154 0.0968784 0 0.9952962 0.2907205 0 0.956808 -0.09687823 0 0.9952962 0.0968784 0 0.9952962 -0.2907206 0 0.956808 -0.09687823 0 0.9952962 -0.4718018 0 0.8817046 -0.2907206 0 0.956808 -0.6334917 0 0.7737495 -0.4718018 0 0.8817046 -6.03695e-7 -1 4.94265e-7 -0.7737483 0 0.6334932 4.76937e-6 -1 -4.91423e-6 -0.6334917 0 0.7737495 -9.28632e-7 -1 4.96912e-7 -0.8817049 0 0.4718013 4.96345e-7 -1 -6.33547e-7 -0.7737483 0 0.6334932 1.42743e-6 -1 -1.446e-6 -0.9568083 0 0.2907195 -0.8817049 0 0.4718013 -1.92088e-7 -1 0 -0.9952962 0 0.09687787 -0.9568083 0 0.2907195 -2.00309e-7 -1 0 -0.9952963 0 -0.09687805 0 -1 0 -0.9952962 0 0.09687787 -1.64195e-7 -1 0 -0.9568083 4.62086e-7 -0.2907195 -0.9952964 1.53982e-7 -0.09687709 -1.44847e-7 -1 0 -0.8821529 0 -0.4709631 -1.30426e-7 -1 0 -0.9568075 0 -0.2907223 -1.20983e-7 -1 0 -0.7739955 0 -0.6331912 -0.8821529 0 -0.4709631 0 -1 0 -0.6331903 0 -0.7739962 -1.7255e-7 -1 0 -0.7739955 0 -0.6331912 0 -1 0 -0.4709699 0 -0.8821493 -6.99193e-7 -1 4.67109e-7 -2.22135e-7 -1 0 -0.6331903 0 -0.7739962 0 -1 -2.56741e-7 -0.2907102 0 -0.9568112 0 -1 -1.28822e-7 1.96802e-6 -1 2.94584e-6 -0.4709699 0 -0.8821493 0 -1 -1.6416e-7 -0.09687823 0 -0.9952962 -0.2907102 0 -0.9568112 0 -1 -1.25568e-7 0.09687823 0 -0.9952963 -0.09687823 0 -0.9952962 0 -1 0 0.2907104 0 -0.9568111 0.09687823 0 -0.9952963 0 -1 0 0.4718014 0 -0.8817048 0.2907104 0 -0.9568111 0 -1 0 0.633498 0 -0.7737444 0.4718014 0 -0.8817048 -3.53465e-7 -1 2.89397e-7 0.7737442 0 -0.6334981 0 -1 0 0 -1 -1.28668e-7 -9.75848e-7 -1 -8.16467e-7 5.27062e-6 -1 3.52113e-6 0.6334979 0 -0.7737444 -2.7303e-7 -1 1.46097e-7 0.8817075 0 -0.4717965 0.7737442 0 -0.6334981 1.21903e-5 -1 -4.71624e-6 0.956808 0 -0.2907204 -1.33679e-7 -1 -1.33679e-7 0.8817075 0 -0.4717965 -3.58459e-7 -1 0 0.9952961 1.53985e-7 -0.096879 0.9568072 4.62092e-7 -0.2907231 -2.2115e-7 -1 0 0.9952962 0 0.09687882 0.9952962 0 -0.09687805 -1.62643e-7 -1 0 0.9568086 0 0.2907187 0.9952962 0 0.09687882 -1.29313e-7 -1 0 0.8821524 0 0.4709638 0.9568086 0 0.2907187 0.8821524 0 0.4709638 0.5555045 0 0.8315136 0.8315123 0 0.5555064 0.8315123 0 0.5555064 -9.84407e-7 -1 -1.8201e-6 0.1950907 0 0.9807852 0 -1 0 0.5555045 0 0.8315136 0 -1 -2.43791e-7 -0.1950907 0 0.9807852 0.1950907 0 0.9807852 5.74645e-7 -1 2.41241e-7 -0.5555027 0 0.8315147 -0.1950907 0 0.9807852 1.63674e-6 -1 -1.82925e-6 -0.8315137 0 0.5555043 4.42947e-7 -1 -6.63026e-7 -1.55006e-7 -1 0 -0.5555028 0 0.8315147 -2.68801e-7 -1 0 -0.9807853 0 0.1950899 0 -1 -2.40317e-7 -0.8315137 0 0.5555043 -1.95054e-7 -1 0 -0.9807855 0 -0.195089 0 -1 -1.79608e-7 -0.9807853 0 0.1950899 -1.44551e-7 -1 0 -0.8315141 0 -0.5555038 0 -1 -1.40194e-7 -0.9807855 0 -0.195089 0 -1 -1.40194e-7 -0.5555036 0 -0.8315141 -1.44551e-7 -1 0 -0.8315141 0 -0.5555038 0 -1 -1.79607e-7 -0.1950895 0 -0.9807854 -1.95055e-7 -1 0 -0.5555036 0 -0.8315141 0 -1 -2.40319e-7 0.1950895 0 -0.9807854 -2.68799e-7 -1 0 -0.1950895 0 -0.9807854 4.4294e-7 -1 -6.63019e-7 0.5555053 0 -0.8315131 1.63674e-6 -1 -1.82926e-6 0.1950895 0 -0.9807854 2.49155e-6 -1 -1.66452e-6 0.8315126 0 -0.5555059 7.10433e-7 -1 -9.30512e-7 0 -1 -2.03091e-7 0 -1 -2.8532e-7 3.14365e-7 -1 -5.4504e-7 -5.65782e-7 -1 2.28608e-7 0.5555053 0 -0.8315131 0.9807863 0 -0.1950849 0.8315126 0 -0.5555059 0.9807862 -3.10081e-7 0.1950858 0.9807861 3.10081e-7 -0.195086 0.9807864 0 0.1950846 0 -1 0 0.5555058 0 0.8315126 0 -1 0 0.8315108 0 0.5555086 0 -1 -2.52087e-7 0.8315108 0 0.5555086 0 -1 0 0.1950907 0 0.9807852 -2.47048e-6 -1 2.2774e-6 -6.93763e-7 -1 5.35502e-7 0.5555058 0 0.8315126 -2.36865e-7 -1 -1.93804e-6 -0.1950907 0 0.9807852 0 -1 0 0.1950907 0 0.9807852 0 -1 0 -0.5555031 0 0.8315145 -0.1950907 0 0.9807852 -0.8315122 0 0.5555064 -0.5555031 0 0.8315145 -0.9807864 0 0.1950849 -0.8315123 0 0.5555064 -0.9807864 0 -0.1950849 -0.9807864 0 0.1950849 -0.8315104 0 -0.5555093 -0.9807864 0 -0.1950849 -0.5555081 0 -0.8315111 -0.8315104 0 -0.5555093 -0.1950836 0 -0.9807866 -0.5555081 0 -0.8315111 -7.28204e-7 -1 5.32108e-7 0.1950836 0 -0.9807866 5.80998e-7 -1 -7.37928e-7 -0.1950836 0 -0.9807866 3.75073e-7 -1 -5.61423e-7 0.555511 0 -0.8315093 -5.90776e-7 -1 3.9468e-7 0.1950836 0 -0.9807866 -5.04258e-7 -1 3.36883e-7 0.8315089 0 -0.5555114 -1.39163e-6 -1 1.20527e-6 -3.99727e-7 -1 2.37417e-7 1.41109e-6 -1 -1.5872e-6 0.555511 0 -0.8315093 -1.93831e-7 -1 0 0.9807866 0 -0.1950835 0.8315089 0 -0.5555114 3.80153e-7 -1 -5.4675e-7 0.9807866 0 0.1950834 7.79599e-7 -1 -9.27495e-7 0.9807866 0 -0.1950834 -4.59354e-7 -1 2.84071e-7 8.24506e-7 -1 -9.65694e-7 1.40439e-5 -1 -1.40439e-5 -1.45446e-6 -1 1.29539e-6 0.9807866 0 0.1950835 0.5555039 0 0.831514 0.831512 0 0.5555069 0.831512 0 0.5555069 0.1950895 0 0.9807854 0.5555039 0 0.831514 -7.28208e-7 -1 5.32112e-7 -0.1950895 0 0.9807854 9.84511e-7 -1 -1.12937e-6 0.1950895 0 0.9807854 3.75061e-7 -1 -5.61411e-7 -0.5555068 0 0.8315121 -5.90779e-7 -1 3.94683e-7 -0.1950895 0 0.9807854 -6.30313e-7 -1 4.21094e-7 -0.8315108 0 0.5555086 -2.9416e-6 -1 2.75525e-6 -1.3895e-7 -1 0 0 -1 -2.04263e-7 -0.5555068 0 0.8315121 -2.42289e-7 -1 0 -0.9807867 0 0.1950829 -0.8315108 0 0.5555086 3.68722e-7 -1 -5.49024e-7 -0.9807868 0 -0.1950832 1.35223e-7 -1 -3.26457e-7 -0.9807867 0 0.1950829 -1.21172e-7 -1 0 -0.8315108 0 -0.5555085 2.71993e-7 -1 -4.44161e-7 -9.82972e-7 -1 7.77476e-7 1.82416e-5 -1 -1.82417e-5 5.97738e-7 -1 -7.7898e-7 -0.9807868 0 -0.1950831 0 -1 0 -0.5555076 0 -0.8315114 -3.07087e-7 -1 0 -0.8315108 0 -0.5555085 0 -1 0 -0.1950907 0 -0.9807852 0 -1 -1.20511e-7 -3.08816e-6 -1 2.84681e-6 -0.5555076 0 -0.8315114 -2.36865e-7 -1 -1.93804e-6 0.1950907 0 -0.9807852 0 -1 0 -0.1950907 0 -0.9807852 0 -1 0 0.5555047 0 -0.8315134 0.1950907 0 -0.9807852 0.8315119 0 -0.5555068 0 -1 0 0.5555047 0 -0.8315134 0.9807863 0 -0.1950849 0.8315119 0 -0.5555068 0.9807864 0 0.1950846 0.9807863 0 -0.1950849 0.9807865 0 0.1950846 0 -1 -1.20166e-7 0.5555036 0 0.8315141 -1.23901e-7 -1 0 0.8315137 0 0.5555043 -1.239e-7 -1 0 0.8315137 0 0.5555043 0 -1 -1.53949e-7 0.1950895 0 0.9807854 -1.6719e-7 -1 0 0.5555036 0 0.8315141 0 -1 -2.05988e-7 -0.1950895 -1.55892e-6 0.9807854 -2.30398e-7 -1 0 0.1950836 -1.55892e-6 0.9807866 3.93726e-7 -1 -5.89352e-7 -0.5555056 0 0.8315128 1.71967e-6 -1 -1.88468e-6 -0.1950836 0 0.9807866 1.9932e-6 -1 -1.3316e-6 -0.8315119 0 0.5555068 -3.55503e-7 -1 1.59877e-7 1.77667e-6 -1 -1.77666e-6 0 -1 -1.62473e-7 0 -1 -2.28256e-7 2.51493e-7 -1 -4.36033e-7 -0.5555056 0 0.8315128 -0.9807866 0 0.1950838 -0.8315119 0 0.5555068 -0.9807865 0 -0.195084 -0.9807866 0 0.1950838 -0.831512 1.05955e-6 -0.5555069 -0.9807868 3.72091e-7 -0.1950826 -0.5555064 0 -0.8315122 -0.8315098 0 -0.5555103 -9.84407e-7 -1 -1.82011e-6 -0.1950907 0 -0.9807852 -0.5555064 0 -0.8315122 0 -1 -2.43791e-7 0.1950907 0 -0.9807852 -0.1950907 0 -0.9807852 5.74644e-7 -1 2.41241e-7 0.5555045 0 -0.8315136 0.1950907 0 -0.9807852 1.71959e-6 -1 -1.88461e-6 0.8315137 0 -0.5555043 3.93735e-7 -1 -5.8936e-7 -1.37783e-7 -1 0 0.5555045 0 -0.8315135 -2.30401e-7 -1 0 0.9807854 3.72104e-7 -0.1950896 0 -1 -2.05986e-7 0.8315113 1.05955e-6 -0.5555077 -1.67189e-7 -1 0 0.9807855 0 0.1950893 0 -1 -1.5395e-7 0.9807857 0 -0.1950882 0 -1 -1.20165e-7 0.9807855 0 0.1950893 0.5555033 -1.45382e-6 0.8315143 0.8315141 0 0.5555036 0.8315121 -9.7125e-7 0.5555068 0.1950837 0 0.9807866 0.555508 0 0.8315113 -0.1950834 0 0.9807866 0.1950837 0 0.9807866 -0.5555073 0 0.8315117 -0.1950835 0 0.9807866 -2.41239e-7 -1 -5.74643e-7 -0.8315101 -9.71255e-7 0.5555095 0 -1 -1.37891e-7 -0.555512 -1.45381e-6 0.8315086 2.43792e-7 -1 0 -0.9807866 0 0.1950836 -0.8315081 0 0.5555126 -3.294e-7 -1 0 -0.9807866 0 -0.1950836 1.42231e-7 -1 0 -0.9807866 0 0.1950836 -1.33847e-7 -1 0 -0.8315096 0 -0.5555104 -0.9807866 0 -0.1950836 0 -1 0 -0.5555094 1.32165e-7 -0.8315103 -0.8315098 0 -0.5555101 0 -1 0 -0.1950858 1.55892e-7 -0.9807862 -0.5555094 1.32165e-7 -0.8315103 0 -1 -1.23383e-7 0.1950861 1.55892e-7 -0.9807861 -0.1950858 1.55892e-7 -0.9807862 0 -1 -1.49126e-7 0.5555054 1.32165e-7 -0.8315129 0.1950861 1.55892e-7 -0.9807861 0.8315136 0 -0.5555045 -2.82254e-7 -1 0 0 -1 0 -2.18017e-7 -1 1.25747e-7 0.5555054 1.32165e-7 -0.8315129 0.9807866 0 -0.1950836 0.8315138 0 -0.5555042 0.9807866 0 0.1950836 0.9807866 0 -0.1950836 0.9807866 0 0.1950836 0.5555083 0 0.831511 0.8315106 0 0.555509 0.8315106 0 0.555509 0.1950843 0 0.9807865 0.5555083 0 0.831511 -0.1950841 0 0.9807866 0.1950843 0 0.9807865 -0.5555094 0 0.8315103 -0.1950841 0 0.9807866 -0.8315094 0 0.5555107 -0.5555094 0 0.8315103 1.36376e-6 -1 -8.93624e-7 -0.9807866 0 0.1950836 -1.92287e-7 -1 0 0 -1 0 -0.8315094 0 0.5555107 0 -1 0 -0.9807866 0 -0.1950836 -0.9807866 0 0.1950836 0 -1 0 -0.8315101 0 -0.5555095 2.00847e-6 -1 -2.17874e-6 -0.9807866 0 -0.1950836 0 -1 0 -0.5555073 0 -0.8315117 1.41789e-6 -1 -1.52976e-6 -5.25419e-7 -1 3.21753e-7 0 -1 -3.07088e-7 -0.8315101 0 -0.5555095 0 -1 -1.61383e-7 -0.1950835 0 -0.9807866 3.73657e-7 -1 -5.50189e-7 -1.27924e-6 -1 1.09595e-6 -0.5555073 0 -0.8315117 0 -1 -2.2323e-7 0.1950837 0 -0.9807866 -2.21154e-7 -1 0 -0.1950835 0 -0.9807866 3.48575e-7 -1 -5.21767e-7 0.5555062 0 -0.8315125 0.1950837 0 -0.9807866 0.8315113 0 -0.5555078 0.5555062 0 -0.8315125 0.9807866 0 -0.1950836 0.8315113 0 -0.5555078 0.9807866 0 0.1950836 0.9807866 0 -0.1950836 0.9807866 0 0.1950836 0 -1 0 0.555506 -2.64331e-7 0.8315125 -1.56156e-7 -1 0 0.8315119 0 0.555507 0.8315114 -1.76591e-7 0.5555076 -6.21867e-7 -1 0 0.1950861 -1.55892e-7 0.9807861 0.5555064 -1.40212e-7 0.8315123 0 -1 -1.85074e-7 -0.1950858 -1.55892e-7 0.9807862 0.1950861 -1.55892e-7 0.9807861 1.10388e-6 -1 -5.50934e-7 -0.5555089 -1.32165e-7 0.8315107 -0.1950858 -1.55892e-7 0.9807862 -0.8315091 -1.76592e-7 0.5555112 -6.56024e-7 -1 1.20764e-7 -2.03993e-7 -1 0 -4.36036e-7 -1 2.51497e-7 -0.5555093 -2.6433e-7 0.8315104 -0.9807869 0 0.1950824 -0.8315086 0 0.5555118 -0.9807869 0 -0.1950824 -0.9807869 0 0.1950824 -0.8315107 8.82957e-7 -0.5555087 -0.980787 3.10073e-7 -0.1950812 -0.5555114 0 -0.8315089 -0.8315089 0 -0.5555115 -0.1950829 0 -0.9807867 -0.5555114 0 -0.8315089 0.1950832 0 -0.9807868 -0.1950829 0 -0.9807867 0.5555086 0 -0.8315108 0.1950832 0 -0.9807868 0 -1 0 0.8315117 0 -0.5555073 0 -1 -1.2257e-7 0.5555086 0 -0.8315108 0 -1 0 0.9807856 0 -0.1950883 0.8315117 0 -0.5555073 1.55375e-6 -1 -3.13306e-7 0.980786 0 0.1950871 -1.97511e-7 -1 -1.29421e-7 0.9807856 0 -0.1950883 0.980786 0 0.1950871 0 -1 0 0.5555077 0 0.8315113 0 -1 0 0.8315134 0 0.5555047 -1.64283e-6 -1 1.40264e-6 -4.77648e-7 -1 2.92498e-7 1.37124e-7 -1 -3.20142e-7 0.8315134 0 0.5555047 0 -1 -1.29106e-7 0.1950893 0 0.9807855 -2.82556e-7 -1 0 8.56369e-7 -1 -1.01723e-6 0.5555077 0 0.8315113 0 -1 -2.08349e-7 -0.1950882 0 0.9807857 2.43711e-7 -1 -4.00555e-7 0.1950893 0 0.9807855 3.25339e-7 -1 -4.86985e-7 -0.5555072 0 0.8315118 -0.1950882 0 0.9807857 -0.8315106 0 0.555509 -0.5555072 0 0.8315118 -0.9807869 0 0.1950824 -0.8315106 0 0.555509 -0.9807869 0 -0.1950824 -0.9807869 0 0.1950824 -0.8315096 0 -0.5555104 -0.9807869 0 -0.1950824 -0.5555093 0 -0.8315104 -0.8315096 0 -0.5555104 -0.1950835 0 -0.9807866 -0.5555093 0 -0.8315104 0.1950823 0 -0.9807869 -0.1950835 0 -0.9807866 0.5555099 0 -0.83151 0.1950823 0 -0.9807869 0.8315124 0 -0.5555062 0.5555098 0 -0.83151 2.04566e-6 -1 -1.34045e-6 0.9807856 0 -0.1950883 -2.56383e-7 -1 0 -1.28921e-7 -1 0 0.8315124 0 -0.5555062 0 -1 0 0.9807857 0 0.1950883 0.9807857 0 -0.1950883 1.78523e-6 -1 -1.93659e-6 0.9807857 0 0.1950883 -3.15331e-5 -1 3.13083e-5 0.7071067 0 -0.7071069 2.19337e-7 -1 -3.80283e-7 0.4996243 1.20314e-7 -0.8662422 0.4996249 0 -0.8662419 0.7071067 0 -0.7071068 -4.88125e-7 -1 2.81537e-7 0.8662418 0 -0.4996248 -2.99537e-6 -1 2.82429e-6 0 -1 -2.60626e-7 -2.3935e-7 -1 0 1 0 0 4.15921e-7 -1 -5.81696e-7 3.76087e-7 -1 -5.44675e-7 0.8662417 0 -0.4996252 5.30149e-7 -1 -7.5938e-7 0.8662417 0 0.4996252 3.26423e-7 -1 -5.65948e-7 1 0 0 0 -1 0 0.7071069 0 0.7071067 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.45496e-7 0.7071068 0 0.7071066 0.8662416 0 0.4996253 0 -1 0 0.499625 -1.37685e-7 0.8662419 -1.45496e-7 -1 0 0 -1 -2.3935e-7 0 -1.58946e-7 1 1.95264e-6 -1 -2.19138e-6 0.4996248 -1.62502e-7 0.8662419 2.40227e-7 -1 -4.16502e-7 -0.499625 -1.22795e-7 0.8662417 -4.4249e-7 -1 2.60628e-7 0 -1.58946e-7 1 -2.38948e-5 -1 2.367e-5 -0.7071068 0 0.7071067 -0.7071067 0 0.7071068 -0.4996252 -1.37685e-7 0.8662417 -4.41637e-7 -1 2.54725e-7 -0.8662417 0 0.4996252 6.97627e-7 -1 -8.76148e-7 -2.41088e-7 -1 0 -1.19675e-7 -1 0 -1 1.58946e-7 0 -1.44789e-6 -1 1.21555e-6 -5.45088e-7 -1 3.765e-7 -0.8662418 0 0.4996249 0 -1 0 -0.8662424 1.92282e-7 -0.4996238 1.63212e-7 -1 -2.82974e-7 -1 1.58946e-7 0 0 -1 0 -0.7071068 0 -0.7071069 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.45496e-7 -0.7071068 0 -0.7071068 -0.8662419 0 -0.4996249 6.62629e-7 -1 -6.97895e-7 -0.499625 1.37685e-7 -0.8662417 -1.45496e-7 -1 0 0 -1 -1.19675e-7 0 1.58946e-7 -1 2.23562e-6 -1 -2.3546e-6 -0.4996252 1.62502e-7 -0.8662417 3.11854e-7 -1 -4.72043e-7 0 1.58946e-7 -1 0.7071068 0 -0.7071068 0 0 -1 0 0 -1 -8.27871e-7 -1 5.06847e-7 0.8528573 0 -0.522144 -2.74465e-7 -1 0 0.7071068 0 -0.7071068 -1.71988e-7 -1 0 0.9969041 0 -0.07862621 0.8528573 0 -0.522144 0 -1 0 0.9238772 0 0.3826889 0.9969041 0 -0.07862621 5.12563e-7 -1 -4.46453e-7 0.6493223 0 0.7605134 0 -1 -1.89777e-7 0.9238772 0 0.3826889 0 -1 0 0.233855 0 0.9722715 0.6493223 0 0.7605135 0 -1 -3.13802e-7 0 0 1 0 -1 0 0.233855 0 0.9722715 0 -1 -1.82213e-7 -0.2338489 0 0.972273 0 0 1 0 -1 -1.26391e-7 -0.6493263 0 0.7605099 -0.2338489 0 0.972273 1.9575e-7 -1 0 -0.9238802 0 0.3826819 -0.6493263 0 0.7605099 -5.09705e-7 -1 0 -0.9969048 0 -0.07861948 0 -1 -1.22149e-7 -0.9238802 0 0.3826819 -1.57904e-7 -1 0 -0.8528573 0 -0.522144 -0.9969048 0 -0.07861948 0 -1 -1.2559e-7 -0.7071068 0 -0.7071067 -0.8528573 0 -0.522144 0 -1 -1.88636e-7 -0.7071068 0 -0.7071067 0 -1 0 -1 0 2.35117e-7 1.82213e-7 -1 0 -0.9722734 0 0.2338473 0 -1 -1.29457e-7 -0.9722734 0 0.2338473 -1.82213e-7 -1 0 -0.972273 0 -0.2338488 -1 0 2.35117e-7 -2.12902e-7 -1 -1.81777e-7 -0.7605094 0 -0.649327 0 -1 -3.735e-7 -0.972273 0 -0.2338488 0 -1 -2.67385e-7 -0.3826841 0 -0.9238793 -0.7605094 0 -0.649327 0 -1 -2.56843e-7 0.07861924 0 -0.9969047 -4.43559e-7 -1 0 -0.3826841 0 -0.9238793 3.31665e-7 -1 -5.41733e-7 0.522144 0 -0.8528573 0.07861924 0 -0.9969047 8.00447e-7 -1 -9.93524e-7 0.7071068 0 -0.7071068 0.522144 0 -0.8528573 1 0 0 0.7071068 0 -0.7071068 0 -1 -1.32792e-7 0.7071067 0 0.7071068 -2.93926e-7 -1 0 1 0 0 0 -1 -1.55961e-7 0.522144 0 0.8528573 0 -1 -1.3494e-7 0.7071067 0 0.7071068 0 -1 -1.28937e-7 0.0786274 0 0.9969041 0.522144 0 0.8528573 -6.187e-7 -1 -2.9031e-7 -0.3826869 0 0.9238781 0.0786274 0 0.9969041 1.26391e-7 -1 0 -0.7605099 0 0.6493263 0 -1 -1.3528e-7 -0.382687 0 0.9238781 -0.7605099 0 0.6493263 0.07862389 0 -0.9969044 0 0 -1 0 0 -1 0.2337455 0 -0.9722978 0.07862389 0 -0.9969044 0.3826819 0 -0.9238802 0.2337455 0 -0.9722979 0.5222353 0 -0.8528015 0.3826819 0 -0.9238802 0.6493232 0 -0.7605126 0.5222353 0 -0.8528015 0.7071078 0 -0.7071057 0.7071079 0 -0.7071058 0.6493232 0 -0.7605126 0.6087611 0 -0.7933537 0.3826825 0 -0.92388 0.608761 0 -0.7933536 0.1305241 0 -0.9914452 0.3826825 0 -0.92388 0 -1 -1.52862e-7 -0.1305243 0 -0.9914452 -1.5562e-7 -1 0 0.1305241 0 -0.9914451 0 -1 -1.26232e-7 -0.3826819 0 -0.9238802 1.57283e-7 -1 -3.3027e-7 -0.1305243 0 -0.9914452 0 -1 -1.2789e-7 -0.6087617 0 -0.7933531 1.23572e-7 -1 -2.82242e-7 -4.61848e-7 -1 2.51972e-7 3.82463e-6 -1 -3.86103e-6 -2.91437e-6 -1 2.66149e-6 -0.3826819 0 -0.9238802 0 -1 0 -0.707108 0 -0.7071057 0 -1 0 -0.707108 0 -0.7071057 -0.6087617 0 -0.7933531 1.45013e-7 -1 -3.49204e-7 -0.7933534 0 -0.6087613 -1.2232e-7 -1 0 -0.9238798 0 -0.3826829 0 -1 -1.20972e-7 -0.7933534 0 -0.6087614 -1.5562e-7 -1 0 -0.9914447 0 -0.1305277 0 -1 -1.52863e-7 -0.9238798 0 -0.3826829 -0.9914448 0 0.1305266 -0.9914447 0 -0.1305277 -0.9238791 0 0.3826844 -0.9914448 0 0.1305266 1.97899e-6 -1 -1.97901e-6 -0.7933534 0 0.6087613 -0.9238792 0 0.3826844 -0.7071037 0 0.7071099 -0.7071037 0 0.7071099 -0.7933534 0 0.6087614 -0.7605139 0 0.6493216 -0.8528036 0 0.5222319 -0.760514 0 0.6493215 -0.9238786 0 0.3826854 -0.8528036 0 0.5222319 -3.54846e-7 -1 0 -0.9722979 0 0.2337455 0 -1 -2.05476e-7 2.6533e-7 -1 -4.33385e-7 -4.25053e-7 -1 2.31975e-7 -0.9238786 0 0.3826854 0 -1 -2.4278e-7 -0.9969042 0 0.07862681 -1.70324e-7 -1 -1.4542e-7 0 -1 -2.13909e-7 -0.9722979 0 0.2337455 -1.76403e-7 -1 -1.37548e-7 -1 0 0 0 -1 -1.46948e-7 -1.82213e-7 -1 0 -0.9969042 0 0.07862681 -1.99845e-6 -1 -1.57614e-7 -0.9969044 0 -0.07862371 0 -1 0 0 -1 0 0 -1 0 -1 0 0 4.73433e-7 -1 -1.36504e-7 -0.9722979 0 -0.2337455 -0.9969044 0 -0.07862371 -2.51105e-7 -1 0 -0.9238802 0 -0.3826819 -0.9722978 0 -0.2337455 1.75385e-7 -1 -1.77994e-7 -0.8528015 0 -0.5222353 -0.9238802 0 -0.3826819 0 -1 0 -0.7605136 0 -0.6493222 -0.8528015 0 -0.5222353 0 -1 0 -0.7071037 0 -0.7071099 0 -1 0 4.65978e-7 -1 -6.27821e-7 -0.7071037 0 -0.7071099 -0.7605135 0 -0.6493221 0 -1 0 -0.7933551 0 -0.6087592 0 -1 0 -1.28179e-7 -1 0 -0.9238789 0 -0.3826849 0 -1 0 -0.7933551 0 -0.6087592 2.01084e-7 -1 -3.41998e-7 -0.9914451 0 -0.1305241 0 -1 -1.60184e-7 -0.9238789 0 -0.3826849 -2.0709e-7 -1 0 -0.9914451 0 0.1305246 0 -1 -1.62278e-7 -0.9914452 0 -0.1305241 4.48773e-7 -1 -5.81305e-7 -0.9238795 -4.86607e-7 0.3826833 1.27155e-7 -1 -3.06982e-7 -0.9914452 -1.6597e-7 0.1305243 -1.15931e-6 -1 8.89572e-7 -0.7933534 0 0.6087614 4.37073e-7 -1 -5.69605e-7 -0.9238791 0 0.3826844 -0.7071076 0 0.7071061 -0.7071068 -8.99133e-7 0.7071068 -0.7933545 -7.74078e-7 0.6087599 -0.6087614 0 0.7933534 -0.3826819 0 0.9238802 -0.6087614 0 0.7933534 -0.1305243 0 0.9914452 -0.3826819 0 0.9238802 0.1305243 -2.52138e-6 0.9914452 -0.13053 -2.52137e-6 0.9914444 0.3826804 0 0.9238809 0.13053 0 0.9914444 0.6087632 0 0.793352 0.3826804 0 0.9238809 0.7071079 0 0.7071058 0.7071099 -8.99129e-7 0.7071037 0.6087613 -1.0088e-6 0.7933534 0 -1 0 0.6493232 0 0.7605126 -2.3912e-6 -1 2.16642e-6 0 -1 -1.46898e-7 0.5222322 0 0.8528033 0 -1 -1.23558e-7 0.6493232 0 0.7605125 0 -1 -1.31972e-7 0.3826851 0 0.9238788 0.5222322 0 0.8528033 2.40018e-7 -1 0 0.2337484 0 0.9722971 0.3826851 0 0.9238788 -2.52865e-7 -1 0 0.07862383 -1.90144e-6 0.9969044 0.2337457 -1.85451e-6 0.9722977 0 -1 -1.65782e-7 0 0 1 0 -1 -3.26366e-7 0 -1 -1.82213e-7 0 -1 -1.26391e-7 1.95749e-7 -1 0 0 -1 -1.22149e-7 0.07862675 0 0.9969041 0 -1 -3.79554e-7 -0.07862389 0 0.9969044 4.04648e-7 -1 -5.72843e-7 0 -1 -1.82212e-7 0 0 1 0 -1 -2.45624e-7 -0.2337461 0 0.9722976 -1.65561e-6 -1 1.01359e-6 -3.43975e-7 -1 0 -2.13908e-7 -1 0 -0.07862389 0 0.9969044 -0.3826827 0 0.9238798 -0.2337461 0 0.9722976 -0.5222337 0 0.8528025 -0.3826827 0 0.9238798 -0.6493238 0 0.7605121 -0.5222337 0 0.8528025 -0.7071048 0 0.7071089 -0.7071048 0 0.7071089 -0.6493238 0 0.7605121 -0.608765 0 0.7933506 -0.3826833 0 0.9238795 -0.608765 0 0.7933506 -0.1305214 0 0.9914455 -0.3826833 0 0.9238795 0.1305212 0 0.9914455 -0.1305214 0 0.9914455 0.382686 0 0.9238784 0.1305212 0 0.9914455 0 -1 -1.2789e-7 0.6087615 0 0.7933533 0 -1 -2.36788e-7 -1.61334e-7 -1 0 2.63212e-6 -1 -2.71678e-6 0 -1 -1.88147e-7 0.382686 0 0.9238784 0 -1 0 0.7071064 0 0.7071072 0 -1 0 0.7071064 0 0.7071072 0.6087615 0 0.7933533 -1.2789e-7 -1 0 0.7933534 0 0.6087614 0.92388 0 0.3826825 0.7933534 0 0.6087614 0.9914448 0 0.130527 0.92388 0 0.3826825 0.9914447 0 -0.1305271 0.9914447 0 0.130527 0.9238806 0 -0.3826809 0.9914447 0 -0.1305271 0 -1 0 0.7933534 0 -0.6087613 0.9238806 0 -0.3826809 0.7071048 0 -0.7071089 0.7071048 0 -0.7071089 0.7933534 0 -0.6087614 0.7605125 0 -0.6493232 0.852802 0 -0.5222344 0.7605126 0 -0.6493232 0.9238795 0 -0.3826834 0.852802 0 -0.5222343 0.9722973 0 -0.2337475 0.9238796 0 -0.3826834 0.9969044 0 -0.07862365 0.9722973 0 -0.2337476 1 0 -1.94185e-7 0.9969044 0 -0.07862365 -2.33141e-6 -1 -1.8388e-7 0.9969041 0 0.07862675 1 0 -1.94185e-7 3.72406e-7 -1 -1.60792e-7 0.9722977 0 0.2337457 0.9969041 0 0.07862675 -3.1388e-7 -1 -1.30013e-7 0.9238799 -4.86606e-7 0.3826826 0.9722977 -2.97224e-7 0.2337461 3.10023e-7 -1 -2.38242e-7 0.852802 0 0.5222343 0.9238802 0 0.3826819 0 -1 0 0.760513 0 0.6493226 0.852802 0 0.5222344 0 -1 0 0.7071068 0 0.7071068 0 -1 0 4.65962e-7 -1 -6.27806e-7 0.7071068 0 0.7071068 0.760513 0 0.6493226 0 -1 0 0.793352 0 0.6087632 0 -1 0 -1.28179e-7 -1 0 0.9238786 0 0.3826859 0 -1 0 0.793352 0 0.6087632 2.01085e-7 -1 -3.41999e-7 0.9914455 0 0.1305214 0 -1 -1.60183e-7 0.9238786 0 0.3826859 -2.07089e-7 -1 0 0.9914455 0 -0.1305212 0 -1 -1.62279e-7 0.9914455 0 0.1305214 4.48783e-7 -1 -5.81315e-7 0.9238775 0 -0.3826885 1.27157e-7 -1 -3.06984e-7 0.9914455 0 -0.1305212 -1.15928e-6 -1 8.89544e-7 0.7933547 0 -0.6087597 4.37074e-7 -1 -5.69606e-7 0.9238775 0 -0.3826885 0.707106 0 -0.7071076 0.707106 0 -0.7071076 0.7933547 0 -0.6087597 0.6087613 0 -0.7933534 0.3826833 0 -0.9238795 0.6087613 0 -0.7933534 0.1305298 0 -0.9914443 0.3826833 0 -0.9238795 -0.13053 2.48966e-7 -0.9914443 0.1305304 -2.48967e-7 -0.9914443 -0.3826844 0 -0.9238791 -0.1305294 0 -0.9914444 -0.6087614 0 -0.7933534 -0.3826844 0 -0.9238791 -0.7071079 8.91548e-7 -0.7071058 -0.7071099 0 -0.7071037 -0.6087613 0 -0.7933534 0 -1 0 -0.6493232 9.67042e-7 -0.7605126 -2.39132e-6 -1 2.16653e-6 0 -1 -1.46898e-7 -0.5222333 0 -0.8528027 0 -1 -1.23558e-7 -0.6493221 0 -0.7605135 0 -1 -1.31971e-7 -0.3826838 0 -0.9238795 -0.5222333 0 -0.8528027 2.40018e-7 -1 0 -0.2337473 0 -0.9722973 -0.3826838 0 -0.9238795 -2.52865e-7 -1 0 -0.07862389 0 -0.9969044 -0.2337473 0 -0.9722973 -0.07862389 0 -0.9969044 1 0 0 0.9722721 0 -0.2338525 0.9722721 0 -0.2338525 0.9722729 0 0.2338492 1 0 0 0.7605168 0 0.6493182 0.9722729 0 0.2338492 0.3826831 0 0.9238797 0.7605168 0 0.6493182 -0.07862579 0 0.9969042 0.3826831 0 0.9238797 -0.5221428 0 0.8528581 -0.07862579 0 0.9969042 -0.7071073 0 0.7071064 -0.5221428 0 0.8528581 -1 0 3.45124e-7 -0.7071072 0 0.7071064 0 -1 -1.32792e-7 -0.7071064 0 -0.7071073 0 -1 -1.55297e-7 -1.21676e-7 -1 0 -1 0 3.45124e-7 0 -1 -1.33681e-7 -0.5221428 1.35558e-6 -0.8528581 0 -1 0 -0.7071067 1.12392e-6 -0.7071068 0 -1 0 -0.07862621 0 -0.9969042 -0.5221378 0 -0.8528611 0 -1 0 0.3826829 0 -0.9238798 -0.07862621 0 -0.9969041 0.7605126 0 -0.6493232 0.3826829 0 -0.9238798 0.7605126 0 -0.6493232 -0.7071068 0 0.7071067 0 0 1 0 0 1 -0.8528611 0 0.5221378 -0.7071069 0 0.7071067 -0.9969041 0 0.07862758 -0.8528611 0 0.5221378 -0.9238793 0 -0.3826841 -0.9969041 0 0.07862758 -0.6493232 0 -0.7605127 -0.9238793 0 -0.3826841 -0.2338525 0 -0.9722721 -0.6493232 0 -0.7605126 0 0 -1 -0.2338525 0 -0.9722721 0.2338492 0 -0.9722729 0 0 -1 0.6493263 0 -0.76051 0.2338492 0 -0.9722729 0.9238781 0 -0.3826869 0.6493263 0 -0.76051 -5.09705e-7 -1 0 0.9969047 0 0.07861882 0.9238781 0 -0.3826869 -1.57904e-7 -1 0 0.8528581 0 0.5221428 0.9969047 0 0.07861882 0 -1 -1.2559e-7 0.7071068 0 0.7071068 0.8528581 0 0.5221428 0.7071068 0 0.7071068 -0.7071068 0 -0.7071068 -0.7071077 0 0.7071058 0.7071059 0 -0.7071078 -0.707107 1.19677e-6 -0.7071067 0.7071066 1.12392e-6 -0.7071069 0.7071069 0 0.7071067 -0.7071077 0 0.7071058 0.7071069 0 0.7071067 -0.7071065 0 -0.7071071 2.35655e-7 -1 -4.14159e-7 -0.7071068 0 0.7071068 -4.66136e-7 -1 2.68859e-7 -0.7071068 0 0.7071068 -0.7071065 0 -0.7071071 0.7071068 0 -0.7071068 0 -1 0 0.7071065 0 0.7071071 0 -1 0 0 -1 0 -9.18983e-7 -1 7.78836e-7 0 -1 0 0.7071065 0 0.7071071 0.7071068 0 -0.7071068 7.78834e-7 -1 -9.18982e-7 0.7071068 0 0.7071068 9.77106e-7 -1 -1.13578e-6 0.7071066 0 -0.707107 -4.66113e-7 -1 2.68837e-7 0.7071066 0 -0.707107 -0.7071068 0 0.7071068 0.7071068 0 0.7071068 0 -1 0 -0.7071061 0 -0.7071076 0 -1 0 0 -1 0 0 -1 0 -1.37847e-6 -1 1.23824e-6 -0.7071059 0 -0.7071076 -0.7071068 0 0.7071068 1.23824e-6 -1 -1.37847e-6 -0.707107 0 -0.7071067 -0.7071068 0 0.7071068 0.7071071 0 -0.7071065 -0.707107 0 -0.7071067 0.7071071 0 -0.7071065 0.7071069 0 0.7071066 -0.7071068 0 0.7071068 0.7071069 0 0.7071066 0.7071074 1.13249e-6 -0.7071062 0.499625 1.37685e-7 -0.8662419 0.499625 1.37685e-7 -0.8662419 0.7071063 0 -0.7071073 0.8662397 7.35867e-7 -0.4996286 1 -1.58946e-7 0 0.8662423 -1.37686e-7 -0.4996243 0.8662423 0 0.4996243 1 0 -9.18982e-7 0.7071071 0 0.7071066 0.8662423 0 0.4996243 0.49963 0 0.866239 0.7071071 0 0.7071066 0 0 1 0.49963 0 0.866239 -0.4996256 -1.37685e-6 0.8662414 -9.18982e-6 -1.58946e-6 1 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.4996187 0 0.8662455 -0.8662406 0 0.499627 -1 0 0 -0.8662406 0 0.499627 -0.8662406 0 -0.499627 -1 0 0 -0.7071068 0 -0.7071067 -0.8662406 0 -0.499627 -0.499625 1.37685e-7 -0.8662419 -0.707107 0 -0.7071067 0 0 -1 -0.4996243 0 -0.8662423 -9.18982e-7 1.58946e-7 -1 0.8662391 0 -0.4996296 0.707108 0 -0.7071056 1 0 0 0.8662391 0 -0.4996296 0.8662455 0 0.4996187 1 0 0 0.7071064 -1.12392e-6 0.7071071 0.8662414 -1.37685e-6 0.4996256 0.4996243 -1.37686e-7 0.8662423 0.707107 0 0.7071065 9.18982e-7 0 1 0.499625 0 0.8662419 -0.499625 -1.37685e-7 0.8662419 0 -1.58946e-7 1 -0.707107 0 0.7071065 -0.7071069 0 0.7071067 -0.499625 -1.37685e-7 0.8662419 -0.8662421 0 0.4996246 -1 0 9.18983e-7 -0.8662421 0 0.4996246 -0.8662424 0 -0.4996239 -1 0 9.18983e-7 -0.7071065 0 -0.7071071 -0.8662424 0 -0.4996239 -0.4996257 0 -0.8662415 -0.7071065 0 -0.7071071 0 0 -1 -0.4996257 0 -0.8662415 0.4996257 0 -0.8662415 0 0 -1 0.707108 0 -0.7071056 0.4996257 0 -0.8662415 0.7071068 0 0.7071068 0.8662455 0 0.4996188 0.8662455 0 0.4996188 0.7071068 0 0.7071068 0.4996188 0 0.8662455 0 0 1 0.4996188 0 0.8662455 -0.4996187 0 0.8662455 0 0 1 -0.7071073 0 0.7071062 -0.4996188 0 0.8662455 -0.8662416 0 0.4996253 -0.7071073 0 0.7071062 -1 0 0 -0.8662416 0 0.4996253 -0.8662416 0 -0.4996253 -1 0 0 -0.7071068 1.1921e-7 -0.7071068 -0.707107 0 -0.7071067 -0.8662416 0 -0.4996253 -0.499625 1.37685e-7 -0.8662419 0 0 -1 -0.4996243 0 -0.8662423 0.4996242 1.37685e-7 -0.8662422 -9.18982e-7 1.58946e-7 -1 0.7071063 0 -0.7071073 0.4996242 1.37685e-7 -0.8662422 0.8662455 0 -0.4996187 0.7071064 0 -0.7071071 1 0 0 0.8662455 0 -0.4996187 1 0 0 -0.4996257 0 -0.8662415 -0.707108 0 -0.7071056 0 0 -1 -0.4996257 0 -0.8662415 0.4996256 0 -0.8662414 0 0 -1 0.7071067 0 -0.7071069 0.4996256 0 -0.8662414 0.8662414 0 -0.4996256 0.7071067 0 -0.7071069 1 0 0 0.8662415 0 -0.4996257 0.8662415 0 0.4996257 1 0 0 0.7071074 -1.19209e-7 0.7071062 0.7071073 0 0.7071063 0.8662415 0 0.4996257 0.4996243 -1.37686e-7 0.8662423 0 -1.58946e-7 1 0.4996243 -1.37686e-7 0.8662423 -0.4996243 0 0.8662423 9.18982e-7 0 1 -0.7071072 0 0.7071064 -0.4996243 0 0.8662423 -0.8662384 0 0.499631 -0.7071072 0 0.7071064 -1 0 0 -0.8662384 0 0.499631 -0.8662406 0 -0.499627 -1 0 0 -0.707108 0 -0.7071056 -0.8662406 0 -0.499627 0 1 0 0 1 1.19221e-7 0 1 1.37468e-7 0 1 0 0 1 2.06392e-7 1.36462e-7 1 0 4.30964e-7 1 -2.75923e-7 -2.28522e-7 1 3.96208e-7 1.54061e-7 1 0 0 1 1.62144e-7 1.76588e-7 1 0 0 1 1.87285e-7 2.14855e-7 1 0 0 1 2.28975e-7 3.01726e-7 1 -1.61454e-7 -1.7215e-7 1 3.21723e-7 7.26645e-7 1 -5.94937e-7 -6.33625e-7 1 7.73898e-7 5.67806e-6 1 -5.40145e-6 1.65736e-5 1 -1.64419e-5 -9.36772e-6 1 9.54578e-6 -2.79514e-7 1 5.22357e-7 0 1 0 0 1 2.90407e-7 0 1 2.161e-7 0 1 2.25348e-7 1.21479e-7 1 0 0 1 1.84719e-7 0 1 1.62952e-7 0 1 1.4673e-7 0 1 1.36106e-7 1.19341e-7 1 0 0 1 1.94119e-7 0 1 0 -5.25512e-7 1 7.86609e-7 0 1 2.49901e-7 2.47594e-6 1 1.76459e-6 6.25835e-6 1 4.18104e-6 0 1 1.57388e-7 -1.8468e-7 1 0 -1.41265e-7 1 0 0 1 0 0 1 0 0 1 0 -3.07483e-7 1 3.75556e-7 5.65678e-7 1 6.76104e-7 0 1 2.05598e-7 0 1 0 -2.18266e-5 1 -3.1432e-5 -1.55229e-7 1 2.90095e-7 -4.60963e-7 1 1.5171e-6 0 1 1.98086e-7 0 1 4.03264e-7 0 1 2.48795e-7 0 1 1.82973e-7 0 1 1.45478e-7 1.20983e-7 1 0 0 1 0 1.7255e-7 1 0 1.41119e-7 1 0 1.32506e-7 1 0 1.64195e-7 1 0 1.59669e-7 1 0 0 1 1.20386e-7 1.92089e-7 1 0 1.79283e-7 1 0 0 1 1.31392e-7 2.54353e-7 1 -1.36103e-7 -6.23701e-6 1 6.51914e-6 0 1 0 -1.09535e-6 1 1.43252e-6 0 1 1.19291e-7 1.57542e-7 1 0 3.52184e-7 1 -2.0313e-7 0 1 0 0 1 0 0 1 0 0 1 1.80629e-7 0 1 0 0 1 0 -2.17109e-7 1 1.08116e-6 1.20984e-7 1 0 1.32735e-7 1 0 1.5358e-7 1 0 1.98821e-7 1 -1.62782e-7 3.78622e-7 1 -4.62449e-7 -7.71568e-7 1 1.44191e-6 -1.40322e-6 1 2.43667e-6 -1.56022e-7 1 5.13497e-7 3.93682e-6 1 -5.89289e-6 0 1 3.2832e-7 8.89083e-7 1 -9.32081e-7 0 1 0 -7.01592e-7 1 7.74725e-7 -1.68698e-6 1 1.86282e-6 2.22135e-7 1 0 0 1 0 -6.55466e-7 1 7.22727e-7 0 1 1.7255e-7 1.84955e-7 1 0 2.89223e-6 1 -3.09014e-6 0 1 2.22134e-7 -2.5675e-7 1 0 2.94564e-6 1 1.96789e-6 1.25009e-7 1 1.5726e-7 -1.6416e-7 1 0 -1.25568e-7 1 0 0 1 0 0 1 0 0 1 0 2.16057e-6 1 -1.10528e-6 3.52085e-6 1 5.2702e-6 0 1 1.7255e-7 0 1 1.94869e-7 0 1 2.8018e-7 0 1 1.5358e-7 -4.60943e-7 1 1.51704e-6 0 1 0 0 1 4.03264e-7 0 1 2.48794e-7 0 1 1.82973e-7 0 1 1.45477e-7 0 1 1.19222e-7 0 1 0 0 1 1.37468e-7 0 1 0 0 1 2.06392e-7 0 1 0 -5.99766e-7 1 7.7457e-7 -2.28522e-7 1 3.96208e-7 -7.38836e-7 1 9.07893e-7 0 1 0 2.4016e-7 1 0 1.20292e-6 1 -1.03386e-6 2.92207e-7 1 0 0 1 3.11401e-7 4.10336e-7 1 -2.19566e-7 -2.34137e-7 1 4.37556e-7 9.88232e-7 1 -8.09108e-7 -8.61635e-7 1 1.05241e-6 -1.05038e-6 1 1.28292e-6 -9.96586e-6 1 1.0145e-5 -9.36825e-6 1 9.54631e-6 -2.48449e-7 1 4.64308e-7 -3.76194e-7 1 6.25334e-7 0 1 2.58141e-7 1.07928e-6 1 -1.02195e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -6.73913e-7 1 8.90669e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.20984e-7 1 0 1.32736e-7 1 0 1.53579e-7 1 0 1.98824e-7 1 -1.62786e-7 -3.06557e-6 1 5.27788e-6 -3.85784e-7 1 7.20955e-7 3.38601e-6 1 -5.21904e-6 0 1 2.56741e-7 1.9682e-6 1 -2.94613e-6 0 1 1.6416e-7 0 1 1.25568e-7 0 1 0 0 1 0 3.77822e-7 1 -2.52411e-7 0 1 0 2.22135e-7 1 0 0 1 0 -4.28431e-7 1 5.37147e-7 0 1 0 0 1 0 0 1 0 -6.89797e-7 1 9.12665e-7 0 1 0 1.92089e-7 1 0 1.79284e-7 1 0 0 1 1.31392e-7 2.54356e-7 1 -1.36106e-7 6.03695e-7 1 -4.94265e-7 0 1 0 8.65106e-7 1 -8.65106e-7 0 1 0 -7.2304e-7 1 9.18984e-7 3.52184e-7 1 -2.0313e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 6.42356e-7 1.5534e-7 1 0 -3.45953e-7 1 5.17843e-7 0 1 3.75696e-7 0 1 0 4.60427e-7 1 -3.07595e-7 2.63726e-7 1 0 -1.41459e-7 1 2.45264e-7 0 1 2.40001e-7 2.14569e-7 1 0 0 1 1.74155e-7 1.60364e-7 1 0 0 1 0 -3.15945e-7 1 5.24742e-7 0 1 0 0 1 0 0 1 0 0 1 0 -4.9367e-7 1 7.20565e-7 7.44431e-7 1 -6.13692e-7 6.07765e-7 1 -4.06026e-7 -4.56682e-7 1 6.83577e-7 0 1 0 0 1 1.42089e-7 1.264e-7 1 0 0 1 0 0 1 2.33319e-7 0 1 0 0 1 0 0 1 0 -1.47285e-6 1 1.72506e-6 4.91713e-7 1 -3.36913e-7 0 1 2.67842e-7 1.37176e-7 1 0 -1.24352e-7 1 3.00214e-7 1.20759e-6 1 -1.03719e-6 -5.39493e-7 1 7.29672e-7 0 1 1.8798e-7 5.13083e-7 1 -3.42779e-7 -3.42451e-7 1 5.12594e-7 4.87109e-7 1 -3.25423e-7 1.64411e-6 1 -1.48242e-6 0 1 2.22265e-7 2.12387e-7 1 0 0 1 5.13356e-7 0 1 2.00303e-7 0 1 0 0 1 2.74264e-7 -1.81944e-6 1 2.00179e-6 0 1 5.13357e-7 -1.5349e-7 1 6.08348e-7 0 1 2.78945e-7 0 1 2.00299e-7 0 1 0 0 1 2.74265e-7 0 1 0 -1.81947e-6 1 2.00183e-6 0 1 0 1.98402e-6 1 -1.90322e-6 -3.07128e-7 1 5.01536e-7 3.13614e-7 1 -1.21367e-7 1.37176e-7 1 0 -1.24353e-7 1 3.00215e-7 -1.07488e-6 1 1.25464e-6 2.19509e-7 1 0 3.991e-7 1 -2.32654e-7 5.13076e-7 1 -3.42772e-7 1.87433e-6 1 -1.70418e-6 5.53161e-7 1 -3.69551e-7 -1.2331e-6 1 1.41671e-6 0 1 2.22267e-7 2.12387e-7 1 0 0 1 0 0 1 0 0 1 0 -3.58744e-7 1 5.51006e-7 0 1 0 2.1457e-7 1 0 0 1 2.39999e-7 4.60435e-7 1 -3.07603e-7 -3.45962e-7 1 5.17852e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.3332e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.85695e-6 1 -1.67819e-6 6.26205e-7 1 -4.18353e-7 -1.69872e-7 1 3.77724e-7 -2.67211e-7 1 4.63285e-7 0 1 1.63199e-7 -6.50852e-7 1 8.29617e-7 0 1 0 0 1 0 0 1 0 6.65807e-7 1 -9.96619e-7 0 1 0 0 1 0 2.18017e-7 1 -1.25747e-7 -1.56106e-6 1 1.89824e-6 0 1 0 3.17695e-7 1 1.71826e-7 0 1 0 0 1 0 2.06286e-6 1 -1.9864e-6 1.97455e-7 1 0 -2.00346e-7 1 3.68799e-7 0 1 2.01907e-7 0 1 1.42903e-7 2.72046e-7 1 0 0 1 0 -2.63879e-7 1 4.46988e-7 1.01398e-6 1 -8.65729e-7 1.47494e-5 1 -1.47495e-5 -1.26545e-6 1 1.43149e-6 0 1 0 2.67843e-7 1 0 -4.84827e-7 1 5.2593e-7 -2.41977e-6 1 2.62492e-6 -5.68984e-7 1 7.37138e-7 -3.5685e-7 1 0 1.31258e-7 1 1.22231e-7 -1.45001e-7 1 0 -5.13352e-7 1 0 0 1 1.49638e-7 -2.74265e-7 1 0 2.71398e-7 1 6.46478e-7 7.4899e-7 1 -1.12112e-6 -1.44996e-6 1 1.78713e-6 2.4527e-7 1 -1.41467e-7 0 1 0 1.28394e-7 1 0 0 1 0 0 1 0 -1.77898e-7 1 3.69949e-7 2.43791e-7 1 0 -7.32993e-7 1 8.95201e-7 2.55255e-6 1 -2.456e-6 -4.66643e-7 1 0 0 1 1.50992e-7 -1.89618e-7 1 1.26678e-7 -4.07053e-7 1 6.09298e-7 8.12205e-7 1 -6.36097e-7 1.97455e-7 1 0 0 1 2.34214e-7 0 1 1.42902e-7 -3.50756e-7 1 5.40707e-7 4.23969e-7 1 -2.59626e-7 -8.25737e-7 1 1.02417e-6 1.75651e-5 1 -1.75652e-5 7.48996e-7 1 -5.74725e-7 -2.51373e-7 1 4.35826e-7 -3.76197e-5 1 3.78725e-5 1.33865e-6 1 -1.1592e-6 0 1 2.81641e-7 0 1 1.19675e-7 -8.3058e-7 1 1.04242e-6 -5.38705e-7 1 7.28366e-7 0 1 0 2.82975e-7 1 -1.63213e-7 0 1 0 0 1 0 0 1 0 0 1 0 1.45496e-7 1 0 0 1 0 0 1 1.45495e-7 -9.13859e-7 1 1.03385e-6 -1.63212e-7 1 2.82974e-7 4.21029e-7 1 -2.42838e-7 -3.52212e-7 1 5.36785e-7 -2.27101e-5 1 2.29349e-5 -2.51373e-7 1 4.35827e-7 5.28455e-6 1 -5.11254e-6 1.69058e-7 1 0 0 1 1.19675e-7 -8.30597e-7 1 1.04244e-6 -5.38692e-7 1 7.28352e-7 0 1 0 2.82975e-7 1 -1.63213e-7 0 1 1.85132e-7 0 1 0 0 1 2.62247e-7 0 1 0 1.45496e-7 1 0 1.67745e-7 1 0 9.18982e-7 1 -7.7314e-7 2.3935e-7 1 0 -3.26423e-7 1 5.65948e-7 4.16502e-7 1 -2.40227e-7 -2.60627e-7 1 4.4249e-7 2.64129e-6 1 -2.54476e-6 0 1 1.2559e-7 0 1 1.27244e-7 0 1 2.7615e-7 0 1 0 0 1 1.22437e-7 0 1 0 1.98634e-7 1 7.49035e-7 0 1 0 0 1 0 0 1 0 0 1 1.85022e-7 0 1 0 0 1 1.82212e-7 0 1 0 0 1 2.36642e-7 0 1 0 0 1 0 0 1 1.77423e-7 -1.65254e-6 1 1.91057e-6 0 1 0 1.85317e-7 1 1.44499e-7 0 1 0 0 1 0 0 1 2.54844e-7 0 1 0 0 1 0 0 1 1.32792e-7 -5.06846e-7 1 8.2787e-7 -1.28339e-7 1 3.12464e-7 0 1 1.71986e-7 0 1 0 0 1 0 -1.30922e-7 1 2.53808e-7 0 1 0 -1.53055e-7 1 1.19343e-7 0 1 7.49423e-7 0 1 2.27308e-7 0 1 1.41246e-7 0 1 0 0 1 0 0 1 0 0 1 0 3.28449e-7 1 -1.59862e-7 -1.85302e-7 1 3.58614e-7 -1.65158e-7 1 3.33746e-7 0 1 1.3352e-7 1.2255e-7 1 0 0 1 1.94563e-7 1.66859e-7 1 0 3.95371e-7 1 -2.04306e-7 2.53559e-7 1 0 0 1 2.54527e-7 -3.48857e-7 1 5.39924e-7 -1.00077e-6 1 1.30423e-6 6.408e-7 1 -4.91701e-7 0 1 0 -2.16614e-6 1 2.39091e-6 0 1 0 0 1 0 0 1 3.38686e-7 0 1 0 0 1 2.46485e-7 -2.12612e-7 1 3.86539e-7 0 1 1.48855e-7 1.2163e-7 1 0 0 1 1.22985e-7 0 1 0 0 1 1.75318e-7 -2.44899e-7 1 4.30881e-7 3.77427e-7 1 -2.17693e-7 -5.24192e-7 1 7.13852e-7 0 1 2.59905e-7 0 1 0 0 1 1.35883e-7 0 1 1.2232e-7 -1.87662e-7 1 3.67111e-7 0 1 1.55621e-7 1.52862e-7 1 0 0 1 0 0 1 1.77423e-7 -3.00377e-6 1 3.20892e-6 0 1 0 2.16688e-7 1 -1.32661e-7 0 1 2.36642e-7 0 1 0 0 1 0 0 1 0 0 1 1.85022e-7 0 1 1.82212e-7 0 1 7.49386e-7 0 1 0 0 1 0 0 1 0 0 1 2.27309e-7 0 1 1.41245e-7 0 1 0 0 1 3.31303e-7 0 1 0 0 1 0 -3.57803e-6 1 3.74662e-6 0 1 0 0 1 0 0 1 1.3352e-7 1.2255e-7 1 0 0 1 1.94563e-7 1.66859e-7 1 0 0 1 2.20035e-7 -1.70777e-7 1 3.90955e-7 5.69591e-7 1 -4.20491e-7 3.2617e-7 1 -1.35105e-7 0 1 0 -1.58563e-6 1 1.73472e-6 0 1 2.40338e-7 3.9064e-6 1 -3.9064e-6 0 1 0 0 1 1.62023e-7 1.51915e-7 1 3.59185e-7 0 1 0 0 1 2.50073e-7 0 1 1.19343e-7 0 1 0 1.57049e-7 1 1.22457e-7 0 1 0 0 1 0 0 1 2.51661e-7 -1.30923e-7 1 2.53809e-7 0 1 0 -5.67797e-7 1 6.51874e-7 2.60975e-7 1 0 4.32657e-6 1 -5.59879e-6 0 1 1.71988e-7 0 1 0 1.35883e-7 1 0 2.99884e-7 1 -1.31296e-7 4.03895e-7 1 -2.45278e-7 3.77412e-7 1 -2.17678e-7 -5.24242e-7 1 7.13902e-7 0 1 0 0 1 2.27125e-7 0 1 0 -2.73821e-6 1 3.56851e-6 4.79804e-7 1 -2.56124e-6 0 1 1.12274e-6 0 1 0 0 1 1.64341e-7 0 1 1.2559e-7 0 1 0 4.03351e-7 1 1.14577e-6 0 1 1.22437e-7 0 1 0 0 1 0 0 1 0 0 1 2.88373e-7 0 1 0 1.38723e-7 1 0 2.18721e-7 1 0 -1.96084e-7 1 3.59713e-7 0 1 1.4873e-7 2.39065e-6 1 -2.29811e-6 0 1 2.358e-7 0 1 0 0 1 0 1.39981e-7 1 0 0 1 0 7.25081e-7 1 -5.61453e-7 0 1 2.18721e-7 -2.59876e-7 1 4.50577e-7 0 -1 0 0.6951993 -0.3708019 0.6157954 0 -1 0 0 -1 0 0.6224596 -0.3444259 0.7027907 0.5793814 -0.3693712 0.726555 0 -1 0 0.7637103 -0.3728236 0.527019 0 -1 0 0.730239 -0.3572492 0.5823436 4.08807e-7 -1 -5.29013e-7 0.8232866 -0.368141 0.4320548 0 -1 0 0 -1 0 0.8670771 -0.374145 0.328927 0 -1 0 0.8413122 -0.3578457 0.4051422 0 -1 0 0.9040153 -0.3647984 0.222887 0 -1 0 -1.33897e-7 -1 0 0.9203412 -0.3748042 0.1117765 0 -1 -1.21782e-7 0.9099424 -0.3589887 0.2076823 -1.69507e-7 -1 0 0.9326782 -0.3607096 -6.87519e-5 0 -1 -1.5017e-7 -2.25209e-7 -1 0 0.9203339 -0.37481 -0.1118164 0 -1 -1.92935e-7 0.9326676 -0.360737 0 -3.20903e-7 -1 0 0.9073346 -0.3560201 -0.2235926 0 -1 -2.6252e-7 -5.1037e-7 -1 1.93456e-7 0.8671597 -0.374155 -0.3286974 1.47664e-7 -1 -3.89481e-7 0.9084069 -0.3630563 -0.2073332 1.06909e-6 -1 -1.30394e-6 0.8292589 -0.3505312 -0.435267 3.50114e-7 -1 -6.67028e-7 -1.50594e-6 -1 1.03962e-6 0.7636213 -0.3728035 -0.5271623 5.23716e-7 -1 -7.5857e-7 0.8384773 -0.3659363 -0.4037901 3.62341e-6 -1 -4.08996e-6 0.7027007 -0.3443655 -0.6225947 0.615845 -0.3708276 -0.6951416 0.726548 -0.3693952 -0.579375 0.5271894 -0.3728048 -0.763602 0.5823253 -0.3572626 -0.7302469 0.432116 -0.3681373 -0.8232561 0.3287588 -0.3741431 -0.8671416 0.4051554 -0.3578192 -0.8413171 0.2227201 -0.3647588 -0.9040724 0.1118084 -0.374828 -0.9203276 0.2077108 -0.3590219 -0.9099228 6.87547e-5 -0.3607645 -0.932657 -0.1117087 -0.3748143 -0.9203453 0 -0.360737 -0.9326676 -0.223769 -0.3559634 -0.9073133 -0.3289058 -0.3741573 -0.8670798 -0.2073352 -0.36308 -0.908397 -0.4352242 -0.3505669 -0.8292663 -0.5270186 -0.3728256 -0.7637097 -0.4037966 -0.3659439 -0.8384708 -0.6224958 -0.3444155 -0.7027637 0 -1 0 -0.6951987 -0.3708018 -0.615796 -0.5793988 -0.369372 -0.7265407 0 -1 0 -0.7637289 -0.3728388 -0.5269815 0 -1 0 -0.730233 -0.3572513 -0.5823498 4.0883e-7 -1 -5.29034e-7 -0.8232628 -0.3681606 -0.4320834 0 -1 0 0 -1 0 -0.8670623 -0.3741521 -0.3289577 0 -1 0 -0.8413048 -0.3578573 -0.4051473 0 -1 0 -0.9040094 -0.3648034 -0.2229025 0 -1 0 -1.33905e-7 -1 0 -0.9203439 -0.3748151 -0.1117182 0 -1 -1.21781e-7 -0.9099406 -0.3589901 -0.2076877 -1.69508e-7 -1 0 -0.9326715 -0.360727 6.87507e-5 0 -1 -1.5017e-7 -2.25191e-7 -1 0 -0.9203367 -0.3748207 0.1117581 0 -1 -1.92922e-7 -0.9326608 -0.3607544 0 -3.20899e-7 -1 0 -0.9073351 -0.3560233 0.2235854 0 -1 -2.62534e-7 -5.10442e-7 -1 1.93527e-7 -0.8671339 -0.374158 0.328762 1.47687e-7 -1 -3.89503e-7 -0.9084067 -0.3630549 0.2073365 1.06885e-6 -1 -1.30371e-6 -0.829268 -0.3505555 0.4352304 3.50045e-7 -1 -6.6696e-7 -1.50642e-6 -1 1.04003e-6 -0.7636007 -0.3728086 0.5271885 5.23727e-7 -1 -7.58587e-7 -0.8384755 -0.3659442 0.4037869 -4.09122e-6 -1 3.62483e-6 -0.7026977 -0.3443771 0.6225917 -0.615875 -0.3708249 0.6951164 -0.7265311 -0.3693929 0.5793976 -0.5271895 -0.3728042 0.7636021 -0.5823446 -0.3572564 0.7302345 -0.4320848 -0.368134 0.823274 -0.3287854 -0.3741535 0.8671271 -0.4051668 -0.3578317 0.8413065 -0.2227604 -0.3647741 0.9040562 -0.1117581 -0.374821 0.9203366 -0.2076858 -0.3590123 0.9099322 -6.87547e-5 -0.3607645 0.932657 0.11171 -0.3748163 0.9203443 0 -0.3607371 0.9326676 0.2237191 -0.3559749 0.9073212 0.3289662 -0.3741527 0.8670588 0.2073364 -0.3630689 0.9084011 0.4352226 -0.3505761 0.8292633 0.5270169 -0.3728241 0.7637116 0.4038126 -0.3659442 0.838463 0 1 0 -0.463622 0.7061997 -0.5351044 -0.5419802 0.6969599 -0.4695788 -0.5545784 0.7048701 -0.442268 0 1 0 -0.3813905 0.708674 -0.5935676 0 1 0 -0.444585 0.7011056 -0.55749 0 1 0 -0.2966417 0.6999236 -0.6497005 0 1 0 0 1 0 -0.1990928 0.707447 -0.6781451 0 1 0 -0.308346 0.7035452 -0.6402709 0 1 0 -0.1004637 0.7082692 -0.6987572 0 1 0 -0.1587275 0.7008422 -0.6954321 0 1 0 0 0.7024654 -0.7117179 0 1 0 0 1 0 0.1004576 0.7082626 -0.6987649 0 1 0 2.42488e-5 0.70246 -0.7117232 0 1 0 0.1991058 0.707449 -0.6781393 0 1 0 0.1587052 0.7008383 -0.6954412 0 1 0 0.2947214 0.7045643 -0.6455451 0 1 0 0 1 0 0.3813927 0.7086699 -0.5935711 0 1 0 0 1 0 0.3091689 0.7016468 -0.6419551 0 1 0 0.4696115 0.6969488 -0.5419662 0 1 0 0 1 0 0 1 0 0.5351045 0.7062051 -0.4636137 0 1 0 0.4422493 0.7048738 -0.5545886 0 1 0 0.593566 0.7086759 -0.3813895 0 1 0 0 1 0 0.5574985 0.7011091 -0.4445689 0 1 0 0.6496803 0.699931 -0.2966687 0 1 0 0 1 0 0 1 0 0.6781451 0.7074427 -0.1991075 0 1 0 0.640276 0.7035427 -0.3083412 0 1 0 0.698767 0.7082688 -0.1003991 0 1 0 0.6954396 0.7008352 -0.1587257 0 1 0 0.7117179 0.7024654 0 0 1 0 0 1 0 0.6987673 0.7082688 0.100398 0 1 0 0.7117179 0.7024654 0 0 1 0 0.6781511 0.7074409 0.1990945 0 1 0 0.6954399 0.7008351 0.158725 0 1 0 0.6455442 0.704554 0.2947479 0 1 0 0 1 0 0.5935555 0.7086709 0.381415 0 1 0 0.6419639 0.7016445 0.3091558 0 1 0 0.5419814 0.6969584 0.4695798 0.4636105 0.7062034 0.5351093 0.5545887 0.7048742 0.4422487 0.3814185 0.7086714 0.5935525 0.44457 0.7011079 0.557499 0.2966315 0.6999186 0.6497104 0.1991058 0.707449 0.6781393 0.3083575 0.7035471 0.6402634 0.1004481 0.7082709 0.6987578 0.1587275 0.7008422 0.6954321 0 0.7024666 0.7117168 -0.1004554 0.7082701 0.6987575 0 0.7024666 0.7117168 -0.1990928 0.707447 0.6781451 -0.1587275 0.7008422 0.6954321 -0.2947493 0.7045598 0.6455374 0 1 0 -0.3813684 0.7086726 0.5935835 0 1 0 -0.3091611 0.7016494 0.6419561 0 1 0 -0.4696055 0.6969506 0.5419691 0 1 0 0 1 0 0 1 0 -0.5351093 0.7061986 0.4636179 0 1 0 -0.4422656 0.7048692 0.5545815 0 1 0 -0.5935679 0.7086765 0.3813853 0 1 0 0 1 0 -0.557487 0.7011063 0.4445875 -0.6496908 0.6999292 0.2966496 -0.6781451 0.707447 0.1990928 -0.6402739 0.7035458 0.3083384 -0.6987577 0.70827 0.1004553 -0.6954324 0.7008421 0.1587268 -0.7117179 0.7024654 0 -0.6987574 0.70827 -0.1004565 -0.7117179 0.7024654 0 -0.6781393 0.707449 -0.1991058 -0.6954321 0.7008422 -0.1587275 -0.6455424 0.7045637 -0.2947285 -0.5935755 0.7086759 -0.3813747 -0.6419593 0.7016519 -0.3091484 -0.866064 0 -0.4999331 -0.49996 -3.54194e-6 -0.8660485 -0.5000264 0 -0.8660102 -1 0 0 -0.8660257 -3.54128e-6 -0.4999995 -0.8660434 8.30503e-6 0.4999688 -1 -7.08887e-6 -1.53284e-4 -0.4999688 7.7702e-6 0.8660434 -0.8660643 6.37355e-6 0.4999326 0 -7.08444e-6 1 -0.4999588 8.3047e-6 0.8660492 0.4999688 -3.542e-6 0.8660434 1.53284e-4 0 1 0.8660128 0 0.5000219 0.5000352 0 0.8660051 1 0 0 0.8659744 -3.54285e-6 0.5000883 0.8660157 8.03412e-6 -0.5000168 1 -7.08878e-6 1.53271e-4 0.49996 7.77021e-6 -0.8660485 0.8660336 6.37382e-6 -0.4999856 0 -7.6294e-6 -1 0.4999945 5.9266e-6 -0.8660286 -1.65061e-4 0 -1 -0.7818271 0 -0.6234953 -0.7818271 0 -0.6234953 -0.6234911 0 -0.7818304 -0.9009705 0 -0.4338805 -0.9009705 0 -0.4338805 -0.974928 0 -0.2225205 -0.974928 0 -0.2225205 -1 0 0 -1 0 0 -0.9749282 0 0.2225195 -0.9749282 0 0.2225195 -0.9009696 0 0.4338824 -0.9009696 0 0.4338824 -0.781827 0 0.6234953 -0.781827 0 0.6234954 -0.6234911 0 0.7818304 -0.6234911 0 0.7818304 -0.4338967 0 0.9009627 -0.4338967 0 0.9009627 -0.2225205 0 0.974928 -0.2225205 0 0.974928 0 0 1 0 0 1 0.2225205 0 0.974928 0.2225205 0 0.974928 0.43391 0 0.9009562 0.43391 0 0.9009562 0.6234722 0 0.7818456 0.6234722 0 0.7818455 0.7818328 0 0.6234881 0.7818461 3.027e-6 0.6234716 -0.6234911 0 -0.7818304 0.9009677 0 0.4338863 0.900974 2.10864e-6 0.433873 0.9749293 0 0.2225148 0.9749293 0 0.2225149 1 0 0 1 0 0 0.974929 0 -0.2225159 0.974929 0 -0.222516 0.9009686 0 -0.4338844 0.9009686 0 -0.4338844 0.7818461 0 -0.6234716 0.7818461 0 -0.6234716 0.6234721 0 -0.7818456 0.6234721 0 -0.7818456 0.4339061 -3.74933e-6 -0.9009582 0.4338823 0 -0.9009695 0.2224882 4.73338e-6 -0.9749354 0.2225483 -4.05831e-6 -0.9749217 3.40706e-5 0 -1 0 4.85507e-6 -1 -0.2225205 0 -0.974928 -0.2225205 0 -0.974928 -0.4338927 0 -0.9009646 -0.4338927 0 -0.9009646 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.615796 -0.3708018 -0.6951987 0 -1 0 0 -1 0 0.7027912 -0.3444262 -0.6224589 0.7265555 -0.3693711 -0.5793809 -5.38616e-7 -1 -6.68842e-7 0.5270166 -0.3728243 -0.7637118 0 -1 0 0.5823442 -0.3572489 -0.7302386 0 -1 0 0.4320584 -0.3681424 -0.8232842 0 -1 0 0 -1 0 0.3289273 -0.3741427 -0.867078 0 -1 0 0.4051387 -0.3578444 -0.8413145 0 -1 0 0.2229444 -0.3648021 -0.9039996 -4.29019e-7 -1 -5.71812e-7 0 -1 0 0.1117191 -0.3747982 -0.9203507 0 -1 0 0.2076891 -0.3589733 -0.909947 0 -1 0 -6.87511e-5 -0.3607096 -0.9326781 0 -1 0 -7.68649e-7 -1 -8.67572e-7 -0.1118166 -0.3748101 -0.9203339 -8.23056e-7 -1 -9.28982e-7 0 -0.3607371 -0.9326676 8.9979e-7 -1 8.99804e-7 -0.2235947 -0.3560197 -0.9073342 1.3126e-7 -1 0 0 -1 0 -0.3287028 -0.374154 -0.8671581 0 -1 0 -0.2073376 -0.3630549 -0.9084064 0 -1 0 -0.4352588 -0.3505334 -0.8292624 0 -1 0 0 -1 0 -0.5271626 -0.3728021 -0.7636218 0 -1 0 -0.4037885 -0.365935 -0.8384786 0 -1 0 -0.622595 -0.3443638 -0.7027014 -0.695147 -0.3708239 -0.6158411 -0.5793783 -0.3693919 -0.7265469 -0.7635993 -0.372803 -0.5271944 -0.7302454 -0.3572615 -0.582328 -0.8232612 -0.3681346 -0.4321089 -0.867133 -0.3741574 -0.3287654 -0.8413015 -0.3578286 -0.4051797 -0.9040669 -0.3647731 -0.2227188 -0.9203276 -0.3748282 -0.1118076 -0.9099268 -0.3590268 -0.2076846 -0.932657 -0.3607645 -6.87547e-5 -0.9203438 -0.3748151 0.1117182 -0.9326676 -0.360737 0 -0.9073139 -0.3559667 0.2237615 -0.8670811 -0.374157 0.3289026 -0.9083969 -0.3630799 0.2073353 -0.8292633 -0.3505637 0.4352325 -0.7637115 -0.3728243 0.5270169 -0.8384694 -0.3659432 0.4038001 -0.7027638 -0.3444134 0.622497 0 -1 0 -0.6157954 -0.3708019 0.6951993 -0.7265424 -0.3693719 0.5793967 -4.26139e-7 -1 -5.41897e-7 -0.5269869 -0.3728453 0.7637219 0 -1 0 -0.5823613 -0.3572564 0.7302213 0 -1 0 -0.4320748 -0.3681647 0.8232654 0 -1 0 0 -1 0 -0.3289865 -0.3741466 0.8670537 0 -1 0 -0.4051362 -0.35786 0.8413091 0 -1 0 -0.2228872 -0.3647959 0.9040161 -4.41772e-7 -1 -5.68699e-7 0 -1 0 -0.1117087 -0.3748143 0.9203453 0 -1 0 -0.2076877 -0.3589882 0.9099413 0 -1 0 6.87514e-5 -0.360727 0.9326715 0 -1 0 0 -1 0 0.1117485 -0.3748199 0.9203382 0 -1 0 0 -0.3607543 0.9326609 0 -1 0 0.2235926 -0.3560201 0.9073346 -7.6836e-7 -1 -8.67274e-7 0 -1 0 0.3287569 -0.3741568 0.8671364 0 -1 0 0.2073374 -0.3630545 0.9084067 0 -1 0 0.4352391 -0.3505511 0.8292652 0 -1 0 0 -1 0 0.5271885 -0.3728086 0.7636007 0 -1 0 0.4037868 -0.3659443 0.8384754 0 -1 0 0.6225917 -0.3443772 0.7026977 0.6951156 -0.3708283 0.6158739 0.5793919 -0.369396 0.726534 0.7636021 -0.3728042 0.5271895 0.7302381 -0.3572581 0.5823392 0.8232697 -0.3681346 0.4320924 0.8671305 -0.374153 0.3287769 0.8413072 -0.3578294 0.4051671 0.9040722 -0.3647681 0.2227053 0.9203271 -0.374827 0.1118155 0.9099269 -0.3590267 0.2076844 0.932657 -0.3607644 6.87503e-5 0.9203453 -0.3748143 -0.1117087 0.9326676 -0.360737 0 0.9073105 -0.3559603 -0.2237856 0.8670788 -0.3741631 -0.3289017 0.9083955 -0.3630839 -0.2073349 0.829264 -0.350574 -0.435223 0.7637076 -0.3728223 -0.5270239 0.8384637 -0.365942 -0.4038131 0 1 0 -0.5351089 0.7061992 0.4636175 -0.4695793 0.6969591 0.5419809 -0.4422659 0.7048701 0.5545802 0 1 0 -0.5935677 0.7086738 0.3813906 0 1 0 -0.5574913 0.7011057 0.4445832 0 1 0 -0.6496947 0.6999247 0.2966514 0 1 0 0 1 0 -0.6781462 0.7074466 0.1990906 0 1 0 -0.6402702 0.7035443 0.3083492 0 1 0 -0.6987574 0.7082691 0.1004637 0 1 0 -0.6954322 0.7008421 0.1587275 0 1 0 -0.711718 0.7024653 0 0 1 0 0 1 0 -0.6987565 0.7082702 -0.1004624 0 1 0 -0.711718 0.7024654 0 0 1 0 -0.6781435 0.7074487 -0.1990923 0 1 0 -0.6954308 0.7008436 -0.1587272 0 1 0 -0.6455426 0.7045636 -0.2947286 0 1 0 0 1 0 -0.5935705 0.7086704 -0.3813924 0 1 0 0 1 0 -0.6419541 0.7016475 -0.3091694 0 1 0 -0.5419663 0.6969496 -0.4696103 0 1 0 0 1 0 0 1 0 -0.4636184 0.7062051 -0.5351003 0 1 0 -0.5545874 0.7048737 -0.4422511 0 1 0 -0.3814269 0.7086725 -0.5935459 0 1 0 0 1 0 -0.4445714 0.7011085 -0.5574972 0 1 0 -0.2966312 0.6999191 -0.6497099 0 1 0 0 1 0 0 1 0 -0.1991077 0.7074423 -0.6781457 0 1 0 -0.30834 0.7035424 -0.640277 0 1 0 -0.1004062 0.7082686 -0.6987662 0 1 0 -0.158729 0.7008352 -0.6954388 0 1 0 0 0.702466 -0.7117174 0 1 0 0 1 0 0.100399 0.7082694 -0.6987665 0 1 0 0 0.702466 -0.7117173 0 1 0 0.1991077 0.7074423 -0.6781457 0 1 0 0.158729 0.7008352 -0.6954388 0 1 0 0.2947311 0.7045573 -0.6455482 0 1 0 0 1 0 0.3814183 0.7086721 -0.5935521 0 1 0 0.3091526 0.7016453 -0.6419646 0 1 0 0.4695789 0.6969598 -0.5419803 0.5351002 0.7062052 -0.4636183 0.4422482 0.7048754 -0.5545874 0.5935528 0.7086711 -0.3814188 0.5574996 0.7011077 -0.4445698 0.6497149 0.6999171 -0.296625 0.6781387 0.7074495 -0.1991057 0.6402629 0.7035477 -0.3083573 0.6987591 0.7082769 -0.1003968 0.6954316 0.7008428 -0.1587274 0.7117097 0.7024737 0 0.6987589 0.708276 0.1004052 0.7117097 0.7024738 0 0.6781455 0.7074472 0.1990904 0.6954316 0.7008428 0.1587274 0.6455463 0.7045614 0.2947257 0 1 0 0.5935421 0.7086726 0.3814328 0 1 0 0.641959 0.701646 0.3091625 0 1 0 0.5419859 0.6969622 0.4695689 0 1 0 0 1 0 0 1 0 0.4636211 0.7062009 0.5351034 0 1 0 0.5545831 0.7048711 0.4422607 0 1 0 0.3813895 0.7086758 0.593566 0 1 0 0 1 0 0.4445835 0.7011067 0.5574898 0.2966686 0.6999309 0.6496802 0.1990539 0.7074412 0.6781626 0.3083382 0.7035418 0.6402784 0.1004565 0.7082699 0.6987577 0.1587275 0.7008421 0.6954322 0 0.7024653 0.711718 -0.1004553 0.70827 0.6987577 0 0.7024654 0.711718 -0.1991059 0.7074488 0.6781394 -0.1587275 0.7008421 0.6954322 -0.2947214 0.7045641 0.6455453 -0.3813813 0.7086747 0.5935728 -0.3091503 0.7016506 0.6419599 -0.4999243 0 0.8660691 -0.8660464 -3.54196e-6 0.4999638 -0.8660081 0 0.5000302 0 0 1 -0.5000265 -5.44893e-6 0.8660103 0.4999549 8.03211e-6 0.8660515 -1.53271e-4 -7.08878e-6 1 0.8660515 8.04266e-6 0.4999549 0.4999327 6.84552e-6 0.8660643 1 -7.08444e-6 0 0.8660514 8.03212e-6 0.4999551 0.8660691 -3.54168e-6 -0.4999243 1 0 -1.53284e-4 0.4999638 2.83175e-6 -0.8660464 0.8660131 1.63494e-6 -0.5000213 0 0 -1 0.5000832 -3.54281e-6 -0.8659774 -0.5000219 8.30677e-6 -0.8660128 1.53273e-4 -7.08886e-6 -1 -0.8660464 8.04266e-6 -0.4999638 -0.4999946 6.84582e-6 -0.8660286 -1 -7.08444e-6 0 -0.8660286 6.39854e-6 -0.4999946 -1 0 1.53273e-4 -0.6234924 3.0271e-6 0.7818295 -0.6235089 0 0.7818161 -0.7818323 0 0.6234888 -0.4338824 0 0.9009696 -0.433869 2.10864e-6 0.9009759 -0.2225205 0 0.974928 -0.2225205 0 0.974928 0 0 1 0 0 1 0.2225205 0 0.974928 0.2225205 0 0.974928 0.4338824 0 0.9009696 0.4338824 0 0.9009696 0.62349 0 0.7818313 0.62349 0 0.7818313 0.7818347 0 0.6234858 0.7818347 0 0.6234858 0.9009626 0 0.4338966 0.9009626 0 0.4338966 0.974928 0 0.2225205 0.974928 0 0.2225205 1 0 0 1 0 0 0.974928 0 -0.2225205 0.974928 0 -0.2225205 0.9009562 0 -0.43391 0.9009562 0 -0.43391 0.781846 0 -0.6234715 0.781846 0 -0.6234715 0.6234887 0 -0.7818323 0.6234722 3.027e-6 -0.7818456 -0.7818323 0 0.6234888 0.4338823 0 -0.9009695 0.4338691 2.10864e-6 -0.900976 0.2225205 0 -0.974928 0.2225205 0 -0.974928 0 0 -1 0 0 -1 -0.2225205 0 -0.974928 -0.2225205 0 -0.974928 -0.4338824 0 -0.9009696 -0.4338824 0 -0.9009696 -0.6234745 0 -0.7818437 -0.6234745 0 -0.7818437 -0.7818437 0 -0.6234745 -0.7818437 0 -0.6234745 -0.9009563 0 -0.43391 -0.9009562 0 -0.43391 -0.974928 0 -0.2225205 -0.974928 0 -0.2225205 -1 0 0 -1 0 0 -0.974928 0 0.2225205 -0.974928 0 0.2225205 -0.9009627 0 0.4338967 -0.9009626 0 0.4338967 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.6951944 -0.3708019 -0.6158009 0 -1 0 0 -1 0 -0.6224994 -0.3444033 -0.7027665 -0.5793837 -0.3693711 -0.7265531 0 -1 0 -0.7637143 -0.3728255 -0.527012 0 -1 0 -0.730237 -0.3572482 -0.5823467 3.98953e-7 -1 -5.34184e-7 -0.8232857 -0.3681432 -0.4320548 0 -1 -1.23361e-7 0 -1 0 -0.8670693 -0.3741568 -0.3289338 0 -1 0 -0.8413003 -0.3578545 -0.4051592 -1.2324e-7 -1 0 -0.9039948 -0.3648161 -0.2229408 0 -1 0 -1.50644e-7 -1 0 -0.9203453 -0.3748143 -0.1117087 0 -1 -1.37004e-7 -0.9099413 -0.3589882 -0.2076879 -1.90694e-7 -1 0 -0.932671 -0.3607284 5.89297e-5 0 -1 -1.68941e-7 -2.5336e-7 -1 0 -0.9203281 -0.3748245 0.1118156 0 -1 -2.17053e-7 -0.9326619 -0.3607519 0 -3.60978e-7 -1 0 -0.907339 -0.3560454 0.2235347 0 -1 -2.95336e-7 -5.74241e-7 -1 2.17712e-7 -0.8671416 -0.3741433 0.3287589 1.6612e-7 -1 -4.38167e-7 -0.9084051 -0.363043 0.2073642 9.45508e-7 -1 -1.23908e-6 -0.829259 -0.3505315 0.4352666 3.93887e-7 -1 -7.50414e-7 -1.8827e-6 -1 1.29971e-6 -0.763621 -0.3728042 0.5271621 6.54482e-7 -1 -9.4805e-7 -0.8384779 -0.3659373 0.403788 4.53048e-6 -1 -5.11347e-6 -0.7027054 -0.3443679 0.6225882 -0.6158695 -0.3708264 0.6951204 -0.7265481 -0.3693932 0.5793761 -0.5271623 -0.3728035 0.7636213 -0.5823273 -0.3572531 0.7302501 -0.4321202 -0.3681365 0.8232543 -0.3287557 -0.374143 0.8671429 -0.4051576 -0.3578177 0.8413168 -0.2227224 -0.364759 0.9040717 -0.1118155 -0.3748266 0.9203273 -0.2077108 -0.3590213 0.909923 -6.87496e-5 -0.3607643 0.932657 0.1117087 -0.3748141 0.9203454 0 -0.360737 0.9326675 0.2237714 -0.3559625 0.9073132 0.3289026 -0.374157 0.8670811 0.2073354 -0.36308 0.908397 0.4352244 -0.3505657 0.8292667 0.5270239 -0.3728223 0.7637076 0.4038009 -0.365941 0.8384702 0.622491 -0.3444154 0.7027681 0 -1 0 0.6951988 -0.3708018 0.615796 0.5793939 -0.3693717 0.7265448 0 -1 0 0.7637339 -0.3728233 0.5269851 0 -1 0 0.7302528 -0.3572431 0.5823301 5.3075e-7 -1 -6.50953e-7 0.823273 -0.3681437 0.4320784 0 -1 -1.23361e-7 0 -1 0 0.8670596 -0.3741505 0.3289665 0 -1 0 0.8412954 -0.3578516 0.4051722 0 -1 0 0.9040102 -0.3648012 0.2229027 0 -1 0 -1.33906e-7 -1 0 0.9203454 -0.374814 0.1117087 0 -1 -1.2178e-7 0.9099416 -0.3589878 0.2076877 -1.69506e-7 -1 0 0.932671 -0.3607284 -5.89291e-5 0 -1 -1.5017e-7 -2.25191e-7 -1 0 0.9203375 -0.3748184 -0.1117582 0 -1 -1.92922e-7 0.9326619 -0.3607518 0 -3.20903e-7 -1 0 0.9073346 -0.35602 -0.2235927 0 -1 -2.62534e-7 -5.10436e-7 -1 1.93521e-7 0.8671365 -0.3741568 -0.3287569 1.47687e-7 -1 -3.89504e-7 0.9084066 -0.3630543 -0.2073375 1.06889e-6 -1 -1.30374e-6 0.8292652 -0.350551 -0.4352393 3.50045e-7 -1 -6.6696e-7 -1.50642e-6 -1 1.04003e-6 0.7636007 -0.3728086 -0.5271885 5.23745e-7 -1 -7.58603e-7 0.8384755 -0.3659442 -0.4037869 -4.09071e-6 -1 3.62432e-6 0.7027021 -0.3443791 -0.6225857 0.6158699 -0.3708246 -0.6951212 0.7265332 -0.3693926 -0.5793949 0.5271944 -0.3728029 -0.7635994 0.5823423 -0.3572571 -0.7302362 0.432085 -0.3681328 -0.8232743 0.3287855 -0.3741526 -0.8671274 0.4051669 -0.3578305 -0.8413068 0.2227605 -0.3647735 -0.9040564 0.1117581 -0.3748205 -0.9203367 0.2076857 -0.3590116 -0.9099326 6.87496e-5 -0.3607643 -0.932657 -0.1117182 -0.374815 -0.9203438 0 -0.360737 -0.9326677 -0.2237191 -0.3559748 -0.9073212 -0.3289577 -0.3741521 -0.8670622 -0.2073361 -0.3630688 -0.9084011 -0.4352311 -0.3505719 -0.8292607 -0.5269848 -0.3728247 -0.7637335 -0.4038106 -0.3659451 -0.8384635 0 1 0 0.4635939 0.7061982 0.5351307 0.5419843 0.6969601 0.4695738 0.5545818 0.7048697 0.4422644 0 1 0 0.3814133 0.7086743 0.5935527 0 1 0 0.4445788 0.7011094 0.5574901 0 1 0 0.2966452 0.6999228 0.6496997 0 1 0 0 1 0 0.1990929 0.7074466 0.6781455 0 1 0 0.3083492 0.7035443 0.6402702 0 1 0 0.1004553 0.7082698 0.6987578 0 1 0 0.1587276 0.7008419 0.6954324 0 1 0 0 0.7024653 0.711718 0 1 0 0 1 0 -0.1004553 0.7082698 0.6987578 0 1 0 0 0.7024653 0.711718 0 1 0 -0.1991059 0.7074486 0.6781397 0 1 0 -0.1587276 0.7008419 0.6954324 0 1 0 -0.2947249 0.7045635 0.6455445 0 1 0 0 1 0 -0.381393 0.7086694 0.5935714 0 1 0 0 1 0 -0.3091705 0.7016463 0.6419547 0 1 0 -0.4696116 0.6969487 0.5419664 0 1 0 0 1 0 0 1 0 -0.5351046 0.706205 0.4636138 0 1 0 -0.4422489 0.7048737 0.5545891 0 1 0 -0.5935424 0.7086722 0.381433 0 1 0 0 1 0 -0.5574982 0.7011091 0.4445694 0 1 0 -0.6497146 0.6999176 0.2966249 0 1 0 0 1 0 0 1 0 -0.6781429 0.7074427 0.1991153 0 1 0 -0.6402767 0.7035426 0.3083398 0 1 0 -0.6987671 0.7082687 0.1003991 0 1 0 -0.6954394 0.7008345 0.1587292 0 1 0 -0.711718 0.7024653 0 0 1 0 0 1 0 -0.6987608 0.7082751 -0.1003971 0 1 0 -0.7117134 0.70247 2.07844e-5 0 1 0 -0.6781429 0.707447 -0.1991005 0 1 0 -0.6954332 0.700841 -0.1587278 0 1 0 -0.6455402 0.7045601 -0.2947422 0 1 0 0 1 0 -0.5935527 0.7086714 -0.3814187 0 1 0 -0.6419552 0.7016467 -0.3091689 0 1 0 -0.5419809 0.6969591 -0.4695793 -0.4636147 0.7062034 -0.5351057 -0.554587 0.7048742 -0.4422506 -0.3814147 0.7086716 -0.5935548 -0.444572 0.7011075 -0.5574981 -0.2966344 0.6999194 -0.6497083 -0.1991059 0.7074486 -0.6781397 -0.3083565 0.7035466 -0.6402645 -0.1004553 0.7082698 -0.6987578 -0.1587276 0.7008419 -0.6954324 0 0.7024653 -0.711718 0.1004637 0.708269 -0.6987575 0 0.7024653 -0.711718 0.1990929 0.7074466 -0.6781455 0.1587276 0.7008419 -0.6954324 0.2947528 0.7045589 -0.6455367 0 1 0 0.3813648 0.7086722 -0.5935862 0 1 0 0.3091611 0.7016492 -0.6419562 0 1 0 0.4696061 0.6969498 -0.5419698 0 1 0 0 1 0 0 1 0 0.5351094 0.7061985 -0.4636179 0 1 0 0.442264 0.7048689 -0.554583 0 1 0 0.5935666 0.7086751 -0.3813899 0 1 0 0 1 0 0.5574893 0.7011057 -0.4445859 0.6496981 0.6999262 -0.2966406 0.6781429 0.707447 -0.1991005 0.640274 0.7035457 -0.3083385 0.6987591 0.70827 -0.1004471 0.6954332 0.700841 -0.1587278 0.711718 0.7024653 0 0.698759 0.7082697 0.1004483 0.711718 0.7024654 0 0.678137 0.7074489 0.1991136 0.6954332 0.700841 0.1587278 0.6455453 0.7045642 0.2947214 0.5935728 0.7086747 0.3813813 0.6419599 0.7016506 0.3091503 0.8660641 0 0.4999331 0.49996 -3.54194e-6 0.8660485 0.5000265 0 0.8660103 1 0 0 0.8660081 -5.1773e-6 0.5000302 0.8660433 8.30502e-6 -0.4999688 1 -7.08886e-6 1.53273e-4 0.4999688 9.67743e-6 -0.8660433 0.8660286 9.67751e-6 -0.4999946 0 -7.08444e-6 -1 0.4999946 8.30587e-6 -0.8660286 -0.4999331 -3.54175e-6 -0.8660641 -1.53284e-4 0 -1 -0.8660433 0 -0.4999688 -0.4999995 0 -0.8660257 -1 0 0 -0.8660257 -1.63487e-6 -0.4999995 -0.8660107 8.03441e-6 0.5000257 -1 -7.08878e-6 -1.53284e-4 -0.4999957 7.77018e-6 0.8660278 -0.8660286 6.37387e-6 0.4999946 0 -7.08444e-6 1 -0.4999857 8.30558e-6 0.8660337 1.53271e-4 0 1 0.7818314 -3.25358e-6 0.62349 0.7818456 0 0.6234722 0.6234858 0 0.7818347 0.9009696 0 0.4338824 0.9009581 -3.75069e-6 0.433906 0.974928 0 0.2225205 0.974928 0 0.2225205 1 0 0 1 0 0 0.974928 0 -0.2225205 0.974928 0 -0.2225205 0.9009695 0 -0.4338823 0.9009695 0 -0.4338823 0.7818295 0 -0.6234924 0.7818295 0 -0.6234924 0.6234887 0 -0.7818323 0.6234887 0 -0.7818323 0.4338967 0 -0.9009626 0.4338967 0 -0.9009626 0.2225205 0 -0.974928 0.2225205 0 -0.9749279 0 0 -1 0 0 -1 -0.2225205 0 -0.974928 -0.2225205 0 -0.974928 -0.4339081 0 -0.9009571 -0.4339081 0 -0.9009571 -0.6234745 0 -0.7818437 -0.6234745 0 -0.7818438 -0.7818304 0 -0.6234911 -0.7818437 3.02701e-6 -0.6234745 0.6234858 0 0.7818347 -0.9009582 0 -0.4339061 -0.9009646 2.10516e-6 -0.4338927 -0.974928 0 -0.2225205 -0.974928 0 -0.2225205 -1 4.16149e-6 2.92033e-5 -1 0 0 -0.974928 0 0.2225205 -0.9749217 4.05831e-6 0.2225483 -0.9009696 0 0.4338824 -0.9009696 0 0.4338824 -0.7818456 0 0.6234722 -0.7818456 0 0.6234722 -0.6234716 0 0.7818461 -0.6234716 0 0.7818461 -0.4339081 -3.74932e-6 0.9009571 -0.4338844 0 0.9009686 -0.2225205 0 0.974928 -0.2225483 -4.05831e-6 0.9749217 0 0 1 0 0 1 0.2225205 0 0.974928 0.2225205 0 0.974928 0.4338967 0 0.9009627 0.4338967 0 0.9009627 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.615796 -0.3708017 0.6951987 0 -1 0 0 -1 0 -0.7027631 -0.3443998 0.6225052 -0.7265533 -0.3693712 0.5793836 -4.26166e-7 -1 -5.41923e-7 -0.5270171 -0.3728241 0.7637115 0 -1 0 -0.5823443 -0.3572489 0.7302387 0 -1 0 -0.4320508 -0.3681417 0.8232884 0 -1 0 0 -1 0 -0.3289358 -0.3741432 0.8670744 0 -1 0 -0.4051386 -0.3578465 0.8413136 0 -1 0 -0.2229444 -0.3648021 0.9039996 -4.41746e-7 -1 -5.68673e-7 0 -1 0 -0.1117191 -0.3747982 0.9203507 0 -1 0 -0.2076891 -0.3589733 0.909947 0 -1 0 6.87511e-5 -0.3607096 0.9326781 0 -1 0 -7.68649e-7 -1 -8.67572e-7 0.1118161 -0.3748098 0.9203341 -6.58445e-7 -1 -7.43185e-7 0 -0.360737 0.9326675 8.99694e-7 -1 8.99693e-7 0.2235292 -0.3560315 0.9073457 1.31262e-7 -1 0 0 -1 0 0.3287644 -0.3741413 0.8671402 0 -1 0 0.2073389 -0.3630377 0.9084131 0 -1 0 0.4352632 -0.3505312 0.829261 0 -1 0 0 -1 0 0.5271623 -0.3728036 0.7636213 0 -1 0 0.4037865 -0.3659361 0.8384791 0 -1 0 0.6225891 -0.3443675 0.7027047 0.6951519 -0.3708238 0.6158356 0.5793786 -0.3693919 0.7265467 0.7636015 -0.3728063 0.5271891 0.7302448 -0.3572635 0.5823275 0.8232535 -0.3681387 0.4321198 0.8671426 -0.3741438 0.3287556 0.8413171 -0.3578192 0.4051554 0.9040688 -0.3647606 0.2227315 0.9203287 -0.3748254 0.1118072 0.909924 -0.3590191 0.2077099 0.9326585 -0.3607605 5.89327e-5 0.9203454 -0.374814 -0.1117087 0.9326676 -0.360737 0 0.9073147 -0.3559641 -0.2237622 0.8670786 -0.3741554 -0.3289114 0.9083977 -0.3630776 -0.2073355 0.8292667 -0.3505658 -0.4352244 0.7637116 -0.3728241 -0.5270169 0.8384712 -0.3659428 -0.403797 0.7027638 -0.3444133 -0.622497 0 -1 0 0.6157906 -0.3708016 -0.6952037 0.7265424 -0.3693717 -0.5793967 -5.38582e-7 -1 -6.68809e-7 0.5269911 -0.3728249 -0.763729 0 -1 0 0.5823317 -0.3572458 -0.7302501 0 -1 0 0.4320785 -0.3681449 -0.8232725 0 -1 0 0 -1 0 0.3289666 -0.3741505 -0.8670597 0 -1 0 0.4051703 -0.357852 -0.841296 0 -1 0 0.2229027 -0.3648011 -0.9040102 -4.29071e-7 -1 -5.71864e-7 0 -1 0 0.1117087 -0.374814 -0.9203454 0 -1 0 0.2076878 -0.3589877 -0.9099416 0 -1 0 -6.87507e-5 -0.360727 -0.9326715 0 -1 0 0 -1 -1.40742e-7 -0.1117485 -0.3748196 -0.9203383 1.20576e-7 -1 0 0 -0.3607543 -0.9326609 0 -1 0 -0.223595 -0.356019 -0.9073344 -9.60628e-7 -1 -1.08428e-6 0 -1 0 -0.3287537 -0.3741565 -0.8671377 0 -1 0 -0.2073376 -0.3630544 -0.9084067 0 -1 0 -0.4352393 -0.3505498 -0.8292657 0 -1 0 0 -1 0 -0.5271912 -0.372817 -0.7635948 0 -1 0 -0.4037736 -0.3659495 -0.8384795 0 -1 0 -0.6225835 -0.3443906 -0.7026984 -0.6951211 -0.3708263 -0.615869 -0.5794075 -0.3693951 -0.726522 -0.7635976 -0.3728182 -0.5271863 -0.7302203 -0.3572652 -0.5823571 -0.8232645 -0.3681498 -0.4320896 -0.8671364 -0.3741568 -0.3287569 -0.8413175 -0.3578357 -0.4051402 -0.9040482 -0.3647801 -0.2227832 -0.9203376 -0.3748185 -0.1117582 -0.9099332 -0.3590098 -0.207686 -0.9326586 -0.3607605 -5.89289e-5 -0.9203454 -0.374814 0.1117087 -0.9326676 -0.360737 0 -0.9073221 -0.3559724 0.2237191 -0.8670607 -0.3741511 0.3289632 -0.9084022 -0.3630668 0.2073354 -0.8292641 -0.3505738 0.4352231 -0.7637339 -0.3728233 0.5269851 -0.838465 -0.3659439 0.4038089 0 1 0 0.5351089 0.7061991 -0.4636175 0.4695464 0.6969649 -0.5420019 0.4422538 0.7048689 -0.5545911 0 1 0 0.5935678 0.7086737 -0.3813907 0 1 0 0.5574914 0.7011056 -0.4445833 0 1 0 0.649699 0.6999237 -0.2966449 0 1 0 0 1 0 0.678144 0.7074465 -0.1990984 0 1 0 0.6402714 0.7035444 -0.3083464 0 1 0 0.6987609 0.7082749 -0.1003983 0 1 0 0.6954334 0.7008409 -0.1587278 0 1 0 0.7117116 0.7024718 0 0 1 0 0 1 0 0.6987674 0.7082685 0.100398 0 1 0 0.7117162 0.7024671 2.07846e-5 0 1 0 0.6781371 0.7074487 0.1991136 0 1 0 0.6954415 0.7008373 0.158708 0 1 0 0.6455442 0.7045637 0.2947247 0 1 0 0 1 0 0.5935734 0.7086699 0.3813889 0 1 0 0 1 0 0.6419548 0.7016471 0.3091687 0 1 0 0.5419669 0.6969488 0.4696108 0 1 0 0 1 0 0 1 0 0.4636149 0.7062041 0.5351046 0 1 0 0.5545881 0.7048729 0.4422515 0 1 0 0.3814271 0.7086723 0.5935462 0 1 0 0 1 0 0.4445714 0.7011083 0.5574973 0 1 0 0.2966344 0.6999192 0.6497084 0 1 0 0 1 0 0 1 0 0.199108 0.7074412 0.6781468 0 1 0 0.3083391 0.7035411 0.6402787 0 1 0 0.100398 0.7082685 0.6987674 0 1 0 0.1587293 0.7008341 0.6954398 0 1 0 0 0.7024651 0.7117181 0 1 0 0 1 0 -0.1003969 0.7082759 0.69876 0 1 0 2.42486e-5 0.7024706 0.7117128 0 1 0 -0.199095 0.7074393 0.6781526 0 1 0 -0.1587516 0.7008382 0.6954306 0 1 0 -0.2947558 0.7045518 0.645543 0 1 0 0 1 0 -0.3814129 0.708675 0.5935521 0 1 0 -0.3091425 0.7016467 0.641968 0 1 0 -0.4695765 0.6969634 0.5419777 -0.5350797 0.7062047 0.4636427 -0.4422603 0.7048748 0.5545786 -0.593575 0.7086748 0.3813773 -0.5574897 0.7011052 0.4445862 -0.6497071 0.6999244 0.2966253 -0.6781371 0.7074487 0.1991136 -0.6402716 0.7035484 0.3083374 -0.6987593 0.7082697 0.1004471 -0.6954337 0.7008408 0.1587271 -0.7117181 0.7024651 0 -0.6987591 0.7082696 -0.1004483 -0.7117181 0.7024651 0 -0.678144 0.7074465 -0.1990984 -0.6954334 0.7008409 -0.1587278 -0.6455395 0.7045593 -0.2947457 0 1 0 -0.5935632 0.708679 -0.3813877 0 1 0 -0.6419627 0.7016527 -0.30914 0 1 0 -0.5419805 0.696965 -0.469571 0 1 0 0 1 0 0 1 0 -0.4636181 0.7061993 -0.5351083 0 1 0 -0.5545719 0.7048704 -0.4422757 0 1 0 -0.3813878 0.7086791 -0.5935633 0 1 0 0 1 0 -0.4445942 0.7011086 -0.5574789 -0.2966424 0.6999298 -0.6496936 -0.1990929 0.7074465 -0.6781457 -0.308329 0.7035459 -0.6402784 -0.1004554 0.7082697 -0.6987579 -0.1587277 0.7008417 -0.6954326 0 0.7024651 -0.7117181 0.1004554 0.7082697 -0.6987579 0 0.7024651 -0.7117181 0.199106 0.7074484 -0.6781398 0.1587277 0.7008417 -0.6954326 0.2947249 0.7045633 -0.6455445 0.3814147 0.7086715 -0.5935549 0.3091675 0.7016469 -0.6419557 0.4999243 0 -0.8660691 0.8660464 -3.54196e-6 -0.4999638 0.8660081 0 -0.5000302 0 0 -1 0.4999907 -3.5413e-6 -0.8660309 -0.49996 7.83277e-6 -0.8660485 1.65075e-4 -7.63416e-6 -1 -0.8660464 9.67741e-6 -0.4999638 -0.4999946 9.67751e-6 -0.8660286 -1 -7.08444e-6 0 -0.8660286 8.0334e-6 -0.4999946 -0.8660641 -3.54175e-6 0.4999331 -1 0 1.53284e-4 -0.4999688 0 0.8660433 -0.8660257 0 0.4999995 0 0 1 -0.5000352 -3.54247e-6 0.866005 0.5000047 8.3062e-6 0.8660228 -1.53271e-4 -7.08886e-6 1 0.8660283 6.37387e-6 0.499995 0.4999946 7.77018e-6 0.8660286 1 -7.08444e-6 0 0.8660286 6.39854e-6 0.4999946 1 0 -1.53273e-4 0.6234745 0 -0.7818437 0.6234745 0 -0.7818437 0.7818323 0 -0.6234887 0.4339041 0 -0.900959 0.4339041 0 -0.900959 0.2225205 0 -0.974928 0.2225205 0 -0.974928 0 0 -1 0 0 -1 -0.2225205 0 -0.974928 -0.2225205 0 -0.9749279 -0.433869 0 -0.900976 -0.433869 0 -0.900976 -0.6235066 0 -0.7818182 -0.6235066 0 -0.7818182 -0.7818181 0 -0.6235066 -0.781818 0 -0.6235066 -0.900976 0 -0.433869 -0.900976 0 -0.433869 -0.974928 0 -0.2225205 -0.974928 0 -0.2225205 -1 0 0 -1 0 0 -0.9749282 0 0.2225195 -0.9749282 0 0.2225195 -0.9009696 -3.74937e-6 0.4338824 -0.9009582 0 0.4339061 -0.7818295 0 0.6234924 -0.7818436 -3.24941e-6 0.6234745 -0.6234888 0 0.7818323 -0.6234888 0 0.7818323 0.7818323 0 -0.6234887 -0.433869 0 0.900976 -0.433869 0 0.9009759 -0.2225529 -4.73331e-6 0.9749206 -0.2225205 0 0.974928 3.40707e-5 0 1 0 -4.85507e-6 1 0.2225205 0 0.974928 0.2225205 0 0.974928 0.4338805 0 0.9009705 0.4338805 0 0.9009705 0.6234745 0 0.7818437 0.6234745 0 0.7818437 0.7818437 0 0.6234745 0.7818437 0 0.6234745 0.9009582 -3.74933e-6 0.4339061 0.9009695 0 0.4338823 0.9749346 4.05718e-6 0.2224917 0.9749219 -4.05829e-6 0.2225472 1 0 2.92035e-5 1 4.16149e-6 0 0.974928 0 -0.2225205 0.974928 0 -0.2225205 0.9009645 0 -0.4338927 0.9009646 0 -0.4338927 0 1 0 0 1 0 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 0 0 -1 1 0 0 0 0 1 3.17891e-7 -1 7.62939e-7 -3.39084e-7 1 -7.84132e-7 -1 0 0 0 0 -1 1 0 0 0 0 1 3.39084e-7 -1 7.84132e-7 -3.17891e-7 1 -7.62939e-7 0 -1 0 -0.8191426 0 -0.5735898 0 -1 0 -0.5735221 -0.01062607 -0.8191213 0 -1 0 -0.6836314 0 -0.7298275 -0.3571746 -0.07004898 -0.9314072 -0.49895 -0.03636223 -0.8658676 -0.6361498 -0.005705773 -0.7715445 -1.58701e-6 -1 -4.25174e-7 -0.9659357 0 -0.2587822 3.07814e-5 -1 -2.30889e-5 0 -1 0 0 -1 0 -0.893405 0 -0.4492523 -0.8594567 -0.005589425 -0.511178 -0.817687 -0.01738578 -0.5754004 -0.8785974 -0.00206542 -0.4775587 -0.7557835 -0.04701888 -0.6531314 -3.37819e-6 -1 2.95602e-7 -0.9961934 0 0.08716994 1.92957e-7 -1 -2.20514e-6 -0.9659357 0 -0.2587822 0 -1 0 -0.9063216 0 0.4225887 -1.02791e-5 -1 7.19647e-6 -0.9961934 0 0.08716994 -0.707111 0 0.7071026 -0.9063216 0 0.4225887 -0.4225854 0 0.9063231 -0.707111 0 0.7071026 -0.08716994 0 0.9961934 -0.4225854 0 0.9063231 -9.85694e-7 -1 -3.67839e-6 0.2588369 0 0.9659211 3.03411e-6 -1 -5.25548e-6 -0.08716994 0 0.9961934 4.50698e-6 -1 -4.50695e-6 0.5735222 -0.01062601 0.8191211 -2.03252e-6 -1 -3.52065e-6 0 -1 -4.88396e-6 0.2588369 0 0.9659211 0.4609354 0 0.8874337 0 -1 0 0.8191674 0 0.5735545 0 -1 0 0.3570635 -0.07007688 0.9314478 0.4995071 -0.03622448 0.865552 0.6359694 -0.005729913 0.7716931 0.683655 0 0.7298054 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0 -1 0 0 -1 0 0.8934148 0 0.4492328 0.7557865 -0.04703426 0.6531267 0.8594003 -0.005607604 0.5112725 0.8177585 -0.01736766 0.5752995 0.8787446 -0.002046763 0.477288 0 -1 0 0.9961942 0 -0.08716166 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0.9063198 0 -0.4225922 0 -1 0 0.9961942 0 -0.08716166 0.7071068 0 -0.7071068 0.9063198 0 -0.4225922 0.4225922 0 -0.9063198 0.7071068 0 -0.7071068 0.08716166 0 -0.9961942 0.4225922 0 -0.9063198 0 -1 0 -0.2588291 0 -0.9659231 0 -1 0 0.08716166 0 -0.9961942 0 -1 0 0 -1 0 -0.2588291 0 -0.9659231 -0.4609354 0 -0.8874337 0.4999817 0 0.866036 0.866036 0 0.4999817 0.866036 0 0.4999817 0 0 1 0.4999817 0 0.866036 -0.4999817 0 0.866036 0 0 1 -0.8660053 0 0.5000348 -0.4999817 0 0.866036 -1 0 0 -0.866026 -5.34057e-6 0.4999991 -0.8660587 4.57711e-6 -0.4999422 -1 0 0 -0.4999766 0 -0.8660389 -0.8660411 0 -0.4999729 0 0 -1 -0.4999766 0 -0.8660389 0.4999817 0 -0.866036 0 0 -1 0.8660537 0 -0.4999511 0.4999817 0 -0.866036 1 0 0 0.866036 4.57747e-6 -0.4999817 1 0 0 0 1 0 -0.5735545 0 -0.8191675 0 1 0 -0.8191119 0.008664548 -0.5735683 0 1 0 -0.9816538 0.1415001 -0.1278033 -0.9585941 0.1073694 -0.2637597 -0.8285199 0.02427434 -0.5594333 -0.7849361 0.008864045 -0.6195133 -0.7504767 0.002461552 -0.6608924 -0.7220277 0 -0.6918643 0 1 0 0 1 0 0 1 0 0 1 0 -0.6462789 0.04281157 -0.7618994 -0.5510178 0.01059919 -0.8344262 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.8191367 0.0086627 0.5735329 0 1 0 0 1 0 -2.88712e-6 1 6.82049e-6 0.5735545 0 0.8191675 0 1 0 0.7222303 0 0.6916526 0.9817858 0.1418315 0.1264135 0.9584861 0.1072542 0.2641988 0.8284423 0.0242241 0.5595502 0.7849586 0.008851826 0.619485 0.7504517 0.002441465 0.6609208 4.2525e-7 1 1.58694e-6 -1.71855e-5 1 2.67392e-5 -9.5939e-6 1 1.66179e-5 0 1 4.88396e-6 0.646288 0.04281723 0.7618914 0.5510078 0.01059806 0.8344327 -2.95602e-7 1 3.37819e-6 2.20514e-6 1 -1.92957e-7 1.29718e-5 1 -1.29717e-5 5.77553e-6 1 -2.69295e-6 0 1 0 0 1 0 0 1 0 0 1 0 -0.4619958 -0.7964017 0.3902616 -0.241838 -0.9396972 0.2418335 -0.7527257 -0.3266307 0.571591 -0.3837047 -0.8554462 0.3478253 -0.633031 -0.5942423 0.4961329 -0.6645746 0.3420773 0.664322 -0.8119049 0.03802835 0.5825496 -0.7789319 -0.2409562 0.5789692 -0.6642985 0.3420527 0.6646107 -0.6643776 0.3420374 0.6645395 -0.6643627 0.3420299 0.6645584 -0.5054911 0.8045916 0.3116265 -0.6645603 0.3424324 0.6641533 -0.7078531 0.5280871 0.4691139 -0.7143563 0.5133354 0.4755858 -0.01545572 0.9985106 -0.05232232 -0.5079306 0.8021693 0.3138964 -0.2308667 0.9684154 0.09419125 0.2418473 0.9396935 -0.2418384 0.0860247 0.9873855 -0.1329273 0.2418277 0.9397026 -0.241823 0.2418143 0.9396926 -0.2418754 0.2418454 0.9396926 -0.2418444 0.2418591 0.9396873 -0.2418515 -0.2418708 0.9396925 0.241819 -0.241887 0.939671 0.2418862 -0.2418448 0.9396926 0.241845 -0.2418369 0.9396957 0.2418407 -0.2418434 0.9396933 0.2418433 -0.6644605 -0.3420302 0.6644605 -0.6645213 -0.3420222 0.6644036 0.2418808 -0.9396741 -0.2418808 -0.6644621 -0.3420236 0.6644621 0.2409695 -0.9396868 -0.2427396 0.2418428 -0.939692 -0.241849 0.2418503 -0.9396874 -0.2418593 -0.2418486 -0.9396919 0.2418437 -0.2410883 -0.9396852 0.2426275 -0.2418587 -0.9396857 0.2418577 0.4618031 -0.7965628 -0.3901608 0.2418565 -0.9396851 -0.2418622 0.7528581 -0.3262275 -0.5716469 0.3335353 -0.8868222 -0.3198449 0.5192666 -0.7388109 -0.4295588 0.6642198 -0.5403723 -0.5165362 0.6643565 0.3420332 -0.6645628 0.8117051 0.0378437 -0.5828401 0.7603857 -0.3037837 -0.5740463 0.8092595 -0.04729223 -0.5855447 0.6646167 0.3419233 -0.6643591 0.6648313 0.3421291 -0.6640383 0.6645047 0.3419632 -0.6644507 0.5036497 0.8052029 -0.3130261 0.6653349 0.3429675 -0.6631007 0.7080128 0.5245324 -0.4728463 0.6239287 0.6704466 -0.4015151 0.01728194 0.9984045 0.0537576 0.4660356 0.839388 -0.2797116 0.2810281 0.9504399 -0.1329929 -0.2418493 0.9396886 0.2418563 -0.1386138 0.9756453 0.1700075 0.06799924 0.9976179 0.01160687 0.2418468 0.9396916 -0.2418468 0.6644579 -0.3420399 -0.6644579 0.6648871 -0.341983 -0.6640578 -0.241458 -0.9396801 0.2422793 0.6633315 -0.342028 -0.6655885 -0.7750051 -0.3371096 0.5345317 -0.2418196 0.9397022 0.2418327 -0.2418693 0.9396845 0.2418517 -0.2418472 0.9396915 0.2418465 -0.2418388 0.9396937 0.2418467 -0.2418503 0.939692 0.2418416 -0.2418473 0.939692 0.2418448 -0.491901 0.7720457 0.4024658 -0.4964562 0.7680413 0.4045292 -0.7750221 -0.3370439 0.5345485 -0.7750159 -0.3370778 0.5345363 -0.7750615 -0.3368655 0.5346038 -0.7750517 -0.336802 0.534658 -0.7748359 -0.3377687 0.534361 -0.7752178 -0.3362621 0.534757 -0.774955 -0.337313 0.5344759 -0.775573 -0.3348076 0.5351547 -0.7750182 -0.3370667 0.5345399 -0.7750213 -0.3370537 0.5345436 -0.7749416 -0.3373916 0.534446 -0.1417785 0.9759464 0.1656126 -0.1306107 0.9815008 0.1399896 -0.1617843 0.9703693 0.1794698 -0.1422649 0.9810234 0.1317333 -0.1809245 0.9667502 0.1807221 -0.1832345 0.9695872 0.1622524 -0.1644973 0.9801353 0.1107941 -0.1916915 0.9662252 0.1722304 -0.2418267 0.939698 0.2418421 -0.2081142 0.9637603 0.1668975 -0.2418521 0.9396915 0.2418417 -0.1953691 0.9752576 0.1034576 -0.2097975 0.9628677 0.1699144 -0.2418391 0.9396942 0.2418442 -0.2175869 0.9655941 0.1424223 -0.2418429 0.9396936 0.2418427 -0.2171025 0.9696673 0.112302 -0.2212007 0.9631074 0.153279 -0.2418506 0.9396929 0.2418382 -0.2220409 0.967664 0.1196836 -0.2418566 0.9396925 0.2418335 -0.2231317 0.9668668 0.124019 -0.2418295 0.9396951 0.2418503 -0.2192219 0.9685239 0.1179117 -0.2418429 0.9396924 0.2418473 -0.221127 0.9684724 0.1147338 -0.2418594 0.9396901 0.24184 -0.1799051 0.9836293 -0.01036322 -0.2418414 0.9396926 0.2418484 -0.2075787 0.9692567 0.1321081 -0.2062468 0.9750479 0.08212047 -0.2418404 0.9396926 0.241849 -0.1302626 0.9912569 -0.02101147 -0.2418478 0.9396921 0.2418436 -0.1909742 0.9711627 0.1427301 -0.1504083 0.9883846 0.0217517 -0.2418402 0.9396923 0.2418506 -0.1351868 0.9883148 0.07041686 -0.2418565 0.9396912 0.2418382 -0.175414 0.9731934 0.1487428 -0.2418468 0.9396926 0.2418428 -0.1575155 0.982065 0.1036209 -0.2418365 0.9396932 0.2418509 -0.1664704 0.9751485 0.1461946 -0.1421281 0.9836853 0.1102856 -0.2418481 0.9396926 0.2418415 -0.1590375 0.9769452 0.1424255 -0.2418379 0.9396933 0.241849 -0.1621406 0.9754326 0.149137 -0.2418431 0.9396926 0.2418465 -0.1538118 0.9785771 0.1368522 -0.2418535 0.9396917 0.2418396 -0.1520044 0.9783368 0.1405409 -0.2418379 0.9396926 0.2418517 -0.1583569 0.9757954 0.1508192 -0.1568892 0.9768213 0.1456223 -0.2418492 0.9396924 0.2418414 -0.1594885 0.9749163 0.1552463 -0.2418468 0.9396927 0.2418426 -0.1511078 0.9780054 0.1437771 -0.2418439 0.9396927 0.2418451 -0.1589148 0.9745735 0.1579638 -0.1485179 0.9781829 0.145261 -0.2418467 0.9396922 0.2418441 -0.1579498 0.9743364 0.160376 -0.2418431 0.9396928 0.241846 -0.1471397 0.9780312 0.1476643 -0.2418436 0.9396924 0.2418466 -0.1552894 0.9746217 0.1612378 -0.1469721 0.9775664 0.1508743 -0.2418456 0.9396924 0.2418448 -0.1557358 0.9739449 0.1648564 -0.2418442 0.9396926 0.2418458 -0.148065 0.9763793 0.1573535 -0.1506518 0.9760016 0.1572415 -0.2418425 0.9396926 0.2418471 -0.1534964 0.9741516 0.1657333 -0.2418451 0.9396924 0.2418453 -0.1438267 0.9772643 0.1557832 -0.2418456 0.9396927 0.2418434 -0.1523579 0.974106 0.1670471 -0.2418453 0.9396928 0.2418437 -0.1446599 0.9764738 0.1599132 -0.1489003 0.9754855 0.1620395 -0.2418459 0.9396923 0.2418444 -0.1456029 0.9758188 0.1630263 -0.2418426 0.9396929 0.2418459 -0.2418455 0.9396927 0.2418435 -0.1452168 0.9761188 0.1615676 -0.2418444 0.9396923 0.241846 -0.1449926 0.9759325 0.162889 -0.2418438 0.9396925 0.2418462 -0.2418449 0.9396923 0.2418455 -0.1449605 0.9759508 0.1628081 -0.1527274 0.973772 0.168649 -0.2418444 0.9396927 0.2418446 -0.1440019 0.976233 0.161965 -0.2418474 0.9396924 0.241843 -0.1435098 0.9763785 0.1615239 -0.1431582 0.9764543 0.1613774 -0.1405784 0.9771529 0.1594049 -0.2418455 0.9396924 0.2418447 -0.1517543 0.9737287 0.1697735 -0.2418446 0.9396926 0.2418451 -0.2418436 0.9396926 0.2418461 -0.1417824 0.976773 0.1606617 -0.1450012 0.9759565 0.1627379 -0.2418453 0.9396925 0.2418448 -0.1538986 0.9725478 0.1745445 -0.241845 0.9396924 0.2418448 -0.2418456 0.9396924 0.2418444 -0.1393805 0.9769314 0.1617964 -0.149031 0.9745044 0.1677228 -0.2418458 0.9396923 0.2418454 -0.1525784 0.9722434 0.1773768 -0.2418445 0.9396924 0.2418459 -0.1393079 0.9761095 0.1667442 -0.1429547 0.9755695 0.1668176 -0.2418444 0.9396924 0.241846 -0.1484047 0.9726728 0.1785601 -0.2418389 0.9396938 0.241846 -0.2418431 0.9396929 0.2418457 -0.2418411 0.9396933 0.241846 -0.2418453 0.9396924 0.2418448 -0.2418462 0.9396923 0.2418446 -0.1319548 0.9774982 0.1645755 -0.001106202 0.8454365 0.5340749 -0.1733914 0.9089639 0.3791041 -0.1415568 0.9744624 0.174312 -0.04523813 0.8249446 0.5634003 -0.1555488 0.8016011 0.5772696 -0.04587435 0.8018137 0.5958107 -0.2617154 0.7746856 0.575645 -0.1993203 0.7479176 0.6331593 -0.3819219 0.7083142 0.5936553 -0.4244131 0.7393975 0.5226516 -0.3522972 0.7432321 0.5687643 -0.4930821 0.6200677 0.6102344 -0.4388388 0.7397944 0.5100243 -0.4440507 0.7135357 0.5419278 -0.4504237 0.7246544 0.5215309 -0.4433028 0.7371653 0.5099705 -0.4473275 0.729202 0.5178442 -0.4427388 0.737586 0.5098522 -0.4443908 0.7353557 0.5116334 -0.4425282 0.7397009 0.506963 -0.4442824 0.7355121 0.5115027 -0.4487821 0.7322309 0.5122819 -0.4461439 0.7400252 0.5033073 -0.4552721 0.7229313 0.5197092 -0.4548708 0.732003 0.5072122 -0.4533426 0.7400912 0.4967348 -0.4703179 0.7103369 0.5236627 -0.4670006 0.7289411 0.500555 -0.4591971 0.7490283 0.4775927 -0.4920791 0.6942207 0.5252768 -0.4936076 0.7133057 0.4975403 -0.4723814 0.7531921 0.4577745 -0.5064218 0.6960168 0.5090164 -0.4861221 0.7477388 0.4522964 -0.5345959 0.68012 0.5016414 -0.5149801 0.7252913 0.4568896 -0.4966961 0.7581077 0.4225705 -0.5364295 0.7000668 0.4713277 -0.5567456 0.6944576 0.4558103 0.2418466 -0.9396904 -0.2418514 0.3137205 -0.9022967 -0.2957028 0.3369717 -0.8872148 -0.3151192 0.2418466 -0.9396916 -0.241847 -0.7745842 -0.3387339 0.5341148 0.2418695 -0.9396786 -0.2418742 0.2418127 -0.9397112 -0.2418048 -0.7750353 -0.3369975 0.5345585 -0.7750916 -0.3367942 0.5346051 -0.7748609 -0.3376485 0.5344007 -0.7752636 -0.3361394 0.5347678 -0.7748337 -0.3377596 0.53437 -0.7751177 -0.3366768 0.5346413 0.2418463 -0.9396923 -0.2418449 -0.01796501 -0.9978349 -0.06326651 0.2418467 -0.9397057 -0.2417916 0.2418415 -0.9396724 -0.2419269 0.2418497 -0.939698 -0.2418189 0.2418428 -0.9396862 -0.2418719 0.2418513 -0.939694 -0.2418331 0.2418411 -0.9396894 -0.2418608 0.2418561 -0.9396918 -0.2418369 0.2418504 -0.9396919 -0.2418416 0.2418344 -0.9396948 -0.2418466 -0.7751581 -0.3364607 0.5347188 -0.1522602 -0.9882687 0.01190888 0.241845 -0.9396924 -0.2418453 -0.01385986 -0.9989992 -0.04252713 0.2418441 -0.9396918 -0.2418484 0.2418453 -0.9396924 -0.2418452 0.2418465 -0.9396927 -0.2418426 0.2418463 -0.9396926 -0.2418431 0.2418416 -0.9396921 -0.2418498 0.2418431 -0.9396922 -0.2418481 -0.121821 -0.992327 0.02113407 0.2418448 -0.9396923 -0.2418462 -0.01187545 -0.9997238 -0.02027732 0.2418472 -0.9396932 -0.24184 0.2418421 -0.9396921 -0.2418494 0.2418433 -0.9396922 -0.2418476 0.2418473 -0.9396923 -0.2418432 -0.1021298 -0.994094 0.03669577 0.2418461 -0.9396927 -0.2418428 -0.006195962 -0.9999798 -0.001409769 0.2418451 -0.9396926 -0.2418445 0.241841 -0.9396924 -0.2418494 -0.09908264 -0.992844 0.06665861 0.2418438 -0.9396929 -0.2418449 0.001516461 -0.9999145 0.01298773 0.2418412 -0.9396923 -0.2418497 0.2418503 -0.9396924 -0.2418399 -0.08965653 -0.9916828 0.09234207 0.2418444 -0.9396929 -0.2418443 -0.003849923 -0.9992963 0.0373156 0.2418441 -0.9396928 -0.2418447 -0.05666816 -0.9943445 0.08982092 0.2418446 -0.9396926 -0.2418449 -0.01319491 -0.9979795 0.0621522 0.2418458 -0.9396926 -0.2418434 0.241845 -0.9396927 -0.2418444 0.004940927 -0.9987001 0.05073207 0.2418447 -0.9396926 -0.241845 -0.02315717 -0.99691 0.07506132 0.2418447 -0.9396928 -0.2418443 -0.02216488 -0.9956028 0.0910148 0.2418445 -0.9396928 -0.2418447 0.2418441 -0.9396924 -0.2418463 0.003798604 -0.9980386 0.06248557 0.2418445 -0.9396927 -0.2418445 -3.97131e-4 -0.9980772 0.06198185 0.2418438 -0.9396923 -0.2418467 0.003681242 -0.9979786 0.06344377 0.001637399 -0.9978416 0.06564629 0.2418458 -0.9396925 -0.241844 0.00352019 -0.9980018 0.06308835 0.2418452 -0.9396922 -0.2418458 0.2418458 -0.9396926 -0.2418441 -0.01689523 -0.9955131 0.09310346 0.2418445 -0.9396924 -0.2418457 0.0140044 -0.9977165 0.06607329 0.2418454 -0.9396927 -0.2418442 0.002798378 -0.9978055 0.06615406 0.2418445 -0.9396927 -0.2418449 -0.1081737 -0.9605878 0.2560653 0.241844 -0.9396925 -0.2418459 0.241846 -0.9396919 -0.2418465 0.07676959 -0.9907106 0.112246 0.241847 -0.9396922 -0.2418441 0.01745009 -0.9972178 0.07247149 0.2418603 -0.9396954 -0.2418186 0.1883618 -0.9740372 0.1255843 0.08075529 -0.9851521 0.1515057 0.2418265 -0.9396897 -0.2418742 0.2945063 -0.9471436 0.1272203 0.2380123 -0.9513158 0.1958273 0.2418679 -0.9396947 -0.2418137 0.4172478 -0.894021 0.1631893 0.3121104 -0.939795 -0.1391848 0.384836 -0.9141039 0.1277317 0.4422225 -0.8924155 0.08963114 0.5147308 -0.8046313 0.2960082 0.4367161 -0.8949818 0.09103125 0.3305865 -0.8944945 -0.3009852 0.3383241 -0.8900384 -0.3055624 0.3277879 -0.8947507 -0.3032762 0.3472997 -0.883412 -0.314589 0.3246339 -0.8953744 -0.3048238 0.3373047 -0.8886523 -0.3106811 0.3389178 -0.8866995 -0.3144816 0.3333093 -0.8887559 -0.3146711 0.337253 -0.8869883 -0.3154554 0.334311 -0.8876926 -0.3166039 0.3197325 -0.897605 -0.3034412 0.3341073 -0.8880162 -0.3159106 0.3342668 -0.8877208 -0.3165716 0.3347992 -0.8874239 -0.3168414 0.335972 -0.8865595 -0.3180172 0.3345452 -0.8875795 -0.3166734 0.3267654 -0.8922746 -0.3115614 0.3308746 -0.8900576 -0.313559 0.3338858 -0.8880044 -0.3161777 0.334405 -0.8874526 -0.3171767 0.3249773 -0.892614 -0.3124578 0.3306764 -0.8896273 -0.3149862 0.3356955 -0.8858467 -0.3202877 0.3227714 -0.8930293 -0.3135557 0.32928 -0.8896507 -0.3163801 0.3345561 -0.8853974 -0.3227131 0.3273319 -0.8886628 -0.3211419 0.3324614 -0.8860569 -0.3230674 0.3212711 -0.8916361 -0.319014 0.3232147 -0.8916282 -0.3170669 0.3322953 -0.8841602 -0.3283909 0.3205757 -0.8908397 -0.3219253 0.3323237 -0.8828758 -0.3317999 0.3195577 -0.8903022 -0.3244147 0.3307171 -0.882654 -0.3339881 0.3185827 -0.8897984 -0.3267477 0.3289119 -0.8824433 -0.3363196 0.3202165 -0.8873018 -0.3318991 0.326075 -0.8829061 -0.3378639 0.3190265 -0.887055 -0.3336996 0.3132792 -0.8902427 -0.330642 0.3254914 -0.8813083 -0.3425653 0.3267951 -0.8754454 -0.3560906 0.3031269 -0.8925622 -0.3338363 0.3254836 -0.8767254 -0.3541369 0.3498155 -0.8317488 -0.4310719 0.2906765 -0.893771 -0.3415853 0.322418 -0.8676224 -0.3785207 0.3118926 -0.8513557 -0.4218015 0.2727975 -0.8974227 -0.346719 0.3317344 -0.8094453 -0.4845106 0.270601 -0.8811803 -0.3876807 0.2581551 -0.8984305 -0.3552162 0.2739952 -0.8677048 -0.4147468 0.2581294 -0.8954871 -0.3625909 0.2634897 -0.8928103 -0.3653259 0.2581943 -0.8951321 -0.3634203 0.2732747 -0.8898869 -0.3652703 0.2597435 -0.9092622 -0.3252316 0.2811977 -0.8935915 -0.3498888 0.2651494 -0.9198735 -0.2890128 0.3102898 -0.8829389 -0.3523337 0.2822787 -0.8986463 -0.335788 0.2804881 -0.9142963 -0.2922137 0.3274114 -0.8838661 -0.3340397 0.3057625 -0.8924466 -0.3317353 0.3480574 -0.8747919 -0.3370386 0.3012077 -0.9046666 -0.3014167 0.7975827 0.2296347 -0.55779 0.7750385 0.3369848 -0.5345619 0.7749984 0.3370825 -0.5345587 0.7999183 0.2116908 -0.5615316 0.7546915 0.4066032 -0.5148929 0.7377436 0.455969 -0.497822 0.7542625 0.3389033 -0.5623457 0.7535932 0.3188048 -0.5748574 0.7682479 0.2476897 -0.5902923 0.7057529 0.45827 -0.5402792 0.7793422 0.2136297 -0.5890568 0.7809503 0.3447693 -0.5208172 0.7402745 0.4678292 -0.4828348 0.7844033 0.3360496 -0.5213273 0.5809794 -0.05939763 0.811748 0.5430227 0.06797361 0.8369624 0.7608026 0.354174 -0.5438201 0.7700247 0.3181022 -0.5530579 0.7706732 0.330295 -0.5449478 0.7994942 0.2785074 -0.5322057 0.711665 0.5136851 -0.4792289 0.7565228 0.3268843 -0.5664097 0.7129748 0.4651876 -0.5246593 0.7569197 0.3259325 -0.5664279 0.7288423 0.445375 -0.5200287 0.7476178 0.3408725 -0.5699768 0.715808 0.4435801 -0.5393103 0.697906 0.498865 -0.5138686 0.7424334 0.3415538 -0.5763103 0.6918177 0.4924954 -0.5280497 0.7447308 0.3383046 -0.5752618 0.7378756 0.3418005 -0.5819896 0.7035931 0.4513463 -0.5488563 0.740625 0.3383653 -0.5805028 0.7010958 0.4711212 -0.535266 0.7341143 0.3416619 -0.5868079 0.7007557 0.4488767 -0.5544829 0.7368855 0.3387412 -0.5850249 0.6890515 0.484875 -0.5386132 0.7312812 0.3412516 -0.5905719 0.6925811 0.4630028 -0.5531364 0.7336814 0.3393144 -0.5887082 0.6883397 0.4750812 -0.5481663 0.7297303 0.340637 -0.5928407 0.6901425 0.4649807 -0.5545235 0.7311669 0.3399624 -0.5914562 0.7290785 0.3405694 -0.5936809 0.6918565 0.4587267 -0.5575881 0.7296473 0.3400701 -0.5932682 0.6892505 0.4670674 -0.5538788 0.729227 0.3403189 -0.5936422 0.6921683 0.4581167 -0.5577026 0.7290469 0.3404534 -0.5937862 0.7300355 0.3401642 -0.5927365 0.6963692 0.4488188 -0.5600281 0.7292894 0.3406156 -0.5933954 0.6970615 0.4459475 -0.5614589 0.7306814 0.3402774 -0.591875 0.7005984 0.4389263 -0.5625883 0.730095 0.3405358 -0.5924497 0.7309017 0.3403257 -0.591575 0.6937446 0.4583207 -0.5555723 0.730697 0.340398 -0.5917863 0.6932154 0.4577796 -0.5566778 0.7307272 0.3404182 -0.5917373 0.69188 0.4628555 -0.5541362 0.7309055 0.3403549 -0.5915537 0.6920802 0.4622322 -0.5544063 0.730184 0.3404947 -0.5923635 0.6905165 0.465075 -0.5539785 0.7307113 0.3403042 -0.5918228 0.7290654 0.3407824 -0.593575 0.6931439 0.4553951 -0.558719 0.729153 0.3406292 -0.5935551 0.7301501 0.340272 -0.5925335 0.6895257 0.4674088 -0.5532478 0.72735 0.340917 -0.5955985 0.6906905 0.4575274 -0.5600136 0.7278194 0.3401071 -0.5954881 0.6862342 0.4706478 -0.5545931 0.7251697 0.3410672 -0.5981656 0.6873413 0.4608214 -0.5614317 0.7256806 0.3402036 -0.5980377 0.7225299 0.3413003 -0.6012192 0.6880983 0.4519538 -0.5676784 0.7231521 0.34028 -0.6010494 0.6813743 0.4748988 -0.5569562 0.7194885 0.3415801 -0.6046977 0.6716547 0.486961 -0.5583448 0.7202922 0.3403175 -0.6044529 0.7160984 0.341891 -0.608534 0.6801349 0.4567224 -0.5734292 0.717149 0.3403284 -0.6081725 0.6804865 0.4660777 -0.5654289 0.7123659 0.3421984 -0.6127274 0.6772548 0.4547536 -0.5783815 0.7137477 0.3402887 -0.6121827 0.6661975 0.4883601 -0.5636358 0.7137181 0.3209275 -0.622585 0.6680796 0.4688311 -0.5778123 0.7071618 0.3375048 -0.6212992 0.7054485 0.3374525 -0.6232722 0.6704626 0.4513394 -0.5888741 0.6583994 0.4909428 -0.5705132 0.6936643 0.3485286 -0.6303631 0.6887781 0.3665209 -0.6254976 0.6531696 0.4840642 -0.5822811 0.6801945 0.3449845 -0.6467775 0.6645664 0.3999006 -0.631214 0.6806714 0.3438836 -0.6468621 0.6944736 0.3398935 -0.6341757 0.6379255 0.498739 -0.5867798 0.6648452 0.3476076 -0.6611731 0.6305353 0.4576352 -0.6268934 0.6687941 0.3395804 -0.6613618 0.6406746 0.4645063 -0.6113673 0.6502883 0.3482719 -0.6751532 0.6205965 0.4454695 -0.6453037 0.6564692 0.3375042 -0.6746401 0.6389064 0.4355946 -0.6340789 0.6079807 0.483111 -0.6300503 0.6366665 0.3477532 -0.6882757 0.5949311 0.4783191 -0.6459628 0.644121 0.3369313 -0.6867208 0.6240075 0.3465356 -0.7003768 0.5936374 0.4464886 -0.6695092 0.6320759 0.3371228 -0.6977308 0.5940185 0.4805121 -0.6451746 0.6123901 0.3450156 -0.7112964 0.5864201 0.4325545 -0.6848418 0.6205843 0.3377134 -0.7076898 0.5609481 0.5217389 -0.6427485 0.6006389 0.3443458 -0.7215669 0.5355489 0.5347213 -0.6536517 0.6098725 0.3381912 -0.7167164 0.5813928 0.3404382 -0.7389751 0.5576103 0.4224588 -0.7145623 0.5775555 0.3464049 -0.7392114 0.5986228 0.3376941 -0.72637 0.5532528 0.4954224 -0.6696776 0.5400378 0.3515236 -0.7647158 0.5418348 0.3447396 -0.7665309 0.5508797 0.3377177 -0.7632026 0.4476054 0.6437268 -0.6206973 0.4819699 0.352119 -0.80232 0.3588594 0.6646538 -0.6553284 0.515673 0.3262087 -0.7922559 0.4142783 0.3373613 -0.8453171 0.4179961 0.3230569 -0.8490663 0.4186008 0.332812 -0.8449909 0.4704678 0.3267244 -0.819702 0.3668653 0.6512587 -0.664283 0.3347852 0.3324823 -0.8816884 0.1033434 0.8470286 -0.5214045 0.3669717 0.3110352 -0.8766921 0.2517951 0.3181408 -0.9139945 0.2553529 0.3045012 -0.9176459 0.3014588 0.2959676 -0.9063806 0.2024298 0.7126626 -0.6716653 0.1856606 0.301 -0.9353766 0.04809117 0.7081638 -0.7044084 0.2285866 0.2839121 -0.9312046 0.1477888 0.2872933 -0.9463726 0.1267734 0.3654798 -0.9221459 0.1706118 0.2761518 -0.9458498 0.09071832 0.6215385 -0.7781131 0.1373286 0.2793897 -0.9503065 0.09533494 0.4313697 -0.8971241 0.1401577 0.2773373 -0.9504944 0.1511663 0.2811333 -0.9476881 0.1075692 0.4379485 -0.8925413 0.1463522 0.2856062 -0.9471061 0.119293 0.3628351 -0.924186 0.1921895 0.2876755 -0.9382463 0.1931502 0.2839218 -0.9391919 0.187395 0.2923412 -0.9377738 0.2627538 0.2927904 -0.9193661 0.1957719 0.5160388 -0.8338928 0.2494945 0.304553 -0.9192388 0.2662191 0.02014535 -0.963702 0.358095 0.2973697 -0.8850645 0.3745578 0.2260359 -0.8992298 0.3237584 0.3225348 -0.8894672 0.4557041 0.3075168 -0.8353245 0.3695828 0.5677078 -0.7356061 0.400964 0.3369563 -0.8518735 0.4487598 -0.1796059 -0.8754178 0.5412634 0.3292171 -0.7737247 0.5637625 0.2252109 -0.7946394 0.5453472 0.3236699 -0.7731974 0.4732433 0.3409419 -0.8122804 0.6249188 0.3172932 -0.7133033 0.5060949 0.6294102 -0.58967 0.6014063 0.3470016 -0.7196528 0.5944393 0.04248952 -0.8030171 0.695388 0.3135457 -0.6466256 0.5968101 0.5843579 -0.5498576 0.6545829 0.3579095 -0.6658995 0.7045744 0.05596572 -0.7074198 0.7051746 0.3554063 -0.6135268 0.7476354 0.0801289 -0.6592576 0.6848697 0.5094707 -0.5209541 0.5750614 0.5708761 -0.5860076 0.6433477 0.1062167 -0.75817 0.6249626 0.4638845 -0.6278796 0.4049561 0.676724 -0.614862 0.5189181 0.103159 -0.8485766 0.460425 0.5816822 -0.6705629 0.3608084 0.469154 -0.806047 -0.01584178 0.9528104 -0.3031525 0.2875552 0.1384279 -0.9477076 0.3821045 0.3085134 -0.8711003 0.05844449 0.6832438 -0.7278477 0.1861334 0.1186966 -0.9753283 0.1974073 0.3302145 -0.9230324 0.1690487 0.1583994 -0.972796 0.1642845 0.1872735 -0.9684726 0.1992689 0.1562095 -0.9674143 0.3303894 -0.4594942 -0.8244441 0.3237945 0.1997065 -0.9248105 0.2305818 0.1411558 -0.9627602 0.4336663 -0.3822753 -0.8159653 0.4359375 0.2608799 -0.8613362 0.4266056 -0.2099679 -0.8797278 0.5134522 0.09734624 -0.8525788 0.5349648 -0.4227058 -0.7315275 0.5749861 0.2275095 -0.7858947 0.5215222 0.1699902 -0.8361327 0.6224628 -0.1771914 -0.7623276 0.6238202 0.2180798 -0.7505263 0.5947353 0.2044547 -0.7774884 0.6334604 0.2275686 -0.7395543 0.6413088 0.1273158 -0.7566463 0.6484425 0.1996882 -0.7346067 0.6508474 0.2518689 -0.7162122 0.6566101 0.1532034 -0.7385064 0.6632561 0.2492803 -0.7056563 0.6733667 0.149069 -0.7241241 0.6779858 0.2363352 -0.6960467 0.685088 0.1751257 -0.7070965 0.6902413 0.2393327 -0.6828518 0.6957373 0.1963093 -0.6909503 0.6985518 0.2645658 -0.6648536 0.7079357 0.195468 -0.6786895 0.705414 0.293455 -0.645194 0.7207759 0.1791958 -0.6696051 0.7187348 0.28761 -0.6330093 0.7306541 0.1748923 -0.6599677 0.7395369 0.211901 -0.6388921 0.7318098 0.2248037 -0.6433643 0.7411705 0.2235234 -0.6330115 0.744134 0.1861499 -0.6415705 0.7474367 0.2022404 -0.632801 0.7471348 0.2235699 -0.6259441 0.7481819 0.1978371 -0.6333122 0.750432 0.2183892 -0.6238253 0.7525944 0.1973391 -0.6282188 0.753129 0.2144515 -0.6219383 0.7539157 0.2189724 -0.6194047 0.7545943 0.2061953 -0.6229533 0.7563302 0.208702 -0.6200066 0.756412 0.2120665 -0.6187638 0.7564415 0.2080554 -0.6200881 0.7570934 0.2087822 -0.6190474 0.756528 0.2113382 -0.6188711 0.7566229 0.2115592 -0.6186795 0.75384 0.2254071 -0.6171848 0.7539247 0.2245973 -0.6173763 0.7526071 0.2282473 -0.6176453 0.7534233 0.2212112 -0.6192083 0.752963 0.2264361 -0.6178781 0.754494 0.217456 -0.6192348 0.756225 0.2158312 -0.6176897 0.7558811 0.2095097 -0.6202816 0.7577495 0.2212511 -0.6138921 0.7601415 0.1946591 -0.6199135 0.763828 0.2002442 -0.6135707 0.7636007 0.2266692 -0.6045951 0.7649531 0.1933714 -0.6143731 0.7755168 0.1673614 -0.6087395 0.7740997 0.2430495 -0.5845482 0.7708848 0.1989112 -0.6051207 0.7722086 0.3240861 -0.5464997 0.7529356 0.3357725 -0.5659902 0.7939442 0.1569296 -0.5873891 0.7977516 0.2778223 -0.5351701 0.8042508 0.1644982 -0.57107 0.5809791 -0.059381 0.8117495 0.6293075 -0.4144693 0.6574096 0.5854097 -0.1913355 0.7878364 0.8128702 0.1965168 -0.5482912 0.416397 -0.124607 0.9006035 0.2948132 0.2380869 0.9254186 0.2948133 0.2380782 0.9254209 0.4443855 0.3047884 0.8423928 0.3145684 0.4860796 0.8153364 0.6739152 -0.2980445 -0.6760236 0.4479047 0.2799957 0.8491076 0.4163872 -0.1246253 0.9006056 0.4767827 -0.4690172 0.7434387 -0.3328353 -0.314452 0.889011 -0.3993693 0.06218069 0.9146789 -0.3328414 -0.314461 0.8890056 -0.5233784 -0.3362101 0.7829673 -0.5480335 0.3933422 0.7382014 -0.5894533 0.04773485 0.8063908 0.04529243 -0.2380465 0.9701971 -0.04903239 0.1330198 0.9898998 0.0453062 -0.2380256 0.9702015 -0.3993601 0.06221449 0.9146808 -0.04903483 0.1330044 0.9899017 0.1329726 -0.574095 0.807919 0.4767819 -0.4690198 0.7434375 -0.2173874 -0.6449213 0.7326796 0.1329667 -0.574121 0.8079016 -0.5222179 -0.3499106 0.7777217 -0.3932327 -0.6703141 0.6293227 -0.2173867 -0.6449031 0.7326956 -0.8208196 -0.2809112 0.497337 -0.8289378 -0.2371023 0.506601 -0.813665 -0.3322194 0.4770529 -0.7909817 -0.2952142 0.5359072 -0.8175989 -0.06453102 0.5721606 -0.7900635 -0.3566827 0.4985751 -0.8120474 0.1951546 0.5499942 -0.8160958 0.1776813 0.5499246 -0.8241001 0.1384641 0.5492602 -0.8380079 0.03704816 0.544399 -0.8424718 -0.07951974 0.5328394 -0.762784 -0.3008742 0.5723942 -0.7910913 -0.06872886 0.6078248 -0.7423669 -0.4237998 0.518927 -0.7833594 0.2014085 0.588033 -0.7231194 -0.3541311 0.5930341 -0.7657848 -0.01062405 0.6430092 -0.7144897 -0.3958736 0.5768783 -0.7547029 0.1962628 0.6260228 -0.7032425 -0.3308603 0.6292706 -0.7347388 0.1147707 0.6685705 -0.6820416 -0.3138324 0.6605517 -0.7171021 -0.01594758 0.6967857 -0.6779124 -0.3960021 0.6193683 -0.7314726 0.1383435 0.6676893 -0.6529759 -0.3335307 0.6799851 -0.6942798 0.01732212 0.7194967 -0.6456259 -0.3875693 0.6579949 -0.6905579 0.1980702 0.6956278 -0.6233611 -0.3653611 0.6913265 -0.6734163 0.07581788 0.7353653 -0.6256379 -0.3515433 0.6964154 -0.6153441 -0.330173 0.7157775 -0.6585069 0.01318472 0.7524591 -0.6645388 0.156597 0.730661 -0.6011211 -0.332467 0.7267181 -0.6447713 0.0977267 0.7581026 -0.6001677 -0.3623639 0.7130857 -0.5883576 -0.3415229 0.7329376 -0.6363786 0.02931106 0.7708198 -0.5874515 -0.3504591 0.7294375 -0.6430894 0.1167737 0.7568355 -0.5813696 -0.3389836 0.7396618 -0.6292408 0.07330572 0.7737456 -0.576704 -0.3369907 0.7442108 -0.6247183 0.04213279 0.7797127 -0.5782356 -0.3459207 0.7389062 -0.6281123 0.08988761 0.7729134 -0.5731916 -0.3387519 0.7461223 -0.6219516 0.04850542 0.7815519 -0.5731382 -0.342876 0.7442772 -0.571781 -0.3394075 0.7469063 -0.6207759 0.06654566 0.7811588 -0.5717542 -0.3397496 0.7467713 -0.5720664 -0.339734 0.7465392 -0.6211543 0.0475648 0.7822434 -0.621432 0.04883545 0.7819447 -0.5722711 -0.3376863 0.7473111 -0.6208691 0.05006742 0.7823137 -0.5724999 -0.3388993 0.7465863 -0.5667343 -0.3327215 0.7537298 -0.6145657 0.03700482 0.7879973 -0.5671967 -0.3454763 0.7476189 -0.6187431 0.0885111 0.7805913 -0.5518383 -0.3299822 0.7658891 -0.6006205 0.06973183 0.7964876 -0.5510925 -0.3505142 0.7572562 -0.4275115 -0.6584437 0.6194238 -0.3176086 -0.7967643 0.5140929 -0.426444 -0.6837829 0.5921034 -0.4354255 -0.6745558 0.5961368 -0.4186252 -0.6979659 0.5810307 -0.4354497 -0.6736913 0.597096 -0.441342 -0.6672642 0.5999799 -0.4311066 -0.681768 0.5910495 -0.4323096 -0.6910843 0.5792332 -0.4654315 -0.6523892 0.598132 -0.4275484 -0.6992192 0.5729702 -0.4870278 -0.6410272 0.5932016 -0.4188603 -0.7360805 0.5317345 -0.4435992 -0.7395448 0.5062541 -0.5204852 -0.6679063 0.531974 -0.4803385 -0.683264 0.5499321 -0.5874933 -0.610125 0.5316005 -0.477042 -0.7347697 0.4822286 -0.6388923 -0.5794121 0.5060616 -0.5013937 -0.7461677 0.4379933 -0.6625622 -0.6001399 0.4481554 -0.5480273 -0.7270216 0.4136493 -0.639337 -0.6736676 0.3707025 -0.6251125 -0.6624767 0.4127457 -0.6843436 -0.6297894 0.3674769 -0.5582776 -0.774865 0.2964971 -0.7750561 -0.3368453 0.5346243 -0.7750449 -0.3370457 0.5345143 -0.7751247 -0.3363691 0.5348247 -0.7767177 -0.3292323 0.5369503 -0.7747802 -0.3380922 0.5342372 -0.6367051 0.6075914 0.4748045 -0.7423975 0.417652 0.5238442 -0.7935402 0.2733431 0.5436703 0.7750279 -0.3370205 -0.5345549 0.2418276 0.9396984 -0.2418394 0.2418539 0.9396901 -0.2418455 0.2418438 0.9396924 -0.2418465 0.2418428 0.9396924 -0.2418475 0.2418434 0.9396928 -0.2418454 0.4351911 0.8290241 -0.3511805 0.4080896 0.8483815 -0.3372116 0.77502 -0.3370478 -0.5345491 0.7750195 -0.3370757 -0.5345323 0.7750887 -0.3367546 -0.5346344 0.7750452 -0.3368787 -0.5346193 0.7743217 -0.3427763 -0.531912 0.7734489 -0.3495602 -0.5287574 0.7752447 -0.3361724 -0.5347747 0.7748462 -0.3377354 -0.534367 0.7751764 -0.3364291 -0.5347121 0.7741666 -0.3404836 -0.5336077 0.7750456 -0.3369459 -0.5345763 0.7750484 -0.3369341 -0.5345797 0.7749083 -0.3375362 -0.534403 0.09091073 0.9878378 -0.1261417 0.08429038 0.9917933 -0.09613126 0.1137776 0.983386 -0.1414449 0.1006747 0.9913916 -0.08371055 0.1414331 0.9800218 -0.1398357 0.1468476 0.9829576 -0.1105905 0.2418465 0.9396922 -0.2418448 0.1335244 0.9895607 -0.05423039 0.1609371 0.9788064 -0.1266379 0.24184 0.9396929 -0.2418484 0.1838444 0.9769092 -0.1088554 0.2418512 0.9396918 -0.2418417 0.1776321 0.9831198 -0.04384332 0.241846 0.9396929 -0.2418423 0.1908686 0.9741325 -0.1209746 0.2418349 0.9396947 -0.2418466 0.2018133 0.9766635 -0.07348382 0.2418453 0.9396934 -0.2418413 0.2058151 0.977246 -0.05128788 0.2088139 0.9735468 -0.0927543 0.2418437 0.9396935 -0.2418424 0.2104511 0.9761492 -0.05331832 0.241855 0.9396933 -0.2418317 0.2088708 0.976754 -0.04821443 0.2418415 0.939693 -0.2418466 0.20525 0.9769676 -0.05836802 0.241843 0.9396927 -0.241846 0.2086061 0.9768617 -0.04716587 0.2418352 0.9396938 -0.2418499 0.1537627 0.9856079 0.07024294 0.2418593 0.9396919 -0.241833 0.1795874 0.980494 -0.07987457 0.1831551 0.982972 -0.01484102 0.2418388 0.9396924 -0.2418517 0.1589 0.9839041 -0.08175277 0.1043594 0.9932696 0.05024635 0.24184 0.9396934 -0.2418466 0.1316935 0.9887689 -0.07065838 0.2418454 0.9396927 -0.2418439 0.2418518 0.9396924 -0.2418384 0.1374342 0.9852398 -0.1020513 0.1132386 0.9924873 -0.0463249 0.241842 0.9396926 -0.2418476 0.12678 0.9867514 -0.1012347 0.1064697 0.9918563 -0.06989407 0.2418427 0.9396931 -0.241845 0.1202837 0.9876877 -0.1000239 0.2418452 0.9396929 -0.2418435 0.1126167 0.9895955 -0.08954495 0.2418457 0.939693 -0.2418425 0.1166298 0.9880081 -0.1011804 0.1129181 0.9889118 -0.09645181 0.2418419 0.9396927 -0.241847 0.1146641 0.9878582 -0.1048241 0.2418418 0.9396928 -0.2418471 0.1116476 0.9885843 -0.1011725 0.2418465 0.9396926 -0.2418431 0.1144718 0.9872588 -0.1105279 0.1080067 0.9888031 -0.1029713 0.2418427 0.9396928 -0.2418459 0.1144044 0.9866004 -0.1163239 0.2418462 0.9396926 -0.2418435 0.1030005 0.9893129 -0.1032027 0.2418475 0.9396927 -0.2418417 0.1120701 0.9864538 -0.1197887 0.2418451 0.939693 -0.2418432 0.09932833 0.9895462 -0.1045574 0.2418443 0.9396924 -0.2418458 0.1035133 0.9876582 -0.1175432 0.2418428 0.9396926 -0.2418467 0.1008318 0.9887461 -0.1105175 0.2418426 0.939693 -0.2418453 0.107813 0.9860727 -0.1266379 0.241848 0.9396926 -0.2418415 0.09470713 0.9890924 -0.1128134 0.1107937 0.9861282 -0.1235961 0.2418482 0.9396926 -0.2418416 0.1061111 0.9858359 -0.1298772 0.2418422 0.9396933 -0.2418448 0.2418443 0.9396932 -0.241843 0.09516543 0.9882579 -0.1195403 0.09873008 0.9878973 -0.1196302 0.2418447 0.9396925 -0.2418451 0.09559088 0.9874877 -0.1254212 0.2418444 0.9396926 -0.2418453 0.2418463 0.9396924 -0.2418439 0.09348535 0.9882718 -0.1207447 0.2418429 0.939693 -0.2418453 0.09360444 0.9874595 -0.1271299 0.2418445 0.9396927 -0.2418447 0.2418453 0.9396926 -0.2418442 0.2418458 0.9396926 -0.2418438 0.0917955 0.988083 -0.1235538 0.1093727 0.9846794 -0.1358098 0.2418459 0.9396925 -0.2418442 0.09529876 0.986868 -0.1304208 0.2418439 0.9396929 -0.2418446 0.2418415 0.9396933 -0.2418454 0.2418442 0.9396929 -0.2418439 0.2418434 0.9396931 -0.2418447 0.09094798 0.9877703 -0.1266426 0.09200698 0.987685 -0.1265429 0.1060458 0.984975 -0.1363031 0.2418476 0.9396917 -0.2418456 0.09012794 0.9878299 -0.1267635 0.2418378 0.9396941 -0.2418461 0.2418504 0.9396916 -0.2418433 0.2418405 0.939693 -0.2418476 0.241847 0.9396924 -0.2418429 0.09098899 0.9876472 -0.1275698 0.09259372 0.9873762 -0.1285089 0.2418496 0.9396907 -0.2418476 0.08035463 0.9898521 -0.1172005 0.2418715 0.9396829 -0.2418558 0.2418264 0.9396981 -0.2418418 0.241829 0.9396973 -0.2418425 0.2419071 0.9396731 -0.2418578 0.2418318 0.9396956 -0.2418465 0.2418476 0.9396919 -0.2418451 0.2418503 0.9396914 -0.2418441 0.2418467 0.9396916 -0.2418467 0.09206002 0.9875701 -0.1273975 0.09127563 0.9876383 -0.1274341 0.08689427 0.9884174 -0.1244204 0.001137316 0.8454506 -0.5340525 0.1311855 0.8978103 -0.4203893 0.09773075 0.9867987 -0.1291402 0.07680839 0.9904398 -0.1145839 0.04526495 0.8249546 -0.5633836 0.1555532 0.8016406 -0.5772137 0.04590213 0.8018507 -0.5957586 0.2616954 0.7747159 -0.5756134 0.1993356 0.747958 -0.6331067 0.3820041 0.7082902 -0.5936311 0.3378028 0.8562561 -0.3907873 0.2296258 0.8584141 -0.458691 0.3741422 0.8169013 -0.4389644 0.5062713 0.5876244 -0.631179 0.3441681 0.8569316 -0.3836879 0.3575972 0.8375408 -0.4130977 0.3501842 0.8521424 -0.3888758 0.3651562 0.8374301 -0.4066594 0.3863158 0.81428 -0.433253 0.3488936 0.8556108 -0.3823655 0.3521397 0.8510484 -0.3895051 0.349258 0.8553144 -0.382696 0.3493121 0.8552644 -0.3827585 0.3511128 0.8535398 -0.3849541 0.349233 0.8555779 -0.3821293 0.3495731 0.855035 -0.3830324 0.3508464 0.8542057 -0.383718 0.3569428 0.8484129 -0.3908804 0.349835 0.856072 -0.3804684 0.353313 0.8519645 -0.3864277 0.3535875 0.8530306 -0.3838157 0.3720138 0.8351189 -0.4051941 0.3522794 0.8562552 -0.3777914 0.3538287 0.8531776 -0.3832665 0.374874 0.8353148 -0.4021427 0.3539966 0.8576623 -0.3729634 0.3616413 0.848247 -0.3869013 0.3949155 0.8197388 -0.4148133 0.3603356 0.8564394 -0.3696887 0.3611255 0.8524497 -0.3780446 0.3538579 0.8647978 -0.3562434 0.3897982 0.8300777 -0.3987836 0.3661359 0.8579594 -0.3603472 0.3971719 0.8296905 -0.3922605 0.3844604 0.847407 -0.3661853 0.3669727 0.8655692 -0.3407654 0.3891436 0.8435961 -0.3700175 0.3635622 0.8717396 -0.3284701 0.4247161 0.8207629 -0.382053 0.3774428 0.8659299 -0.3281803 0.463853 0.7961001 -0.3886709 -0.2418318 -0.9396899 0.2418684 -0.1624381 -0.9845098 0.06598824 -0.2418408 -0.9396932 0.2418466 -0.2418472 -0.9396924 0.2418431 0.2537804 -0.8490042 -0.4634517 -0.1330803 -0.9873857 0.08578586 -0.2418053 -0.9396833 0.2419204 -0.1883251 -0.9740504 -0.1255367 -0.09965419 -0.9297395 -0.3544763 -0.080778 -0.9851589 -0.1514489 -0.2418415 -0.9396893 0.2418608 -0.2945234 -0.9471288 -0.1272902 -0.2380414 -0.9513014 -0.1958616 -0.2419583 -0.9397033 0.2416898 -0.4173284 -0.8939621 -0.1633058 -0.3467488 -0.9341042 0.08493912 -0.3848193 -0.9141097 -0.127741 -0.441871 -0.892566 -0.08986574 -0.4941734 -0.8380475 -0.2312339 -0.3890422 -0.8506629 0.3535798 -0.3770879 -0.8592228 0.3457468 -0.2418472 -0.9396924 0.2418429 -0.3891472 -0.8508011 0.3531316 -0.2418473 -0.9396934 0.2418393 -0.3887878 -0.851306 0.35231 -0.2418434 -0.9396929 0.2418453 -0.3884282 -0.8513827 0.352521 -0.2418405 -0.9396929 0.2418478 -0.3848061 -0.8546166 0.3486471 -0.2418473 -0.9396934 0.2418392 -0.3844653 -0.854784 0.3486127 -0.2418473 -0.9396924 0.2418432 -0.3826867 -0.8565337 0.3462672 -0.2418495 -0.939693 0.2418386 -0.2418416 -0.9396928 0.2418472 -0.3816457 -0.8571477 0.3458965 -0.2418432 -0.9396934 0.2418433 -0.3837341 -0.85579 0.3469462 -0.2418381 -0.9396924 0.2418522 -0.3831009 -0.8561982 0.3466386 -0.2418426 -0.9396923 0.2418482 -0.38345 -0.8558108 0.3472089 -0.2418507 -0.939693 0.2418372 -0.3846577 -0.8550438 0.3477623 -0.2418476 -0.9396924 0.2418431 -0.3822702 -0.8566029 0.346556 -0.2418438 -0.9396922 0.2418474 -0.3831786 -0.8560299 0.3469684 -0.2418459 -0.9396925 0.2418441 -0.3822581 -0.8562617 0.3474113 -0.2418448 -0.9396923 0.241846 -0.2418476 -0.9396923 0.2418431 -0.384353 -0.8549103 0.3484266 -0.241842 -0.9396922 0.2418491 -0.3812984 -0.8565697 0.3477066 -0.2418441 -0.9396926 0.2418458 -0.3843014 -0.8545736 0.3493085 -0.2418501 -0.9396933 0.241837 -0.3807802 -0.8565315 0.3483681 -0.2418431 -0.9396922 0.2418481 -0.383665 -0.8545534 0.3500567 -0.2418435 -0.9396932 0.2418438 -0.3810478 -0.8557636 0.3499588 -0.3834627 -0.854057 0.3514871 -0.2418438 -0.9396932 0.2418434 -0.3817122 -0.8546354 0.3519861 -0.2418434 -0.9396932 0.2418439 -0.2418447 -0.9396924 0.2418459 -0.3743043 -0.8587028 0.3500369 -0.2418476 -0.9396937 0.241838 -0.2418441 -0.9396932 0.2418431 -0.3819561 -0.8544351 0.3522075 -0.241845 -0.9396921 0.2418466 -0.3635711 -0.8641513 0.3479349 -0.2418463 -0.9396923 0.2418445 -0.3450243 -0.8805401 0.3249728 -0.3691713 -0.8623085 0.3466075 -0.3808374 -0.8520498 0.3591296 -0.2418446 -0.9396926 0.241845 -0.3633396 -0.8614816 0.3547307 -0.2418414 -0.9396924 0.2418488 -0.3589759 -0.8677975 0.3436042 -0.3770033 -0.8521586 0.362897 -0.2418467 -0.9396927 0.2418427 -0.3585197 -0.8625063 0.3571364 -0.2418448 -0.9396925 0.2418449 -0.35997 -0.8642935 0.3513094 -0.3743513 -0.8506565 0.3691131 -0.2418464 -0.9396931 0.241841 -0.3634002 -0.855507 0.3688468 -0.241844 -0.9396928 0.2418445 -0.3672727 -0.8546088 0.3670893 -0.2418428 -0.9396922 0.2418487 -0.3563072 -0.8589714 0.3677138 -0.2418459 -0.9396932 0.2418415 -0.3589093 -0.8596268 0.3636287 -0.3654925 -0.851383 0.3762475 -0.2418449 -0.9396924 0.2418455 -0.3554196 -0.8573021 0.3724379 -0.3629978 -0.8509021 0.3797345 -0.2418457 -0.9396923 0.2418445 -0.358875 -0.851655 0.3819588 -0.2418453 -0.9396924 0.2418456 -0.3500706 -0.8569612 0.3782435 -0.2418458 -0.9396925 0.2418445 -0.3570124 -0.8535878 0.379381 -0.2418456 -0.9396924 0.2418451 -0.3366975 -0.8640303 0.3742813 -0.364031 -0.8410014 0.4002475 -0.2418462 -0.9396924 0.2418445 -0.3736484 -0.8055735 0.4598241 -0.241846 -0.9396927 0.2418435 -0.3189617 -0.8607031 0.396804 -0.2418453 -0.9396923 0.2418453 -0.341765 -0.8506116 0.3995705 -0.2418454 -0.9396925 0.2418447 -0.4128294 -0.4903861 0.7675242 -0.2418391 -0.9396916 0.2418545 -0.2849767 -0.863204 0.4167338 -0.3135855 -0.8571933 0.4085143 -0.2418497 -0.9396921 0.2418418 -0.2664548 -0.8748704 0.4044795 -0.2936209 -0.8182377 0.4942407 -0.2418453 -0.939693 0.2418423 -0.2657344 -0.8631305 0.4294075 -0.2418441 -0.9396924 0.2418464 -0.2654257 -0.863996 0.4278554 -0.2418438 -0.9396926 0.2418454 -0.2713059 -0.8759819 0.3988096 -0.2418389 -0.9396922 0.241852 -0.2993072 -0.8496439 0.4341895 -0.2713046 -0.8759887 0.3987953 -0.2418484 -0.9396876 0.2418605 -0.2822442 -0.9011323 0.3290879 -0.2418478 -0.9396917 0.2418455 -0.2418501 -0.9396908 0.2418466 -0.337519 -0.8543717 0.3951327 -0.3054913 -0.8627641 0.402881 -0.2418517 -0.9396911 0.2418439 -0.3745121 -0.8341067 0.4049775 -0.3145786 -0.8833589 0.3474439 -0.241896 -0.9396641 0.2419043 -0.3771666 -0.8480417 0.3722506 -0.2418467 -0.939692 0.2418453 -0.3411986 -0.8752221 0.3428847 -0.2418561 -0.9396879 0.241852 -0.372877 -0.8625844 0.3419224 -0.3821428 -0.8552708 0.3499698 0.7747937 -0.3379325 -0.5343186 0.7749446 -0.337323 -0.5344849 0.7757581 -0.3342725 -0.5352208 0.7750912 -0.3367832 -0.5346127 0.7751067 -0.3367242 -0.5346275 0.7750065 -0.3371099 -0.5345295 -0.004484117 -0.9950923 0.09885036 0.7751455 -0.3365152 -0.5347026 -0.0984674 -0.9843121 0.1464031 -0.05169129 -0.9902844 0.1290926 -0.1205314 -0.9810887 0.1514505 -0.01713085 -0.9960972 0.08658456 -0.1290063 -0.9805858 0.1476781 -0.02573484 -0.9970814 0.07187694 -0.1296362 -0.9819171 0.137961 -0.04235947 -0.9969083 0.0661782 -0.1262894 -0.9840401 0.1253635 -0.05835729 -0.9962644 0.06365334 -0.1188895 -0.9868391 0.1096077 -0.07805448 -0.9945594 0.06898599 -0.1057007 -0.99048 0.08818495 -0.1236462 -0.9869319 0.1033295 -0.1006402 -0.9915226 0.08218508 -0.08930331 -0.9942963 0.05830866 -0.1226613 -0.9878798 0.09512025 -0.1178189 -0.9886004 0.09374451 -0.1017167 -0.9925647 0.0668509 -0.1246392 -0.9877762 0.09361237 -0.1201832 -0.9885962 0.09073996 -0.1182447 -0.9893921 0.08438938 -0.125089 -0.9878435 0.09229278 -0.1201868 -0.9889316 0.08700227 -0.1249303 -0.9879244 0.09164029 -0.123843 -0.9882062 0.09006279 -0.1236308 -0.9882591 0.08977276 -0.1254217 -0.9878703 0.09155088 -0.1250886 -0.9878968 0.09172135 -0.1171043 -0.9899608 0.07914668 -0.07453626 -0.9970101 0.02038049 -0.1310921 -0.9872242 0.09057158 -0.1220854 -0.9888805 0.08491522 -0.1076541 -0.9928185 0.0521717 -0.8000582 0.2265921 0.5554843 -0.77502 0.3370591 0.534542 -0.7750326 0.3370286 0.534543 -0.8072828 0.1476628 0.5713933 -0.7547795 0.4063366 0.5149744 -0.7482236 0.3392956 0.5701229 -0.7434077 0.357401 0.5653403 -0.6811472 0.515722 0.519682 -0.7434347 0.3492991 0.5703465 -0.7787973 0.1502938 0.6090046 -0.7434657 0.3400123 0.575891 -0.6808731 0.5191459 0.516623 -0.7436439 0.3396711 0.5758623 -0.5809995 -0.0593962 -0.8117338 -0.5215038 0.1281273 -0.8435741 -0.7458588 0.339182 0.5732803 -0.6828107 0.5195212 0.5136802 -0.6873794 0.5062978 0.5207419 -0.7477529 0.3388269 0.5710184 -0.6889585 0.509643 0.5153641 -0.7459159 0.3399034 0.5727784 -0.7493021 0.3387299 0.5690417 -0.6867178 0.5179924 0.5100026 -0.7478816 0.3398516 0.5702404 -0.6885494 0.5104831 0.5150793 -0.7505203 0.3386748 0.5674668 -0.6933158 0.5057356 0.5133661 -0.7494782 0.3396801 0.5682429 -0.7516027 0.3385714 0.5660943 -0.6898434 0.5159018 0.5078991 -0.7507468 0.3395273 0.5666573 -0.6889629 0.5148026 0.5102044 -0.7523306 0.3388019 0.5649885 -0.690155 0.5168989 0.5064601 -0.7517272 0.3393064 0.5654887 -0.6917533 0.5121012 0.509146 -0.7527263 0.3388844 0.5644116 -0.6910998 0.5156918 0.5064019 -0.7523589 0.3390704 0.5647897 -0.6917476 0.5140298 0.5072067 -0.752776 0.3389461 0.5643084 -0.6911797 0.5156577 0.5063276 -0.7527315 0.338971 0.5643527 -0.7524595 0.3390561 0.5646641 -0.6913004 0.5147691 0.5070667 -0.75277 0.338867 0.5643639 -0.6906576 0.5166907 0.5059871 -0.751888 0.3392094 0.565333 -0.6888951 0.518966 0.5060611 -0.7524395 0.3388454 0.5648174 -0.751004 0.3393255 0.5664373 -0.689993 0.5146929 0.5089213 -0.7518337 0.3387409 0.565686 -0.6901132 0.5164894 0.5069345 -0.7498515 0.3394852 0.5678666 -0.68909 0.514306 0.5105336 -0.7509174 0.3386994 0.5669264 -0.6864114 0.5215512 0.5067778 -0.748436 0.3397347 0.5695822 -0.6858537 0.5186069 0.5105406 -0.7497333 0.3387523 0.5684601 -0.7467513 0.3400177 0.5716211 -0.6869572 0.5126537 0.5150495 -0.7481917 0.3384018 0.5706956 -0.6836411 0.5229608 0.5090646 -0.7449026 0.3401995 0.5739202 -0.6797254 0.5248338 0.5123697 -0.7461538 0.338474 0.5733147 -0.7429717 0.3399613 0.5765581 -0.6831836 0.5128654 0.5198358 -0.7437145 0.3387966 0.5762861 -0.6809083 0.5224847 0.5131993 -0.7401282 0.3408631 0.5796747 -0.6800509 0.5142253 0.5225927 -0.7410614 0.3392708 0.5794163 -0.6745316 0.5283139 0.5156468 -0.7367371 0.3414288 0.583648 -0.6748676 0.5187944 0.5247914 -0.7382985 0.3390914 0.5830373 -0.7331565 0.3415642 0.5880607 -0.6754915 0.5095888 0.5329452 -0.7351342 0.3385048 0.5873604 -0.6696408 0.5290881 0.5211976 -0.7293043 0.3416447 0.5927851 -0.6691665 0.5155193 0.535216 -0.7310728 0.338866 0.5922014 -0.661926 0.5341855 0.5258324 -0.7252178 0.341808 0.597684 -0.663943 0.5184385 0.5388889 -0.7268381 0.3392691 0.5971624 -0.720936 0.3419191 0.6027791 -0.6636667 0.5096176 0.5475732 -0.7224223 0.3396245 0.6022967 -0.6548479 0.5360201 0.5327821 -0.7169587 0.3400031 0.6085788 -0.6475693 0.5358774 0.5417466 -0.7172924 0.3393936 0.6085258 -0.7118104 0.3418743 0.6135535 -0.6541113 0.5111091 0.5575893 -0.6499698 0.5311737 0.5435016 -0.7067719 0.3430114 0.6187219 -0.6299439 0.5538976 0.544397 -0.7113645 0.3387511 0.6157989 -0.6936991 0.3549806 0.6267139 -0.6413605 0.5074102 0.5754925 -0.6957753 0.3505157 0.6269253 -0.705142 0.338699 0.6229429 -0.6448791 0.5246276 0.5557849 -0.6779755 0.3553912 0.6434643 -0.6456071 0.4576258 0.6113675 -0.6851485 0.343077 0.6425494 -0.692018 0.3407382 0.6364028 -0.6712772 0.4347181 0.6003391 -0.6152669 0.5479221 0.56677 -0.6622712 0.3539201 0.6604073 -0.6145945 0.4967898 0.612759 -0.6775088 0.3252307 0.6597021 -0.610885 0.5336598 0.5848305 -0.6465563 0.3518292 0.6768909 -0.6051716 0.4799386 0.6351585 -0.6585971 0.3295366 0.6765024 -0.6144878 0.4970302 0.612671 -0.5850213 0.5356312 0.6089739 -0.6310926 0.3500869 0.6922148 -0.5889763 0.4810439 0.6493872 -0.6412427 0.3326632 0.6914789 -0.5647937 0.5493977 0.6157681 -0.6163311 0.3483986 0.7062255 -0.5695579 0.4923004 0.658213 -0.6256291 0.3344083 0.7048116 -0.548102 0.5530045 0.6275112 -0.6019824 0.3475469 0.7189077 -0.5502494 0.5046305 0.665262 -0.6117251 0.3356468 0.7163335 -0.5350194 0.5468884 0.6439467 -0.5778908 0.3525167 0.7360532 -0.5155078 0.5342152 0.6699745 -0.5984901 0.3343943 0.7280041 -0.5320146 0.3510759 0.7705232 -0.4998502 0.455959 0.736377 -0.5740025 0.3299944 0.7494164 -0.4983917 0.5680649 0.6549107 -0.4637009 0.3428602 0.8169628 -0.4538966 0.3783657 0.8067325 -0.4668594 0.3384435 0.8170056 -0.5291046 0.3308803 0.7813876 -0.3658635 0.6953236 0.6186025 -0.3683444 0.347715 0.8622161 -0.1945889 0.7630605 0.6163391 -0.4014598 0.3139964 0.8603699 -0.2632209 0.3301216 0.9064956 -0.2402181 0.4109684 0.8794317 -0.3178563 0.2877306 0.9034259 -0.2838725 0.6210449 0.7305612 -0.1877676 0.2972103 0.9361674 0.01374161 0.8323576 0.5540688 -0.2180979 0.269232 0.9380552 -0.1512429 0.2726204 0.9501599 -0.1019815 0.4495313 0.8874241 -0.1490083 0.2756698 0.9496329 -0.1530517 0.5231162 0.838406 -0.1371957 0.2796064 0.9502618 -0.06735217 0.5212815 0.8507227 -0.1491737 0.2883098 0.945846 -0.09413444 0.4811865 0.8715494 -0.1468312 0.2909546 0.9454026 -0.09246927 0.4575654 0.8843548 -0.1927908 0.2840925 0.9392141 -0.1936552 0.2807016 0.9400554 -0.2640962 0.2858498 0.9211639 -0.1811197 0.5553155 0.8116776 -0.2067029 0.3170846 0.9255978 -0.1952894 0.2757293 0.9411883 -0.3574904 0.2979834 0.8851025 -0.3841207 0.1768082 0.9061954 -0.3051692 0.3369204 0.8907055 -0.4543283 0.3107795 0.8348664 -0.3536953 0.601942 0.7159368 -0.4148093 0.3477848 0.8408204 -0.4045464 0.09458547 0.909613 -0.5430518 0.3197067 0.7764549 -0.5611313 0.2363258 0.7932729 -0.511858 0.3563753 0.7816636 -0.6220179 0.326745 0.7115697 -0.5114696 0.6185143 0.5965223 -0.5989811 0.3601763 0.7151886 -0.5524477 0.2698782 0.788649 -0.6900874 0.3330626 0.642533 -0.5852824 0.6049729 0.5398633 -0.6759532 0.357873 0.644216 -0.6831597 0.2256469 0.6945331 -0.7203341 0.07285344 0.6897907 -0.7621886 0.2469799 0.5983892 -0.6504135 -0.002620339 0.7595757 -0.6333511 0.4280158 0.6447239 -0.417393 0.6094212 0.6740839 -0.4680628 0.07747346 0.8802926 -0.555025 0.257557 0.7909563 -0.1033563 0.8144283 0.5709852 -0.2568283 0.09982502 0.9612879 -0.3965053 0.1433266 0.9067751 -0.2064622 0.0300824 0.9779921 -0.179426 0.3363787 0.9244759 -0.1815275 0.1399491 0.9733766 -0.1898601 0.07612955 0.9788552 -0.2766477 -0.01368594 0.960874 -0.3272234 0.248477 0.911693 -0.302895 -0.1330443 0.9436917 -0.4664906 -0.2317366 0.8536303 -0.4916996 0.2298424 0.8398832 -0.4541776 -0.09962862 0.885323 -0.5785079 -0.1664245 0.7985183 -0.6065109 0.1595557 0.7789008 -0.5526798 0.1247949 0.8239972 -0.6281933 0.1839435 0.7560013 -0.6249579 0.04579734 0.7793139 -0.6437668 0.1673982 0.7466875 -0.6465532 0.1055733 0.7555284 -0.658235 0.1582098 0.7360002 -0.6600261 0.1307446 0.7397779 -0.6714099 0.1719138 0.7208707 -0.673448 0.1454609 0.7247819 -0.6824284 0.2098991 0.7001671 -0.6885155 0.1351891 0.7125098 -0.6953978 0.239076 0.6776906 -0.7033721 0.1142151 0.7015858 -0.718657 0.1595538 0.6768124 -0.7132133 0.138444 0.687139 -0.7251153 0.1568974 0.6705155 -0.7260294 0.1176264 0.6775289 -0.7324119 0.1463058 0.6649566 -0.7365546 0.1659269 0.6557101 -0.7354639 0.1248706 0.665958 -0.7434363 0.1593011 0.649558 -0.744634 0.1235145 0.6559454 -0.7511903 0.1415736 0.6447249 -0.7547852 0.1573607 0.6368178 -0.751399 0.1399823 0.644829 -0.759073 0.1572754 0.631722 -0.7597098 0.1271429 0.6377112 -0.7645927 0.142236 0.6286231 -0.7669824 0.1583847 0.6218135 -0.7652245 0.1374038 0.628929 -0.7707055 0.1539575 0.6183123 -0.7711027 0.1324341 0.6227857 -0.7742672 0.1456832 0.6158627 -0.7758502 0.1554968 0.6114551 -0.775308 0.1379625 0.6163311 -0.7786312 0.150901 0.6090667 -0.7790899 0.137929 0.6115508 -0.7808029 0.1490696 0.6067331 -0.7820605 0.1529683 0.6041376 -0.7817238 0.1422945 0.6071739 -0.7842236 0.141861 0.6040436 -0.7843706 0.1505233 0.601752 -0.783412 0.148391 0.6035279 -0.78498 0.1507273 0.6009057 -0.7850404 0.1460468 0.6019816 -0.7855153 0.1485393 0.6007511 -0.7854457 0.1491694 0.6006858 -0.7854386 0.1491327 0.6007043 -0.7851629 0.148494 0.6012228 -0.7851186 0.1513239 0.6005746 -0.7843495 0.1511779 0.6016154 -0.7837859 0.1473208 0.6033045 -0.7840873 0.1530823 0.6014757 -0.7823634 0.1495285 0.6046063 -0.7820718 0.1568404 0.6031291 -0.7807073 0.1507936 0.6064301 -0.7792887 0.1451019 0.6096349 -0.7794331 0.1594653 0.6058506 -0.7768862 0.1461127 0.6124531 -0.7762505 0.1606408 0.6096144 -0.5810006 -0.05945128 -0.811729 -0.6293091 -0.4145463 -0.6573595 -0.5999819 -0.2475736 -0.7607424 -0.4163799 -0.1246898 -0.9005999 -0.2947773 0.2380847 -0.9254307 -0.2947765 0.2381625 -0.9254109 -0.444396 0.3048908 -0.8423503 -0.3119277 0.4892374 -0.8144618 -0.41413 0.3382571 -0.8450316 -0.4164332 -0.1245918 -0.9005888 -0.4768265 -0.4690765 -0.7433732 0.3328387 -0.3144953 -0.8889944 0.3728795 -0.1293825 -0.918815 0.3327752 -0.3144016 -0.8890513 0.5158378 -0.3355619 -0.788232 0.51428 0.5131354 -0.687174 0.5707476 -0.1478844 -0.8076989 -0.04529792 -0.2380025 -0.9702076 0.0490418 0.1331239 -0.9898853 -0.04522705 -0.2381096 -0.9701848 0.3389162 0.2531607 -0.9061156 0.3993687 0.06224483 -0.914675 0.04906588 0.1329707 -0.9899047 -0.1329224 -0.5742379 -0.8078259 -0.4768018 -0.4691554 -0.7433394 0.217364 -0.6448163 -0.7327787 -0.132982 -0.5739764 -0.8080018 0.5162943 -0.3430922 -0.7846833 0.4610685 -0.5126283 -0.7243122 0.2057062 -0.473114 -0.8566492 0.8320193 -0.3379794 -0.4399023 0.8613339 -0.1837353 -0.473651 0.8335303 -0.3288237 -0.4439619 0.8158401 -0.3237058 -0.4791862 0.8345601 -0.2318679 -0.4997466 0.8655639 -0.02893233 -0.499962 0.8315136 0.2025536 -0.5172594 0.7943369 -0.3170535 -0.5181756 0.8254172 -0.009020566 -0.5644512 0.8055542 -0.3513479 -0.4771134 0.7700563 -0.3084712 -0.5584433 0.7713983 -0.3025461 -0.5598308 0.775013 -0.367672 -0.5139767 0.8188245 0.07262992 -0.5694307 0.7429321 -0.3021711 -0.597281 0.7302356 -0.3537463 -0.5844823 0.7400279 -0.3841961 -0.5520436 0.77506 0.1508552 -0.6136162 0.713078 -0.3073252 -0.6301357 0.720161 -0.274088 -0.6373727 0.7046604 -0.3919803 -0.5914433 0.7479881 0.1040343 -0.6555079 0.6829376 -0.3248981 -0.6542457 0.7204539 0.00158739 -0.6935011 0.6758772 -0.3807135 -0.6310684 0.6565817 -0.3425549 -0.6719797 0.685341 -0.1987746 -0.7005686 0.654199 -0.3598543 -0.6652282 0.7201407 -0.07494139 -0.689769 0.6388983 -0.341338 -0.6894181 0.6646898 -0.2174138 -0.7147857 0.6928277 0.04377174 -0.7197735 0.6260452 -0.3343279 -0.7044801 0.6680261 -0.04377341 -0.7428494 0.634231 -0.3527458 -0.6879835 0.6143292 -0.3338449 -0.7149457 0.6426329 -0.1908403 -0.7420263 0.6171861 -0.3531137 -0.7031302 0.6682173 -0.0327804 -0.7432437 0.6042155 -0.3358418 -0.7225884 0.6477198 -0.04329216 -0.7606477 0.6048623 -0.3501239 -0.7152306 0.5958747 -0.3385164 -0.7282445 0.628421 -0.1713734 -0.7587609 0.5958272 -0.3460292 -0.724744 0.6473044 -0.0567454 -0.7601165 0.5892 -0.3407593 -0.7326161 0.6296052 -0.1104496 -0.7690242 0.5891427 -0.3423377 -0.731926 0.5847792 -0.3395733 -0.7366976 0.632676 0.03512167 -0.7736198 0.5813511 -0.3387475 -0.7397845 0.6165744 -0.153999 -0.7720884 0.5835954 -0.3417987 -0.7366071 0.6256151 -0.1356664 -0.7682449 0.578649 -0.3388704 -0.7418439 0.6189169 -0.1108386 -0.7775967 0.5795897 -0.3414632 -0.739918 0.5766533 -0.3391712 -0.743259 0.6221533 -0.04839646 -0.7813982 0.5770038 -0.340763 -0.7422581 0.5752609 -0.3394612 -0.744205 0.61111 -0.1516991 -0.7768733 0.5753492 -0.3400983 -0.7438458 0.6163749 -0.1329815 -0.776143 0.5743798 -0.3395643 -0.7448382 0.6111913 -0.1444118 -0.7781969 0.5743868 -0.3396527 -0.7447925 0.5739891 -0.3394189 -0.7452057 0.6119283 -0.1348257 -0.7793368 0.5739088 -0.3394766 -0.7452412 0.6121319 -0.1325522 -0.7795668 0.5739305 -0.3395023 -0.7452127 0.573746 -0.3391485 -0.7455158 0.6095219 -0.1519528 -0.7780703 0.5738899 -0.3394988 -0.7452456 0.610458 -0.1490386 -0.7779 0.5719482 -0.3386715 -0.7471123 0.6097492 -0.1349292 -0.7810249 0.5723307 -0.3403869 -0.746039 0.5679651 -0.3390997 -0.7499514 0.613909 -0.04854112 -0.7878829 0.568139 -0.3405175 -0.7491769 0.5616406 -0.3412325 -0.7537375 0.6101344 0.1390058 -0.7800087 0.5615005 -0.3389581 -0.7548674 0.5551403 -0.3366363 -0.7605888 0.5894823 -0.1614152 -0.7914897 0.6091328 -0.1019251 -0.7864912 0.5459234 -0.3342332 -0.7682811 0.5895708 -0.07723951 -0.8040152 0.5505207 -0.3425236 -0.7613176 0.533544 -0.3327069 -0.7775839 0.5823552 0.1728159 -0.7943532 0.5361504 -0.3439373 -0.7708761 0.3257609 -0.7867883 -0.5242559 0.4970885 -0.5069341 -0.7042164 0.3812056 -0.703305 -0.6000369 0.5005117 -0.523092 -0.689828 0.4590568 -0.6261163 -0.6302739 0.4047258 -0.722742 -0.5602152 0.5159978 -0.5155265 -0.6840897 0.5038408 -0.5294634 -0.6825051 0.5158324 -0.5160306 -0.6838344 0.5108363 -0.52926 -0.6774438 0.5184544 -0.5134055 -0.6838274 0.5140702 -0.521035 -0.6813621 0.5130513 -0.5307905 -0.6745665 0.4837726 -0.600089 -0.6370694 0.5276305 -0.5119566 -0.6778692 0.5169194 -0.5239365 -0.6769673 0.4855079 -0.6150923 -0.6212435 0.5462711 -0.498337 -0.673237 0.5162237 -0.5480624 -0.6581343 0.5506001 -0.5124239 -0.6589851 0.4968093 -0.6186724 -0.6086255 0.5586415 -0.5241177 -0.6428222 0.6127573 -0.4249459 -0.6662953 0.5052946 -0.6393697 -0.5795548 0.6424831 -0.4002038 -0.6534926 0.5080588 -0.6750268 -0.5349907 0.6708706 -0.3974012 -0.626103 0.5458375 -0.6598179 -0.5164319 0.6986789 -0.4109776 -0.5856153 0.5884556 -0.6417658 -0.4917894 0.6287032 -0.6332929 -0.4513007 0.7252427 -0.5044358 -0.4685804 0.6847215 -0.5255957 -0.5048817 0.8020181 -0.3638408 -0.473695 0.6071673 -0.7077682 -0.3611261 0.7817569 -0.4803814 -0.3976051 0.585021 -0.7648478 -0.2697374 0.7747682 -0.3354216 -0.5359353 0.7749286 -0.3374186 -0.5344477 0.6310452 -0.7143664 -0.3024278 0.7774755 -0.3247044 -0.5386081 0.7752921 -0.3358908 -0.5348828 0.3716725 -0.9189808 -0.1316581 0.4811565 -0.8524034 -0.2046874 0.1763988 -0.9842346 -0.01287555 0.592065 0.6794896 -0.4333048 0.6686863 0.5788081 -0.4667333 0.6015931 0.6679592 -0.4380826 0.7595357 0.413598 -0.5020378 0.8066573 0.2857792 -0.5173338 0.8301896 0.2039982 -0.5188159 0.7885028 0.3408513 -0.5119413 0.8564215 0.03725111 -0.5149316 0.4975426 0.5939201 -0.6322266 0.3872843 0.5994573 -0.7004725 0.5146067 0.5964596 -0.6159674 0.50032 0.5870373 -0.6364489 0.5199593 0.5929476 -0.6148622 0.518011 0.5887401 -0.6205238 0.5210471 0.595018 -0.6119342 0.5205333 0.5916668 -0.6156099 0.5242292 0.598907 -0.6053876 0.5242866 0.5878386 -0.616092 0.5295252 0.604196 -0.5954414 0.531933 0.5821563 -0.614932 0.5367661 0.6107873 -0.5820835 0.5436335 0.5744149 -0.6119723 0.5456839 0.6185147 -0.5653924 0.5595074 0.5646054 -0.6067721 0.5559697 0.6272287 -0.5454189 0.5797337 0.5524362 -0.598935 0.5670982 0.6368929 -0.5222709 0.604085 0.538453 -0.5874943 0.578557 0.6473246 -0.4962285 0.6321655 0.5231191 -0.5715883 0.590415 0.6574667 -0.4681323 0.6636266 0.5064055 -0.5505935 0.6965721 0.4907184 -0.5234336 0.5782006 0.2414115 -0.7793617 0.6056639 0.2434996 -0.7575481 0.579089 0.2336423 -0.781068 0.6117902 0.2397468 -0.753813 0.6067706 0.235332 -0.7592419 0.6147214 0.2420306 -0.7506922 0.6120153 0.2381317 -0.7541422 0.6219246 0.2466068 -0.7432327 0.6158761 0.233843 -0.752339 0.6333217 0.2527914 -0.731437 0.6247441 0.2272984 -0.7470142 0.6487087 0.2604327 -0.7150886 0.6386483 0.2181576 -0.7379266 0.6675409 0.2702878 -0.6937822 0.657449 0.2072697 -0.7244309 0.6893375 0.2818667 -0.6673566 0.6810566 0.1942087 -0.7060064 0.7132911 0.2951469 -0.6356918 0.7091019 0.1795082 -0.6818733 0.7385461 0.3096233 -0.5989015 0.7409694 0.1634273 -0.6513493 0.7638472 0.3253939 -0.5573654 0.7754694 0.1480653 -0.6137784 0.8113473 0.1333384 -0.5691541 -0.08605349 0.776929 -0.6236796 -0.2101278 0.6573069 -0.7237362 -0.168513 0.9819155 0.08628559 -0.2137517 0.969659 0.118624 -0.3158249 0.926844 0.203015 -0.4518506 0.8328099 0.3197792 -0.4857787 0.8032804 0.3446155 -0.5776511 0.6977482 0.4236353 -0.4836311 0.8037285 0.3465853 -0.4830655 0.8042487 0.346167 -0.2119153 0.969858 0.1202808 -0.2115064 0.969984 0.1199832 -0.486943 0.8044903 0.3401204 -0.4891805 0.8041561 0.3376913 -0.4882745 0.8032718 0.3410899 -0.4907226 0.8039097 0.3360365 -0.4900854 0.8033294 0.3383464 -0.4916909 0.8036419 0.3352607 -0.491342 0.8033443 0.3364832 -0.4919013 0.8035206 0.3352429 -0.4918599 0.8034877 0.3353824 -0.4914451 0.8034642 0.336046 -0.4917322 0.8036749 0.3351211 -0.4903527 0.803416 0.337753 -0.4910091 0.8038622 0.3357316 -0.4887187 0.8033198 0.3403399 -0.4897499 0.8039668 0.3373166 -0.4861313 0.8034994 0.3436059 -0.4875963 0.8043469 0.3395231 -0.4830251 0.8035695 0.3477971 -0.4849407 0.8045911 0.3427329 -0.4790804 0.8037868 0.3527163 -0.4814977 0.8049734 0.3466668 -0.4745908 0.8038578 0.358575 -0.4775493 0.8051987 0.3515706 -0.4691734 0.8041141 0.365071 -0.4727182 0.8055913 0.3571557 -0.4630503 0.8043183 0.372366 -0.4672243 0.8059261 0.3635719 -0.456134 0.8045243 0.3803714 -0.4609861 0.8062473 0.3707522 -0.4485366 0.8045948 0.3891555 -0.4541096 0.8064277 0.3787596 -0.4399006 0.8048343 0.3984083 -0.4462387 0.8067702 0.3872892 -0.4304872 0.8049758 0.4082827 -0.4376316 0.8069983 0.3965253 -0.4202365 0.8050418 0.4186993 -0.4282235 0.8071529 0.4063603 -0.4093431 0.8048194 0.4297719 -0.4182067 0.8070133 0.4169325 -0.3973178 0.8047996 0.4409491 -0.4070637 0.8070573 0.4277355 -0.3844867 0.8046054 0.4525263 -0.395166 0.8069363 0.4389732 -0.3710472 0.8042529 0.4642211 -0.3824959 0.8066079 0.4506447 -0.3492174 0.8022761 0.484149 -0.3690888 0.8062498 0.4623144 -0.2955602 0.7963221 0.5277454 -0.3452095 0.8064639 0.4800484 -0.1935308 0.7829415 0.5912262 -0.2885649 0.8041338 0.5197105 -0.05296891 0.7614817 0.6460186 -0.1849705 0.7939621 0.579146 0.0156306 0.7541195 0.6565511 -0.04750972 0.7703741 0.6358196 -0.02421003 0.7649909 0.6435859 0.0160892 0.7549688 0.6555633 -0.1628814 0.7881269 0.5935702 -0.02706569 0.7601426 0.6491924 -0.3112841 0.8031328 0.5080158 -0.1677008 0.7817056 0.6006771 -0.4131475 0.8066333 0.4226725 -0.3144704 0.799661 0.511518 -0.4148181 0.805001 0.4241454 -0.2136499 0.9700542 0.1155366 -0.2151476 0.9699119 0.1139397 -0.2152071 0.9695771 0.1166461 -0.216332 0.969761 0.1129784 -0.2163497 0.9695442 0.1147903 -0.2170701 0.9696449 0.1125586 -0.217066 0.9695366 0.1134954 -0.2173081 0.9695814 0.1126455 -0.2173065 0.9695726 0.1127248 -0.2170778 0.969561 0.1132643 -0.2171057 0.9696432 0.1125032 -0.2164719 0.9695503 0.1145081 -0.2165609 0.9697189 0.1129002 -0.215382 0.969583 0.1162723 -0.215564 0.9698282 0.1138657 -0.2137863 0.9696582 0.1185688 -0.2141001 0.969976 0.1153588 -0.2117448 0.9697526 0.1214246 -0.2122281 0.9701367 0.117448 -0.2092174 0.9698716 0.124808 -0.2099108 0.9703173 0.1200902 -0.2062226 0.9699969 0.128756 -0.207176 0.9705023 0.1233021 -0.2026596 0.9701533 0.1331598 -0.203912 0.9707136 0.1270238 -0.1985264 0.9703289 0.1380178 -0.2001263 0.9709425 0.1312256 -0.1940274 0.970445 0.1434914 -0.1960251 0.9711125 0.1360686 -0.1888142 0.9706014 0.1492715 -0.1912521 0.9713202 0.1412791 -0.1831207 0.9707077 0.1555424 -0.1860533 0.9714785 0.1470158 -0.1768111 0.9707975 0.162142 -0.1802725 0.9716203 0.1531525 -0.1700196 0.9708114 0.1691701 -0.1740583 0.9716886 0.1597651 -0.1625331 0.9708073 0.1763978 -0.1671891 0.9717384 0.1666506 -0.1545894 0.9706984 0.1839745 -0.1598821 0.9716869 0.1739606 -0.1460447 0.9705139 0.1917645 -0.1520209 0.9715636 0.1815315 -0.1369759 0.9702788 0.199491 -0.1435416 0.9713714 0.1892972 -0.1228017 0.9691709 0.2136056 -0.1345852 0.9711125 0.1970462 -0.08762246 0.9656986 0.2444351 -0.117857 0.970954 0.2082259 -0.01956135 0.9571822 0.2888242 -0.07922857 0.9690341 0.2338711 0.07521009 0.9425845 0.3253887 -0.009877741 0.9619824 0.2729328 0.1217868 0.9368309 0.327896 0.08098393 0.9468106 0.3114343 0.09520101 0.9435588 0.3172278 0.1221252 0.9371402 0.3268846 0.002926468 0.9590132 0.2833464 0.09233671 0.9413147 0.3246547 -0.09616583 0.9691243 0.2270466 -0.002620637 0.9561126 0.2929878 -0.1645468 0.9714753 0.1707635 -0.1002388 0.9675622 0.2318955 -0.1666888 0.9707671 0.1727021 0.3098484 -0.8019308 -0.5107848 0.1460728 -0.7777643 -0.6113473 0.3400638 -0.8011064 -0.4925294 0.3135449 -0.7973015 -0.5157517 0.3353787 -0.806304 -0.4872319 0.3438411 -0.8035031 -0.4859588 0.3431138 -0.8043044 -0.4851468 0.3494682 -0.8011001 -0.485912 0.3448593 -0.8061634 -0.4808042 0.3610825 -0.7974863 -0.4833582 0.3500555 -0.8094992 -0.4713515 0.3783937 -0.7928755 -0.4776677 0.3588483 -0.8138846 -0.4569681 0.4016247 -0.7868367 -0.4685996 0.3706678 -0.8195139 -0.4370381 0.4307199 -0.7790117 -0.4556547 0.3853803 -0.8258662 -0.411615 0.4649947 -0.7695158 -0.4377506 0.402557 -0.8325327 -0.3805747 0.5037835 -0.7580839 -0.4141387 0.4213072 -0.8392732 -0.3436866 0.5460115 -0.7444672 -0.3842395 0.4411151 -0.8452832 -0.3015192 0.5893275 -0.7295299 -0.3471012 0.4614322 -0.8497595 -0.2549294 0.1676185 -0.9848073 -0.04537421 0.3309573 -0.9303632 -0.1577702 0.1587619 -0.9843565 -0.07640069 0.2913455 -0.9398484 -0.1783328 0.1501234 -0.9830437 -0.1052997 0.2538471 -0.9477481 -0.193223 0.1420148 -0.9810956 -0.1314657 0.2199199 -0.9540922 -0.2033307 0.1347207 -0.9787766 -0.1544234 0.190739 -0.9589295 -0.2099349 0.1283528 -0.9764005 -0.1736882 0.166659 -0.9625233 -0.2139481 0.1233322 -0.9741527 -0.1892502 0.1474612 -0.9652366 -0.2158089 0.1198161 -0.9722419 -0.2009718 0.1332083 -0.9672153 -0.2162176 0.1179718 -0.9708084 -0.2088388 0.1236478 -0.9686573 -0.2154396 0.1176784 -0.9700334 -0.2125727 0.1186118 -0.9696789 -0.2136679 0.111339 -0.9707509 -0.212712 0.1172094 -0.9684979 -0.2197129 0.1005215 -0.9663007 -0.2369779 0.09565514 -0.9684553 -0.2300966 -0.6220355 -0.4550418 -0.6371882 -0.6110316 -0.6062577 -0.5090107 -0.5684081 -0.7381491 -0.3633844 -0.06392484 0.3033232 0.9507412 -0.751947 -0.2449163 0.612039 -0.1187353 0.2636754 0.9572759 -0.608898 -0.6019195 0.5166587 -0.7537463 -0.2379319 0.6125805 -0.6155812 -0.5917458 0.5204775 -0.6137856 -0.5920897 0.5222041 -0.6135367 -0.5925377 0.5219883 -0.751841 -0.2380846 0.6148584 -0.7516406 -0.2391908 0.614674 -0.6171557 -0.5917797 0.5185707 -0.6160329 -0.5935024 0.5179366 -0.6183644 -0.5920817 0.5167831 -0.6175723 -0.5932927 0.5163413 -0.6189898 -0.5925958 0.5154432 -0.6186642 -0.5930926 0.515263 -0.6195135 -0.5925322 0.5148869 -0.6191477 -0.5930894 0.5146854 -0.6192063 -0.5930833 0.514622 -0.6195324 -0.5925865 0.5148017 -0.6187984 -0.5930522 0.5151484 -0.6190487 -0.5926704 0.5152868 -0.6177834 -0.5932826 0.5161002 -0.6184609 -0.5922471 0.516478 -0.6163507 -0.5934308 0.5176405 -0.6172291 -0.5920836 0.5181365 -0.6146928 -0.5932005 0.5198711 -0.6155537 -0.591873 0.5203652 -0.6122367 -0.5934721 0.522453 -0.6136253 -0.5913174 0.5232664 -0.60953 -0.5934086 0.5256801 -0.6108742 -0.5913069 0.5264872 -0.6062999 -0.5933581 0.5294587 -0.6078156 -0.5909668 0.5303947 -0.6026965 -0.5931757 0.5337597 -0.6042341 -0.5907239 0.5347396 -0.5984594 -0.5931397 0.5385461 -0.6001985 -0.5903322 0.5396942 -0.5939605 -0.5927301 0.5439504 -0.5955258 -0.5901674 0.5450244 -0.5885972 -0.5928807 0.549587 -0.5905402 -0.5896496 0.5509771 -0.582917 -0.5926974 0.5558036 -0.5846585 -0.5897513 0.5571067 -0.5765645 -0.5928024 0.56228 -0.5784447 -0.5895604 0.5637556 -0.569752 -0.5927582 0.5692278 -0.5714937 -0.5896911 0.5706658 -0.5625246 -0.5925419 0.5765935 -0.5640853 -0.5897275 0.5779527 -0.554641 -0.5925418 0.5841812 -0.5562139 -0.5896301 0.58563 -0.5461177 -0.5928481 0.5918502 -0.5477129 -0.5898115 0.593408 -0.5372194 -0.5929045 0.599883 -0.5385317 -0.5903285 0.6012454 -0.5211415 -0.5954626 0.6114212 -0.5241291 -0.589276 0.6148515 -0.483148 -0.5997466 0.6378651 -0.4877501 -0.5887079 0.6446107 -0.414097 -0.6084492 0.6769884 -0.4187096 -0.5928012 0.6879455 -0.3222281 -0.6206173 0.7148448 -0.3237676 -0.6084399 0.7245519 -0.2798592 -0.6250557 0.7286866 -0.2799073 -0.6240355 0.729542 -0.3083627 -0.6156249 0.7252024 -0.3077103 -0.6221278 0.7199108 -0.4026511 -0.5980317 0.6929865 -0.4001451 -0.6073548 0.6862973 -0.501231 -0.5901074 0.6328828 -0.4988695 -0.5954554 0.6297318 -0.5681315 -0.5895521 0.5741559 -0.5669345 -0.5916886 0.5731403 -0.6820461 -0.2378721 0.6915418 -0.6825755 -0.2353432 0.6918846 -0.5804817 -0.2430276 0.7771605 -0.5813418 -0.237095 0.7783493 -0.4326521 -0.2598714 0.8632954 -0.4331445 -0.2498143 0.8660131 -0.2938452 -0.2827899 0.9130635 -0.2934898 -0.2748244 0.9156066 -0.2521919 -0.2866817 0.9242364 -0.2522876 -0.2879788 0.9238069 -0.3170715 -0.2651547 0.9105815 -0.3175119 -0.2798978 0.9060041 -0.4576933 -0.2432249 0.8551949 -0.4565977 -0.2604076 0.8507094 -0.5611747 -0.2359225 0.7933622 -0.5594884 -0.2487314 0.7906361 -0.616502 -0.2357087 0.7512435 -0.6153047 -0.2428441 0.7499512 -0.6387186 -0.2365149 0.732188 -0.6381567 -0.2396021 0.7316741 -0.652257 -0.2361976 0.7202579 -0.6516619 -0.2393185 0.7197663 -0.6650404 -0.2355559 0.7086852 -0.6643013 -0.239275 0.7081322 -0.6769307 -0.2354313 0.6973787 -0.6762244 -0.2388569 0.6968988 -0.6880244 -0.2352633 0.6864938 -0.6872482 -0.2389042 0.6860136 -0.6982157 -0.2355824 0.6760146 -0.6974942 -0.2388664 0.675607 -0.707686 -0.2353232 0.6661857 -0.7068052 -0.2392273 0.6657302 -0.7162332 -0.235654 0.6568694 -0.7154648 -0.2389813 0.6565045 -0.7239916 -0.2358748 0.6482276 -0.7231975 -0.2392423 0.64788 -0.7309617 -0.2361447 0.6402583 -0.7301883 -0.2393647 0.6399451 -0.7370338 -0.2369607 0.6329541 -0.7364193 -0.2394763 0.6327224 -0.742546 -0.2368778 0.6265096 -0.7417533 -0.2400775 0.6262306 -0.7471248 -0.2375959 0.6207678 -0.7465866 -0.2397431 0.6205897 -0.7511469 -0.2376914 0.615858 -0.7505202 -0.2401664 0.6156617 -0.7543008 -0.2382453 0.6117757 -0.7538803 -0.2398928 0.6116502 -0.7567557 -0.2389454 0.6084619 -0.7564617 -0.2400884 0.6083774 -0.7586325 -0.239218 0.6060128 -0.7583358 -0.2403659 0.6059299 -0.7598555 -0.2392415 0.6044694 -0.7596197 -0.2401512 0.6044048 -0.7603479 -0.2396805 0.6036757 -0.7603381 -0.2397179 0.6036731 -0.7602946 -0.2394588 0.6038308 -0.7602602 -0.239591 0.6038216 -0.7594305 -0.2399609 0.6047182 -0.7597192 -0.2388455 0.6047971 -0.7578636 -0.2405532 0.6064462 -0.7583296 -0.2387492 0.6065765 -0.7558507 -0.2403708 0.6090251 -0.756268 -0.2387479 0.6091454 -0.01052868 0.8425329 0.5385421 0.1310101 0.7376784 0.6623194 0.2127704 0.6542962 0.7256895 0.07043725 0.9971067 0.02858299 0.07408297 0.9969067 0.02624219 0.2520112 0.9623345 -0.1019932 0.2825146 0.9514471 -0.1222046 0.3516892 0.9200642 -0.1726171 0.494548 0.8235144 -0.2779323 0.4729729 0.8408896 -0.2630618 0.6731067 -0.3012863 -0.6753917 0.6319406 0.671239 -0.3874136 0.6564735 0.6360985 -0.405489 0.5947481 0.67249 -0.4404906 0.5946578 0.6726159 -0.4404202 0.4431626 0.8409033 -0.3106259 0.4428098 0.8411893 -0.3103548 0.2615589 0.9518789 -0.15973 0.2608796 0.9521512 -0.1592164 0.06146454 0.998106 0.002549529 0.06113564 0.9981256 0.00279355 0.6240271 0.6683992 -0.4047625 0.6132904 0.6696932 -0.4187912 0.6211302 0.6723723 -0.4026324 0.6037366 0.6707428 -0.4308203 0.6108455 0.6730664 -0.4169524 0.5956525 0.6715623 -0.4406838 0.6017667 0.673476 -0.4293096 0.5891689 0.6722542 -0.4482793 0.5940972 0.6737307 -0.4394716 0.5845462 0.6727725 -0.4535227 0.5880758 0.6737843 -0.4474166 0.5821731 0.673269 -0.4558326 0.5838639 0.6737303 -0.4529795 0.5819619 0.6734709 -0.4558041 0.5820187 0.673486 -0.4557092 0.5824629 0.6734284 -0.4552267 0.5820626 0.6733295 -0.4558846 0.5829845 0.6733974 -0.454604 0.5825558 0.6732977 -0.4553009 0.582502 0.6733345 -0.4553154 0.582958 0.6734347 -0.4545829 0.5806377 0.6733215 -0.4577097 0.5822722 0.6736572 -0.4551318 0.5777097 0.6732969 -0.4614354 0.5802975 0.6737999 -0.4574368 0.5736575 0.6734195 -0.4662865 0.5771659 0.6740636 -0.4609965 0.5685175 0.6734927 -0.4724356 0.5730487 0.6742802 -0.4657912 0.5621371 0.6736677 -0.4797642 0.5677402 0.6745954 -0.4717968 0.554597 0.673827 -0.4882411 0.5612834 0.6748837 -0.4790542 0.5458086 0.6740079 -0.4978015 0.5536438 0.6751918 -0.4874368 0.5357982 0.6740894 -0.5084523 0.5448366 0.6754078 -0.4969681 0.5245963 0.6740056 -0.5201109 0.5348585 0.6754527 -0.5076318 0.5119302 0.6740047 -0.5325835 0.5235067 0.6755992 -0.5191403 0.4981057 0.6736518 -0.5459706 0.5109966 0.675383 -0.5317334 0.4825819 0.6736336 -0.5597611 0.4968458 0.6755308 -0.5447957 0.4657031 0.6727123 -0.5749598 0.4817892 0.6748294 -0.5590029 0.4321205 0.6707451 -0.6028043 0.4640977 0.6751654 -0.5733802 0.360463 0.6631069 -0.6560149 0.4300941 0.6739277 -0.6007001 0.2357738 0.6470949 -0.7250373 0.3566872 0.6694365 -0.6516357 0.08973997 0.6240433 -0.7762194 0.231835 0.6545824 -0.7195655 0.03834939 0.6178849 -0.7853327 0.08739435 0.6293336 -0.7722055 0.0986154 0.6310575 -0.7694423 0.03847688 0.6175781 -0.7855679 0.2572339 0.6566203 -0.7089996 0.1000937 0.6277817 -0.771927 0.4131295 0.6716139 -0.6150276 0.2597281 0.6520152 -0.7123325 0.5202137 0.6751962 -0.5229606 0.414513 0.6694073 -0.6165006 0.5210162 0.6740194 -0.5236793 0.4699356 0.8366436 -0.2814035 0.4605222 0.8377847 -0.2933188 0.4637247 0.8415704 -0.2769813 0.4519722 0.8388594 -0.3033744 0.4551248 0.842099 -0.2893625 0.4447882 0.8396692 -0.3116396 0.4476827 0.8423122 -0.3001505 0.4390033 0.8403427 -0.3179625 0.4414589 0.8423659 -0.3090851 0.4346441 0.8410294 -0.3221085 0.4364724 0.8424029 -0.3159893 0.4323069 0.8415854 -0.3237975 0.4332048 0.8422052 -0.3209736 0.4319682 0.8418283 -0.3236182 0.4319918 0.8418432 -0.3235477 0.4323493 0.8418387 -0.3230813 0.4321209 0.8417032 -0.3237393 0.4327996 0.8418083 -0.3225575 0.4325534 0.841672 -0.3232428 0.4326348 0.8415699 -0.3233997 0.4329153 0.8417136 -0.322649 0.4311715 0.8414783 -0.3255848 0.4321711 0.8419491 -0.3230324 0.4286732 0.8414982 -0.3288161 0.43029 0.8422004 -0.3248831 0.4252814 0.841547 -0.3330683 0.4275225 0.8424432 -0.3278932 0.4209938 0.8415427 -0.3384822 0.4239588 0.8426371 -0.3319965 0.4154912 0.8417257 -0.3447678 0.4192374 0.842997 -0.3370405 0.408953 0.8419306 -0.3520087 0.4135258 0.8433615 -0.3431292 0.4015721 0.8419364 -0.360393 0.4070485 0.8435265 -0.350392 0.3930059 0.8419961 -0.3695794 0.3994485 0.8437304 -0.3585527 0.383318 0.8420208 -0.3795633 0.390776 0.8438975 -0.367602 0.3723758 0.8420628 -0.3902132 0.3809356 0.8440737 -0.3773959 0.3604437 0.8418529 -0.4017016 0.3701597 0.8439958 -0.3881402 0.3473076 0.8415462 -0.4137361 0.3582168 0.8438227 -0.3995547 0.3323553 0.8412695 -0.4263867 0.3448666 0.8437387 -0.4113051 0.3049948 0.8381541 -0.45219 0.3303057 0.8431441 -0.4242714 0.2436664 0.8317114 -0.4988816 0.2997197 0.8431686 -0.4463574 0.137124 0.8168342 -0.5603383 0.2362968 0.8393856 -0.4894852 0.01034271 0.7979078 -0.6026907 0.128893 0.8271418 -0.5470128 -0.034819 0.7940821 -0.6068123 0.006197631 0.8046659 -0.5936957 0.01638931 0.806306 -0.5912715 -0.03469264 0.7938536 -0.6071184 0.1527006 0.8277702 -0.5398881 0.01962035 0.8011798 -0.5981019 0.2865674 0.8405803 -0.4596779 0.1572818 0.8222688 -0.5469337 0.3787748 0.8433994 -0.3810605 0.289612 0.8376217 -0.4631575 0.3803157 0.8420658 -0.3824726 0.2827401 0.9492071 -0.138072 0.2753157 0.9500389 -0.1470628 0.2755687 0.9520213 -0.133106 0.2686966 0.9507192 -0.1547103 0.2692773 0.9524261 -0.1427384 0.2629241 0.95132 -0.1608142 0.2636809 0.9527159 -0.1510128 0.2582775 0.951795 -0.1654666 0.25906 0.9528675 -0.1578972 0.2548059 0.9521999 -0.1684916 0.2554659 0.9529264 -0.1633046 0.2529469 0.9524852 -0.1696751 0.2532969 0.9528095 -0.1673163 0.2524875 0.9526659 -0.1693447 0.2524917 0.9526695 -0.1693186 0.2527552 0.9526723 -0.1689097 0.2526523 0.9525994 -0.1694738 0.2532185 0.9526017 -0.1686131 0.2531056 0.9525306 -0.1691838 0.2530593 0.9525293 -0.1692597 0.2532019 0.9526085 -0.1686001 0.2520216 0.952488 -0.1710316 0.2525361 0.9527409 -0.1688503 0.2501658 0.9525163 -0.1735796 0.2510273 0.9528907 -0.1702487 0.2476175 0.952571 -0.1769016 0.2488545 0.9530489 -0.1725379 0.2442619 0.9526626 -0.1810248 0.2459595 0.9532468 -0.1755688 0.2400644 0.9527934 -0.1858868 0.2422783 0.9534749 -0.1794064 0.2353574 0.9528088 -0.191735 0.2381415 0.9535859 -0.1842895 0.2295334 0.9529394 -0.1980427 0.2329564 0.953806 -0.1896984 0.2229346 0.9530163 -0.2050852 0.2270642 0.9539736 -0.1958979 0.2155832 0.9530038 -0.2128558 0.2204867 0.9540527 -0.2029016 0.2072793 0.9529615 -0.2211329 0.2130153 0.9541046 -0.2104968 0.1981198 0.9528177 -0.2299717 0.2047489 0.9540619 -0.2187325 0.1879065 0.9526391 -0.2391027 0.1954831 0.9539831 -0.2273819 0.1767079 0.9522141 -0.2491233 0.1855191 0.9537141 -0.2366687 0.1556906 0.9503923 -0.2692862 0.1738721 0.9535188 -0.2461108 0.1089497 0.9457208 -0.3061736 0.149842 0.9532114 -0.2625555 0.02720367 0.9345672 -0.3547453 0.1009425 0.9500593 -0.2952928 -0.07073634 0.9196377 -0.3863455 0.01858019 0.9405442 -0.3391627 -0.1055525 0.9159823 -0.3870853 -0.07473725 0.9236391 -0.3759058 -0.06629389 0.9251298 -0.373818 -0.1054539 0.9158676 -0.3873834 0.03786849 0.9418484 -0.3338975 -0.06332451 0.9222822 -0.3812945 0.1405987 0.9516738 -0.2730366 0.04289925 0.9385635 -0.3424301 0.2115514 0.9538295 -0.2132021 0.1441863 0.9498954 -0.277325 0.2133916 0.9530367 -0.214907 0.07514441 0.9970499 0.01564198 0.07038491 0.997469 0.01007866 0.06977701 0.9973768 0.01925456 0.06616437 0.9977945 0.005342364 0.06589388 0.9977391 0.01321691 0.06246775 0.9980457 0.001589179 0.06243729 0.9980166 0.008031785 0.05954951 0.9982245 -0.001303255 0.05966222 0.9982119 0.003667771 0.05741637 0.9983453 -0.003197133 0.05757671 0.9983412 1.88553e-4 0.05609935 0.998418 -0.003779888 0.05620419 0.9984167 -0.002267479 0.05583316 0.9984337 -0.003569602 0.05583274 0.9984337 -0.003574132 0.05603814 0.9984231 -0.003318965 0.0559985 0.998424 -0.003697156 0.05625319 0.9984118 -0.003084361 0.05620872 0.9984132 -0.003450393 0.05621904 0.9984121 -0.003563284 0.05628311 0.9984101 -0.003107428 0.05552893 0.9984462 -0.004663825 0.05576413 0.9984388 -0.003212511 0.05441683 0.9984983 -0.006323695 0.05482715 0.9984874 -0.004119098 0.0528565 0.9985662 -0.008461952 0.0534687 0.9985539 -0.005580365 0.050722 0.9986518 -0.01104533 0.05158936 0.9986406 -0.007455289 0.04820549 0.9987363 -0.01421165 0.04936659 0.9987312 -0.009950459 0.04503357 0.9988283 -0.01772135 0.04653644 0.9988341 -0.01283627 0.04148316 0.9989016 -0.02179187 0.04336971 0.9989258 -0.01631808 0.03736025 0.998957 -0.02625006 0.03967916 0.9990077 -0.02022957 0.03269851 0.9989811 -0.0311045 0.03549879 0.9990671 -0.02458965 0.02742666 0.9989657 -0.03626626 0.03074824 0.9990975 -0.02930706 0.0216372 0.998892 -0.04179441 0.02552735 0.9990803 -0.03445225 0.01529675 0.9987485 -0.04761862 0.01979392 0.9990051 -0.03996455 0.008213341 0.9985123 -0.05390495 0.01350378 0.9988611 -0.04576319 -0.004948258 0.9977487 -0.06688076 0.006127297 0.9986466 -0.05164492 -0.03416937 0.99529 -0.09072118 -0.009055852 0.9980342 -0.06201356 -0.08587187 0.9888651 -0.1215384 -0.04007148 0.9958025 -0.08228939 -0.1475986 0.9789538 -0.14094 -0.09182035 0.9897089 -0.1097515 -0.1692388 0.9755282 -0.1403678 -0.1501735 0.9796735 -0.1329959 -0.1443755 0.9807332 -0.1315987 -0.1691559 0.9754983 -0.1406749 -0.07887679 0.9911599 -0.1066797 -0.1423387 0.9802088 -0.137588 -0.01444041 0.9975423 -0.06856215 -0.07534354 0.9907153 -0.113166 0.03010916 0.999064 -0.03105592 -0.01187604 0.9973534 -0.07172906 0.03148609 0.9989809 -0.03233665 0.6217103 -0.4193754 0.6615139 0.5822163 -0.3000698 -0.7556336 0.6077102 -0.6213008 0.4946449 0.5701085 -0.7344653 0.3681535 0.5813011 -0.3051714 -0.754294 0.8196406 -0.03623342 -0.571731 0.7709212 -0.3039594 -0.5597224 0.8182222 -0.0511713 -0.5726203 0.1689093 0.2613736 -0.9503439 0.6686512 -0.5431849 -0.5077952 0.7690811 -0.3095903 -0.5591673 0.5187177 -0.7448318 -0.4197115 0.667595 -0.5449427 -0.5073011 0.521601 -0.7419288 -0.4212767 0.5084086 -0.7375913 -0.444387 0.5077883 -0.7383255 -0.443877 0.6446481 -0.5381873 -0.5429397 0.6445447 -0.5383956 -0.5428559 0.7372599 -0.3012832 -0.6047117 0.7371429 -0.3017557 -0.6046187 0.7793173 -0.04432439 -0.6250599 0.7792976 -0.04486596 -0.6250459 0.7050997 -0.04271143 -0.7078208 0.7051633 -0.04157978 -0.7078247 0.5981531 -0.04683786 -0.8000121 0.5981986 -0.04386585 -0.8001463 0.4427148 -0.06387358 -0.8943846 0.4424226 -0.05744147 -0.8949652 0.284047 -0.08969992 -0.9546054 0.2834874 -0.08460605 -0.9552364 0.2228465 -0.09901827 -0.9698117 0.2228966 -0.09938663 -0.9697625 0.2721072 -0.08503735 -0.9585021 0.2728505 -0.09146976 -0.9576982 0.4174445 -0.05857384 -0.9068126 0.4180652 -0.06956881 -0.9057492 0.542939 -0.04620754 -0.8384999 0.5429909 -0.05425631 -0.8379841 0.6158981 -0.04264068 -0.786671 0.6157816 -0.04789942 -0.7864596 0.6497013 -0.0428068 -0.7589835 0.6496284 -0.04486835 -0.7589267 0.6668289 -0.04235404 -0.7440063 0.6667438 -0.0443837 -0.7439643 0.6821506 -0.04142242 -0.7300374 0.6820222 -0.04412388 -0.7299993 0.6960757 -0.04213428 -0.716731 0.6960106 -0.04336345 -0.7167208 0.7087302 -0.04161173 -0.7042514 0.7085809 -0.04419302 -0.7042443 0.720038 -0.04171174 -0.6926798 0.7199132 -0.04372823 -0.6926853 0.7300727 -0.04195988 -0.6820802 0.7299498 -0.04382914 -0.682094 0.7388732 -0.04210889 -0.6725276 0.7387415 -0.0440154 -0.67255 0.7464565 -0.04250168 -0.6640754 0.7463449 -0.04405629 -0.6640997 0.7528535 -0.04283177 -0.6567929 0.7527458 -0.04428291 -0.6568202 0.758093 -0.04317617 -0.6507156 0.7579998 -0.04439848 -0.650742 0.7621738 -0.04348152 -0.6459106 0.7620963 -0.04447805 -0.6459342 0.7651942 -0.0437591 -0.6423106 0.7651358 -0.04449993 -0.6423294 0.7671711 -0.04400283 -0.6399314 0.7671347 -0.04446059 -0.6399434 0.7677994 -0.04431933 -0.6391557 0.7678054 -0.04424303 -0.6391536 0.7671082 -0.04432892 -0.6399843 0.76713 -0.04405725 -0.6399771 0.7664793 -0.04422861 -0.6407444 0.7664911 -0.04407936 -0.6407405 0.7668406 -0.04397565 -0.6403294 0.7668094 -0.04436659 -0.6403396 0.7689534 -0.04362535 -0.6378147 0.7688552 -0.04484772 -0.6378483 0.7733565 -0.04338788 -0.632485 0.7731802 -0.04554098 -0.6325492 0.7796621 -0.04333525 -0.6246992 0.7794139 -0.04628396 -0.6247975 0.7875921 -0.04343277 -0.6146643 0.7872647 -0.0471937 -0.6148065 0.7969549 -0.0438323 -0.6024464 0.7965517 -0.04828816 -0.602639 0.8074792 -0.04443132 -0.5882204 0.806985 -0.04966795 -0.5884798 0.5172442 -0.7410202 -0.4281911 0.5213637 -0.7367386 -0.4305764 0.5131947 -0.7404014 -0.4340933 0.5167497 -0.7366429 -0.4362646 0.5097478 -0.7397347 -0.4392605 0.5125377 -0.7367398 -0.4410436 0.5068278 -0.7392094 -0.4435033 0.5090332 -0.7368109 -0.4449661 0.5045809 -0.7387404 -0.4468342 0.5061536 -0.7370125 -0.4479075 0.5031497 -0.7382999 -0.44917 0.5040532 -0.7373001 -0.4497987 0.5026381 -0.737939 -0.4503343 0.5028833 -0.7376669 -0.4505064 0.502709 -0.7377271 -0.4506024 0.502597 -0.7378515 -0.4505237 0.5030522 -0.737675 -0.4503045 0.5028167 -0.7379363 -0.4501393 0.5031622 -0.7378585 -0.4498805 0.5031577 -0.7378635 -0.4498775 0.502749 -0.7379655 -0.450167 0.5030335 -0.7376499 -0.4503665 0.5017581 -0.7380847 -0.451076 0.5023669 -0.737407 -0.4515069 0.5003764 -0.7381516 -0.4524996 0.5011494 -0.7372863 -0.4530542 0.4987757 -0.7379456 -0.4545978 0.4995016 -0.7371271 -0.4551283 0.4962382 -0.7382645 -0.4568514 0.4975986 -0.7367171 -0.4578686 0.4937363 -0.7379783 -0.4600135 0.4947109 -0.7368577 -0.4607624 0.4902724 -0.7382633 -0.4632498 0.4918404 -0.7364364 -0.4644938 0.4867956 -0.7379891 -0.4673352 0.4879551 -0.7366175 -0.468289 0.4827001 -0.7378455 -0.471789 0.4840137 -0.7362629 -0.4729139 0.4778657 -0.7380116 -0.4764277 0.4794309 -0.7360881 -0.4778289 0.4726327 -0.7380485 -0.4815628 0.4740583 -0.7362567 -0.4829024 0.4670752 -0.7378497 -0.4872562 0.4682488 -0.736336 -0.4884184 0.4605922 -0.7382037 -0.4928591 0.4620924 -0.7362125 -0.4944306 0.4534536 -0.7384796 -0.4990268 0.4547978 -0.7366367 -0.5005251 0.4383944 -0.7404097 -0.5095134 0.4414729 -0.7358881 -0.5133911 0.4075863 -0.7436555 -0.5299527 0.411605 -0.7367019 -0.5365182 0.3557966 -0.7502888 -0.5572034 0.3594107 -0.7412747 -0.5668647 0.2971022 -0.7583094 -0.5802561 0.2980696 -0.7532411 -0.5863294 0.2775661 -0.7601776 -0.5874412 0.2775332 -0.7604563 -0.5870958 0.3037768 -0.7529212 -0.5838059 0.3029003 -0.7570519 -0.5788988 0.3706112 -0.7415812 -0.5592001 0.3684412 -0.7465022 -0.5540629 0.4345014 -0.7367337 -0.5181044 0.4327705 -0.7393669 -0.5157968 0.4779028 -0.736479 -0.4787563 0.4771357 -0.7374275 -0.478061 0.6604293 -0.5436213 -0.5179855 0.664921 -0.535917 -0.5202625 0.6539831 -0.5423265 -0.5274355 0.6576733 -0.5358771 -0.5294352 0.6482121 -0.5413076 -0.5355437 0.6512906 -0.5358362 -0.5373082 0.6433915 -0.5403963 -0.5422353 0.6457617 -0.5361236 -0.5436573 0.6396261 -0.5395941 -0.547464 0.6413279 -0.5364912 -0.5485214 0.6371629 -0.538794 -0.5511121 0.6381292 -0.5370184 -0.5517269 0.6361817 -0.5381135 -0.5529074 0.6364371 -0.5376429 -0.5530715 0.6361097 -0.5378667 -0.5532303 0.6360675 -0.5379447 -0.553203 0.6366643 -0.5376768 -0.5527769 0.6363661 -0.5382261 -0.5525855 0.6369177 -0.5380318 -0.5521391 0.6369245 -0.5380196 -0.5521434 0.636257 -0.5383801 -0.5525612 0.6366356 -0.5376824 -0.5528045 0.6348179 -0.5385203 -0.5540778 0.6354172 -0.5374115 -0.5544672 0.6327697 -0.5384888 -0.5564463 0.6335056 -0.5371193 -0.5569323 0.6298857 -0.5386894 -0.5595157 0.6309467 -0.5366997 -0.5602319 0.6265015 -0.5384119 -0.5635679 0.6274895 -0.5365399 -0.5642535 0.6220059 -0.5387446 -0.5682102 0.6234693 -0.5359379 -0.5692597 0.6170531 -0.53854 -0.5737771 0.6183355 -0.5360447 -0.5747324 0.6111652 -0.5385707 -0.5800162 0.6126494 -0.535632 -0.5811704 0.6045252 -0.5385387 -0.5869629 0.6060104 -0.535539 -0.5881746 0.5970637 -0.5385555 -0.594536 0.5985696 -0.5354439 -0.5958308 0.5888552 -0.5383515 -0.6028493 0.5902255 -0.5354443 -0.6040969 0.5796965 -0.5384057 -0.6116137 0.5811188 -0.5352969 -0.6129913 0.56953 -0.5389266 -0.6206396 0.571047 -0.5355004 -0.6222096 0.5580056 -0.5398222 -0.6302554 0.5595831 -0.5361226 -0.632012 0.5349285 -0.5425171 -0.6477089 0.5378151 -0.5351719 -0.6514183 0.4864338 -0.5475694 -0.680845 0.4903059 -0.5355083 -0.687627 0.4041723 -0.5580995 -0.724686 0.4073125 -0.54219 -0.734933 0.3098047 -0.5705609 -0.7605795 0.3102844 -0.5611827 -0.7673315 0.2778428 -0.5733641 -0.7707509 0.2778425 -0.573601 -0.7705747 0.3187076 -0.5616477 -0.7635294 0.3182389 -0.568827 -0.758393 0.4244375 -0.5438975 -0.7238981 0.4225703 -0.5522083 -0.7186797 0.5266931 -0.5359563 -0.659807 0.5247638 -0.5410886 -0.65715 0.5965074 -0.5353403 -0.5979882 0.5954766 -0.5374878 -0.5970883 0.759603 -0.3079687 -0.5728513 0.7623243 -0.2993808 -0.5737881 0.7507948 -0.306679 -0.5850258 0.7531438 -0.2991006 -0.5859294 0.7430316 -0.3053988 -0.5955128 0.7448974 -0.2992582 -0.5962989 0.7364873 -0.3042966 -0.6041442 0.7379298 -0.299466 -0.6047971 0.7313441 -0.3032736 -0.6108691 0.7323593 -0.2998266 -0.6113541 0.7278615 -0.3022684 -0.6155092 0.7284312 -0.3003146 -0.6157916 0.7263132 -0.3014619 -0.6177296 0.7264681 -0.3009282 -0.6178077 0.7260875 -0.301271 -0.618088 0.7260913 -0.301258 -0.6180899 0.726714 -0.3010541 -0.617457 0.7265363 -0.3016654 -0.6173676 0.7272065 -0.3013912 -0.6167123 0.7271881 -0.3014545 -0.6167032 0.7265117 -0.3017746 -0.6173434 0.7267339 -0.3010098 -0.6174552 0.7247343 -0.301899 -0.6193685 0.7250856 -0.3006842 -0.6195483 0.7220541 -0.3020147 -0.6224347 0.7225414 -0.3003182 -0.6226902 0.7184557 -0.3021438 -0.6265226 0.7190666 -0.2999968 -0.6268534 0.713959 -0.3019202 -0.6317489 0.7145806 -0.2997082 -0.6320993 0.7083601 -0.3020671 -0.637951 0.7091714 -0.2991354 -0.6384309 0.7019002 -0.3016667 -0.6452391 0.7026233 -0.299005 -0.6456907 0.6943057 -0.3016335 -0.6534193 0.695168 -0.2983887 -0.6539922 0.6856271 -0.3017575 -0.6624636 0.686544 -0.2982196 -0.6631157 0.6760292 -0.3012691 -0.6724742 0.6767818 -0.2982781 -0.6730502 0.6649911 -0.3021707 -0.6829932 0.6660557 -0.2977991 -0.6838755 0.6530523 -0.3021956 -0.6944066 0.6538515 -0.2987899 -0.695128 0.6401521 -0.301548 -0.7065934 0.6407288 -0.2989755 -0.7071635 0.6252321 -0.3029382 -0.7192449 0.6261817 -0.2984787 -0.7202826 0.5956195 -0.3069333 -0.7423135 0.5973343 -0.2979497 -0.7445923 0.5328723 -0.3133817 -0.7860274 0.5348163 -0.2997261 -0.7900227 0.4257714 -0.3260872 -0.8440296 0.4267574 -0.3090448 -0.8499231 0.3017196 -0.344043 -0.8891567 0.3012301 -0.332283 -0.8937833 0.2591282 -0.3476282 -0.9011145 0.2592036 -0.348625 -0.9007076 0.3115563 -0.3332827 -0.8898625 0.3118117 -0.3411625 -0.8867816 0.4486821 -0.3102418 -0.8381136 0.4479652 -0.3196586 -0.8349524 -0.9951846 0 -0.09801888 -0.9569392 0 -0.2902886 -0.8819207 0 -0.4713978 -0.7730085 0 -0.6343956 -0.634393 0 -0.7730107 -0.4713944 0 -0.8819225 -0.290284 0 -0.9569406 -0.09801524 0 -0.995185 0.09802061 0 -0.9951844 0.2902874 0 -0.9569395 0.4713951 0 -0.8819222 0.6343949 0 -0.7730091 0.7730116 0 -0.6343919 0.8819223 0 -0.4713949 0.9569411 0 -0.2902822 0.9951848 0 -0.09801506 0.9951845 0 0.09801954 0.9569397 0 0.2902868 0.8819199 0 0.4713995 0.773009 0 0.6343951 0.6343917 0 0.7730119 0.4713937 0 0.8819229 0.2902822 0 0.9569411 0.09801459 0 0.995185 -0.09801989 0 0.9951846 -0.2902866 0 0.9569398 -0.4714003 0 0.8819193 -0.634396 0 0.7730082 -0.7730125 0 0.6343909 -0.8819223 0 0.4713948 7.94083e-7 1 -8.60355e-7 -0.9951849 0 0.09801602 -0.9569417 0 0.2902801 0 -1 0 0 -1 0 -0.8191702 0 -0.5735506 0 -1 0 -0.5735221 -0.01062446 -0.8191212 0 -1 0 -0.6834676 0 -0.729981 -0.3571799 -0.0700466 -0.9314054 -0.4994044 -0.03624594 -0.8656104 -0.6361654 -0.005682826 -0.7715317 0 -1 0 -0.9659244 0 -0.2588243 0 -1 0 0 -1 0 0 -1 0 -0.893523 0 -0.4490174 -0.8595225 -0.005587637 -0.5110672 -0.81769 -0.01740211 -0.5753957 -0.8784951 -0.002095937 -0.4777467 -0.7557989 -0.0470283 -0.6531128 0 -1 0 -0.9961931 0 0.08717429 0 -1 0 -0.9659244 0 -0.2588243 0 -1 0 -0.9063216 0 0.4225887 0 -1 0 -0.9961931 0 0.08717429 -0.7070817 0 0.7071319 -0.9063216 0 0.4225887 -0.4226078 0 0.9063127 -0.7070817 0 0.7071319 -0.08716922 0 0.9961935 -0.4226078 0 0.9063127 0 -1 0 0.2588369 0 0.9659211 0 -1 0 -0.08716922 0 0.9961935 0 -1 0 0.5735221 -0.01062446 0.8191212 0 -1 0 0 -1 0 0.2588369 0 0.9659211 0.4609493 0 0.8874264 0 -1 0 0.8191674 0 0.5735545 0 -1 0 0.3570689 -0.07007449 0.9314458 0.4988955 -0.03637719 0.8658983 0.6361713 -0.005703747 0.7715268 0.6836329 0 0.7298261 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0 -1 0 0 -1 0 0.8935132 0 0.4490371 0.7557985 -0.04702615 0.6531135 0.8594247 -0.005615293 0.5112314 0.8176897 -0.0174002 0.5753962 0.878696 -0.002067267 0.4773775 0 -1 0 0.9961934 0 -0.08716994 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0.9063127 0 -0.4226078 0 -1 0 0.9961934 0 -0.08716994 0.7071319 0 -0.7070817 0.9063127 0 -0.4226078 0.4225955 0 -0.9063184 0.7071319 0 -0.7070817 0.08716601 0 -0.9961937 0.4225955 0 -0.9063184 0 -1 0 -0.2588144 0 -0.965927 0 -1 0 0.08716601 0 -0.9961937 0 -1 0 0 -1 0 -0.2588144 0 -0.965927 -0.4609493 0 -0.8874264 0.4999459 0 0.8660566 0.8660566 0 0.4999459 0.8660566 0 0.4999459 0 0 1 0.4999459 0 0.8660566 -0.4999817 0 0.866036 0 0 1 -0.8660566 -5.34e-6 0.4999459 -0.5000436 -9.24988e-6 0.8660002 -1 0 0 -0.866036 0 0.4999817 -0.866036 0 -0.4999817 -1 0 0 -0.4999817 0 -0.866036 -0.866036 0 -0.4999817 0 0 -1 -0.4999817 0 -0.866036 0.4999459 0 -0.8660566 0 0 -1 0.866036 0 -0.4999817 0.4999459 0 -0.8660566 1 0 0 0.866036 0 -0.4999817 1 0 0 0 1 0 -0.5735545 0 -0.8191674 0 1 0 -0.8191393 0.008676171 -0.573529 0 1 0 -0.9816746 0.141552 -0.1275854 -0.9584425 0.1072065 -0.264376 -0.8283234 0.02416384 -0.559729 -0.7850629 0.00886929 -0.6193527 -0.7506756 0.002479135 -0.6606663 -0.7220277 0 -0.6918642 0 1 0 0 1 0 0 1 0 0 1 0 -0.6462793 0.04281181 -0.7618992 -0.5510083 0.01059621 -0.8344324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.8191366 0.00867474 0.5735329 0 1 0 0 1 0 0 1 0 0.5735545 0 0.8191674 0 1 0 0.7220277 0 0.6918642 0.9816778 0.1415603 0.1275521 0.9585391 0.1073113 0.2639832 0.8285197 0.02427315 0.5594336 0.784958 0.00887078 0.6194855 0.7504475 0.002458989 0.6609255 0 1 0 0 1 0 0 1 0 0 1 0 0.6462793 0.04281181 0.7618992 0.5510083 0.01059621 0.8344324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4618903 -0.7964901 0.3902063 -0.241818 -0.9397039 0.2418277 -0.7528011 -0.3264135 0.5716159 -0.3837249 -0.8554324 0.3478371 -0.6331795 -0.5940163 0.4962139 -0.6645904 0.3420631 0.6643135 -0.8119032 0.03803575 0.5825517 -0.7789186 -0.2410059 0.5789663 -0.6645712 0.3419557 0.664388 -0.6643207 0.3420086 0.6646113 -0.6643626 0.3420299 0.6645584 -0.5054081 0.8046713 0.3115555 -0.6640012 0.3411285 0.6653823 -0.7077683 0.5282849 0.4690194 -0.7143402 0.5133827 0.4755589 -0.01545935 0.9985106 -0.05232059 -0.5079421 0.8021553 0.3139133 -0.2308988 0.9684051 0.09421998 0.2418772 0.9396772 -0.2418721 0.08600658 0.987388 -0.1329197 0.2418442 0.9396924 -0.241846 0.2417318 0.9396933 -0.2419546 0.2418439 0.9396934 -0.2418426 0.241836 0.9396964 -0.2418385 -0.2417318 0.9396933 0.2419546 -0.2418493 0.9396923 0.2418411 -0.2418426 0.9396934 0.2418438 -0.241867 0.9396837 0.2418572 -0.24185 0.9396899 0.24185 -0.6644607 -0.342029 0.6644607 -0.6647908 -0.3419852 0.6641531 0.2415183 -0.9396793 -0.2422224 -0.6634947 -0.3420228 0.6654285 0.2408514 -0.9396883 -0.2428509 0.2418622 -0.939684 -0.2418609 0.2418537 -0.9396892 -0.2418491 -0.2418571 -0.939684 0.2418655 -0.2423595 -0.9396872 0.2413498 -0.2418516 -0.9396875 0.241858 0.4619926 -0.7964042 -0.3902606 0.2418236 -0.9397035 -0.2418236 0.7527334 -0.3266167 -0.5715889 0.3333511 -0.8869293 -0.3197395 0.5192474 -0.7388248 -0.429558 0.6642133 -0.5403717 -0.5165454 0.6646341 0.342072 -0.6642654 0.8117083 0.03875213 -0.5827761 0.7603955 -0.3037847 -0.5740327 0.8092627 -0.0473833 -0.5855329 0.6641804 0.3420785 -0.6647154 0.6643209 0.3420086 -0.6646111 0.664344 0.3420203 -0.664582 0.5038288 0.8050349 -0.3131695 0.6644734 0.3425033 -0.6642038 0.7074924 0.5256394 -0.4723957 0.6240651 0.6702491 -0.4016328 0.01727259 0.9984043 0.05376464 0.4660421 0.8393874 -0.2797025 0.2809898 0.9504566 -0.1329557 -0.2418244 0.9397039 0.2418215 -0.1386492 0.9756379 0.1700207 0.0680508 0.9976148 0.01156508 0.24185 0.9396899 -0.24185 0.6644583 -0.3420386 -0.6644583 0.6645602 -0.3420251 -0.6643633 -0.2418399 -0.9396952 0.2418399 0.664461 -0.342028 -0.664461 -0.7751186 -0.3366672 0.5346462 -0.2418007 0.9397085 0.2418268 -0.2418455 0.9396927 0.2418438 -0.2418392 0.9396948 0.2418424 -0.241849 0.9396922 0.2418422 -0.2418503 0.939692 0.2418416 -0.2418461 0.9396919 0.2418462 -0.4918572 0.772085 0.402444 -0.4964307 0.7680648 0.4045157 -0.7750223 -0.3370433 0.5345487 -0.7750262 -0.3370193 0.5345581 -0.7749605 -0.3373236 0.5344614 -0.7750095 -0.3371469 0.5345017 -0.7751315 -0.3366165 0.5346593 -0.7746071 -0.3386788 0.5341166 -0.7756377 -0.3345547 0.535219 -0.7746356 -0.3386092 0.5341192 -0.7750473 -0.3369455 0.5345741 -0.7749343 -0.3374121 0.5344435 -0.775118 -0.3366332 0.5346683 -0.1418057 0.975938 0.165638 -0.1305579 0.9815136 0.1399488 -0.1617522 0.9703774 0.1794547 -0.1423191 0.9810069 0.131798 -0.1809545 0.9667389 0.1807521 -0.1833087 0.9695582 0.1623414 -0.1644291 0.9801605 0.1106728 -0.1916475 0.9662429 0.1721798 -0.24183 0.9396966 0.241844 -0.2080733 0.9637852 0.1668035 -0.241848 0.939692 0.2418438 -0.1953997 0.9752391 0.1035736 -0.2097971 0.9628714 0.1698927 -0.2418549 0.9396906 0.2418425 -0.2176402 0.9655595 0.1425746 -0.2418458 0.939692 0.2418459 -0.2171027 0.9696679 0.1122972 -0.2211962 0.9631119 0.1532565 -0.2418379 0.9396929 0.2418506 -0.222021 0.9676734 0.1196447 -0.2418396 0.9396928 0.2418493 -0.2231178 0.966872 0.1240038 -0.2418447 0.939693 0.2418434 -0.2192361 0.9685211 0.1179077 -0.2418456 0.9396928 0.2418432 -0.2211225 0.9684703 0.114761 -0.24185 0.9396921 0.2418416 -0.1798034 0.9836441 -0.01072019 -0.2418407 0.9396933 0.2418459 -0.2075754 0.9692589 0.1320978 -0.2062429 0.9750509 0.08209514 -0.2418539 0.9396919 0.2418381 -0.1303263 0.991251 -0.02089083 -0.2418465 0.9396925 0.2418435 -0.1909757 0.9711617 0.1427348 -0.1503875 0.9883891 0.02169156 -0.2418486 0.9396924 0.2418416 -0.1352173 0.9883075 0.07045811 -0.2418379 0.9396932 0.2418492 -0.1752776 0.9732431 0.1485781 -0.241845 0.9396923 0.2418458 -0.1573588 0.9821153 0.1033811 -0.2418456 0.9396926 0.2418443 -0.1664927 0.9751425 0.1462103 -0.1421527 0.9836793 0.110307 -0.2418398 0.9396928 0.241849 -0.1590269 0.9769471 0.1424243 -0.2418574 0.939691 0.2418386 -0.1621384 0.9754365 0.1491132 -0.2418437 0.9396927 0.241845 -0.1538835 0.9785539 0.1369383 -0.2418363 0.9396932 0.2418512 -0.1518616 0.9783793 0.1403992 -0.2418447 0.9396927 0.2418447 -0.1584372 0.9757702 0.1508973 -0.1569738 0.9767935 0.1457175 -0.2418496 0.9396922 0.2418417 -0.1594108 0.974942 0.1551647 -0.2418459 0.9396927 0.2418436 -0.1510486 0.978023 0.1437197 -0.2418442 0.9396926 0.2418455 -0.1589148 0.9745735 0.1579638 -0.1484853 0.9781937 0.1452212 -0.2418438 0.9396926 0.2418458 -0.1579581 0.9743332 0.1603871 -0.241844 0.9396926 0.2418457 -0.1471359 0.9780324 0.147661 -0.2418423 0.9396926 0.241847 -0.1553568 0.9746004 0.1613017 -0.1470307 0.9775493 0.1509287 -0.2418481 0.9396926 0.2418414 -0.1557146 0.9739522 0.1648337 -0.2418447 0.9396929 0.2418439 -0.1481943 0.9763396 0.157478 -0.1507901 0.9759601 0.1573664 -0.2418444 0.9396925 0.2418457 -0.15344 0.9741691 0.1656824 -0.2418453 0.9396924 0.241845 -0.1437792 0.977278 0.1557409 -0.2418423 0.9396924 0.2418477 -0.152342 0.9741099 0.1670383 -0.2418433 0.9396924 0.2418469 -0.1445409 0.9765086 0.1598087 -0.1487678 0.9755243 0.1619275 -0.241847 0.9396924 0.2418429 -0.1456723 0.9757991 0.163082 -0.2418446 0.9396929 0.241844 -0.2418449 0.9396927 0.2418438 -0.1452865 0.9760991 0.1616244 -0.2418467 0.939692 0.2418451 -0.1450219 0.9759244 0.1629112 -0.2418465 0.9396921 0.2418452 -0.2418434 0.9396924 0.241847 -0.1449883 0.9759436 0.1628268 -0.1526418 0.973797 0.1685824 -0.2418425 0.9396927 0.2418467 -0.1440265 0.9762257 0.1619875 -0.241848 0.939692 0.2418438 -0.1434597 0.9763933 0.1614795 -0.1431009 0.9764706 0.16133 -0.1404675 0.9771833 0.1593165 -0.2418428 0.9396927 0.2418463 -0.151794 0.9737164 0.1698083 -0.2418435 0.9396927 0.241846 -0.2418422 0.9396926 0.2418473 -0.1417706 0.9767768 0.1606496 -0.1449381 0.9759734 0.1626926 -0.2418448 0.9396935 0.2418416 -0.1539976 0.9725189 0.1746192 -0.2418452 0.9396933 0.2418414 -0.2418456 0.9396933 0.2418411 -0.1394699 0.9769075 0.1618636 -0.1490855 0.9744882 0.1677687 -0.2418454 0.9396927 0.2418437 -0.1526341 0.9722275 0.1774163 -0.2418422 0.9396932 0.2418449 -0.1393577 0.9760963 0.166779 -0.1429967 0.9755574 0.1668522 -0.2418375 0.939695 0.2418428 -0.1484066 0.9726722 0.1785618 -0.2418882 0.9396818 0.2418434 -0.2418285 0.9396961 0.2418478 -0.2418726 0.9396866 0.2418406 -0.2418495 0.9396909 0.2418465 -0.2418425 0.9396921 0.241849 -0.1319783 0.9774918 0.1645954 -0.001083672 0.8454236 0.5340954 -0.1734352 0.9089729 0.3790626 -0.1415933 0.974453 0.1743351 -0.04522162 0.8249226 0.5634338 -0.1555411 0.8015994 0.5772741 -0.04585641 0.8018049 0.5958241 -0.2617483 0.7746939 0.5756192 -0.1993181 0.7479129 0.6331655 -0.3819112 0.7083522 0.5936169 -0.4243769 0.739449 0.5226083 -0.3522766 0.7432777 0.5687173 -0.4930733 0.6200833 0.6102256 -0.4388417 0.7397927 0.5100243 -0.4440553 0.7135255 0.5419374 -0.4504405 0.7246339 0.5215449 -0.4432948 0.7371749 0.5099636 -0.447308 0.7292347 0.5178149 -0.4427292 0.7375967 0.5098451 -0.444401 0.7353397 0.5116477 -0.4425373 0.7396928 0.5069669 -0.4442981 0.7354882 0.5115236 -0.4487599 0.7322604 0.5122591 -0.4461349 0.7400419 0.503291 -0.4552766 0.7229229 0.5197169 -0.4548581 0.7320234 0.5071943 -0.4533361 0.7400931 0.4967376 -0.4702839 0.7103891 0.5236222 -0.467004 0.7289351 0.5005607 -0.4591992 0.7490284 0.4775904 -0.4920974 0.6941924 0.5252972 -0.4936061 0.7133098 0.4975361 -0.4723751 0.7531985 0.4577707 -0.5064082 0.6960376 0.5090014 -0.4861894 0.7476614 0.4523521 -0.5346387 0.6800642 0.5016714 -0.5150425 0.7252114 0.4569459 -0.496746 0.7580631 0.4225916 -0.5365322 0.699932 0.4714113 -0.556658 0.6945644 0.4557548 0.241859 -0.9396849 -0.2418607 0.3134498 -0.9024572 -0.2955 0.3368006 -0.8873215 -0.3150014 0.2418423 -0.9396941 -0.2418414 -0.7756289 -0.3346781 0.5351546 0.2419164 -0.9396523 -0.2419298 0.2418515 -0.9396895 -0.2418503 -0.7750056 -0.3371012 0.5345362 -0.7749406 -0.337336 0.5344824 -0.7752918 -0.3360334 0.5347936 -0.7751003 -0.3367526 0.5346188 -0.7748906 -0.3375425 0.5344248 -0.7748179 -0.3378188 0.5343554 0.2418441 -0.9396921 -0.241847 -0.01795774 -0.9978347 -0.06327307 0.2418443 -0.9396963 -0.2418308 0.2418447 -0.9396989 -0.2418204 0.2418429 -0.9396933 -0.2418437 0.2418407 -0.9396896 -0.2418607 0.2418487 -0.939697 -0.2418239 0.2418394 -0.9396927 -0.2418496 0.2418493 -0.9396942 -0.2418336 0.2418435 -0.9396945 -0.2418385 0.2418349 -0.9396961 -0.2418411 -0.7746849 -0.338427 0.5341635 -0.1522556 -0.9882695 0.01190763 0.2418467 -0.9396923 -0.2418441 -0.01385271 -0.9989991 -0.0425328 0.2418482 -0.9396934 -0.2418383 0.2418476 -0.939693 -0.2418401 0.2418501 -0.9396938 -0.2418348 0.241836 -0.9396911 -0.2418593 0.2418453 -0.9396922 -0.2418458 0.2418448 -0.9396922 -0.2418463 -0.1218165 -0.9923277 0.02112942 0.2418435 -0.939692 -0.241848 -0.01189476 -0.999724 -0.02026063 0.2418467 -0.9396934 -0.2418395 0.2418421 -0.9396925 -0.2418482 0.2418428 -0.9396924 -0.2418471 0.2418413 -0.9396924 -0.2418488 -0.1021711 -0.9940884 0.03673249 0.2418473 -0.9396921 -0.2418442 -0.006215333 -0.9999797 -0.001390993 0.2418497 -0.9396925 -0.2418399 0.2418414 -0.9396922 -0.2418498 -0.09911555 -0.9928387 0.06668728 0.2418451 -0.9396929 -0.2418437 0.00152117 -0.9999145 0.01298469 0.2418435 -0.9396924 -0.2418466 0.2418429 -0.9396924 -0.2418472 -0.08967012 -0.9916803 0.09235459 0.2418444 -0.9396921 -0.2418465 -0.003850877 -0.999296 0.03731656 0.2418481 -0.9396927 -0.2418414 -0.05665856 -0.9943459 0.08981144 0.2418437 -0.9396926 -0.2418459 -0.01319468 -0.9979795 0.06215023 0.2418419 -0.9396925 -0.2418481 0.241847 -0.9396929 -0.2418414 0.004933238 -0.9986995 0.05074352 0.2418442 -0.9396926 -0.2418456 -0.02317231 -0.9969083 0.07507938 0.2418428 -0.939693 -0.2418449 -0.02215749 -0.995604 0.09100288 0.2418433 -0.9396932 -0.2418438 0.2418441 -0.9396919 -0.241848 0.003800868 -0.9980386 0.06248551 0.2418452 -0.939693 -0.2418426 -3.98417e-4 -0.9980772 0.06198173 0.2418454 -0.9396921 -0.2418459 0.003682255 -0.9979788 0.0634427 0.001645922 -0.9978421 0.06563705 0.2418448 -0.9396924 -0.2418451 0.003521203 -0.9980018 0.06308722 0.2418442 -0.9396922 -0.2418466 0.2418464 -0.9396926 -0.2418435 -0.01687115 -0.9955167 0.09306842 0.2418423 -0.9396929 -0.2418462 0.0139907 -0.9977152 0.06609511 0.2418434 -0.9396931 -0.2418445 0.002780079 -0.997804 0.06617736 0.2418488 -0.939692 -0.2418432 -0.1081411 -0.9606044 0.256017 0.2418487 -0.9396919 -0.2418435 0.2418398 -0.9396928 -0.2418489 0.0767796 -0.9907126 0.1122211 0.2418412 -0.9396933 -0.2418456 0.01746571 -0.9972193 0.07244873 0.2418183 -0.9396876 -0.241891 0.1883214 -0.9740475 0.1255642 0.08076471 -0.9851549 0.1514822 0.241851 -0.939693 -0.2418372 0.2945151 -0.9471402 0.1272252 0.238002 -0.9513124 0.1958568 0.2419567 -0.9397056 -0.2416825 0.4173154 -0.8939855 0.1632118 0.3121409 -0.9397934 -0.1391272 0.3848574 -0.9140981 0.1277092 0.4422173 -0.8924188 0.08962458 0.5147446 -0.8046025 0.2960624 0.4367411 -0.894963 0.0910952 0.3306042 -0.8944818 -0.3010035 0.3383599 -0.8900148 -0.3055915 0.3277246 -0.8947913 -0.3032244 0.347217 -0.8834669 -0.314526 0.3246539 -0.8953614 -0.3048407 0.337293 -0.8886606 -0.3106695 0.3389102 -0.8867031 -0.3144797 0.3333607 -0.8887213 -0.3147141 0.3373047 -0.8869532 -0.3154989 0.3342915 -0.8877066 -0.3165848 0.3196541 -0.8976546 -0.3033768 0.3340112 -0.8880807 -0.315831 0.334172 -0.8877829 -0.3164973 0.3349063 -0.8873527 -0.3169274 0.3361488 -0.8864396 -0.318165 0.3346655 -0.8875004 -0.316768 0.3267978 -0.892253 -0.311589 0.3309495 -0.8900091 -0.313618 0.3338653 -0.8880206 -0.3161538 0.3343951 -0.8874576 -0.3171734 0.3250886 -0.8925372 -0.3125616 0.3307066 -0.889607 -0.3150119 0.3357854 -0.8857806 -0.3203763 0.3226694 -0.8931007 -0.3134574 0.3289607 -0.8898714 -0.3160914 0.334285 -0.8855835 -0.3224833 0.3273109 -0.8886801 -0.3211156 0.3324292 -0.88608 -0.3230376 0.3212203 -0.8916651 -0.318984 0.3232514 -0.8916038 -0.3170979 0.3323677 -0.8841052 -0.3284659 0.3204922 -0.8909049 -0.321828 0.3321421 -0.883012 -0.3316195 0.3195577 -0.8903022 -0.3244147 0.3307114 -0.882658 -0.3339833 0.3187137 -0.889698 -0.326893 0.3289822 -0.8823829 -0.3364093 0.3202174 -0.8873017 -0.3318984 0.3261796 -0.8828272 -0.337969 0.3190261 -0.8870549 -0.3337002 0.3131995 -0.8903003 -0.3305624 0.3254834 -0.8813151 -0.3425557 0.3265985 -0.8756383 -0.3557962 0.3031476 -0.8925464 -0.3338599 0.3254953 -0.8767148 -0.3541526 0.3497826 -0.8318082 -0.4309839 0.2906929 -0.8937354 -0.3416649 0.3225441 -0.8674808 -0.378738 0.3118896 -0.8513671 -0.4217807 0.2728118 -0.8974019 -0.3467615 0.3317676 -0.8093789 -0.4845988 0.2706085 -0.8811165 -0.3878203 0.2581776 -0.8984324 -0.3551951 0.2739442 -0.8678758 -0.4144227 0.2581507 -0.895371 -0.3628624 0.2635077 -0.89276 -0.3654356 0.2582028 -0.8950852 -0.3635297 0.2733482 -0.8897377 -0.3655785 0.2597638 -0.9092071 -0.3253695 0.2812893 -0.8934595 -0.350152 0.2652065 -0.9198181 -0.2891372 0.3102826 -0.8829432 -0.3523295 0.2822941 -0.898638 -0.335797 0.2804654 -0.9143144 -0.2921789 0.3273869 -0.8838835 -0.3340179 0.3057416 -0.8924654 -0.3317039 0.3476756 -0.8750685 -0.3367148 0.3011232 -0.9047269 -0.3013203 0.7976942 0.2289018 -0.5579319 0.775023 0.3370513 -0.5345426 0.7750252 0.3370459 -0.5345427 0.7998802 0.2120884 -0.5614359 0.754755 0.4064137 -0.5149492 0.7376561 0.4562147 -0.4977266 0.7542398 0.3388682 -0.5623973 0.7535739 0.318873 -0.5748446 0.768157 0.2481936 -0.590199 0.7056494 0.4585462 -0.5401799 0.7792482 0.2140496 -0.5890288 0.7809605 0.3447548 -0.5208117 0.7403758 0.4675902 -0.482911 0.7843911 0.3360919 -0.5213184 0.5809876 -0.05935937 0.811745 0.5431006 0.06779563 0.8369262 0.7607842 0.3542199 -0.5438159 0.7699337 0.3184587 -0.5529795 0.7706812 0.3302778 -0.5449467 0.7994707 0.2786239 -0.5321798 0.7115564 0.5139065 -0.479153 0.75653 0.3268783 -0.5664036 0.7130783 0.4649333 -0.524744 0.7569029 0.3259841 -0.5664206 0.7289506 0.4451028 -0.5201101 0.7476498 0.3408283 -0.5699613 0.7156973 0.4439398 -0.5391613 0.6979015 0.4988638 -0.513876 0.7424392 0.3415139 -0.5763267 0.6915752 0.4930655 -0.5278354 0.7447482 0.3382477 -0.5752727 0.7378752 0.3417823 -0.5820008 0.7035408 0.4514748 -0.5488178 0.7406353 0.3383337 -0.5805082 0.7010348 0.4712954 -0.5351926 0.7341188 0.3416197 -0.5868268 0.7006399 0.4491769 -0.5543862 0.7368805 0.3387088 -0.5850501 0.6889503 0.4851006 -0.5385397 0.7312787 0.3412697 -0.5905644 0.6925015 0.4632167 -0.553057 0.7336946 0.33932 -0.5886884 0.6882588 0.4752911 -0.5480861 0.7297133 0.3406787 -0.5928377 0.6900517 0.4652023 -0.5544506 0.731166 0.3399966 -0.5914377 0.7290911 0.3405665 -0.5936672 0.6919147 0.4586014 -0.5576189 0.729628 0.3400952 -0.5932776 0.689315 0.4669257 -0.5539181 0.7292446 0.34026 -0.5936543 0.692193 0.458057 -0.5577209 0.7290476 0.3404073 -0.5938119 0.7300416 0.3401312 -0.5927479 0.6962882 0.4490348 -0.559956 0.7293105 0.3405736 -0.5933935 0.6969878 0.4461347 -0.5614017 0.7306702 0.3402499 -0.5919047 0.7004225 0.4393724 -0.5624592 0.7301007 0.3405008 -0.5924627 0.7309125 0.3403487 -0.5915486 0.6938563 0.4580644 -0.5556439 0.7306929 0.3404262 -0.5917751 0.6933171 0.4575126 -0.5567706 0.7307347 0.3403756 -0.5917528 0.6919559 0.4626471 -0.5542154 0.730908 0.3403139 -0.5915743 0.6921057 0.4621807 -0.5544175 0.73018 0.3404772 -0.5923787 0.6905804 0.4648873 -0.5540563 0.7307214 0.3402814 -0.5918232 0.7290613 0.3407981 -0.5935709 0.6932085 0.4552214 -0.5587803 0.7291326 0.3406735 -0.5935548 0.7301542 0.3403077 -0.592508 0.6896145 0.4671641 -0.5533441 0.7273752 0.3408814 -0.5955883 0.6906764 0.4576052 -0.5599675 0.7278149 0.3401226 -0.5954848 0.6863184 0.4704381 -0.5546665 0.7251709 0.3410458 -0.5981765 0.6872967 0.4609286 -0.5613983 0.7256932 0.3401628 -0.5980457 0.7225291 0.3413087 -0.6012155 0.6880062 0.4522076 -0.5675877 0.7231664 0.3402637 -0.6010416 0.6813049 0.4750593 -0.556904 0.7194661 0.3416209 -0.6047013 0.6714869 0.4873474 -0.5582095 0.7202907 0.3403254 -0.6044501 0.7160611 0.3419623 -0.6085379 0.6802518 0.4563595 -0.5735796 0.7171309 0.3403714 -0.60817 0.6806091 0.4657802 -0.5655266 0.7123644 0.3422651 -0.612692 0.6773946 0.4544156 -0.5784833 0.7137321 0.3403752 -0.6121529 0.666449 0.4877327 -0.5638816 0.7137241 0.3209345 -0.6225745 0.6682018 0.4685289 -0.5779159 0.7071478 0.3375611 -0.6212845 0.7054445 0.3374794 -0.6232621 0.6704972 0.4512513 -0.5889022 0.6584476 0.4908223 -0.5705614 0.6936556 0.348559 -0.6303558 0.6886686 0.3669096 -0.6253902 0.6531525 0.484077 -0.5822896 0.680208 0.344969 -0.6467716 0.6646097 0.3997904 -0.6312381 0.6806747 0.3438917 -0.6468544 0.6944668 0.3399048 -0.634177 0.637953 0.4987086 -0.5867756 0.6648393 0.3475883 -0.6611891 0.6305269 0.4576295 -0.6269059 0.66879 0.3395571 -0.661378 0.6406794 0.4645088 -0.6113603 0.6502888 0.348266 -0.6751558 0.6207438 0.4450457 -0.6454544 0.6564723 0.3374934 -0.6746424 0.6388664 0.4356739 -0.6340646 0.6079974 0.4830999 -0.6300426 0.6366642 0.3477535 -0.6882777 0.5950778 0.4779273 -0.6461176 0.6441223 0.3369268 -0.6867218 0.6240071 0.3465419 -0.7003741 0.5936607 0.4464262 -0.6695302 0.6320766 0.3371277 -0.6977279 0.5940445 0.4804114 -0.6452254 0.612391 0.3450182 -0.7112944 0.5864034 0.4326089 -0.6848216 0.6205831 0.3377178 -0.7076886 0.5609439 0.5217449 -0.6427475 0.6006391 0.3443285 -0.7215751 0.535497 0.5348314 -0.6536042 0.6098676 0.3381783 -0.7167265 0.5813959 0.3404422 -0.7389709 0.5574848 0.4228586 -0.7144239 0.5775547 0.3464149 -0.7392072 0.5986294 0.3376981 -0.7263628 0.5531134 0.4957466 -0.6695528 0.5400036 0.3515667 -0.7647202 0.5418989 0.3444086 -0.7666344 0.550877 0.3377212 -0.763203 0.4475401 0.6438673 -0.6205986 0.4819898 0.352154 -0.8022927 0.3590977 0.6642647 -0.6555923 0.5156555 0.3262724 -0.792241 0.4142745 0.3373627 -0.8453183 0.4180676 0.3227645 -0.8491423 0.4186876 0.3327176 -0.8449849 0.4704356 0.3266455 -0.8197518 0.3669397 0.6511359 -0.6643623 0.3348082 0.3324721 -0.8816835 0.1033958 0.8469704 -0.5214887 0.3669732 0.3110391 -0.87669 0.2517271 0.3181489 -0.9140102 0.2553188 0.304377 -0.9176966 0.3014627 0.2959399 -0.9063884 0.202378 0.7127465 -0.6715918 0.1857171 0.3009799 -0.9353717 0.04833287 0.7077082 -0.7048497 0.2285288 0.2839374 -0.9312111 0.1477175 0.2873286 -0.9463731 0.1268133 0.3651192 -0.9222832 0.1706656 0.2761259 -0.9458476 0.09071451 0.6215493 -0.7781049 0.1373154 0.2794768 -0.9502828 0.09554672 0.4306851 -0.8974304 0.1401326 0.2774333 -0.9504702 0.1512241 0.2811515 -0.9476735 0.1076639 0.4378221 -0.8925919 0.146337 0.2856916 -0.9470827 0.1194577 0.3622428 -0.9243971 0.1921801 0.2876723 -0.9382492 0.1930969 0.2840901 -0.939152 0.1873856 0.2923383 -0.9377766 0.2627139 0.2927557 -0.9193886 0.1956718 0.5161914 -0.833822 0.2494342 0.3045361 -0.9192608 0.266121 0.02054965 -0.9637206 0.3581309 0.2974029 -0.8850389 0.3746231 0.2259377 -0.8992273 0.3238204 0.3225502 -0.889439 0.4556819 0.3075262 -0.8353332 0.3696435 0.5675219 -0.7357191 0.4009619 0.3369544 -0.8518753 0.4487779 -0.1794359 -0.8754435 0.5412772 0.3292117 -0.7737175 0.5638282 0.22492 -0.7946753 0.5453013 0.3237454 -0.7731982 0.4732537 0.3410075 -0.8122468 0.6248703 0.3173952 -0.7133004 0.5061418 0.6292909 -0.589757 0.6014375 0.347 -0.7196277 0.5944392 0.04249042 -0.8030172 0.6954135 0.3135145 -0.6466134 0.596665 0.584668 -0.5496855 0.6545131 0.35798 -0.6659301 0.7045721 0.05563408 -0.7074482 0.7052108 0.3554293 -0.6134718 0.747675 0.08024507 -0.6591985 0.6850179 0.5091261 -0.5210959 0.5746351 0.5716531 -0.5856683 0.643457 0.1053588 -0.758197 0.6252722 0.4630877 -0.6281597 0.405022 0.6765758 -0.6149815 0.5189141 0.103425 -0.8485467 0.4604406 0.581589 -0.6706331 0.360697 0.4694654 -0.8059156 -0.01570868 0.9527439 -0.3033683 0.2874454 0.1386436 -0.9477093 0.3820334 0.3088873 -0.870999 0.05856025 0.6829637 -0.7281011 0.186168 0.1185787 -0.9753361 0.1974462 0.3300024 -0.9230998 0.1692012 0.1577361 -0.9728773 0.1643783 0.1869815 -0.9685131 0.1994654 0.1555456 -0.9674808 0.3303377 -0.4590629 -0.824705 0.3237818 0.1997532 -0.9248049 0.2305517 0.141176 -0.9627644 0.4336659 -0.3822337 -0.8159848 0.4358901 0.2613823 -0.861208 0.4266067 -0.2099779 -0.879725 0.5132865 0.09824138 -0.8525759 0.5349695 -0.42267 -0.7315449 0.5749815 0.2275279 -0.7858927 0.5215198 0.1700048 -0.8361312 0.6224624 -0.1772196 -0.7623212 0.6237492 0.2185475 -0.7504491 0.5946512 0.2048923 -0.7774375 0.6334547 0.2275538 -0.7395638 0.6412849 0.1276751 -0.7566061 0.6484481 0.199651 -0.7346118 0.6508481 0.2518754 -0.7162092 0.6566114 0.1531859 -0.738509 0.6632486 0.2493221 -0.7056486 0.6733627 0.1491022 -0.7241209 0.6779797 0.2363728 -0.6960398 0.6850821 0.1751801 -0.7070887 0.6902306 0.2393352 -0.6828619 0.6957189 0.1963793 -0.6909489 0.6986056 0.2643146 -0.664897 0.7079581 0.1953836 -0.6786904 0.705357 0.2937005 -0.6451445 0.720768 0.1791381 -0.669629 0.7187166 0.2876986 -0.6329898 0.7306417 0.1750133 -0.6599493 0.7395785 0.2116625 -0.6389231 0.7318565 0.2245622 -0.6433956 0.7411553 0.2235735 -0.6330116 0.7441192 0.1862174 -0.6415683 0.747438 0.2022358 -0.6328009 0.7472041 0.223192 -0.6259963 0.7482429 0.1974758 -0.6333529 0.7503806 0.2187429 -0.6237632 0.7525837 0.1973246 -0.6282362 0.753075 0.2148126 -0.6218791 0.753937 0.2187698 -0.6194505 0.7546032 0.2062097 -0.6229378 0.756411 0.2082331 -0.6200657 0.7563967 0.2122027 -0.6187358 0.7564271 0.2081395 -0.6200775 0.7570357 0.2091256 -0.619002 0.7565345 0.2113165 -0.6188706 0.7566276 0.2115336 -0.6186828 0.7538604 0.225255 -0.6172153 0.7539315 0.2245755 -0.6173762 0.7526503 0.228044 -0.6176679 0.7534182 0.2211689 -0.6192296 0.7529442 0.2265473 -0.6178603 0.7544856 0.2174251 -0.619256 0.756238 0.2157966 -0.6176859 0.7558888 0.2093837 -0.620315 0.7577198 0.2215446 -0.6138229 0.7601364 0.1947237 -0.6198995 0.7637465 0.2007432 -0.6135091 0.7635942 0.2267248 -0.6045825 0.7649483 0.1934108 -0.6143664 0.7755154 0.1674044 -0.6087296 0.7740908 0.2430759 -0.584549 0.7708783 0.1989783 -0.6051069 0.772212 0.3240877 -0.5464941 0.7529757 0.3356099 -0.5660331 0.7939578 0.1567623 -0.5874153 0.797697 0.2780861 -0.5351146 0.8042226 0.1647455 -0.5710384 0.5809888 -0.05942362 0.8117393 0.6293057 -0.414509 0.6573863 0.5854057 -0.191342 0.7878378 0.8128688 0.1965532 -0.5482801 0.4163812 -0.12465 0.9006048 0.2947911 0.2380835 0.9254267 0.2947904 0.2381514 0.9254094 0.444342 0.3048593 0.84239 0.31469 0.48593 0.8153786 0.6737001 -0.2989636 -0.6758322 0.4478945 0.2800354 0.8490999 0.4163833 -0.1246463 0.9006044 0.4767764 -0.4690472 0.7434238 -0.3328489 -0.3144488 0.889007 -0.3993772 0.06214272 0.9146782 -0.3328477 -0.3144471 0.8890082 -0.5233836 -0.3361875 0.7829737 -0.5480421 0.3932967 0.7382192 -0.5894519 0.04769009 0.8063946 0.04530465 -0.2380455 0.9701967 -0.04902499 0.1330394 0.9898975 0.04530704 -0.2380419 0.9701976 -0.3993467 0.06225436 0.9146838 -0.04903233 0.1329929 0.9899033 0.1329604 -0.5740809 0.8079311 0.4768162 -0.4689211 0.743478 -0.2173776 -0.6449388 0.732667 0.1329519 -0.5741184 0.8079059 -0.5222226 -0.3498945 0.7777258 -0.3932399 -0.6703029 0.6293301 -0.217376 -0.6449011 0.7327007 -0.820822 -0.2809098 0.4973338 -0.8288481 -0.2376584 0.5064871 -0.8136778 -0.3321567 0.4770749 -0.7909817 -0.2952109 0.5359091 -0.8175979 -0.06454098 0.5721609 -0.7900633 -0.3566875 0.4985721 -0.8127358 0.1922503 0.5500003 -0.8160995 0.1776477 0.5499298 -0.8240717 0.1386205 0.5492634 -0.8380494 0.03660047 0.5443654 -0.8424851 -0.07856631 0.5329598 -0.7627909 -0.3008225 0.5724124 -0.7910839 -0.06882196 0.6078239 -0.7423703 -0.4237897 0.5189302 -0.7833611 0.201396 0.5880349 -0.7230956 -0.3542571 0.592988 -0.7657924 -0.0103138 0.6430053 -0.7145001 -0.3958259 0.5768982 -0.7547141 0.1961756 0.6260365 -0.7032088 -0.3309755 0.6292477 -0.7346958 0.1151515 0.6685525 -0.6820269 -0.3138919 0.6605386 -0.7171015 -0.01595169 0.6967862 -0.6778937 -0.3960638 0.6193493 -0.7314738 0.1383779 0.6676808 -0.652978 -0.3335265 0.6799852 -0.6942806 0.01730704 0.7194963 -0.6456233 -0.3875964 0.6579815 -0.6905606 0.1980536 0.6956297 -0.6233747 -0.3652812 0.6913564 -0.6734067 0.07583039 0.7353729 -0.6256384 -0.3515409 0.6964163 -0.6153608 -0.3301146 0.7157901 -0.658508 0.01300507 0.7524613 -0.6645576 0.1563978 0.7306865 -0.6011187 -0.332515 0.7266982 -0.6447902 0.0975092 0.7581144 -0.6001673 -0.3623446 0.7130958 -0.5883626 -0.3414798 0.7329536 -0.6363723 0.02932143 0.7708246 -0.5874473 -0.3505076 0.7294177 -0.643085 0.1168336 0.7568301 -0.5813825 -0.3389434 0.73967 -0.6292433 0.07326382 0.7737476 -0.5767033 -0.3369761 0.7442179 -0.6247142 0.04212272 0.7797166 -0.5782356 -0.3459097 0.7389115 -0.6281105 0.08991014 0.7729123 -0.5731986 -0.3387562 0.746115 -0.6219603 0.04846727 0.7815475 -0.5731458 -0.3428483 0.7442843 -0.5717743 -0.339437 0.7468981 -0.6207762 0.06663143 0.7811512 -0.5717488 -0.3397624 0.7467696 -0.5720521 -0.339755 0.7465406 -0.6211441 0.0476154 0.7822485 -0.6214327 0.04893618 0.7819378 -0.5722807 -0.3376635 0.747314 -0.620873 0.04999423 0.7823154 -0.5725092 -0.3388749 0.7465902 -0.5667256 -0.332739 0.7537288 -0.6145598 0.03691613 0.7880059 -0.5671874 -0.3454826 0.7476231 -0.6187449 0.08849483 0.7805917 -0.5518455 -0.329963 0.7658923 -0.600623 0.06962984 0.7964947 -0.551099 -0.3505141 0.7572515 -0.4275243 -0.6584299 0.6194295 -0.3176071 -0.7967689 0.5140867 -0.4264583 -0.6837487 0.5921326 -0.435419 -0.6745719 0.5961234 -0.4185929 -0.6980159 0.5809938 -0.4354436 -0.6736988 0.597092 -0.4413321 -0.6672801 0.5999693 -0.4310944 -0.6817865 0.591037 -0.4323019 -0.6910938 0.5792276 -0.4654021 -0.6524516 0.5980868 -0.427503 -0.6992924 0.572915 -0.4870359 -0.6410053 0.5932186 -0.4188806 -0.7360497 0.5317612 -0.4436004 -0.7395424 0.5062564 -0.5204909 -0.6679039 0.5319713 -0.480338 -0.6832641 0.5499323 -0.587556 -0.6100131 0.5316597 -0.4770955 -0.7347005 0.4822812 -0.6388733 -0.5794405 0.506053 -0.50141 -0.7461518 0.4380018 -0.6625622 -0.6001399 0.4481554 -0.5480124 -0.7270356 0.4136443 -0.6392898 -0.6737338 0.3706633 -0.6250751 -0.6625338 0.4127107 -0.6843307 -0.6298061 0.3674725 -0.5582689 -0.7748722 0.2964946 -0.7750052 -0.3371047 0.5345346 -0.7750145 -0.3369388 0.5346257 -0.7748919 -0.3379716 0.5341516 -0.7758172 -0.3333843 0.5356891 -0.7751268 -0.3365235 0.5347247 -0.6365084 0.6078695 0.4747122 -0.7431145 0.4159941 0.5241466 -0.7927088 0.2762895 0.5433938 0.7749223 -0.33743 -0.5344498 0.2418505 0.9396914 -0.2418441 0.2418276 0.9396986 -0.2418388 0.2418518 0.939693 -0.2418361 0.2418388 0.9396933 -0.2418481 0.2418401 0.9396941 -0.2418435 0.4352225 0.8290004 -0.3511977 0.4081631 0.8483306 -0.3372507 0.7750199 -0.3370472 -0.5345496 0.7750126 -0.3370872 -0.534535 0.7750334 -0.3369901 -0.534566 0.7750485 -0.3368105 -0.5346572 0.7753936 -0.3338921 -0.5359861 0.77404 -0.3450055 -0.5308797 0.7744764 -0.3391625 -0.5339991 0.775273 -0.3360444 -0.5348137 0.7749786 -0.3372119 -0.5345057 0.7751232 -0.3366276 -0.5346642 0.7750464 -0.3369393 -0.5345792 0.7750465 -0.336939 -0.5345794 0.7749066 -0.3375399 -0.534403 0.09089946 0.987841 -0.1261247 0.08426052 0.9917974 -0.09611427 0.1137331 0.9833969 -0.1414051 0.1007254 0.9913824 -0.08375865 0.1414972 0.9800042 -0.1398933 0.1468755 0.9829485 -0.1106337 0.2418494 0.9396922 -0.2418417 0.1335482 0.989556 -0.05425667 0.1609696 0.9787948 -0.1266871 0.2418492 0.9396923 -0.2418417 0.1838533 0.9769064 -0.1088662 0.2418454 0.939692 -0.2418464 0.1776083 0.9831268 -0.04378312 0.2418446 0.9396922 -0.2418465 0.1908474 0.9741419 -0.1209328 0.2418355 0.9396938 -0.2418494 0.2018013 0.9766694 -0.07343685 0.2418543 0.9396914 -0.2418398 0.2058191 0.9772459 -0.05127263 0.2088193 0.9735456 -0.0927546 0.2418316 0.939693 -0.2418563 0.2104341 0.9761544 -0.05329382 0.2418512 0.9396928 -0.2418377 0.2088742 0.9767513 -0.0482555 0.2418424 0.9396929 -0.2418459 0.2052506 0.9769676 -0.05836617 0.2418453 0.9396925 -0.2418448 0.2086023 0.9768619 -0.04717862 0.2418488 0.9396922 -0.2418425 0.1538038 0.9856085 0.07014596 0.2418478 0.9396923 -0.2418432 0.1795467 0.9805073 -0.07980281 0.1831161 0.9829813 -0.01470214 0.2418406 0.9396925 -0.2418498 0.1588947 0.9839061 -0.08173811 0.1043609 0.9932695 0.05024373 0.2418392 0.9396936 -0.2418467 0.1316816 0.9887719 -0.07064098 0.2418461 0.9396927 -0.2418432 0.2418431 0.9396932 -0.2418439 0.1374456 0.9852357 -0.1020749 0.1132392 0.9924874 -0.04632389 0.2418483 0.9396932 -0.2418391 0.1267892 0.98675 -0.1012378 0.1065028 0.9918497 -0.06993746 0.2418431 0.9396932 -0.2418444 0.1202661 0.9876919 -0.1000031 0.241845 0.939693 -0.2418433 0.1126025 0.9895986 -0.08952879 0.2418452 0.939693 -0.2418428 0.1166139 0.9880117 -0.101163 0.1128992 0.988916 -0.09643054 0.2418487 0.9396924 -0.2418413 0.1146324 0.9878664 -0.1047822 0.2418441 0.9396929 -0.2418439 0.1116362 0.9885874 -0.1011552 0.2418445 0.9396926 -0.2418448 0.1144121 0.9872722 -0.1104697 0.107959 0.9888129 -0.1029268 0.2418404 0.9396932 -0.2418471 0.114428 0.9865947 -0.1163488 0.2418457 0.9396928 -0.2418434 0.1029689 0.9893202 -0.1031639 0.2418459 0.9396926 -0.2418437 0.1120761 0.9864521 -0.119796 0.2418402 0.9396931 -0.2418473 0.09934514 0.9895424 -0.1045768 0.2418449 0.9396926 -0.241845 0.1035139 0.987658 -0.1175438 0.2418444 0.9396926 -0.2418453 0.1008334 0.9887455 -0.1105213 0.2418457 0.9396929 -0.2418431 0.1078491 0.9860652 -0.1266655 0.241848 0.9396926 -0.2418414 0.09475636 0.9890829 -0.1128551 0.1108468 0.9861166 -0.1236404 0.2418449 0.9396925 -0.2418447 0.1061363 0.98583 -0.129902 0.2418426 0.9396929 -0.241846 0.2418451 0.9396927 -0.2418439 0.09513437 0.9882643 -0.1195119 0.09869199 0.9879046 -0.1196005 0.2418462 0.9396924 -0.2418444 0.09561496 0.9874832 -0.1254385 0.2418432 0.9396927 -0.2418457 0.2418457 0.9396926 -0.2418439 0.09351325 0.988266 -0.1207712 0.2418433 0.9396924 -0.241847 0.09358745 0.9874625 -0.1271184 0.2418444 0.9396923 -0.2418466 0.2418451 0.9396922 -0.2418462 0.2418438 0.9396923 -0.2418473 0.09177696 0.9880865 -0.1235395 0.1093567 0.9846829 -0.1357969 0.241846 0.9396927 -0.2418436 0.09529393 0.9868692 -0.1304158 0.2418498 0.9396918 -0.2418428 0.2418376 0.9396938 -0.2418472 0.2418447 0.939693 -0.2418432 0.2418505 0.9396928 -0.2418385 0.09100204 0.9877594 -0.1266888 0.09207028 0.9876732 -0.1265883 0.1060581 0.9849723 -0.1363131 0.2418407 0.9396936 -0.2418448 0.09010875 0.9878332 -0.126752 0.2418462 0.9396923 -0.2418445 0.2418544 0.9396907 -0.2418428 0.2418349 0.9396935 -0.2418513 0.2418468 0.9396926 -0.2418426 0.09096622 0.9876512 -0.127555 0.09259492 0.9873763 -0.128508 0.2418476 0.939692 -0.2418439 0.0803923 0.9898458 -0.1172286 0.2418399 0.9396948 -0.241841 0.2418496 0.9396916 -0.2418441 0.2418503 0.9396914 -0.2418442 0.241849 0.9396917 -0.241844 0.2418465 0.9396924 -0.2418435 0.2418371 0.9396947 -0.2418444 0.2418484 0.9396928 -0.2418401 0.2418388 0.9396934 -0.2418475 0.09214472 0.9875534 -0.1274662 0.09136128 0.9876215 -0.1275026 0.08708554 0.9883828 -0.1245613 0.001134932 0.8454518 -0.5340507 0.1312249 0.8978259 -0.4203433 0.09777235 0.9867901 -0.1291732 0.07688462 0.9904273 -0.1146405 0.04526424 0.8249614 -0.5633737 0.1555311 0.8015537 -0.5773403 0.0459038 0.8017646 -0.5958746 0.2617179 0.7746933 -0.5756337 0.1992703 0.7479017 -0.6331936 0.3819474 0.708307 -0.5936476 0.3379273 0.8561341 -0.3909469 0.2297094 0.8583242 -0.4588173 0.3739877 0.8170858 -0.4387528 0.5065735 0.5868646 -0.6316434 0.3440952 0.8569962 -0.3836089 0.3574914 0.8376587 -0.4129502 0.3501895 0.8521454 -0.3888643 0.365135 0.8374605 -0.4066159 0.3858717 0.8147974 -0.4326759 0.3488936 0.8556108 -0.3823655 0.3521325 0.8510584 -0.3894897 0.3492842 0.855293 -0.3827197 0.3492326 0.8553408 -0.38266 0.3511173 0.8535361 -0.384958 0.3492748 0.8555455 -0.3821636 0.3496261 0.8549844 -0.383097 0.3508269 0.8542253 -0.383692 0.3568953 0.84846 -0.3908215 0.3498168 0.8560854 -0.3804551 0.3532741 0.8520026 -0.3863793 0.3535881 0.8530289 -0.3838191 0.3720284 0.8351027 -0.4052141 0.3521845 0.8563455 -0.3776748 0.3537353 0.853266 -0.3831562 0.3747633 0.8354292 -0.4020081 0.3539891 0.8576693 -0.3729547 0.3616245 0.848266 -0.3868753 0.3949296 0.8197254 -0.4148265 0.3601952 0.8565586 -0.3695493 0.3609848 0.8525782 -0.3778893 0.3539636 0.8647098 -0.356352 0.3898807 0.8300001 -0.3988643 0.3661402 0.8579593 -0.360343 0.3973293 0.8295428 -0.3924133 0.3844501 0.8474156 -0.3661763 0.3670923 0.8654818 -0.3408589 0.3892759 0.8434877 -0.3701253 0.3636182 0.8717035 -0.3285042 0.4248812 0.820619 -0.3821787 0.37743 0.8659359 -0.3281794 0.4637582 0.7961827 -0.3886147 -0.2418628 -0.9396968 0.2418103 -0.1624402 -0.984512 0.06594854 -0.2418496 -0.939692 0.2418425 -0.241845 -0.9396925 0.2418451 0.2540594 -0.8487178 -0.4638231 -0.1330632 -0.98739 0.08576226 -0.2418363 -0.9396904 0.2418621 -0.1883519 -0.9740424 -0.1255585 -0.09962612 -0.9298027 -0.3543184 -0.0807684 -0.9851543 -0.1514841 -0.2418367 -0.9396904 0.2418615 -0.2945113 -0.9471443 -0.1272033 -0.2380124 -0.9513185 -0.1958141 -0.2418344 -0.9396901 0.2418648 -0.4172196 -0.8940402 -0.1631563 -0.3468191 -0.9340882 0.08482742 -0.3848449 -0.9140987 -0.1277417 -0.4418759 -0.892562 -0.08988261 -0.494085 -0.8381713 -0.2309741 -0.3892618 -0.8504996 0.353731 -0.377187 -0.8591501 0.3458192 -0.2418459 -0.9396927 0.2418432 -0.3893638 -0.8506339 0.3532955 -0.241837 -0.9396939 0.2418476 -0.3889484 -0.8511734 0.3524528 -0.2418357 -0.9396937 0.2418495 -0.3886073 -0.8512464 0.3526531 -0.2418463 -0.9396926 0.2418431 -0.3846828 -0.8547146 0.3485428 -0.2418479 -0.9396927 0.2418411 -0.3843365 -0.8548846 0.348508 -0.2418438 -0.9396922 0.2418471 -0.3827182 -0.8565072 0.3462978 -0.2418433 -0.9396921 0.2418482 -0.2418498 -0.9396923 0.2418411 -0.3816771 -0.8571215 0.3459268 -0.2418461 -0.9396923 0.2418449 -0.3837794 -0.8557566 0.3469785 -0.2418461 -0.9396923 0.2418449 -0.3831202 -0.8561816 0.3466582 -0.2418424 -0.9396926 0.2418468 -0.3833988 -0.8558499 0.3471692 -0.2418404 -0.9396925 0.2418495 -0.3846383 -0.8550627 0.3477373 -0.2418472 -0.9396927 0.2418421 -0.3822534 -0.8566159 0.3465425 -0.2418441 -0.9396926 0.2418456 -0.3831522 -0.8560489 0.3469507 -0.2418453 -0.9396924 0.2418451 -0.3821609 -0.8563328 0.3473432 -0.2418469 -0.9396926 0.2418425 -0.2418475 -0.9396926 0.2418419 -0.3842982 -0.8549543 0.3483791 -0.2418456 -0.9396927 0.2418438 -0.3812102 -0.8566406 0.3476287 -0.2418439 -0.9396924 0.2418463 -0.3841665 -0.8546763 0.3492055 -0.2418434 -0.9396929 0.241845 -0.380801 -0.8565086 0.3484014 -0.2418418 -0.9396927 0.2418475 -0.3836933 -0.8545252 0.3500945 -0.2418445 -0.9396929 0.2418438 -0.3809263 -0.8558564 0.3498642 -0.3834117 -0.8541004 0.351437 -0.2418441 -0.9396923 0.2418463 -0.3815925 -0.8547256 0.3518968 -0.2418487 -0.9396927 0.2418409 -0.2418456 -0.9396927 0.2418438 -0.374232 -0.8587597 0.3499745 -0.2418466 -0.9396931 0.241841 -0.2418414 -0.9396925 0.2418486 -0.3818574 -0.8545082 0.3521373 -0.2418437 -0.9396927 0.2418454 -0.363521 -0.8641896 0.3478921 -0.2418437 -0.9396927 0.2418453 -0.3447934 -0.8807038 0.3247745 -0.3694062 -0.8621196 0.346827 -0.3808914 -0.8520153 0.359154 -0.2418443 -0.9396926 0.2418454 -0.3633277 -0.8614912 0.3547199 -0.241845 -0.9396926 0.2418447 -0.3591107 -0.8676897 0.3437354 -0.3770242 -0.8521457 0.3629058 -0.2418463 -0.9396927 0.2418429 -0.3585724 -0.8624625 0.3571892 -0.241844 -0.9396926 0.2418457 -0.3599871 -0.8642789 0.3513279 -0.3743842 -0.8506255 0.3691513 -0.241847 -0.9396927 0.2418422 -0.3633996 -0.8555071 0.3688471 -0.2418466 -0.9396926 0.2418426 -0.3672775 -0.8546076 0.3670874 -0.2418439 -0.9396923 0.241847 -0.3563221 -0.8589593 0.3677276 -0.2418453 -0.9396927 0.2418437 -0.3589105 -0.8596252 0.363631 -0.3654925 -0.851383 0.3762475 -0.2418496 -0.939693 0.2418384 -0.3555102 -0.8572275 0.3725233 -0.3630108 -0.8508917 0.3797454 -0.2418392 -0.9396927 0.2418495 -0.3589972 -0.8515276 0.382128 -0.2418432 -0.9396929 0.2418453 -0.3500688 -0.8569621 0.3782432 -0.2418425 -0.9396927 0.2418469 -0.3570124 -0.8535878 0.379381 -0.2418457 -0.9396932 0.2418416 -0.3367158 -0.8640137 0.3743032 -0.3640333 -0.8409975 0.4002536 -0.2418432 -0.9396932 0.2418444 -0.3736846 -0.8055182 0.4598914 -0.2418456 -0.9396935 0.2418406 -0.3189634 -0.8607025 0.3968042 -0.2418445 -0.9396931 0.2418432 -0.3417666 -0.8506108 0.3995708 -0.2418434 -0.9396929 0.241845 -0.4128419 -0.4902518 0.7676033 -0.2418488 -0.9396938 0.2418364 -0.2849529 -0.8633116 0.4165271 -0.3135187 -0.8573095 0.4083216 -0.2418404 -0.9396933 0.2418465 -0.2664266 -0.8749207 0.4043894 -0.2936245 -0.8182291 0.4942528 -0.2418457 -0.9396922 0.2418454 -0.2657153 -0.8632299 0.4292196 -0.241847 -0.939693 0.241841 -0.2654022 -0.8641061 0.4276475 -0.2418455 -0.939692 0.241846 -0.2712818 -0.8760588 0.3986567 -0.2418395 -0.9396916 0.241854 -0.2993133 -0.8496306 0.4342113 -0.2712942 -0.8759921 0.3987947 -0.2418453 -0.939697 0.2418275 -0.2822374 -0.9011542 0.329034 -0.2418463 -0.9396911 0.241849 -0.2418433 -0.939693 0.2418451 -0.3376395 -0.8542281 0.3953401 -0.3055718 -0.8626326 0.4031015 -0.2418431 -0.939693 0.2418453 -0.3745688 -0.8340357 0.4050715 -0.3146466 -0.8832954 0.3475437 -0.2418596 -0.9396848 0.2418601 -0.377132 -0.8480789 0.3722012 -0.2418464 -0.9396924 0.2418443 -0.3411925 -0.8752343 0.3428598 -0.2418419 -0.9396953 0.241837 -0.3728454 -0.8626093 0.341894 -0.382161 -0.8552565 0.3499846 0.7752976 -0.3359697 -0.5348253 0.7749567 -0.3372778 -0.5344958 0.7761587 -0.3327574 -0.5355839 0.7748241 -0.3377871 -0.5343664 0.7754442 -0.3354179 -0.5349591 0.7743599 -0.3395844 -0.5339001 -0.004573166 -0.995086 0.09890758 0.7737452 -0.3421736 -0.5331375 -0.09846085 -0.9843138 0.1463956 -0.05167949 -0.9902859 0.1290856 -0.1205594 -0.9810821 0.1514701 -0.01711905 -0.9960982 0.08657473 -0.1290171 -0.9805825 0.1476905 -0.02575099 -0.99708 0.07188981 -0.1295687 -0.9819347 0.1378993 -0.04230868 -0.9969135 0.06613254 -0.1262362 -0.9840541 0.1253075 -0.05829924 -0.9962714 0.06359684 -0.1188678 -0.9868441 0.1095861 -0.07803213 -0.9945628 0.0689637 -0.1056638 -0.9904881 0.08813881 -0.1237121 -0.9869154 0.1034082 -0.1007036 -0.9915102 0.08225792 -0.08935886 -0.9942873 0.05837661 -0.1226367 -0.9878854 0.0950936 -0.1178008 -0.9886048 0.09372049 -0.1016454 -0.9925782 0.06675958 -0.1246681 -0.9877691 0.09364902 -0.1202095 -0.9885897 0.09077519 -0.1182914 -0.9893812 0.08445179 -0.1251263 -0.9878348 0.09233582 -0.1201986 -0.9889289 0.08701777 -0.124968 -0.9879153 0.09168559 -0.1238903 -0.988195 0.09012198 -0.1238089 -0.9882153 0.09001082 -0.125383 -0.9878805 0.0914945 -0.1250473 -0.9879071 0.09166622 -0.1171491 -0.98995 0.07921463 -0.07437521 -0.9970265 0.02016329 -0.131129 -0.9872146 0.090622 -0.1221197 -0.9888722 0.08496218 -0.107706 -0.9928088 0.0522502 -0.8000386 0.2267135 0.555463 -0.775026 0.337035 0.5345485 -0.7750336 0.3370164 0.5345491 -0.8072747 0.1477336 0.5713864 -0.7549734 0.4057438 0.5151573 -0.7482269 0.3392837 0.5701256 -0.7434083 0.3573996 0.5653403 -0.6811254 0.5157677 0.5196652 -0.7434648 0.3492318 0.5703482 -0.7788046 0.1503617 0.6089786 -0.7434898 0.3399831 0.5758772 -0.680847 0.519236 0.5165669 -0.7436742 0.3396297 0.5758475 -0.5809783 -0.05944013 -0.8117457 -0.5214521 0.1281746 -0.8435987 -0.7458344 0.3391695 0.5733193 -0.6828113 0.5194651 0.5137358 -0.6872764 0.5065456 0.5206369 -0.747725 0.3389384 0.5709886 -0.6890479 0.5094413 0.515444 -0.7459009 0.3400074 0.5727362 -0.7492875 0.3387594 0.5690435 -0.6867499 0.5179075 0.5100455 -0.7478455 0.3398979 0.5702601 -0.6885798 0.510403 0.5151181 -0.7505159 0.3387603 0.5674217 -0.6934744 0.5054091 0.5134733 -0.7494738 0.3397654 0.5681975 -0.7515951 0.3386241 0.5660728 -0.6898089 0.5159892 0.5078572 -0.7507349 0.3395847 0.5666385 -0.6889256 0.5148871 0.5101693 -0.7523437 0.3387408 0.5650076 -0.690127 0.5169571 0.5064387 -0.7517054 0.3392746 0.5655369 -0.6917096 0.5122077 0.5090982 -0.7527112 0.3388873 0.5644301 -0.6911882 0.5154667 0.5065107 -0.752377 0.3390566 0.564774 -0.6917378 0.5140554 0.507194 -0.7527583 0.3389976 0.564301 -0.6912787 0.5154281 0.5064263 -0.7527191 0.3390195 0.5643402 -0.7524783 0.339069 0.5646315 -0.6913368 0.5147315 0.5070552 -0.752751 0.3389026 0.5643676 -0.6907615 0.5164521 0.5060888 -0.7518835 0.3391876 0.5653522 -0.6887995 0.519158 0.5059945 -0.7524538 0.338811 0.5648189 -0.7509855 0.3393607 0.5664409 -0.6899402 0.5147919 0.508893 -0.7518342 0.3387626 0.5656723 -0.6900603 0.5165953 0.5068985 -0.7498325 0.3395783 0.5678362 -0.6891524 0.5141758 0.5105803 -0.7509062 0.3387868 0.5668893 -0.686467 0.5214426 0.5068142 -0.7484367 0.3397255 0.5695868 -0.6859017 0.5184971 0.5105875 -0.7497016 0.3387676 0.5684927 -0.7467412 0.3400847 0.5715941 -0.6869219 0.5127469 0.5150038 -0.7482023 0.3384461 0.5706555 -0.6836381 0.5229523 0.5090776 -0.7449228 0.3401569 0.5739192 -0.6797006 0.5249068 0.512328 -0.7461266 0.3384968 0.5733368 -0.742954 0.3400123 0.5765509 -0.6831533 0.5129255 0.5198164 -0.7437471 0.3387687 0.5762605 -0.6808656 0.5225937 0.5131451 -0.74015 0.340802 0.5796826 -0.6800171 0.5143137 0.5225498 -0.7410221 0.3393144 0.5794413 -0.6745248 0.5283308 0.5156384 -0.736719 0.3414292 0.5836706 -0.6747975 0.5189153 0.5247622 -0.7383211 0.3390308 0.5830438 -0.7331525 0.34158 0.5880566 -0.6755411 0.5094749 0.5329912 -0.7351271 0.3385253 0.5873574 -0.6696976 0.5289593 0.5212556 -0.7293331 0.3416088 0.5927703 -0.6691442 0.5156094 0.5351569 -0.7310687 0.3388817 0.5921974 -0.6619913 0.534051 0.525887 -0.7252194 0.341778 0.5976994 -0.663889 0.5185478 0.5388502 -0.7268525 0.3392187 0.5971734 -0.7209224 0.3419462 0.6027799 -0.6636351 0.5096769 0.5475563 -0.7224383 0.3396061 0.6022879 -0.6548083 0.5360975 0.5327529 -0.7169284 0.3400896 0.6085661 -0.6475294 0.5359463 0.5417261 -0.7172905 0.3394286 0.6085085 -0.7118025 0.3419529 0.613519 -0.6541989 0.5109323 0.5576487 -0.6500656 0.5309755 0.5435804 -0.7067684 0.3429808 0.6187427 -0.6299275 0.5539128 0.5444007 -0.7113433 0.3387368 0.6158313 -0.693713 0.3549593 0.6267106 -0.6414549 0.5072048 0.5755683 -0.6957837 0.350506 0.6269214 -0.7051476 0.3386927 0.6229398 -0.6449754 0.5244142 0.5558745 -0.6779833 0.3553562 0.6434754 -0.6455379 0.4578101 0.6113024 -0.6851493 0.3430536 0.642561 -0.6920314 0.3407115 0.6364025 -0.6710987 0.4352014 0.6001886 -0.6151592 0.5481626 0.5666542 -0.6622827 0.3538218 0.6604483 -0.6144891 0.4970155 0.6126815 -0.6775141 0.3251388 0.6597419 -0.6107702 0.5339029 0.5847284 -0.6465649 0.3518429 0.6768755 -0.6052104 0.4798678 0.6351749 -0.6586212 0.329522 0.6764861 -0.6146162 0.4967293 0.6127863 -0.5851387 0.5353694 0.6090913 -0.6310931 0.3500837 0.692216 -0.5888741 0.4813104 0.6492825 -0.6412454 0.3326556 0.6914799 -0.5647506 0.5494665 0.6157461 -0.6163319 0.3483975 0.7062255 -0.5695548 0.4923083 0.6582096 -0.62563 0.3344068 0.7048114 -0.5480397 0.5531643 0.6274247 -0.6019817 0.3475478 0.718908 -0.5502389 0.5046567 0.6652509 -0.6117259 0.3356457 0.7163333 -0.5350129 0.5469013 0.6439413 -0.5779062 0.3524593 0.7360686 -0.5154956 0.5342423 0.6699622 -0.5984793 0.334358 0.7280297 -0.5320171 0.3510714 0.7705236 -0.4998503 0.4559634 0.7363743 -0.5740246 0.3299793 0.749406 -0.4983914 0.5680672 0.6549088 -0.4636945 0.3429182 0.8169422 -0.4538742 0.3784752 0.8066937 -0.4669 0.338436 0.8169856 -0.529107 0.3308763 0.7813876 -0.3658428 0.6953565 0.6185777 -0.3683125 0.3477171 0.8622289 -0.1944402 0.7632582 0.6161412 -0.4014052 0.314026 0.8603847 -0.2632773 0.3300968 0.9064884 -0.2402678 0.4109604 0.879422 -0.3178501 0.2877579 0.9034195 -0.2839142 0.6209572 0.7306196 -0.1877254 0.2971908 0.9361821 0.01388454 0.83255 0.553776 -0.2181181 0.2691541 0.9380728 -0.1512429 0.2726203 0.9501598 -0.1019815 0.4495313 0.8874241 -0.1490065 0.2756721 0.9496326 -0.1530513 0.5231155 0.8384064 -0.1371957 0.2796064 0.9502618 -0.06735217 0.5212815 0.8507227 -0.1491769 0.2883054 0.9458469 -0.09425026 0.480829 0.8717341 -0.1468309 0.2909542 0.9454027 -0.09258908 0.4572513 0.8845046 -0.1927883 0.2840881 0.939216 -0.1937511 0.28031 0.9401525 -0.2641636 0.2858152 0.9211554 -0.1811167 0.5554666 0.8115748 -0.2067031 0.317087 0.9255968 -0.1952986 0.2755998 0.9412242 -0.3575132 0.2978969 0.8851225 -0.3840348 0.1772577 0.906144 -0.3051922 0.336835 0.89073 -0.4542633 0.310783 0.8349006 -0.3535455 0.6021469 0.7158384 -0.4148328 0.3477047 0.8408419 -0.4044395 0.09519922 0.9095966 -0.5430805 0.319672 0.7764492 -0.5611678 0.2362427 0.7932718 -0.511826 0.3564118 0.781668 -0.6220217 0.3267371 0.71157 -0.5115844 0.6183019 0.5966442 -0.5990087 0.3601351 0.7151863 -0.5525255 0.2696487 0.788673 -0.6901039 0.3329967 0.6425495 -0.5852824 0.6049729 0.5398633 -0.6759432 0.357856 0.6442359 -0.6831746 0.2254889 0.6945699 -0.7203015 0.0731911 0.6897889 -0.7621196 0.247378 0.5983125 -0.6504297 -0.002474665 0.7595624 -0.6333418 0.4280465 0.6447126 -0.4172512 0.6096713 0.6739453 -0.4680678 0.07743823 0.880293 -0.5550336 0.2575145 0.790964 -0.1033439 0.8144465 0.5709613 -0.2567274 0.1003414 0.9612609 -0.3963935 0.1438093 0.9067475 -0.2064792 0.02999353 0.9779911 -0.179416 0.3365328 0.9244217 -0.1815294 0.1399361 0.9733782 -0.189867 0.07607525 0.978858 -0.2766492 -0.01369535 0.9608734 -0.3271117 0.2489634 0.9116003 -0.3028244 -0.132698 0.9437631 -0.4664516 -0.2311332 0.8538151 -0.4917943 0.2295652 0.8399037 -0.4542205 -0.09998548 0.8852608 -0.5785088 -0.1663917 0.7985244 -0.6065126 0.1596875 0.7788726 -0.5526518 0.1249615 0.8239906 -0.6281512 0.1840917 0.7560002 -0.6249421 0.04614394 0.7793061 -0.6437694 0.1673856 0.7466881 -0.6465556 0.1055463 0.7555302 -0.6582384 0.1581841 0.7360027 -0.6600282 0.1307342 0.7397779 -0.6714035 0.1719701 0.7208631 -0.6734483 0.145437 0.7247865 -0.6823707 0.2104141 0.7000687 -0.6885111 0.1352446 0.7125037 -0.695354 0.2392277 0.6776821 -0.703332 0.1148406 0.7015239 -0.7186722 0.1593651 0.6768406 -0.7132273 0.1382641 0.6871607 -0.7250905 0.1571934 0.670473 -0.7260161 0.1175794 0.6775514 -0.7323884 0.1466001 0.6649177 -0.736523 0.1662486 0.655664 -0.7354422 0.1251879 0.6659225 -0.7434366 0.1590478 0.6496196 -0.7446163 0.1238199 0.6559079 -0.7512304 0.1412211 0.6447554 -0.7547988 0.1573432 0.636806 -0.7514019 0.1399124 0.6448408 -0.7590633 0.1573861 0.631706 -0.7597026 0.1272619 0.6376962 -0.7645825 0.1423504 0.6286096 -0.7669785 0.1584006 0.6218146 -0.7652235 0.1374496 0.6289201 -0.7707138 0.1539571 0.6183022 -0.7711116 0.1323638 0.6227895 -0.7742267 0.1457972 0.6158865 -0.7758406 0.1558701 0.6113721 -0.7752882 0.1379249 0.6163643 -0.7786234 0.1507425 0.6091162 -0.7790597 0.1384497 0.6114717 -0.7808446 0.1488705 0.6067283 -0.7820575 0.1526836 0.6042135 -0.7817305 0.1423497 0.6071524 -0.7842955 0.1411678 0.6041128 -0.7843767 0.1505273 0.6017431 -0.7834031 0.1483641 0.6035459 -0.7849931 0.1506415 0.6009101 -0.7850525 0.1460089 0.6019749 -0.7855042 0.1485518 0.6007624 -0.7854381 0.1492562 0.6006743 -0.7854232 0.1491796 0.6007129 -0.7851338 0.1489812 0.6011403 -0.7850933 0.1515248 0.600557 -0.7842509 0.15189 0.6015648 -0.7837904 0.1473008 0.6033034 -0.7840912 0.153047 0.6014795 -0.7823945 0.1494005 0.6045976 -0.7821059 0.1566612 0.6031315 -0.7806895 0.1507036 0.6064754 -0.7793377 0.1446959 0.6096686 -0.7794859 0.1589096 0.6059287 -0.7768898 0.1463021 0.6124034 -0.7762737 0.1603882 0.6096513 -0.5809765 -0.05934268 -0.8117542 -0.6293131 -0.4145163 -0.6573744 -0.599959 -0.2474467 -0.7608019 -0.4164566 -0.124542 -0.9005848 -0.2948023 0.238301 -0.9253671 -0.2948068 0.2378743 -0.9254754 -0.4445097 0.3046564 -0.842375 -0.3119059 0.4892243 -0.8144779 -0.4142026 0.3380832 -0.8450656 -0.416378 -0.1246867 -0.9006012 -0.4767689 -0.4690731 -0.7434123 0.3327729 -0.3144066 -0.8890504 0.3728755 -0.1288823 -0.918887 0.332838 -0.3145028 -0.888992 0.5158376 -0.3356519 -0.7881938 0.5145205 0.5123702 -0.6875648 0.5707948 -0.1474517 -0.8077446 -0.04521507 -0.2381256 -0.9701813 0.04908901 0.1328472 -0.9899201 -0.04530924 -0.2379831 -0.9702119 0.339003 0.2526428 -0.9062277 0.399316 0.06207472 -0.9147095 0.04902851 0.1332316 -0.9898715 -0.1329636 -0.5740323 -0.8079651 -0.4768103 -0.4689415 -0.7434687 0.2173749 -0.644953 -0.7326554 -0.1329353 -0.5741568 -0.8078814 0.5162889 -0.343101 -0.784683 0.4611954 -0.5123003 -0.7244634 0.2056765 -0.4727278 -0.8568696 0.8320367 -0.3379405 -0.439899 0.8613197 -0.1839239 -0.4736037 0.8335397 -0.3288333 -0.4439371 0.8158524 -0.3236578 -0.4791978 0.83456 -0.2318704 -0.4997456 0.8655668 -0.02891612 -0.4999579 0.8314971 0.2026357 -0.5172538 0.7943493 -0.3170005 -0.5181891 0.8254171 -0.009020447 -0.5644513 0.8055674 -0.3513009 -0.4771254 0.7700667 -0.3083935 -0.5584717 0.7713783 -0.3026025 -0.5598278 0.7750277 -0.3676202 -0.5139917 0.8188183 0.07268452 -0.5694326 0.7429364 -0.3021516 -0.5972855 0.7302111 -0.3538373 -0.5844579 0.7400365 -0.3841369 -0.5520731 0.7750837 0.1506636 -0.6136331 0.7130876 -0.3073419 -0.6301167 0.7202162 -0.2738784 -0.6374004 0.7046754 -0.3919424 -0.5914507 0.748009 0.103864 -0.6555112 0.6829277 -0.3249072 -0.6542515 0.7204431 0.002023279 -0.6935111 0.6758586 -0.3807784 -0.6310491 0.6565831 -0.3425526 -0.6719793 0.6853386 -0.1987967 -0.7005646 0.654201 -0.3598489 -0.6652292 0.7201393 -0.07496893 -0.6897674 0.6388992 -0.3413359 -0.6894184 0.6646896 -0.2174192 -0.7147845 0.6928285 0.04375493 -0.7197737 0.6260426 -0.3343358 -0.7044788 0.6680256 -0.04376411 -0.7428502 0.6342279 -0.3527534 -0.6879826 0.614323 -0.3338176 -0.7149637 0.6425956 -0.1910037 -0.7420166 0.6171849 -0.3531181 -0.7031289 0.6682169 -0.03276711 -0.7432445 0.6042185 -0.3359008 -0.7225585 0.6477049 -0.04397642 -0.7606211 0.604861 -0.3500891 -0.7152487 0.5958691 -0.3385195 -0.7282476 0.6284109 -0.1714078 -0.7587615 0.5958211 -0.3460982 -0.724716 0.6473103 -0.05667197 -0.7601169 0.5891847 -0.3408496 -0.7325865 0.6295962 -0.1106281 -0.7690059 0.5891304 -0.3423449 -0.7319327 0.5847331 -0.3396556 -0.7366961 0.6326555 0.03604394 -0.7735942 0.5813466 -0.3387669 -0.7397791 0.6165783 -0.1539735 -0.7720903 0.5835862 -0.3418118 -0.7366084 0.6256071 -0.1356645 -0.7682518 0.578676 -0.3387824 -0.7418628 0.6189173 -0.1108824 -0.7775902 0.5796306 -0.3414129 -0.7399092 0.5766648 -0.3391122 -0.7432769 0.6221646 -0.04815137 -0.7814043 0.5770136 -0.3406954 -0.7422816 0.5752887 -0.3394411 -0.7441927 0.6110879 -0.1520543 -0.7768211 0.5753706 -0.3400322 -0.7438595 0.6163344 -0.1334191 -0.7761 0.5743653 -0.3396633 -0.7448043 0.6111719 -0.1446632 -0.7781655 0.5743637 -0.3396438 -0.7448143 0.5739631 -0.3395136 -0.7451825 0.6119329 -0.1347717 -0.7793425 0.573897 -0.3395163 -0.7452322 0.6121366 -0.1324977 -0.7795724 0.5739321 -0.3395578 -0.7451862 0.5737308 -0.3392263 -0.7454922 0.6095453 -0.1518093 -0.7780799 0.5738652 -0.3395537 -0.7452396 0.6104685 -0.1489341 -0.7779118 0.5719483 -0.3386895 -0.7471042 0.6097711 -0.1347858 -0.7810326 0.5723394 -0.3404437 -0.7460064 0.5679556 -0.3390979 -0.7499594 0.6139312 -0.0480175 -0.7878977 0.5681324 -0.3405386 -0.7491724 0.5616325 -0.3411132 -0.7537975 0.6100208 0.1404746 -0.7798343 0.5614996 -0.3389565 -0.7548688 0.5551782 -0.3365489 -0.7605998 0.5894096 -0.1620554 -0.791413 0.6090685 -0.1026266 -0.7864498 0.5459469 -0.3342126 -0.7682734 0.5895301 -0.07791459 -0.8039799 0.5505282 -0.3424754 -0.7613338 0.5335159 -0.3327303 -0.7775933 0.5823161 0.1730971 -0.7943207 0.5361238 -0.3439664 -0.7708815 0.3259491 -0.7865375 -0.524515 0.4970737 -0.5069602 -0.7042082 0.381215 -0.7032894 -0.6000493 0.5004976 -0.5231235 -0.6898145 0.459042 -0.6261422 -0.630259 0.4044405 -0.723185 -0.5598493 0.5160399 -0.5153989 -0.6841542 0.5039061 -0.5293131 -0.6825733 0.5157718 -0.5162153 -0.6837407 0.5111715 -0.5284073 -0.6778566 0.5184061 -0.5135354 -0.6837664 0.5140073 -0.5211883 -0.6812924 0.5130366 -0.5308088 -0.6745632 0.4834123 -0.6008535 -0.636622 0.5277357 -0.5116838 -0.6779932 0.5170365 -0.523656 -0.6770951 0.4856533 -0.6147976 -0.6214217 0.5463142 -0.498256 -0.673262 0.5162252 -0.5480551 -0.6581392 0.5505002 -0.5126433 -0.6588978 0.4969033 -0.618505 -0.6087191 0.558548 -0.5243374 -0.6427243 0.6127646 -0.4249205 -0.6663048 0.5052738 -0.6393977 -0.579542 0.642583 -0.3998811 -0.6535918 0.5081064 -0.6749463 -0.5350471 0.6708693 -0.3974065 -0.6261009 0.5459427 -0.6596582 -0.5165246 0.6987489 -0.410772 -0.585676 0.5884568 -0.6417632 -0.4917913 0.628812 -0.6331053 -0.4514122 0.7251227 -0.5047047 -0.4684766 0.6846078 -0.5258409 -0.5047807 0.8018999 -0.3642496 -0.4735807 0.6070026 -0.7079764 -0.3609946 0.7818266 -0.4802444 -0.3976336 0.5848587 -0.7650123 -0.2696225 0.7751825 -0.3375203 -0.5340151 0.7749751 -0.3371692 -0.5345377 0.6311007 -0.7143009 -0.3024666 0.7794896 -0.3135474 -0.5422949 0.774387 -0.3401438 -0.5335044 0.371649 -0.9189924 -0.1316435 0.4811583 -0.8524018 -0.2046896 0.1764073 -0.984233 -0.0128805 0.5927916 0.6786265 -0.4336637 0.6681601 0.579595 -0.4665101 0.6015713 0.6679903 -0.438065 0.7597839 0.4130395 -0.5021226 0.8055821 0.2893196 -0.5170412 0.8301887 0.204011 -0.5188123 0.7884739 0.3409337 -0.5119307 0.8564224 0.03726798 -0.514929 0.4974568 0.5941252 -0.6321014 0.3872208 0.5996181 -0.70037 0.5147072 0.5962314 -0.6161044 0.5004146 0.5867951 -0.6365979 0.5199685 0.592936 -0.6148655 0.5180172 0.5887233 -0.6205346 0.5209482 0.5952414 -0.6118012 0.520435 0.5918955 -0.6154732 0.5242596 0.5988258 -0.6054417 0.5243175 0.5877757 -0.6161257 0.5295638 0.6041219 -0.5954821 0.5319741 0.5820471 -0.6149998 0.5367773 0.6107555 -0.5821064 0.5436399 0.5744056 -0.6119754 0.545799 0.6183086 -0.5655068 0.559624 0.5643416 -0.6069099 0.5559933 0.6271881 -0.5454417 0.5797556 0.5523892 -0.5989572 0.5670784 0.6369314 -0.5222457 0.6040784 0.5384649 -0.5874904 0.5785402 0.6473485 -0.496217 0.6321387 0.5231844 -0.5715581 0.590323 0.657585 -0.4680817 0.6635185 0.50662 -0.5505266 0.6965609 0.4907399 -0.5234284 0.5782518 0.2409328 -0.7794718 0.6056215 0.243842 -0.7574718 0.5790451 0.233996 -0.7809948 0.6117861 0.2397688 -0.7538095 0.6067718 0.2353615 -0.7592319 0.6147181 0.2421026 -0.7506716 0.6120051 0.2381968 -0.75413 0.6219373 0.2464649 -0.7432692 0.6158992 0.2337278 -0.7523561 0.6333275 0.2527679 -0.7314401 0.6247416 0.2272517 -0.7470306 0.6487086 0.2604321 -0.715089 0.6386495 0.2181628 -0.7379239 0.6675346 0.2703239 -0.6937742 0.6574441 0.2073016 -0.7244262 0.6893286 0.2819032 -0.6673506 0.6810516 0.1942489 -0.706 0.7132972 0.2951421 -0.6356874 0.7091059 0.1794791 -0.6818768 0.7385522 0.3095893 -0.5989117 0.7409719 0.163442 -0.6513428 0.7638307 0.3254437 -0.557359 0.7754599 0.1480997 -0.6137821 0.8113365 0.1334057 -0.5691537 -0.086066 0.7769208 -0.6236881 -0.209985 0.657468 -0.7236311 -0.1685414 0.981909 0.08630371 -0.2137094 0.9696725 0.1185907 -0.3155679 0.9269783 0.2028006 -0.4518367 0.8328229 0.3197647 -0.4857856 0.8032761 0.3446156 -0.5777994 0.6975528 0.4237547 -0.4836406 0.8037155 0.3466023 -0.4831411 0.804175 0.346233 -0.2119595 0.9698444 0.1203129 -0.2114751 0.9699937 0.1199604 -0.4869473 0.8044832 0.3401311 -0.4891688 0.8041675 0.3376812 -0.4882608 0.8032813 0.3410874 -0.4907646 0.8038725 0.3360641 -0.4901282 0.8032909 0.3383759 -0.4916915 0.8036425 0.3352586 -0.4913426 0.803345 0.336481 -0.491912 0.8035082 0.3352571 -0.4918726 0.8034772 0.335389 -0.4914668 0.80344 0.3360723 -0.491755 0.8036513 0.3351441 -0.4903788 0.8033949 0.3377653 -0.4910306 0.8038381 0.3357577 -0.4886452 0.8033861 0.3402891 -0.4896783 0.8040348 0.3372583 -0.4861165 0.8035176 0.3435845 -0.4875776 0.8043629 0.3395121 -0.4831241 0.803475 0.347878 -0.4850436 0.8045013 0.3427979 -0.4790907 0.803775 0.3527291 -0.4815072 0.8049613 0.3466817 -0.4746259 0.8038253 0.3586016 -0.4775829 0.8051655 0.3516009 -0.4691385 0.804146 0.3650454 -0.4726832 0.8056235 0.3571292 -0.4631901 0.8041833 0.3724838 -0.4673654 0.8057948 0.3636816 -0.4562089 0.8044501 0.3804387 -0.4610575 0.8061769 0.3708164 -0.448462 0.8046627 0.3891015 -0.4540334 0.8064956 0.3787064 -0.4399559 0.8047814 0.3984543 -0.446293 0.8067158 0.3873399 -0.4304648 0.804995 0.4082686 -0.4376106 0.8070181 0.396508 -0.4202684 0.8050131 0.4187223 -0.4282526 0.8071226 0.4063898 -0.4093441 0.8048197 0.4297705 -0.4182085 0.8070139 0.4169294 -0.3973198 0.8047887 0.440967 -0.4070742 0.8070483 0.4277425 -0.3845818 0.8045093 0.4526162 -0.3952587 0.806836 0.4390744 -0.3710473 0.8042521 0.4642223 -0.3824964 0.8066073 0.4506453 -0.3492251 0.8022681 0.4841568 -0.3690966 0.8062413 0.4623231 -0.2955768 0.7963008 0.5277684 -0.3452283 0.8064443 0.4800677 -0.193551 0.7829136 0.5912566 -0.2885878 0.8041062 0.5197406 -0.05297791 0.7614626 0.6460402 -0.1849838 0.7939435 0.5791673 0.0156064 0.7541104 0.6565622 -0.04750412 0.7703791 0.6358139 -0.02418547 0.7650058 0.6435691 0.0160821 0.7549915 0.6555373 -0.162851 0.7881613 0.5935328 -0.02703529 0.7601674 0.6491646 -0.3113034 0.8031342 0.5080018 -0.167697 0.7817047 0.6006791 -0.4130451 0.8067312 0.4225856 -0.3143721 0.7997912 0.5113747 -0.4149171 0.8049022 0.4242362 -0.2136076 0.9700672 0.1155056 -0.2151682 0.9699056 0.1139548 -0.2152276 0.9695708 0.1166599 -0.2163012 0.9697713 0.1129496 -0.2163183 0.9695538 0.1147685 -0.2170185 0.9696614 0.1125159 -0.2170146 0.9695532 0.1134521 -0.2173033 0.9695828 0.1126434 -0.2173019 0.9695748 0.1127151 -0.2171035 0.9695524 0.1132882 -0.2171314 0.9696353 0.1125227 -0.2164351 0.9695619 0.1144793 -0.2165237 0.9697296 0.1128798 -0.2153818 0.9695826 0.1162766 -0.2155641 0.9698284 0.1138629 -0.2137871 0.9696589 0.1185601 -0.2140998 0.9699756 0.1153631 -0.2116771 0.9697743 0.1213692 -0.2121619 0.9701581 0.1173914 -0.2092357 0.9698657 0.1248238 -0.2099303 0.9703121 0.1200983 -0.2061202 0.97003 0.1286713 -0.2070714 0.9705342 0.1232272 -0.2026314 0.9701633 0.13313 -0.2038834 0.9707235 0.1269944 -0.1984899 0.9703406 0.1379886 -0.2000934 0.9709538 0.1311923 -0.1939554 0.970468 0.1434332 -0.1959552 0.9711343 0.1360133 -0.1888391 0.9705931 0.1492944 -0.1912778 0.9713122 0.1412988 -0.1831004 0.9707146 0.1555234 -0.1860312 0.9714851 0.1470003 -0.1768662 0.9707783 0.1621968 -0.1803312 0.971602 0.1531999 -0.1700369 0.9708059 0.1691843 -0.1740726 0.9716829 0.1597847 -0.1625257 0.9708105 0.1763867 -0.1671805 0.9717413 0.1666419 -0.1545842 0.9706996 0.1839725 -0.1598793 0.9716885 0.1739537 -0.146036 0.9705171 0.1917549 -0.1520109 0.9715665 0.1815249 -0.1369668 0.9702821 0.1994817 -0.1435329 0.9713745 0.1892876 -0.1228005 0.9691725 0.2135996 -0.1345817 0.9711138 0.1970426 -0.08760112 0.9657081 0.244405 -0.1178345 0.970963 0.2081968 -0.01953536 0.9571975 0.2887757 -0.07919639 0.9690473 0.2338272 0.07522791 0.9426007 0.325338 -0.009852409 0.9619962 0.2728853 0.121802 0.9368555 0.3278198 0.08100271 0.9468266 0.3113808 0.09524536 0.9435909 0.3171194 0.1221507 0.9371742 0.3267778 0.002918422 0.9590085 0.2833622 0.09233492 0.9413109 0.3246659 -0.09622973 0.9691003 0.227122 -0.002647399 0.9560976 0.2930366 -0.16446 0.9715055 0.1706747 -0.1001812 0.9675849 0.2318263 -0.1666448 0.9707836 0.172652 0.3099088 -0.8018582 -0.5108621 0.1460392 -0.7777047 -0.6114311 0.3401432 -0.8010163 -0.4926211 0.3135585 -0.7972872 -0.5157657 0.3353919 -0.8062885 -0.4872486 0.3438944 -0.8034422 -0.4860219 0.3431906 -0.8042178 -0.4852361 0.3494896 -0.8010755 -0.4859372 0.3449124 -0.8061047 -0.4808645 0.3609983 -0.7975816 -0.4832638 0.3500773 -0.8094778 -0.4713721 0.378504 -0.7927528 -0.4777845 0.3587687 -0.8139672 -0.4568835 0.4016031 -0.7868567 -0.4685845 0.3707718 -0.8194066 -0.437151 0.4305942 -0.7791531 -0.4555315 0.3853532 -0.8258929 -0.4115871 0.4648812 -0.7696518 -0.4376317 0.4024409 -0.8326434 -0.3804553 0.5039347 -0.7579081 -0.4142768 0.4212307 -0.8393353 -0.3436288 0.5459877 -0.7444941 -0.3842211 0.4412463 -0.8451778 -0.3016225 0.5893262 -0.729532 -0.3470989 0.4614011 -0.8497835 -0.2549062 0.1676154 -0.9848078 -0.04537397 0.3309836 -0.9303506 -0.1577903 0.1587064 -0.9843689 -0.07635539 0.2913124 -0.9398646 -0.1783018 0.1501993 -0.983025 -0.1053655 0.2537637 -0.9477843 -0.1931552 0.1420546 -0.9810847 -0.1315044 0.220061 -0.9540312 -0.2034637 0.1347235 -0.9787755 -0.1544286 0.190809 -0.9588997 -0.2100076 0.1282958 -0.9764187 -0.1736283 0.166659 -0.9625233 -0.2139481 0.123414 -0.9741249 -0.1893405 0.1473878 -0.9652659 -0.2157279 0.1198279 -0.9722375 -0.2009866 0.1332995 -0.9671793 -0.2163227 0.1179689 -0.9708099 -0.2088336 0.1236555 -0.9686547 -0.2154467 0.1176645 -0.9700385 -0.2125569 0.1186091 -0.9696798 -0.2136655 0.1112437 -0.9707868 -0.2125978 0.1171954 -0.9685035 -0.2196958 0.1004256 -0.9663429 -0.2368463 0.09557092 -0.968491 -0.2299811 -0.6220559 -0.4560766 -0.636428 -0.6110106 -0.6064399 -0.5088188 -0.5689021 -0.7371048 -0.3647285 -0.05744224 0.3075398 0.9497998 -0.7519868 -0.2447317 0.6120639 -0.1242211 0.256111 0.9586325 -0.6087564 -0.6021459 0.5165618 -0.7537734 -0.2377932 0.6126012 -0.6154747 -0.5919237 0.5204011 -0.6139156 -0.5918523 0.5223203 -0.6135133 -0.5925763 0.521972 -0.7518302 -0.2381326 0.6148532 -0.7516976 -0.2388641 0.6147313 -0.6171034 -0.5918684 0.5185317 -0.6159258 -0.5936746 0.5178667 -0.6183277 -0.5921528 0.5167456 -0.6175208 -0.5933861 0.5162954 -0.6190474 -0.592493 0.5154923 -0.6186205 -0.5931439 0.5152562 -0.6193027 -0.5928727 0.5147486 -0.6192127 -0.5930096 0.5146991 -0.6193834 -0.5928069 0.5147274 -0.6193158 -0.5929098 0.5146902 -0.6187927 -0.5930605 0.5151454 -0.6192274 -0.5923975 0.5153859 -0.6179116 -0.5930788 0.516181 -0.6184535 -0.5922502 0.5164832 -0.6164344 -0.5932955 0.5176959 -0.6173575 -0.5918789 0.5182172 -0.6145397 -0.5934333 0.5197863 -0.615639 -0.5917384 0.5204173 -0.6124033 -0.5932114 0.5225537 -0.6134723 -0.5915526 0.52318 -0.6095771 -0.5933172 0.5257286 -0.6110348 -0.5910372 0.5266036 -0.606372 -0.5932585 0.5294878 -0.6078724 -0.5908908 0.5304142 -0.6025661 -0.5933609 0.5337011 -0.6042929 -0.5906075 0.5348017 -0.598596 -0.5929274 0.5386278 -0.6000788 -0.5905336 0.5396067 -0.5937807 -0.5930268 0.5438234 -0.5956603 -0.5899497 0.545113 -0.5886571 -0.5927894 0.5496214 -0.590363 -0.5899533 0.5508418 -0.5829201 -0.5926878 0.5558106 -0.5847144 -0.589652 0.5571532 -0.5765746 -0.5927736 0.5622998 -0.5784448 -0.5895487 0.5637677 -0.5698863 -0.5925104 0.5693516 -0.5715029 -0.5896621 0.5706863 -0.5625147 -0.59256 0.5765848 -0.5642206 -0.5894827 0.5780704 -0.554641 -0.5925418 0.5841812 -0.5562041 -0.5896484 0.5856209 -0.5461189 -0.5928485 0.5918487 -0.5477141 -0.5898119 0.5934064 -0.5371079 -0.5931468 0.5997433 -0.5385423 -0.5903321 0.6012323 -0.5211359 -0.595474 0.6114149 -0.5240106 -0.5895233 0.6147155 -0.4830525 -0.600007 0.6376927 -0.4877585 -0.5887233 0.6445901 -0.4141781 -0.6081805 0.6771802 -0.4186286 -0.5930832 0.6877518 -0.322251 -0.6202922 0.7151166 -0.3237829 -0.6081529 0.7247859 -0.2798504 -0.6247892 0.7289185 -0.2799012 -0.623705 0.7298271 -0.3083488 -0.6154863 0.725326 -0.30771 -0.6218636 0.7201389 -0.4026494 -0.5980318 0.6929874 -0.4001913 -0.6071795 0.6864256 -0.501208 -0.5901672 0.6328454 -0.4988727 -0.5954552 0.6297293 -0.568126 -0.5895893 0.574123 -0.5669142 -0.5917521 0.5730949 -0.6820599 -0.2378065 0.6915507 -0.6826519 -0.234976 0.691934 -0.5804817 -0.2430276 0.7771605 -0.5813499 -0.2370374 0.7783607 -0.4326264 -0.2605662 0.8630989 -0.4331547 -0.249814 0.8660081 -0.2938662 -0.2826455 0.9131014 -0.2935466 -0.2754669 0.9153952 -0.2521868 -0.2866979 0.9242327 -0.2522724 -0.2878572 0.9238489 -0.3170868 -0.2656209 0.9104403 -0.3175126 -0.2799134 0.9059991 -0.4577179 -0.2428379 0.8552919 -0.4565696 -0.2608428 0.850591 -0.5611578 -0.2360627 0.7933325 -0.5595376 -0.2483754 0.7907131 -0.6165505 -0.2353431 0.7513183 -0.6152778 -0.2429321 0.7499448 -0.6387186 -0.2365149 0.732188 -0.6382215 -0.2392479 0.7317335 -0.6522605 -0.2361817 0.7202599 -0.6516624 -0.2393186 0.7197658 -0.6650362 -0.2355715 0.7086839 -0.6643035 -0.2392589 0.7081356 -0.6768767 -0.2357659 0.697318 -0.6762348 -0.2388774 0.6968817 -0.6880425 -0.2352143 0.6864923 -0.6871837 -0.239241 0.6859608 -0.6982424 -0.235417 0.6760447 -0.697497 -0.238811 0.6756237 -0.7076153 -0.2356168 0.6661572 -0.7068377 -0.2390627 0.6657549 -0.7162502 -0.2355829 0.6568763 -0.7153983 -0.2392707 0.6564716 -0.7239648 -0.2360432 0.6481964 -0.7232239 -0.2391842 0.6478721 -0.7309455 -0.2362126 0.6402518 -0.7301488 -0.2395275 0.6399291 -0.737087 -0.2367104 0.6329857 -0.7363946 -0.2395457 0.632725 -0.7425371 -0.2369353 0.6264985 -0.7418195 -0.2398331 0.6262459 -0.7471212 -0.237626 0.6207607 -0.746576 -0.2398007 0.6205804 -0.7510715 -0.237937 0.6158552 -0.7505019 -0.2401856 0.6156767 -0.7543091 -0.2382695 0.6117562 -0.753827 -0.2401572 0.6116121 -0.7567951 -0.2388146 0.6084643 -0.7564629 -0.2401071 0.6083688 -0.7586255 -0.239201 0.6060283 -0.7583616 -0.2402222 0.6059547 -0.7598375 -0.2393639 0.6044436 -0.7596331 -0.2401521 0.6043877 -0.7603846 -0.2394663 0.6037145 -0.7602941 -0.2398151 0.60369 -0.760159 -0.2400314 0.6037741 -0.7603222 -0.2394025 0.6038184 -0.7593986 -0.2401068 0.6047005 -0.7595784 -0.239413 0.6047496 -0.7579122 -0.2404112 0.6064417 -0.7583022 -0.2389013 0.6065509 -0.7558778 -0.240234 0.6090455 -0.7563008 -0.238588 0.6091673 -0.01052552 0.8425297 0.538547 0.1310103 0.7376756 0.6623225 0.2125293 0.6545624 0.7255201 0.07040709 0.9971082 0.02860337 0.07407814 0.996907 0.02624624 0.251923 0.9623642 -0.1019309 0.2824064 0.9514889 -0.1221288 0.3516529 0.9200831 -0.1725906 0.4946932 0.8233919 -0.2780368 0.47303 0.8408437 -0.2631054 0.6731324 -0.3012364 -0.6753883 0.6319641 0.671212 -0.387422 0.6563842 0.6362383 -0.4054141 0.5948987 0.6722696 -0.4406237 0.5948413 0.6723496 -0.4405789 0.4431626 0.8409033 -0.3106259 0.4428081 0.8411907 -0.3103535 0.2615166 0.9518958 -0.159698 0.2608796 0.9521512 -0.1592164 0.06151336 0.9981031 0.00251466 0.06106609 0.9981297 0.002846539 0.6240409 0.6683688 -0.4047915 0.613469 0.669445 -0.4189264 0.6213046 0.6721228 -0.4027795 0.6038528 0.6705676 -0.4309303 0.6109709 0.6728938 -0.4170476 0.5956657 0.671553 -0.4406803 0.6017661 0.6734637 -0.4293299 0.5892581 0.6721116 -0.4483759 0.5942028 0.6735931 -0.4395401 0.5846543 0.6726158 -0.4536158 0.5881777 0.6736246 -0.4475231 0.5823506 0.6730197 -0.4559739 0.5840392 0.6734799 -0.4531261 0.5817663 0.6737512 -0.4556394 0.58182 0.6737656 -0.4555496 0.5825322 0.6733281 -0.4552862 0.5821367 0.6732307 -0.4559357 0.5828594 0.6735885 -0.4544815 0.5824196 0.6734862 -0.4551963 0.5823916 0.6734898 -0.4552268 0.5828568 0.6735922 -0.4544794 0.5806471 0.6733112 -0.4577128 0.5822797 0.6736471 -0.4551374 0.5776107 0.6734355 -0.4613571 0.5802007 0.6739389 -0.4573549 0.573748 0.6732971 -0.466352 0.5772534 0.6739394 -0.4610687 0.5685148 0.6734922 -0.4724394 0.5730523 0.6742807 -0.465786 0.5620344 0.6738203 -0.4796703 0.5676341 0.6747412 -0.4717158 0.5545404 0.6738973 -0.4882084 0.561237 0.6749558 -0.4790071 0.5461127 0.6735653 -0.498067 0.5539429 0.6747531 -0.4877043 0.5358026 0.6740902 -0.5084468 0.5448341 0.675408 -0.4969707 0.5243818 0.674321 -0.5199183 0.5346414 0.675774 -0.5074328 0.5119256 0.6740282 -0.5325581 0.5234919 0.6756219 -0.5191255 0.4979196 0.67393 -0.5457971 0.5108134 0.6756695 -0.5315452 0.4825674 0.6736542 -0.5597488 0.4968315 0.6755522 -0.5447824 0.4655334 0.6729725 -0.5747928 0.4816103 0.6750978 -0.5588333 0.4324768 0.6701643 -0.6031947 0.4644768 0.6745877 -0.5737533 0.3603875 0.6632611 -0.6559006 0.4300336 0.6740037 -0.600658 0.2357239 0.6471855 -0.7249725 0.3566079 0.6695942 -0.6515169 0.08975666 0.6240018 -0.776251 0.2318551 0.6545395 -0.7195979 0.03835314 0.6178746 -0.7853407 0.08739548 0.6293272 -0.7722107 0.0984075 0.631523 -0.769087 0.03827959 0.6180512 -0.7852054 0.257468 0.6561875 -0.7093154 0.1003015 0.6273261 -0.7722704 0.4132541 0.6713998 -0.6151775 0.2597999 0.6518793 -0.7124306 0.5201736 0.6752411 -0.5229424 0.4144816 0.6694415 -0.6164845 0.5212226 0.6737024 -0.5238817 0.4699912 0.8365972 -0.2814489 0.4604938 0.837811 -0.2932885 0.4636947 0.8415921 -0.2769656 0.4520202 0.8388142 -0.303428 0.4551776 0.8420604 -0.2893919 0.4448884 0.8395912 -0.3117065 0.4477795 0.8422287 -0.3002406 0.4388948 0.84043 -0.3178817 0.4413536 0.8424544 -0.3089944 0.4347669 0.8409281 -0.3222075 0.4365952 0.8423019 -0.3160887 0.4322193 0.8416545 -0.3237348 0.4331179 0.8422751 -0.3209073 0.4320874 0.8417316 -0.3237106 0.4321084 0.8417452 -0.323647 0.4321574 0.8419964 -0.3229272 0.4319291 0.8418611 -0.3235851 0.4329066 0.8417213 -0.3226408 0.4326602 0.8415853 -0.3233253 0.4325467 0.8416448 -0.3233223 0.4328258 0.8417873 -0.3225769 0.4311466 0.841498 -0.3255668 0.4321486 0.8419703 -0.323007 0.4286113 0.8415529 -0.3287568 0.4302241 0.8422535 -0.3248326 0.4251797 0.841637 -0.3329704 0.4274172 0.8425334 -0.3277989 0.4207828 0.8417198 -0.3383041 0.4237535 0.8428118 -0.3318147 0.4154425 0.8417683 -0.3447223 0.4191833 0.8430435 -0.3369912 0.4090896 0.8418158 -0.3521246 0.4136664 0.8432468 -0.3432416 0.4015851 0.8419232 -0.360409 0.4070636 0.8435139 -0.3504049 0.3930578 0.8419455 -0.3696395 0.3995056 0.8436803 -0.3586069 0.3835054 0.8418514 -0.3797497 0.3909704 0.8437263 -0.3677882 0.3725429 0.8419102 -0.390383 0.381108 0.8439186 -0.3775688 0.3604432 0.8418527 -0.4017023 0.3701538 0.8439948 -0.3881481 0.3474511 0.8414021 -0.4139087 0.3583804 0.8436779 -0.3997136 0.3325393 0.8411079 -0.426562 0.3450264 0.8435814 -0.4114938 0.3049758 0.8381618 -0.4521886 0.3303012 0.8431555 -0.4242521 0.2435964 0.831799 -0.4987697 0.2995969 0.8432738 -0.446241 0.1371663 0.816775 -0.5604142 0.2364004 0.8392922 -0.4895952 0.01020944 0.7981514 -0.6023704 0.1287255 0.8273431 -0.5467477 -0.0348314 0.794067 -0.6068313 0.006228387 0.80464 -0.5937303 0.01640868 0.8063091 -0.5912668 -0.03471195 0.793851 -0.6071208 0.1524884 0.8280481 -0.5395218 0.01944828 0.8014885 -0.5976938 0.2862572 0.8408899 -0.4593048 0.1570461 0.8225808 -0.5465322 0.3787767 0.8433994 -0.3810586 0.2896211 0.8376229 -0.4631495 0.3803203 0.8420633 -0.3824734 0.2826325 0.9492501 -0.1379973 0.2752955 0.9500486 -0.1470377 0.2755466 0.9520299 -0.1330904 0.2685517 0.9507777 -0.1546018 0.2691345 0.9524834 -0.1426255 0.2629975 0.95129 -0.1608713 0.2637529 0.9526877 -0.1510644 0.2582809 0.951794 -0.1654663 0.2590623 0.9528663 -0.1579006 0.2547217 0.9522342 -0.1684255 0.2553822 0.9529604 -0.1632373 0.253015 0.9524571 -0.1697317 0.2533657 0.9527818 -0.1673695 0.2524973 0.9526606 -0.1693603 0.2525025 0.9526646 -0.1693301 0.2528027 0.9526535 -0.1689441 0.2526979 0.9525794 -0.1695175 0.2532753 0.9525775 -0.1686645 0.2531636 0.9525074 -0.1692267 0.2531065 0.9525102 -0.1692965 0.2532473 0.9525888 -0.1686426 0.2521206 0.9524459 -0.1711202 0.2526377 0.9526999 -0.1689294 0.2502683 0.9524734 -0.1736672 0.2511295 0.9528475 -0.1703397 0.2476339 0.952564 -0.1769155 0.2488706 0.9530412 -0.1725567 0.2443907 0.9526079 -0.1811391 0.2460881 0.9531944 -0.175673 0.2402456 0.9527176 -0.1860408 0.2424601 0.9533992 -0.1795638 0.2352996 0.9528338 -0.1916812 0.2380804 0.9536104 -0.1842421 0.2295427 0.9529353 -0.1980515 0.2329675 0.9538022 -0.1897031 0.2228546 0.953052 -0.2050065 0.2269796 0.9540087 -0.1958251 0.2154806 0.9530497 -0.2127544 0.2203808 0.9540988 -0.2027999 0.2071799 0.953005 -0.2210385 0.2129146 0.954149 -0.2103973 0.1980083 0.9528713 -0.2298455 0.2046353 0.9541109 -0.2186248 0.1879105 0.9526351 -0.2391151 0.1954973 0.9539808 -0.2273794 0.1767174 0.9522116 -0.2491266 0.1855229 0.9537104 -0.2366807 0.1555608 0.9504541 -0.2691431 0.1737538 0.9535744 -0.2459784 0.1090945 0.9456416 -0.3063662 0.1499933 0.9531379 -0.2627359 0.02718609 0.9345725 -0.3547325 0.1008981 0.950084 -0.2952287 -0.0706464 0.9195441 -0.3865848 0.01868039 0.94047 -0.3393628 -0.105638 0.9160811 -0.3868281 -0.07484084 0.9237388 -0.3756401 -0.06626087 0.9250945 -0.3739112 -0.1054213 0.9158298 -0.3874818 0.03798031 0.94177 -0.3341056 -0.06323111 0.9221872 -0.3815395 0.1407082 0.9516202 -0.2731674 0.04301106 0.9384824 -0.3426383 0.2115094 0.9538493 -0.2131555 0.1441183 0.9499294 -0.2772437 0.2133951 0.9530369 -0.2149025 0.0751394 0.9970504 0.0156461 0.07045108 0.9974648 0.01002931 0.06984376 0.9973731 0.01921021 0.06616431 0.9977945 0.005342364 0.06589388 0.9977391 0.01321369 0.06250184 0.9980437 0.001564741 0.0624715 0.9980146 0.008007109 0.05955773 0.998224 -0.001307129 0.05967015 0.9982115 0.003662645 0.0573697 0.998348 -0.003160715 0.05753004 0.9983438 2.26329e-4 0.05609965 0.998418 -0.003780782 0.05620443 0.9984167 -0.002267003 0.0558198 0.9984344 -0.00355935 0.05581939 0.9984346 -0.003564417 0.05605554 0.9984221 -0.003332018 0.05601572 0.998423 -0.003710627 0.05624788 0.9984121 -0.003080904 0.05620348 0.9984134 -0.003446042 0.05621385 0.9984124 -0.003557503 0.05627769 0.9984103 -0.003103852 0.05552572 0.9984464 -0.004661679 0.05576145 0.998439 -0.003208696 0.05439972 0.9984993 -0.006310224 0.0548098 0.9984884 -0.004105925 0.0528599 0.9985661 -0.008463382 0.05347156 0.9985538 -0.00558263 0.05072259 0.9986518 -0.01104283 0.0515896 0.9986405 -0.007454276 0.04814839 0.9987397 -0.01416468 0.04930955 0.9987344 -0.009901463 0.04503768 0.998828 -0.01772409 0.04654055 0.9988338 -0.01283973 0.04145306 0.9989035 -0.02176499 0.04334169 0.9989274 -0.0162937 0.03735846 0.9989571 -0.02624845 0.03968173 0.9990075 -0.02023106 0.03269851 0.9989812 -0.03110462 0.03549885 0.9990671 -0.02458965 0.02742618 0.9989657 -0.03626728 0.03074818 0.9990974 -0.02930706 0.02167105 0.9988898 -0.04182803 0.0255593 0.9990785 -0.03448414 0.01528877 0.998749 -0.04761034 0.01978337 0.9990057 -0.03995412 0.008212924 0.9985123 -0.05390644 0.01350432 0.998861 -0.04576373 -0.004914641 0.997746 -0.06692427 0.00614959 0.9986453 -0.05167114 -0.0341683 0.9952903 -0.09071701 -0.009057819 0.9980341 -0.06201505 -0.08587199 0.9888652 -0.1215385 -0.04006886 0.9958028 -0.08228719 -0.1476377 0.9789644 -0.1408259 -0.09185373 0.9897131 -0.1096856 -0.1692411 0.9755312 -0.1403437 -0.1501792 0.9796743 -0.1329831 -0.1443498 0.9807252 -0.1316863 -0.1691268 0.9754899 -0.1407675 -0.07883816 0.9911546 -0.1067568 -0.1423144 0.9802007 -0.1376714 -0.01444625 0.997543 -0.06855183 -0.07537543 0.9907189 -0.1131132 0.03006345 0.9990668 -0.03100889 -0.01189821 0.9973554 -0.07169896 0.03142416 0.9989849 -0.03227454 0.6217096 -0.4194515 0.6614664 0.5822277 -0.3000302 -0.7556406 0.6077516 -0.6210741 0.4948788 0.5698096 -0.7351042 0.3673405 0.5813802 -0.304758 -0.7544002 0.8196297 -0.03643876 -0.5717337 0.7710344 -0.3036097 -0.5597564 0.8182352 -0.05111461 -0.5726069 0.1678882 0.262517 -0.9502096 0.66852 -0.5434042 -0.5077331 0.7689982 -0.3098416 -0.5591421 0.5187659 -0.7447812 -0.4197416 0.6675593 -0.5450028 -0.5072834 0.5215328 -0.7419955 -0.4212437 0.5083959 -0.7376059 -0.4443774 0.5080153 -0.7380564 -0.4440644 0.6446561 -0.5381883 -0.5429291 0.6447122 -0.5380752 -0.5429744 0.737246 -0.3012816 -0.6047294 0.7369023 -0.302668 -0.604456 0.7793095 -0.04441112 -0.6250635 0.7793089 -0.0444265 -0.6250631 0.7051298 -0.04221522 -0.7078205 0.705193 -0.04108226 -0.7078241 0.5981361 -0.04790991 -0.7999613 0.5982074 -0.04330581 -0.8001703 0.4426869 -0.06324911 -0.8944426 0.4424708 -0.05847805 -0.8948743 0.2839979 -0.08947569 -0.954641 0.28339 -0.08394861 -0.9553233 0.2227541 -0.0983389 -0.969902 0.2228722 -0.09920781 -0.9697864 0.2720843 -0.08505547 -0.958507 0.2727484 -0.09079718 -0.9577913 0.417445 -0.05856889 -0.9068127 0.4180672 -0.06959295 -0.9057464 0.542939 -0.04620754 -0.8384999 0.5429908 -0.05425161 -0.8379843 0.6158893 -0.04307091 -0.7866546 0.6157816 -0.04789942 -0.7864596 0.6497184 -0.04227751 -0.7589984 0.6496109 -0.04532176 -0.7589147 0.6668277 -0.04235541 -0.7440072 0.6667657 -0.04384076 -0.7439768 0.6821506 -0.04142653 -0.7300373 0.6820222 -0.04412645 -0.7299991 0.6960906 -0.04159092 -0.7167484 0.6959958 -0.04338634 -0.7167339 0.7087216 -0.04160976 -0.7042602 0.7086035 -0.0436601 -0.704255 0.7200635 -0.04129427 -0.6926783 0.7199132 -0.04372823 -0.6926853 0.7300441 -0.04229658 -0.6820899 0.7299713 -0.04340445 -0.6820982 0.7388623 -0.04241102 -0.6725205 0.7387273 -0.04436022 -0.672543 0.7464671 -0.04246389 -0.6640661 0.7463306 -0.04436087 -0.6640955 0.7528472 -0.04282933 -0.6568005 0.7527425 -0.04424011 -0.6568269 0.7581166 -0.04295915 -0.6507025 0.7580067 -0.04440063 -0.6507337 0.7621415 -0.0438463 -0.645924 0.7621096 -0.04425638 -0.6459338 0.7652055 -0.04375487 -0.6422974 0.7651173 -0.04487174 -0.6423256 0.7671859 -0.04368889 -0.6399351 0.7671255 -0.04444968 -0.6399554 0.7678213 -0.04393953 -0.6391554 0.7678222 -0.04392939 -0.6391553 0.7671285 -0.04402494 -0.6399809 0.767156 -0.04367887 -0.6399719 0.7664899 -0.04401189 -0.6407466 0.7665088 -0.04377424 -0.6407402 0.7668203 -0.04414957 -0.6403418 0.7668202 -0.04414993 -0.6403418 0.7689411 -0.04390734 -0.6378102 0.7688508 -0.0450294 -0.6378408 0.7733599 -0.04333394 -0.6324844 0.7731561 -0.04582011 -0.6325585 0.7796474 -0.04361832 -0.6246979 0.7794269 -0.04623425 -0.624785 0.7875928 -0.04341322 -0.6146647 0.7872391 -0.04747205 -0.6148179 0.7969295 -0.04417216 -0.6024551 0.7965582 -0.04826837 -0.6026318 0.8074809 -0.04436975 -0.5882227 0.8069484 -0.05000507 -0.5885014 0.5173131 -0.7409503 -0.4282287 0.5212952 -0.7368116 -0.4305344 0.513264 -0.7403289 -0.4341351 0.5168169 -0.736572 -0.4363051 0.509761 -0.7397177 -0.4392736 0.5126064 -0.7366629 -0.4410924 0.5067004 -0.7393496 -0.4434148 0.5090472 -0.7367983 -0.4449713 0.5044952 -0.7388412 -0.4467643 0.5060279 -0.7371577 -0.4478104 0.5031725 -0.7382763 -0.4491833 0.5039665 -0.7373977 -0.4497359 0.502651 -0.7379221 -0.4503475 0.5029052 -0.7376402 -0.4505258 0.5026959 -0.7377372 -0.4506003 0.5026094 -0.7378333 -0.4505395 0.503193 -0.7375135 -0.4504116 0.502803 -0.7379462 -0.4501383 0.5031436 -0.7378809 -0.4498648 0.5033012 -0.7377061 -0.449975 0.5029242 -0.7377693 -0.4502929 0.5030135 -0.7376701 -0.4503555 0.5017921 -0.738041 -0.4511098 0.5025398 -0.7372083 -0.4516389 0.50044 -0.7380762 -0.452552 0.5011838 -0.7372436 -0.4530857 0.4985564 -0.7381914 -0.4544393 0.4995665 -0.7370528 -0.4551773 0.496658 -0.7377815 -0.4571753 0.4973767 -0.7369638 -0.4577125 0.4937986 -0.7378982 -0.4600753 0.4951277 -0.7363685 -0.4610965 0.490546 -0.7379309 -0.4634896 0.4918986 -0.7363539 -0.4645628 0.4867353 -0.7380665 -0.4672757 0.4882383 -0.7362878 -0.4685121 0.482581 -0.7379903 -0.4716842 0.4839522 -0.736339 -0.4728584 0.4778658 -0.7380114 -0.4764278 0.4793099 -0.736237 -0.4777207 0.4726213 -0.7380625 -0.4815524 0.4740582 -0.7362567 -0.4829026 0.4668847 -0.7380957 -0.4870662 0.4682431 -0.7363442 -0.4884113 0.460614 -0.7381876 -0.4928629 0.4619109 -0.7364671 -0.4942213 0.4534536 -0.7384796 -0.4990268 0.4548107 -0.7366189 -0.5005396 0.4382228 -0.7406768 -0.5092727 0.441483 -0.7358904 -0.5133791 0.4075571 -0.7437067 -0.5299034 0.4114588 -0.7369586 -0.5362776 0.3558699 -0.7500941 -0.5574187 0.3593658 -0.7413734 -0.5667643 0.297143 -0.7580253 -0.5806064 0.2980949 -0.7530311 -0.5865865 0.2775476 -0.7603346 -0.5872467 0.2775673 -0.7601681 -0.5874527 0.303717 -0.7532489 -0.5834142 0.3028792 -0.7571921 -0.5787265 0.3705406 -0.7417981 -0.5589591 0.3683217 -0.7468243 -0.553708 0.4345263 -0.7366939 -0.51814 0.432603 -0.7396189 -0.5155758 0.4781089 -0.7362235 -0.4789435 0.4771358 -0.737427 -0.4780614 0.6603992 -0.5436737 -0.5179691 0.6648862 -0.5359783 -0.5202438 0.6541046 -0.542111 -0.5275062 0.6576439 -0.5359243 -0.5294239 0.6482731 -0.5411943 -0.5355844 0.6514089 -0.5356187 -0.5373817 0.6433933 -0.5403994 -0.5422303 0.6458248 -0.5360155 -0.543689 0.6396681 -0.5395151 -0.5474926 0.6413272 -0.5364899 -0.5485236 0.6372721 -0.5385779 -0.5511969 0.6381668 -0.5369332 -0.5517662 0.6362124 -0.5380495 -0.5529346 0.6365484 -0.5374296 -0.5531507 0.6360429 -0.5379895 -0.5531877 0.6361004 -0.5378835 -0.5532248 0.636544 -0.5378992 -0.5526991 0.6363001 -0.5383485 -0.5525424 0.6369099 -0.5380655 -0.5521153 0.6368097 -0.5382499 -0.5520511 0.6362488 -0.5383899 -0.5525611 0.6366195 -0.5377069 -0.5527992 0.6348795 -0.5384052 -0.5541189 0.6354105 -0.5374228 -0.5544639 0.6327755 -0.5384724 -0.5564556 0.6335653 -0.5370023 -0.5569772 0.6299161 -0.5386337 -0.559535 0.6309544 -0.5366865 -0.5602359 0.6262803 -0.5388201 -0.5634233 0.6275157 -0.5364804 -0.5642806 0.6219551 -0.5388742 -0.568143 0.6232646 -0.5363643 -0.5690823 0.6168965 -0.53884 -0.5736639 0.6182726 -0.5361638 -0.574689 0.6112682 -0.5384014 -0.5800648 0.6125072 -0.5359483 -0.5810285 0.6045373 -0.5385086 -0.586978 0.6060956 -0.5353605 -0.5882493 0.5970574 -0.5385529 -0.5945445 0.5985776 -0.5354115 -0.5958517 0.5888637 -0.5383315 -0.6028587 0.5902248 -0.535444 -0.604098 0.5795272 -0.538804 -0.6114233 0.5811342 -0.5352933 -0.6129798 0.5696923 -0.53853 -0.6208351 0.5708622 -0.5358873 -0.6220459 0.5580173 -0.5397948 -0.6302685 0.5597539 -0.5357201 -0.6322022 0.5349603 -0.5424667 -0.6477248 0.5378363 -0.5351481 -0.6514204 0.4864144 -0.5475913 -0.6808412 0.4903101 -0.5354557 -0.6876649 0.4041 -0.5584536 -0.7244534 0.4073084 -0.5422099 -0.7349205 0.3097984 -0.5709724 -0.7602733 0.3102816 -0.5615668 -0.7670515 0.277863 -0.5733483 -0.7707554 0.2778623 -0.5740177 -0.7702572 0.3187052 -0.5618299 -0.7633964 0.3182491 -0.5688124 -0.7583996 0.4245377 -0.5434007 -0.7242124 0.4225046 -0.5524541 -0.7185293 0.5266472 -0.5360462 -0.6597705 0.5249218 -0.5406383 -0.6573945 0.5966662 -0.5349861 -0.5981464 0.5954564 -0.5375079 -0.5970905 0.759652 -0.3077997 -0.5728772 0.7622428 -0.2996242 -0.5737692 0.7507216 -0.3069158 -0.5849955 0.7531948 -0.2989375 -0.5859471 0.7430852 -0.30522 -0.5955376 0.7448256 -0.2994925 -0.5962709 0.7365272 -0.3041808 -0.6041538 0.7379865 -0.2992922 -0.6048141 0.7314493 -0.3028807 -0.610938 0.7323859 -0.2996975 -0.6113855 0.7278264 -0.3023747 -0.6154985 0.7285401 -0.2999261 -0.6158521 0.7263164 -0.3014567 -0.6177284 0.7264376 -0.3010394 -0.6177894 0.726098 -0.3012374 -0.618092 0.7260935 -0.3012527 -0.6180898 0.7266302 -0.3013572 -0.6174077 0.7265496 -0.3016346 -0.6173672 0.7271777 -0.3015149 -0.6166859 0.7271065 -0.3017592 -0.6166503 0.7265331 -0.3016789 -0.6173651 0.7266941 -0.3011249 -0.6174461 0.7247273 -0.3019216 -0.6193657 0.7251114 -0.3005929 -0.6195621 0.7220399 -0.3020711 -0.6224239 0.7225363 -0.3003425 -0.6226841 0.7183906 -0.3024012 -0.6264731 0.7190582 -0.3000563 -0.6268346 0.7139135 -0.3020852 -0.6317214 0.7145109 -0.2999608 -0.6320584 0.7083538 -0.3021074 -0.6379389 0.7091303 -0.2993021 -0.6383983 0.7018177 -0.301977 -0.6451837 0.7026147 -0.2990447 -0.6456818 0.6942762 -0.3017914 -0.6533777 0.6950981 -0.2987008 -0.6539239 0.6856212 -0.3017957 -0.6624521 0.6865088 -0.2983729 -0.6630833 0.6759124 -0.3017553 -0.6723735 0.6767783 -0.2983177 -0.6730363 0.6649821 -0.3022074 -0.6829857 0.6659398 -0.2982779 -0.6837795 0.6531721 -0.301692 -0.6945129 0.653844 -0.2988264 -0.6951193 0.6399248 -0.3025508 -0.7063705 0.6408386 -0.2984783 -0.707274 0.6252407 -0.3029752 -0.7192219 0.6259849 -0.299487 -0.7200351 0.5957033 -0.3065065 -0.7424226 0.5973291 -0.2979831 -0.7445831 0.5328593 -0.3133903 -0.7860327 0.5348581 -0.2993378 -0.7901417 0.4257708 -0.3260873 -0.8440297 0.4267565 -0.3090534 -0.8499206 0.3017202 -0.3440593 -0.8891503 0.3012301 -0.332283 -0.8937833 0.2591524 -0.347832 -0.9010289 0.2592135 -0.348638 -0.9006997 0.3115658 -0.3332824 -0.8898593 0.3118289 -0.3414065 -0.8866817 0.4486712 -0.3099182 -0.8382391 0.4479302 -0.3196632 -0.8349695 -0.9951846 0 -0.09801858 -0.9569397 0 -0.2902867 -0.8819199 0 -0.4713992 -0.7730104 0 -0.6343934 -0.6343914 0 -0.773012 -0.4713954 0 -0.881922 -0.2902829 0 -0.9569409 -0.09801197 0 -0.9951853 0.09801524 0 -0.9951848 0.2902885 0 -0.9569392 0.471398 0 -0.8819205 0.6343956 0 -0.7730085 0.77301 0 -0.6343939 0.8819241 0 -0.4713914 0.9569405 0 -0.290284 0.995185 0 -0.09801524 0.9951846 0 0.098019 0.9569396 0 0.2902874 0.8819199 0 0.4713992 0.7730087 0 0.6343954 0.634392 0 0.7730116 0.4713944 0 0.8819225 0.2902809 0 0.9569415 0.09801459 0 0.995185 -0.09802031 0 0.9951844 -0.2902869 0 0.9569397 -0.4714001 0 0.8819195 -0.6343953 0 0.7730088 -0.7730128 0 0.6343905 -0.8819227 0 0.471394 -1.58828e-6 1 -6.25718e-7 -0.995185 0 0.09801417 -0.9569414 0 0.2902812 0 -1 4.76471e-6 -0.9951845 0 -0.09801888 -0.9569392 0 -0.2902886 -0.8819207 0 -0.4713978 -0.7730085 0 -0.6343956 -0.634393 0 -0.7730107 -0.4713944 0 -0.8819225 -0.290284 0 -0.9569406 -0.09801524 0 -0.995185 0.09802061 0 -0.9951844 0.2902874 0 -0.9569395 0.4713951 0 -0.8819221 0.6343949 0 -0.7730091 0.7730116 0 -0.634392 0.8819223 0 -0.4713949 0.9569411 0 -0.2902821 0.995185 0 -0.09801506 0.9951845 0 0.09801954 0.9569398 0 0.2902868 0.8819199 0 0.4713995 0.773009 0 0.6343951 0.6343917 0 0.7730118 0.4713937 0 0.881923 0.2902822 0 0.9569412 0.09801459 0 0.995185 -0.09801989 0 0.9951846 -0.2902866 0 0.9569398 -0.4714003 0 0.8819194 -0.634396 0 0.7730082 -0.7730125 0 0.6343909 -0.8819223 0 0.4713948 2.41055e-6 1 4.05884e-7 -6.46402e-7 1 -8.60358e-7 5.84011e-7 1 -6.65193e-7 -2.05243e-7 1 -7.72605e-7 -4.44985e-7 1 -2.38973e-7 0 1 -4.65912e-7 -4.25025e-7 1 -1.95558e-7 -2.34637e-7 1 -2.38237e-6 0 1 -8.65062e-7 2.86663e-7 1 -1.41482e-7 8.77554e-7 1 0 2.08022e-7 1 -3.31339e-7 -1.43565e-6 1 -9.23542e-7 2.99339e-6 1 -1.23338e-6 9.72947e-7 1 -1.40264e-6 0 1 -8.77555e-7 0 1 -7.72404e-7 0 1 -8.16391e-7 0 1 0 1.82024e-7 1 -9.15082e-7 0 1 -6.37249e-7 0 1 -6.38451e-7 -3.91071e-7 1 -1.28919e-6 0 1 -7.39914e-7 0 1 -6.16252e-7 -2.89822e-7 1 -6.53425e-7 0 1 -6.53424e-7 0 1 -6.46813e-7 0 1 -6.00545e-7 -0.9951849 0 0.09801602 -0.9569418 0 0.2902801 0 -1 1.60885e-6 0 -1 1.60885e-6 0 -1 6.60482e-7 0 -1 6.60482e-7 0 -1 7.36173e-7 0 -1 7.36174e-7 0 -1 6.04162e-7 0 -1 6.04162e-7 0 -1 3.53035e-7 0 -1 3.53035e-7 0 -1 9.76078e-7 0 -1 9.76078e-7 0 -1 3.12856e-7 0 -1 3.12858e-7 0 -1 7.82139e-7 0 -1 7.82139e-7 0 -1 4.8804e-7 0 -1 4.88038e-7 0 -1 8.82585e-7 0 -1 8.82588e-7 0 -1 6.04164e-7 0 -1 6.04162e-7 0 -1 7.36176e-7 0 -1 7.36174e-7 0 -1 6.60484e-7 0 -1 6.60487e-7 0 -1 0 0 -1 0 0 -1 0 -0.9951846 0 -0.09801858 -0.9569397 0 -0.2902867 -0.8819199 0 -0.4713992 -0.7730104 0 -0.6343933 -0.6343914 0 -0.773012 -0.4713954 0 -0.881922 -0.2902829 0 -0.9569409 -0.09801191 0 -0.9951852 0.09801524 0 -0.9951848 0.2902885 0 -0.9569392 0.471398 0 -0.8819205 0.6343956 0 -0.7730085 0.77301 0 -0.6343939 0.881924 0 -0.4713914 0.9569405 0 -0.290284 0.9951849 0 -0.09801518 0.9951846 0 0.09801894 0.9569395 0 0.2902874 0.88192 0 0.4713993 0.7730087 0 0.6343954 0.634392 0 0.7730116 0.4713944 0 0.8819225 0.2902809 0 0.9569415 0.09801459 0 0.995185 -0.09802031 0 0.9951844 -0.2902869 0 0.9569397 -0.4714001 0 0.8819195 -0.6343953 0 0.7730088 -0.7730128 0 0.6343905 -0.8819227 0 0.4713941 -1.22789e-6 1 -1.18588e-6 1.2446e-7 1 -6.25714e-7 -1.70679e-6 1 0 -3.98377e-7 1 -7.29714e-7 1.79854e-7 1 -7.51761e-7 2.41008e-7 1 -7.84449e-7 -3.05406e-7 1 -4.19349e-7 0 1 0 -3.13865e-7 1 -1.57793e-6 0 1 -4.60022e-7 -9.72948e-7 1 -1.40265e-6 -1.32624e-7 1 -8.41156e-7 -1.43565e-6 1 -9.23541e-7 -1.67979e-6 1 -3.03842e-7 4.43005e-7 1 -7.66339e-7 -6.94897e-7 1 2.29074e-6 0 1 -8.77557e-7 -3.91068e-7 1 -1.28919e-6 -4.8306e-7 1 -1.47566e-7 0 1 -4.52978e-7 -1.58627e-7 1 -4.05264e-7 0 1 -6.37251e-7 0 1 -6.3845e-7 0 1 -6.18798e-7 0 1 -6.29713e-7 1.84057e-7 1 -6.06751e-7 0 1 -6.06751e-7 0 1 -6.03446e-7 3.81165e-7 1 -8.94751e-7 -0.995185 0 0.09801417 -0.9569414 0 0.2902812 0 -1 0 0 -1 0 0 -1 9.90722e-7 0 -1 9.90723e-7 0 -1 4.90782e-7 0 -1 4.90783e-7 0 -1 6.04162e-7 0 -1 6.04162e-7 0 -1 5.29554e-7 0 -1 5.29553e-7 0 -1 8.13395e-7 0 -1 8.13397e-7 0 -1 3.12856e-7 0 -1 3.12858e-7 0 -1 9.38567e-7 0 -1 9.38567e-7 0 -1 3.2536e-7 0 -1 3.2536e-7 0 -1 8.8259e-7 0 -1 8.82587e-7 0 -1 6.0416e-7 0 -1 6.04163e-7 0 -1 7.36175e-7 0 -1 7.36174e-7 0 -1 6.60482e-7 0 -1 6.60482e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.8191674 0 -0.5735545 0 -1 0 -0.5735221 -0.01062446 -0.8191212 0 -1 0 -0.6834675 0 -0.7299809 -0.3570689 -0.07007449 -0.9314458 -0.4994722 -0.03623169 -0.865572 -0.6361654 -0.005682826 -0.7715318 0 -1 0 -0.9659249 0 -0.2588222 0 -1 0 0 -1 0 0 -1 0 -0.8935132 0 -0.4490371 -0.8595219 -0.005585968 -0.5110683 -0.8176898 -0.01740014 -0.575396 -0.8784935 -0.002094626 -0.4777498 -0.7557983 -0.04702621 -0.6531137 0 -1 0 -0.996193 0 0.08717501 0 -1 0 -0.9659249 0 -0.2588222 0 -1 0 -0.9063231 -4.5137e-6 0.4225854 0 -1 0 -0.9961934 -9.31076e-7 0.08716994 -0.7071026 0 0.707111 -0.9063127 0 0.4226078 -0.4225955 0 0.9063184 -0.7071026 0 0.707111 -0.08721905 -9.12038e-6 0.9961892 -0.4226368 -8.29742e-6 0.9062992 0 -1 0 0.2588369 0 0.9659211 0 -1 0 -0.08716922 0 0.9961935 0 -1 0 0.5735615 -0.01061487 0.8190938 0 -1 0 0 -1 0 0.2588369 0 0.9659211 0.4611094 0 0.8873433 0 -1 0 0.8191674 0 0.5735545 0 -1 0 0.3571614 -0.07005381 0.9314119 0.4988982 -0.03637653 0.8658969 0.6361712 -0.005703806 0.7715269 0.6836329 0 0.7298261 -1.58693e-6 -1 -4.25249e-7 0.9659211 0 0.2588369 3.07798e-5 -1 -2.30874e-5 0 -1 0 0 -1 0 0.8935824 0 0.4488993 0.7557885 -0.04703295 0.6531246 0.8594393 -0.005612671 0.5112071 0.8176901 -0.01740205 0.5753955 0.8785049 -0.002103686 0.4777288 -3.37819e-6 -1 2.95602e-7 0.9961934 0 -0.08716994 1.92955e-7 -1 -2.20514e-6 0.9659211 0 0.2588369 0 -1 0 0.9063127 0 -0.4226078 -1.02792e-5 -1 7.19665e-6 0.9961934 0 -0.08716994 0.7071319 0 -0.7070817 0.9063127 0 -0.4226078 0.4225887 9.68056e-6 -0.9063216 0.7071026 7.55276e-6 -0.707111 0.08716922 0 -0.9961935 0.4226368 0 -0.9062992 4.89338e-6 -1 -5.98496e-6 -0.2588369 0 -0.9659211 3.03467e-6 -1 -5.25572e-6 0.08716922 0 -0.9961935 0 -1 0 0 -1 0 -0.2588369 0 -0.9659211 -0.4609493 0 -0.8874264 0.5000348 0 0.8660053 0.866036 0 0.4999817 0.866036 0 0.4999817 0 0 1 0.5000348 0 0.8660053 -0.5000348 0 0.8660053 0 0 1 -0.866036 0 0.4999817 -0.5000348 0 0.8660053 -1 0 0 -0.866036 0 0.4999817 -0.8660389 0 -0.4999766 -1 0 0 -0.4999729 0 -0.8660411 -0.8660389 0 -0.4999766 0 1.06812e-5 -1 -0.5000348 9.24993e-6 -0.8660053 0.4999372 0 -0.8660618 8.25374e-5 0 -1 0.8660389 0 -0.4999766 0.4999372 0 -0.8660618 1 0 0 0.8660389 0 -0.4999766 1 0 0 0 1 0 -0.5735545 0 -0.8191674 0 1 0 -0.8191366 0.0086748 -0.5735329 0 1 0 -0.9816761 0.1415565 -0.1275684 -0.9584288 0.1071928 -0.2644314 -0.828513 0.02425473 -0.5594442 -0.7850798 0.008894145 -0.6193307 -0.7504475 0.00245893 -0.6609256 -0.7220276 0 -0.6918642 -4.69882e-6 1 6.71102e-6 0 1 0 0 1 0 0 1 0 -0.6462897 0.04281824 -0.76189 -0.5509933 0.01059436 -0.8344424 -2.95599e-7 1 3.37819e-6 2.20514e-6 1 -1.92956e-7 1.29739e-5 1 -1.2974e-5 5.77581e-6 1 -2.69323e-6 0 1 0 0 1 0 0 1 0 0.8191558 0.008684575 0.5735054 0 1 0 0 1 0 0 1 0 0.5735545 -2.22308e-5 0.8191674 0 1 0 0.722 -1.87768e-5 0.6918931 0.9816542 0.1414979 0.1278021 0.9585246 0.107289 0.2640447 0.828513 0.02425473 0.5594442 0.7849587 0.008853375 0.619485 0.7504804 0.002446174 0.6608883 0 1 0 0 1 0 0 1 0 0 1 0 0.646295 0.04280054 0.7618864 0.5510134 0.01057958 0.8344293 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4618909 -0.79649 0.3902058 -0.2418324 -0.9396976 0.2418377 -0.7527996 -0.3264177 0.5716155 -0.3837047 -0.8554462 0.3478253 -0.6331792 -0.5940163 0.4962143 -0.6646453 0.3420742 0.664253 -0.811896 0.03817117 0.5825528 -0.7788464 -0.2412772 0.5789505 -0.6645377 0.3419452 0.6644269 -0.6643207 0.3420086 0.6646113 -0.6643366 0.3420167 0.6645913 -0.5055018 0.8045847 0.311627 -0.6640273 0.3412043 0.6653176 -0.7077683 0.5282856 0.4690183 -0.7143407 0.5133827 0.4755582 -0.01548904 0.9985114 -0.05229759 -0.5079583 0.8021455 0.3139126 -0.2309062 0.9684031 0.09422188 0.2418552 0.9396883 -0.2418509 0.08601444 0.9873868 -0.132924 0.2418242 0.9397026 -0.2418264 0.2417322 0.9396916 -0.2419609 0.2418472 0.9396918 -0.241846 0.2418438 0.939693 -0.2418442 -0.2417594 0.9396925 0.2419305 -0.2418392 0.9396973 0.241832 -0.2418453 0.9396926 0.2418442 -0.241864 0.9396852 0.2418545 -0.24185 0.9396899 0.24185 -0.6644583 -0.3420386 0.6644583 -0.6648178 -0.341991 0.6641232 0.2418735 -0.9397079 -0.2417564 -0.66463 -0.3419964 0.6643083 0.2420927 -0.9397047 -0.2415499 0.2418623 -0.9396839 -0.241861 0.2418284 -0.9397048 -0.241814 -0.2418553 -0.9396861 0.2418598 -0.2429152 -0.9396914 0.240774 -0.2418447 -0.9396926 0.2418451 0.4619773 -0.7964165 -0.3902534 0.2418357 -0.9396975 -0.2418352 0.7527944 -0.3264188 -0.5716217 0.3333616 -0.8869228 -0.319747 0.519261 -0.7388103 -0.4295665 0.6642419 -0.5403211 -0.5165616 0.6643397 0.3420124 -0.6645903 0.8117055 0.037997 -0.5828297 0.7603675 -0.3038475 -0.5740365 0.809259 -0.04731845 -0.5855432 0.6642195 0.3420745 -0.6646785 0.6643209 0.3420086 -0.6646111 0.6643555 0.3420262 -0.6645674 0.5038298 0.8050348 -0.3131687 0.6658037 0.3443774 -0.6618985 0.707999 0.524557 -0.4728398 0.6240343 0.6702926 -0.4016079 0.01729941 0.998405 0.05374246 0.4660634 0.8393698 -0.2797198 0.2810524 0.9504312 -0.1330044 -0.2418473 0.9396935 0.2418384 -0.138619 0.9756458 0.1700008 0.0679847 0.9976187 0.01162022 0.2418535 0.9396881 -0.2418535 0.6644607 -0.342029 -0.6644607 0.664452 -0.3420301 -0.664469 -0.2418735 -0.9397079 0.2417564 0.6646226 -0.3420251 -0.6643008 -0.7750534 -0.3369197 0.5345814 -0.2418017 0.9397085 0.2418259 -0.2418692 0.9396846 0.2418516 -0.24185 0.9396907 0.2418472 -0.2418462 0.9396916 0.2418473 -0.2418372 0.939693 0.2418513 -0.2418434 0.939693 0.2418444 -0.4919 0.7720458 0.4024671 -0.496481 0.7680184 0.4045422 -0.7750239 -0.3370224 0.5345594 -0.775017 -0.3370885 0.5345279 -0.7751431 -0.3365026 0.5347142 -0.7749972 -0.3372406 0.5344607 -0.7751167 -0.3366717 0.5346459 -0.7752396 -0.3361862 0.5347734 -0.7749045 -0.3375263 0.5344149 -0.7747306 -0.3382258 0.5342245 -0.7750269 -0.3370277 0.5345519 -0.7751489 -0.3365226 0.5346932 -0.7748342 -0.3378564 0.534308 -0.1417769 0.9759462 0.1656149 -0.1305585 0.9815146 0.1399409 -0.1617614 0.9703752 0.1794579 -0.1422018 0.9810422 0.1316624 -0.1808944 0.9667615 0.1806919 -0.1832008 0.9696017 0.1622039 -0.1643874 0.9801727 0.1106263 -0.1915878 0.9662691 0.1720986 -0.2418293 0.9396972 0.2418425 -0.2080808 0.9637809 0.1668198 -0.2418667 0.9396877 0.2418419 -0.1953557 0.9752661 0.1034037 -0.2097903 0.9628747 0.1698834 -0.2418397 0.9396933 0.2418469 -0.2175687 0.965609 0.1423479 -0.2418456 0.9396924 0.2418447 -0.2170853 0.9696816 0.1122123 -0.2211827 0.9631236 0.1532033 -0.241851 0.9396919 0.2418415 -0.2220247 0.9676792 0.1195912 -0.2418397 0.9396924 0.2418505 -0.2230811 0.9669081 0.1237884 -0.2418314 0.9396952 0.2418479 -0.2191923 0.9685503 0.1177496 -0.2418454 0.9396924 0.2418448 -0.2210924 0.9684988 0.1145783 -0.2418435 0.9396932 0.2418438 -0.1797397 0.9836535 -0.01092797 -0.2418585 0.9396911 0.2418368 -0.2076502 0.9692183 0.1322771 -0.2063115 0.9750146 0.08235317 -0.2418379 0.9396933 0.241849 -0.1302441 0.9912584 -0.02105319 -0.2418462 0.9396927 0.2418429 -0.1909757 0.9711617 0.1427348 -0.1504098 0.9883844 0.02175587 -0.2418482 0.9396927 0.241841 -0.1352173 0.9883075 0.07045811 -0.2418489 0.939692 0.2418432 -0.1753727 0.9732082 0.1486951 -0.2418446 0.9396925 0.2418452 -0.1574708 0.9820798 0.1035484 -0.2418351 0.9396933 0.2418519 -0.1665122 0.9751332 0.1462492 -0.142151 0.9836789 0.1103121 -0.2418508 0.9396926 0.2418392 -0.1590943 0.9769269 0.1424875 -0.2418445 0.9396925 0.2418456 -0.1620849 0.9754523 0.1490678 -0.2418444 0.9396924 0.2418456 -0.1537834 0.9785857 0.1368232 -0.2418469 0.9396921 0.2418441 -0.1519047 0.9783674 0.1404357 -0.2418376 0.9396927 0.2418514 -0.1583508 0.9757975 0.1508119 -0.1568831 0.9768234 0.1456145 -0.2418482 0.9396924 0.241842 -0.1594757 0.9749203 0.1552346 -0.2418451 0.9396928 0.2418437 -0.151089 0.9780112 0.1437573 -0.2418439 0.9396927 0.2418451 -0.1589207 0.9745717 0.1579698 -0.1485215 0.9781818 0.1452643 -0.2418432 0.9396929 0.2418452 -0.1579581 0.9743332 0.1603871 -0.2418445 0.9396928 0.2418445 -0.1471384 0.9780315 0.147664 -0.2418466 0.9396927 0.2418424 -0.1554216 0.9745812 0.1613557 -0.1470974 0.9775303 0.1509864 -0.2418448 0.9396926 0.2418451 -0.1557821 0.9739302 0.1648992 -0.2418444 0.9396925 0.2418454 -0.148144 0.9763553 0.1574283 -0.1507334 0.9759771 0.1573157 -0.2418449 0.9396923 0.2418461 -0.1535197 0.9741448 0.1657512 -0.2418429 0.9396924 0.2418475 -0.1438757 0.97725 0.1558279 -0.2418459 0.9396922 0.241845 -0.152305 0.9741217 0.1670029 -0.2418456 0.9396923 0.2418452 -0.1445845 0.9764958 0.159848 -0.1488093 0.9755115 0.1619657 -0.2418448 0.9396922 0.2418466 -0.1455777 0.9758254 0.1630082 -0.241841 0.9396927 0.2418483 -0.2418472 0.9396924 0.2418431 -0.1451896 0.9761269 0.1615431 -0.2418462 0.9396923 0.2418444 -0.1450074 0.9759287 0.1628992 -0.2418513 0.9396914 0.2418429 -0.2418441 0.9396921 0.2418473 -0.1449798 0.9759443 0.1628297 -0.1528742 0.9737285 0.1687666 -0.2418425 0.9396929 0.2418459 -0.1439669 0.9762428 0.1619372 -0.2418472 0.9396923 0.2418434 -0.1434893 0.9763839 0.1615092 -0.1431487 0.9764573 0.1613674 -0.1405242 0.9771679 0.1593607 -0.2418441 0.9396931 0.2418435 -0.1517287 0.9737362 0.1697536 -0.2418449 0.939693 0.2418432 -0.2418428 0.9396929 0.2418452 -0.1417325 0.9767872 0.16062 -0.1449306 0.9759761 0.1626827 -0.2418426 0.9396932 0.2418447 -0.1539687 0.9725269 0.1745997 -0.2418404 0.9396935 0.2418453 -0.2418455 0.9396934 0.241841 -0.13941 0.976924 0.161816 -0.1490404 0.9745019 0.1677294 -0.2418437 0.9396935 0.2418425 -0.1525321 0.972257 0.1773421 -0.2418445 0.9396933 0.2418421 -0.1393987 0.9760836 0.1668192 -0.1430528 0.9755423 0.1668927 -0.2418394 0.9396939 0.241845 -0.148416 0.9726694 0.1785691 -0.2418839 0.9396824 0.2418455 -0.2418376 0.9396934 0.241849 -0.2418111 0.9396991 0.2418533 -0.2418109 0.9396991 0.2418534 -0.2418442 0.9396936 0.2418416 -0.1319342 0.9775041 0.1645573 -0.001127421 0.8454493 0.5340545 -0.1735102 0.9089943 0.3789771 -0.1416524 0.9744375 0.1743733 -0.04527175 0.8249545 0.5633834 -0.1555669 0.8016441 0.5772051 -0.04590886 0.8018553 0.595752 -0.2616784 0.7747094 0.57563 -0.1993468 0.7479634 0.6330969 -0.3818304 0.7083812 0.5936344 -0.4244594 0.73932 0.5227238 -0.3523258 0.7431592 0.5688419 -0.4931564 0.6199002 0.6103445 -0.4388663 0.7397458 0.5100711 -0.4440775 0.7134872 0.5419697 -0.450494 0.7245462 0.5216205 -0.4433377 0.7371137 0.5100148 -0.4473662 0.7291415 0.517896 -0.4427657 0.7375404 0.5098948 -0.4444531 0.7352617 0.5117143 -0.4424986 0.739762 0.5068995 -0.4442772 0.7355156 0.5115022 -0.4486886 0.7323707 0.5121638 -0.4461464 0.7400151 0.5033201 -0.4552423 0.7229827 0.5196638 -0.4548943 0.7319732 0.5072342 -0.4533178 0.740124 0.4967086 -0.4702864 0.7103846 0.5236262 -0.4669683 0.728981 0.500527 -0.4591898 0.7490385 0.4775838 -0.4920841 0.6942102 0.5252859 -0.4936109 0.7133056 0.4975374 -0.4723762 0.7531967 0.4577723 -0.5064031 0.696047 0.5089938 -0.4861984 0.7476509 0.4523596 -0.5346456 0.6800546 0.501677 -0.5150533 0.7251989 0.4569537 -0.49677 0.7580351 0.4226137 -0.536544 0.6999171 0.4714196 -0.5567418 0.694461 0.4558098 0.2418438 -0.9396921 -0.2418476 0.3135854 -0.9023773 -0.2955999 0.3368174 -0.8873153 -0.3150011 0.2418381 -0.9396954 -0.2418406 -0.7750691 -0.3368532 0.5346007 0.2420119 -0.9395973 -0.2420478 0.2418084 -0.9397137 -0.241799 -0.7750126 -0.3370621 0.5345509 -0.7751533 -0.3365535 0.5346672 -0.7748714 -0.3375979 0.5344175 -0.775153 -0.3365432 0.5346742 -0.7748886 -0.3375391 0.5344295 -0.7751305 -0.3366162 0.5346608 0.2418444 -0.939692 -0.2418475 -0.01796227 -0.9978348 -0.06327003 0.2418445 -0.939696 -0.2418318 0.2418452 -0.9397006 -0.2418135 0.2418429 -0.9396935 -0.2418435 0.2418407 -0.9396896 -0.2418608 0.2418488 -0.939697 -0.2418238 0.2418307 -0.9396889 -0.2418733 0.2418638 -0.939694 -0.2418205 0.2418297 -0.9396955 -0.2418489 0.2418546 -0.939691 -0.2418411 -0.775026 -0.3370252 0.5345547 -0.1522454 -0.9882711 0.01189905 0.2418463 -0.9396918 -0.2418462 -0.01384019 -0.9989988 -0.04254269 0.2418501 -0.9396946 -0.2418318 0.2418449 -0.9396922 -0.2418463 0.2418384 -0.9396903 -0.2418602 0.2418555 -0.9396936 -0.2418305 0.2418419 -0.939692 -0.2418503 0.2418432 -0.939692 -0.2418487 -0.121798 -0.9923304 0.02111566 0.241846 -0.9396926 -0.2418437 -0.01187437 -0.9997239 -0.02027797 0.2418463 -0.9396927 -0.2418428 0.2418444 -0.9396923 -0.2418463 0.2418363 -0.9396914 -0.2418578 0.2418483 -0.9396918 -0.2418445 -0.1021215 -0.994095 0.03669059 0.2418448 -0.9396925 -0.241845 -0.006195783 -0.9999798 -0.001409947 0.2418482 -0.9396932 -0.2418391 0.2418403 -0.9396928 -0.2418485 -0.09909731 -0.9928417 0.06667184 0.2418461 -0.9396926 -0.2418435 0.001527726 -0.9999147 0.01297771 0.2418446 -0.9396923 -0.2418461 0.2418471 -0.9396923 -0.2418434 -0.08965158 -0.9916837 0.09233647 0.2418413 -0.9396924 -0.241849 -0.003836214 -0.9992968 0.0373001 0.2418442 -0.9396926 -0.2418448 -0.05665051 -0.9943471 0.08980244 0.2418471 -0.9396921 -0.2418445 -0.01317805 -0.9979811 0.06213051 0.2418457 -0.939692 -0.2418463 0.2418478 -0.939692 -0.2418441 0.004941165 -0.9987002 0.05073052 0.2418477 -0.939692 -0.2418441 -0.02315288 -0.9969105 0.07505589 0.2418435 -0.9396927 -0.2418458 -0.02217841 -0.9956008 0.09103298 0.2418428 -0.9396924 -0.2418473 0.2418457 -0.9396929 -0.2418424 0.003801822 -0.998039 0.06248027 0.2418455 -0.9396927 -0.2418439 -3.93461e-4 -0.9980776 0.06197702 0.2418424 -0.9396924 -0.241848 0.003677308 -0.997978 0.06345272 0.001623451 -0.9978404 0.06566601 0.241846 -0.9396921 -0.2418455 0.003515124 -0.9980013 0.06309461 0.241846 -0.9396921 -0.2418455 0.2418465 -0.9396921 -0.241845 -0.016882 -0.9955152 0.09308272 0.2418435 -0.9396932 -0.2418438 0.01399171 -0.9977153 0.0660935 0.2418418 -0.9396929 -0.2418466 0.002780735 -0.9978041 0.06617569 0.2418445 -0.9396928 -0.2418442 -0.1081666 -0.9605926 0.2560506 0.241845 -0.9396929 -0.2418432 0.2418243 -0.9396878 -0.2418839 0.07677036 -0.9907077 0.1122694 0.24184 -0.9396936 -0.2418457 0.01744252 -0.9972172 0.07248115 0.2418316 -0.9396896 -0.2418695 0.188345 -0.9740444 0.1255533 0.08075058 -0.985157 0.1514761 0.2418827 -0.9396981 -0.2417856 0.294553 -0.9471287 0.1272237 0.2380347 -0.9513075 0.1958408 0.2418974 -0.9396998 -0.2417638 0.4172313 -0.8940321 0.1631711 0.3121652 -0.9397912 -0.1390883 0.3848146 -0.914116 0.1277095 0.4422094 -0.8924241 0.08961057 0.51476 -0.8045675 0.2961307 0.4367535 -0.894953 0.09113401 0.3305568 -0.8945093 -0.3009739 0.3384875 -0.889941 -0.3056654 0.3277119 -0.8947983 -0.3032176 0.3471782 -0.88349 -0.3145037 0.3245201 -0.8954427 -0.3047444 0.3373298 -0.8886356 -0.3107014 0.3389399 -0.8866866 -0.3144941 0.3332413 -0.8888008 -0.3146162 0.3371609 -0.8870449 -0.3153948 0.3342759 -0.8877164 -0.316574 0.3198711 -0.8975163 -0.3035569 0.3341225 -0.8880074 -0.3159191 0.3342814 -0.8877129 -0.316578 0.3347355 -0.8874644 -0.3167949 0.3359068 -0.8866043 -0.3179616 0.334509 -0.8876033 -0.3166452 0.3266682 -0.8923392 -0.3114783 0.3308079 -0.8900999 -0.31351 0.3337447 -0.8880979 -0.3160641 0.3342626 -0.8875478 -0.3170604 0.3250435 -0.8925694 -0.3125166 0.3307881 -0.8895505 -0.3150861 0.335783 -0.8857867 -0.3203619 0.3225982 -0.8931453 -0.3134037 0.3289471 -0.8898822 -0.3160752 0.3342888 -0.8855803 -0.322488 0.3271779 -0.8887744 -0.3209904 0.332275 -0.8861868 -0.322903 0.3213407 -0.8915837 -0.3190904 0.3231028 -0.8917078 -0.3169571 0.3322632 -0.8841757 -0.3283812 0.3204867 -0.8909084 -0.3218233 0.332249 -0.882938 -0.3317092 0.3195466 -0.8903104 -0.324403 0.3306986 -0.8826678 -0.33397 0.3185523 -0.8898202 -0.3267176 0.3288993 -0.8824532 -0.336306 0.3202077 -0.8873109 -0.331883 0.3260278 -0.8829445 -0.3378089 0.319006 -0.8870621 -0.3337005 0.3131366 -0.8903589 -0.330464 0.3253146 -0.8814564 -0.3423524 0.3265482 -0.8756883 -0.3557195 0.3031312 -0.8925576 -0.3338451 0.3254979 -0.8767129 -0.3541549 0.3499945 -0.8314752 -0.4314543 0.2906475 -0.8938211 -0.341479 0.3222677 -0.8677896 -0.3782656 0.3119122 -0.8513222 -0.4218546 0.2727849 -0.8974437 -0.3466746 0.3317234 -0.8094797 -0.484461 0.2705848 -0.8811821 -0.3876881 0.2581806 -0.8984273 -0.3552058 0.2739315 -0.8679033 -0.4143735 0.2581536 -0.8953634 -0.3628787 0.2635332 -0.8926848 -0.3656012 0.2582166 -0.8950173 -0.3636869 0.2733413 -0.8897538 -0.3655444 0.2597769 -0.9091944 -0.3253944 0.2812663 -0.8934691 -0.3501461 0.2651314 -0.9199026 -0.2889369 0.3102775 -0.8829299 -0.3523672 0.2823125 -0.8986126 -0.3358497 0.2803674 -0.9143949 -0.2920208 0.3275517 -0.8837472 -0.3342167 0.3058636 -0.8923545 -0.3318901 0.34784 -0.8749536 -0.3368436 0.3011448 -0.904713 -0.3013405 0.7976956 0.2289003 -0.5579304 0.775021 0.3370555 -0.5345429 0.7750381 0.3370136 -0.5345443 0.7998597 0.2122662 -0.5613979 0.7544451 0.4073541 -0.5146603 0.7376288 0.4562557 -0.4977291 0.754257 0.33884 -0.5623912 0.7535896 0.3188171 -0.5748551 0.7681761 0.2480973 -0.5902146 0.7056315 0.4585906 -0.5401657 0.7792387 0.2141889 -0.5889908 0.7809291 0.3448382 -0.5208036 0.7403291 0.4676855 -0.4828903 0.7844043 0.3360633 -0.5213171 0.5809667 -0.05931991 0.8117628 0.5431529 0.06761282 0.836907 0.7608139 0.3541485 -0.5438209 0.7699748 0.3183297 -0.5529963 0.7706485 0.3303579 -0.5449447 0.7995882 0.278049 -0.5323039 0.7117239 0.5135325 -0.4793053 0.7565144 0.3269085 -0.5664069 0.713006 0.465101 -0.5246936 0.7569312 0.3259088 -0.5664262 0.7289015 0.4452463 -0.520056 0.7476099 0.3408951 -0.5699736 0.7157062 0.4438549 -0.5392192 0.6978408 0.4989923 -0.5138336 0.7424319 0.3415632 -0.5763068 0.6917226 0.4927257 -0.5279595 0.7447211 0.3383256 -0.575262 0.737873 0.3418364 -0.5819719 0.7034928 0.4516351 -0.5487473 0.7406321 0.3383894 -0.5804798 0.7009959 0.4713767 -0.5351718 0.7341156 0.3416384 -0.58682 0.7006443 0.4491682 -0.5543876 0.7368694 0.3387358 -0.5850483 0.6888992 0.4852533 -0.5384675 0.7312892 0.3412073 -0.5905876 0.6925686 0.4630264 -0.5531323 0.7336801 0.3392775 -0.5887311 0.6882632 0.4752825 -0.5480877 0.7297332 0.3406236 -0.5928449 0.6901347 0.4649995 -0.5545175 0.7311773 0.3399453 -0.5914531 0.7290741 0.3405848 -0.5936775 0.6917778 0.4589344 -0.5575147 0.729653 0.3400765 -0.5932574 0.689194 0.4671996 -0.5538377 0.7292293 0.3403291 -0.5936336 0.6921098 0.4582853 -0.5576367 0.7290424 0.3404687 -0.5937831 0.7300181 0.3401597 -0.5927604 0.696415 0.4486457 -0.56011 0.7292868 0.3406023 -0.5934063 0.6970549 0.4459905 -0.5614328 0.7306755 0.3403296 -0.5918522 0.7007983 0.4383825 -0.5627633 0.7300868 0.340589 -0.5924292 0.7309095 0.3403768 -0.5915361 0.6938484 0.4580965 -0.5556277 0.7306916 0.3404536 -0.5917611 0.6933043 0.4575406 -0.5567636 0.7307198 0.340388 -0.5917641 0.6918286 0.4629528 -0.554119 0.7309026 0.340323 -0.5915758 0.6919733 0.462503 -0.554314 0.7301889 0.3404811 -0.5923655 0.690507 0.4651038 -0.5539661 0.7307066 0.340294 -0.5918343 0.7290661 0.3407813 -0.5935745 0.6931882 0.4552767 -0.5587605 0.7291309 0.340668 -0.5935599 0.730161 0.3402991 -0.5925043 0.6895521 0.4673533 -0.553262 0.7273425 0.3409343 -0.5955978 0.6906445 0.457643 -0.5599759 0.727822 0.3401069 -0.595485 0.686229 0.470641 -0.5546051 0.7251642 0.3411079 -0.5981491 0.687307 0.4609254 -0.5613884 0.7256858 0.3402262 -0.5980186 0.7225391 0.3412657 -0.6012279 0.6881508 0.4518097 -0.5677292 0.7231212 0.3403112 -0.6010691 0.6813927 0.4748769 -0.5569524 0.7194957 0.3415656 -0.6046974 0.6717301 0.4867827 -0.5584097 0.7203097 0.3402867 -0.6044493 0.7160621 0.3419631 -0.6085363 0.6802409 0.4563935 -0.5735656 0.7171671 0.3403197 -0.6081562 0.6805971 0.4658029 -0.5655221 0.7123611 0.3422675 -0.6126946 0.6772307 0.4548523 -0.5783321 0.7137309 0.3403744 -0.6121547 0.6663239 0.4880135 -0.5637866 0.7136524 0.3211194 -0.6225614 0.6679821 0.4690359 -0.5777588 0.7071462 0.3375651 -0.6212844 0.7054352 0.3375352 -0.6232426 0.6706818 0.4507559 -0.5890715 0.6586136 0.4904444 -0.5706948 0.6936507 0.3486108 -0.6303327 0.6888641 0.3662419 -0.6255663 0.6533675 0.4835622 -0.5824763 0.6802277 0.3448965 -0.6467897 0.6644736 0.400232 -0.6311015 0.6806887 0.3438319 -0.6468714 0.694472 0.3398486 -0.6342015 0.6378743 0.4988451 -0.5867452 0.6648524 0.3475351 -0.661204 0.6303464 0.4581224 -0.6267274 0.6688112 0.3394864 -0.661393 0.640492 0.4650052 -0.6111794 0.6502895 0.3482673 -0.6751544 0.6206082 0.4454362 -0.6453155 0.656496 0.3374544 -0.6746389 0.6388972 0.4356241 -0.6340677 0.6079731 0.4831355 -0.6300387 0.6366814 0.3476829 -0.6882975 0.5949357 0.4782972 -0.6459748 0.6441081 0.3369009 -0.6867479 0.62401 0.3465368 -0.7003741 0.5936731 0.4463949 -0.6695401 0.6321073 0.3370897 -0.6977183 0.5940575 0.4804076 -0.6452165 0.6123928 0.3450166 -0.7112936 0.5863866 0.432664 -0.6848011 0.6205868 0.3377145 -0.7076869 0.560934 0.5217657 -0.6427392 0.6006177 0.3442999 -0.7216066 0.5353446 0.5351215 -0.6534916 0.6098565 0.3381422 -0.716753 0.5814423 0.3403665 -0.7389693 0.5576414 0.4224555 -0.7145399 0.5774953 0.3465034 -0.7392121 0.598636 0.3377615 -0.7263278 0.5532933 0.4952911 -0.6697412 0.5399984 0.3515661 -0.7647242 0.5418193 0.3446914 -0.7665635 0.5509311 0.3376442 -0.7631981 0.4474543 0.6440081 -0.6205144 0.4819921 0.3521633 -0.8022871 0.3590672 0.6643279 -0.6555451 0.5156592 0.3262806 -0.7922352 0.4142761 0.3373636 -0.8453172 0.4179047 0.3234084 -0.8489775 0.4186904 0.3327174 -0.8449838 0.470434 0.3266457 -0.8197526 0.3667651 0.651446 -0.6641546 0.3347846 0.3324847 -0.8816877 0.1032366 0.8471648 -0.5212044 0.366971 0.3110378 -0.8766914 0.2517417 0.3181523 -0.9140051 0.2553397 0.3043568 -0.9176974 0.3014497 0.2959603 -0.9063861 0.202395 0.7127463 -0.671587 0.1857212 0.3009644 -0.9353759 0.04831629 0.7077457 -0.7048132 0.2285313 0.2839226 -0.931215 0.1477181 0.2873266 -0.9463735 0.126816 0.3651095 -0.9222867 0.1706752 0.2761195 -0.9458478 0.09071677 0.6215525 -0.778102 0.1373074 0.2794724 -0.9502852 0.09552782 0.4307192 -0.8974159 0.1401288 0.2774258 -0.950473 0.151212 0.2811624 -0.9476723 0.1077023 0.4376743 -0.8926598 0.1463363 0.2856923 -0.9470826 0.119488 0.3621337 -0.9244359 0.1922209 0.2875863 -0.9382671 0.1931992 0.2837632 -0.9392297 0.1873379 0.2923383 -0.9377862 0.2627043 0.292766 -0.9193881 0.195666 0.5161926 -0.8338226 0.2495175 0.3044645 -0.9192619 0.266105 0.02061676 -0.9637236 0.3581377 0.2974064 -0.8850349 0.3746377 0.2259055 -0.8992294 0.3238155 0.3225622 -0.8894364 0.4556757 0.3074682 -0.8353579 0.3696931 0.5673676 -0.7358132 0.4009209 0.3369135 -0.8519106 0.4487807 -0.1793988 -0.8754495 0.5413173 0.3291375 -0.7737209 0.5639374 0.2244395 -0.7947337 0.5453497 0.3236598 -0.7731999 0.4732376 0.3409345 -0.8122868 0.624888 0.3173174 -0.7133194 0.5061311 0.6293074 -0.5897487 0.6014561 0.3469251 -0.7196482 0.594439 0.0424931 -0.8030172 0.695411 0.3135095 -0.6466184 0.5966917 0.5846088 -0.5497195 0.6545543 0.3579296 -0.6659168 0.7045721 0.05563473 -0.7074483 0.7052026 0.3553966 -0.6135002 0.7476709 0.07992988 -0.6592417 0.6850103 0.5091689 -0.5210643 0.5749326 0.5710974 -0.5859184 0.6434094 0.1058813 -0.7581647 0.6251049 0.4635053 -0.628018 0.4049561 0.676724 -0.614862 0.5189085 0.1031727 -0.8485808 0.4603917 0.5817458 -0.6705306 0.3606799 0.4693757 -0.8059754 -0.01569682 0.9527318 -0.3034067 0.2875401 0.1385031 -0.9477012 0.3820902 0.3085666 -0.8710877 0.05825358 0.6835817 -0.7275456 0.1863049 0.1179422 -0.9753872 0.1975988 0.3295192 -0.9232399 0.1692199 0.1576262 -0.9728918 0.1644441 0.1865959 -0.9685763 0.1994981 0.155435 -0.9674918 0.33034 -0.4590821 -0.8246935 0.3237543 0.1998425 -0.9247952 0.2305265 0.1412751 -0.962756 0.4336674 -0.3822575 -0.8159729 0.4359703 0.2610297 -0.8612743 0.426624 -0.2101808 -0.8796682 0.5133368 0.09783339 -0.8525926 0.5349047 -0.42301 -0.7313956 0.5749974 0.2276301 -0.7858514 0.5214954 0.1700745 -0.8361324 0.6225118 -0.1762058 -0.762516 0.6238464 0.2181105 -0.7504956 0.5947327 0.2044708 -0.7774862 0.6334283 0.2275817 -0.7395777 0.6412522 0.1278743 -0.7566002 0.6484575 0.1996112 -0.7346143 0.6508191 0.2521442 -0.7161409 0.6566063 0.1532287 -0.7385047 0.6631988 0.2494755 -0.705641 0.673294 0.1497067 -0.7240601 0.6780228 0.2362064 -0.6960543 0.6851134 0.1750621 -0.7070876 0.69014 0.2398738 -0.6827645 0.6957133 0.1963128 -0.6909735 0.6985067 0.2648204 -0.6647996 0.7078791 0.1959521 -0.6786089 0.7054147 0.2933903 -0.6452227 0.7207371 0.1794984 -0.6695658 0.718836 0.2871266 -0.6331139 0.7307082 0.1744654 -0.6600207 0.73958 0.2116459 -0.6389266 0.7318384 0.2245796 -0.64341 0.7412043 0.223412 -0.6330112 0.7441754 0.1858734 -0.6416028 0.7474561 0.2021725 -0.6327998 0.7471232 0.2234907 -0.6259862 0.7481607 0.1980102 -0.6332833 0.7504827 0.2181302 -0.623855 0.7526631 0.196843 -0.6282923 0.7531672 0.2142093 -0.6219755 0.7538853 0.2190898 -0.6194003 0.7545638 0.2063389 -0.6229429 0.7563849 0.2084546 -0.6200231 0.7563899 0.2121655 -0.6187569 0.7564192 0.208255 -0.6200482 0.7570566 0.208954 -0.6190344 0.7565801 0.2110432 -0.6189081 0.756668 0.2112487 -0.6187306 0.7538748 0.2252217 -0.6172099 0.753961 0.2243965 -0.6174049 0.7526232 0.2281061 -0.6176779 0.7534475 0.2210504 -0.6192364 0.7529922 0.2262265 -0.6179193 0.7545357 0.2172314 -0.6192628 0.7561901 0.2161055 -0.6176365 0.7558445 0.2097342 -0.6202505 0.7577676 0.2210626 -0.6139378 0.760125 0.1948567 -0.6198716 0.7638273 0.2001107 -0.6136152 0.7636182 0.2266479 -0.6045808 0.764978 0.1930725 -0.6144359 0.7754831 0.1676263 -0.6087096 0.7741295 0.2429094 -0.584567 0.7709097 0.1987659 -0.6051365 0.7721456 0.3243071 -0.5464578 0.752826 0.3361898 -0.5658883 0.7939009 0.1573541 -0.5873338 0.797865 0.2772825 -0.5352811 0.8043125 0.1640062 -0.5711246 0.5809687 -0.05942237 0.811754 0.6292913 -0.4144024 0.6574672 0.5854581 -0.1915439 0.7877498 0.8128343 0.1967097 -0.5482753 0.4163972 -0.124658 0.9005963 0.2948085 0.2380409 0.925432 0.294807 0.2381791 0.925397 0.4443408 0.3048702 0.8423867 0.3145428 0.4861195 0.8153225 0.6737973 -0.2985213 -0.6759307 0.4477815 0.2802223 0.8490979 0.4164469 -0.1245667 0.900586 0.4768287 -0.4689043 0.7434804 -0.3328543 -0.3144097 0.8890188 -0.3993784 0.06218755 0.9146745 -0.3329204 -0.3145074 0.8889597 -0.5233789 -0.33623 0.7829585 -0.5480638 0.3932124 0.738248 -0.5894531 0.04772961 0.8063914 0.04530948 -0.237985 0.9702115 -0.04902708 0.1331305 0.9898852 0.04529935 -0.2380003 0.9702081 -0.3993618 0.06224834 0.9146776 -0.04905813 0.1329327 0.9899102 0.1330016 -0.5742087 0.8078335 0.4767456 -0.4691678 0.7433674 -0.2174379 -0.6449767 0.7326157 0.1330186 -0.5741342 0.8078837 -0.522225 -0.3498529 0.7777428 -0.3932408 -0.6702888 0.6293445 -0.2174345 -0.6448949 0.7326889 -0.8208211 -0.2808902 0.4973464 -0.8289964 -0.2367285 0.50668 -0.8136623 -0.3322309 0.4770495 -0.7909941 -0.2951804 0.5359077 -0.8176053 -0.06446367 0.5721591 -0.7900772 -0.3566379 0.4985856 -0.8126244 0.1927182 0.5500013 -0.8160991 0.1776502 0.5499295 -0.8240914 0.138511 0.5492613 -0.837961 0.03754818 0.5444369 -0.8424633 -0.08001196 0.5327792 -0.762774 -0.3008956 0.5723964 -0.7910889 -0.06859737 0.6078426 -0.7423508 -0.4238391 0.5189179 -0.7833188 0.2016083 0.5880185 -0.7231052 -0.3541998 0.5930106 -0.7657858 -0.01026809 0.6430138 -0.7144872 -0.3958775 0.5768787 -0.7546832 0.1963493 0.6260192 -0.7032227 -0.3309201 0.6292613 -0.7346943 0.1151655 0.6685515 -0.6820277 -0.3138894 0.660539 -0.7171015 -0.01595163 0.6967862 -0.6778961 -0.3960441 0.6193593 -0.7314738 0.1383801 0.6676802 -0.6529695 -0.3335515 0.679981 -0.6942796 0.01718318 0.7195002 -0.6456155 -0.3876107 0.6579807 -0.6905681 0.1980161 0.6956331 -0.6233686 -0.3653242 0.6913392 -0.6734186 0.07568454 0.735377 -0.6256362 -0.3515617 0.6964077 -0.6153557 -0.3301541 0.7157763 -0.6585144 0.01317316 0.7524529 -0.664548 0.156468 0.7306803 -0.6011138 -0.3325055 0.7267065 -0.6447732 0.09774821 0.7580981 -0.6001606 -0.3623844 0.7130812 -0.5883604 -0.3414733 0.7329583 -0.6363677 0.02933567 0.7708278 -0.5874459 -0.3504947 0.729425 -0.6430816 0.1168944 0.7568234 -0.5813858 -0.338939 0.7396694 -0.629247 0.07322955 0.7737479 -0.5766947 -0.3370191 0.7442052 -0.6247165 0.04204827 0.7797186 -0.5782243 -0.3459373 0.7389073 -0.6281161 0.08985465 0.7729142 -0.573201 -0.3387546 0.746114 -0.6219617 0.04839444 0.7815508 -0.5731477 -0.3428733 0.7442712 -0.5717824 -0.3393731 0.7469208 -0.6207657 0.06673818 0.7811504 -0.5717521 -0.33976 0.7467681 -0.5720723 -0.3397048 0.746548 -0.6211525 0.04762315 0.7822414 -0.6214284 0.04888582 0.7819444 -0.5722724 -0.3376956 0.7473058 -0.6208732 0.05007314 0.7823102 -0.5724971 -0.3388868 0.7465941 -0.5667304 -0.3327516 0.7537195 -0.6145712 0.03711581 0.7879877 -0.5671922 -0.3454945 0.747614 -0.6187425 0.08858346 0.7805835 -0.5518381 -0.3299283 0.7659125 -0.6006058 0.06988292 0.7964854 -0.5510893 -0.3505428 0.7572451 -0.4274783 -0.6585085 0.6193777 -0.3175706 -0.7968124 0.5140419 -0.42641 -0.6838377 0.5920647 -0.4353994 -0.6745918 0.5961151 -0.4186093 -0.6979864 0.5810175 -0.4354234 -0.6737365 0.5970641 -0.4413737 -0.6672214 0.600004 -0.4310907 -0.6817929 0.5910323 -0.4323605 -0.6909951 0.5793016 -0.4654378 -0.6523836 0.598133 -0.427541 -0.6992303 0.5729622 -0.4870145 -0.6410489 0.593189 -0.418873 -0.7360655 0.5317453 -0.4435824 -0.7395699 0.5062324 -0.5205523 -0.6678024 0.5320388 -0.4804008 -0.6831622 0.5500042 -0.5875474 -0.6100226 0.5316581 -0.477105 -0.7346894 0.4822889 -0.6389005 -0.5793938 0.5060721 -0.5014073 -0.7461516 0.4380051 -0.6625587 -0.6001428 0.4481569 -0.5480277 -0.7270199 0.4136517 -0.639324 -0.6736867 0.3706902 -0.6250994 -0.6624941 0.4127377 -0.6843174 -0.6298304 0.3674557 -0.5582619 -0.7748816 0.2964832 -0.7749933 -0.3372032 0.5344898 -0.7749763 -0.3375055 0.5343236 -0.7750917 -0.3365304 0.5347712 -0.7760515 -0.3323093 0.5360173 -0.7747713 -0.3381218 0.5342314 -0.6364991 0.6078829 0.4747078 -0.7424253 0.4175797 0.5238625 -0.7936285 0.2730185 0.5437046 0.7748172 -0.3378269 -0.5343512 0.2418578 0.9396881 -0.2418497 0.241836 0.9396949 -0.2418445 0.2418553 0.9396905 -0.2418425 0.2418442 0.9396908 -0.2418527 0.2418454 0.9396914 -0.2418489 0.4350576 0.8291242 -0.3511095 0.4081063 0.8483712 -0.3372178 0.7750205 -0.3370452 -0.53455 0.775013 -0.3370872 -0.5345346 0.7750468 -0.3369302 -0.5345847 0.7750422 -0.3368629 -0.5346336 0.7744264 -0.341901 -0.5323228 0.7763115 -0.3256837 -0.5396949 0.7758504 -0.3337736 -0.5353984 0.7749286 -0.3374086 -0.5344539 0.7751709 -0.3364496 -0.5347073 0.7740017 -0.341138 -0.5334289 0.7749049 -0.3375114 -0.5344235 0.7751594 -0.3364526 -0.5347219 0.7748311 -0.3378639 -0.5343079 0.09090721 0.9878396 -0.1261299 0.08426535 0.9917967 -0.09611803 0.1137393 0.9833955 -0.1414093 0.1007159 0.991384 -0.08375054 0.1414879 0.9800067 -0.1398862 0.1468752 0.982949 -0.1106301 0.2418359 0.9396933 -0.2418507 0.1335348 0.9895581 -0.05425202 0.1609474 0.9788021 -0.1266585 0.2418516 0.9396916 -0.2418419 0.183874 0.9768978 -0.1089088 0.2418542 0.9396903 -0.2418439 0.177629 0.983121 -0.04382932 0.241849 0.9396916 -0.2418445 0.190867 0.974133 -0.1209741 0.2418356 0.9396938 -0.2418496 0.2018085 0.9766659 -0.0734651 0.2418415 0.939693 -0.2418465 0.2058125 0.9772465 -0.05128675 0.2088097 0.9735495 -0.09273606 0.2418462 0.9396927 -0.2418431 0.2104534 0.9761487 -0.05331933 0.2418533 0.9396926 -0.2418364 0.2088624 0.9767575 -0.04818069 0.2418302 0.9396942 -0.2418532 0.205243 0.9769703 -0.05834662 0.2418435 0.9396922 -0.241848 0.2086012 0.9768638 -0.04714614 0.2418463 0.9396923 -0.2418447 0.1537448 0.9856075 0.07028859 0.2418501 0.9396919 -0.2418419 0.1795845 0.9804942 -0.07987862 0.1831529 0.9829725 -0.01483148 0.2418397 0.9396921 -0.2418515 0.1588653 0.9839152 -0.08168625 0.1043326 0.9932698 0.05029731 0.2418468 0.9396929 -0.2418416 0.1316584 0.9887779 -0.07060068 0.2418488 0.9396927 -0.2418406 0.2418454 0.939693 -0.2418426 0.1374467 0.9852358 -0.102073 0.1132338 0.9924885 -0.04630964 0.2418444 0.939693 -0.2418436 0.126791 0.9867493 -0.1012414 0.1064957 0.9918512 -0.06992703 0.2418466 0.9396924 -0.2418436 0.1202787 0.9876888 -0.1000191 0.2418425 0.9396929 -0.2418459 0.1126047 0.989598 -0.08953136 0.241841 0.9396927 -0.2418481 0.1166564 0.9880015 -0.1012148 0.1129148 0.9889126 -0.096448 0.2418472 0.9396926 -0.2418426 0.114667 0.9878582 -0.1048228 0.2418444 0.9396929 -0.2418442 0.1116799 0.9885771 -0.1012069 0.2418418 0.9396927 -0.2418472 0.1144585 0.9872614 -0.1105183 0.107998 0.9888045 -0.1029667 0.2418479 0.9396923 -0.2418425 0.1144275 0.9865956 -0.1163425 0.2418425 0.9396927 -0.2418463 0.1030123 0.9893111 -0.1032092 0.2418463 0.9396926 -0.2418436 0.1120808 0.9864511 -0.1198003 0.2418478 0.9396924 -0.2418426 0.09933429 0.9895449 -0.1045626 0.2418454 0.9396925 -0.2418444 0.1035363 0.9876533 -0.117563 0.2418456 0.9396925 -0.2418443 0.1008553 0.9887412 -0.1105396 0.2418437 0.9396926 -0.2418462 0.1078671 0.9860608 -0.1266841 0.2418442 0.9396925 -0.2418458 0.09475398 0.9890834 -0.1128522 0.1108336 0.9861195 -0.12363 0.2418447 0.9396927 -0.2418445 0.1060995 0.9858379 -0.1298711 0.241845 0.9396927 -0.2418444 0.241845 0.9396927 -0.2418444 0.09513449 0.9882639 -0.1195158 0.0986911 0.9879043 -0.1196043 0.241845 0.9396926 -0.2418447 0.09562736 0.9874804 -0.1254502 0.2418442 0.9396927 -0.241845 0.2418444 0.9396927 -0.2418448 0.09352058 0.9882652 -0.1207722 0.2418454 0.9396927 -0.2418438 0.09362953 0.9874548 -0.1271479 0.2418458 0.9396927 -0.2418438 0.2418458 0.9396927 -0.2418437 0.2418457 0.9396926 -0.2418438 0.09182071 0.9880784 -0.1235727 0.1093658 0.9846805 -0.1358061 0.2418453 0.9396925 -0.2418447 0.09530043 0.9868677 -0.1304219 0.2418459 0.9396925 -0.2418445 0.2418428 0.9396929 -0.2418456 0.2418461 0.9396924 -0.2418437 0.2418439 0.9396926 -0.2418455 0.09095138 0.9877696 -0.1266452 0.09201079 0.9876843 -0.1265456 0.1060647 0.9849712 -0.1363162 0.2418441 0.9396926 -0.2418454 0.09013754 0.9878278 -0.1267728 0.2418447 0.9396924 -0.2418454 0.241844 0.9396926 -0.2418456 0.2418448 0.9396926 -0.2418452 0.2418447 0.9396925 -0.2418453 0.09098798 0.9876474 -0.1275692 0.09259468 0.9873761 -0.1285094 0.2418471 0.9396917 -0.2418461 0.08038187 0.9898474 -0.1172217 0.2418358 0.9396956 -0.2418419 0.241833 0.9396966 -0.2418411 0.2418521 0.9396905 -0.2418458 0.2418529 0.9396902 -0.241846 0.2418413 0.9396936 -0.2418442 0.2418442 0.9396929 -0.241844 0.2418417 0.9396933 -0.2418449 0.2418481 0.939693 -0.2418401 0.09208774 0.9875648 -0.1274189 0.09129804 0.9876334 -0.1274557 0.08699488 0.9883991 -0.1244956 0.001113712 0.845439 -0.534071 0.1312838 0.8978421 -0.4202905 0.09778332 0.9867879 -0.1291822 0.07689243 0.990426 -0.114647 0.04523557 0.8249521 -0.5633895 0.155537 0.8015992 -0.5772755 0.04587203 0.8018099 -0.595816 0.2617238 0.7746949 -0.5756288 0.1993094 0.7479173 -0.6331632 0.3819204 0.708331 -0.5936363 0.3378934 0.8561671 -0.390904 0.2296681 0.8583539 -0.4587824 0.374115 0.8169353 -0.4389246 0.5058497 0.5886736 -0.630539 0.3441905 0.8569118 -0.3837121 0.3576356 0.837495 -0.4131574 0.3502213 0.8521103 -0.3889127 0.3650493 0.8375419 -0.4065249 0.3864312 0.8141483 -0.4333976 0.3488968 0.8556045 -0.3823769 0.3521308 0.8510587 -0.3894907 0.3492748 0.8552968 -0.3827196 0.3493848 0.8551951 -0.3828468 0.3511328 0.8535207 -0.3849781 0.3492553 0.8555546 -0.382161 0.3495921 0.8550169 -0.3830552 0.3508949 0.85416 -0.3837754 0.3569597 0.8483963 -0.3909007 0.3498724 0.8560336 -0.3805205 0.353336 0.8519423 -0.3864555 0.3536367 0.8529821 -0.3838784 0.3720198 0.8351098 -0.4052072 0.3522433 0.8562925 -0.3777405 0.3537988 0.8532038 -0.3832359 0.3747759 0.8354158 -0.4020243 0.3539648 0.857687 -0.3729371 0.3615861 0.8483017 -0.3868327 0.3950325 0.8196185 -0.4149397 0.3602691 0.8565009 -0.3696113 0.3610589 0.8525106 -0.3779709 0.3538058 0.8648369 -0.3561999 0.3896353 0.8302373 -0.3986104 0.3660295 0.8580507 -0.3602378 0.3971719 0.8296905 -0.3922605 0.384309 0.8475292 -0.3660613 0.3670873 0.8654881 -0.340848 0.3892859 0.8434793 -0.3701338 0.3635389 0.8717548 -0.328455 0.4246865 0.820788 -0.382032 0.3773571 0.8659875 -0.3281272 0.463758 0.7961834 -0.3886137 -0.2418467 -0.9396942 0.2418361 -0.162437 -0.9845117 0.06596231 -0.2418426 -0.9396928 0.2418463 -0.2418465 -0.9396923 0.2418442 0.253992 -0.8487868 -0.4637337 -0.133069 -0.9873887 0.08576834 -0.2418373 -0.939692 0.2418547 -0.1883374 -0.9740457 -0.1255549 -0.09964621 -0.9297574 -0.3544318 -0.08077383 -0.9851561 -0.1514703 -0.2418524 -0.9396945 0.2418298 -0.2945259 -0.9471372 -0.1272222 -0.2380213 -0.9513102 -0.1958429 -0.2418165 -0.9396901 0.2418825 -0.4172303 -0.8940311 -0.1631789 -0.3468393 -0.9340842 0.08478969 -0.3848311 -0.9141054 -0.1277363 -0.441873 -0.8925646 -0.08987039 -0.4941258 -0.8381159 -0.231087 -0.3891283 -0.8505976 0.3536421 -0.3772687 -0.8590933 0.3458713 -0.2418469 -0.9396923 0.2418434 -0.3892329 -0.8507349 0.3531967 -0.2418435 -0.9396929 0.2418451 -0.3888524 -0.851251 0.3523715 -0.241843 -0.9396928 0.2418459 -0.3885026 -0.8513258 0.3525765 -0.2418439 -0.9396928 0.241845 -0.3847629 -0.8546525 0.3486065 -0.241844 -0.9396929 0.2418448 -0.3844091 -0.8548263 0.3485709 -0.2418435 -0.9396924 0.2418469 -0.3827182 -0.8565072 0.3462978 -0.241845 -0.9396928 0.2418438 -0.241844 -0.9396928 0.2418449 -0.381689 -0.8571144 0.3459312 -0.2418467 -0.9396924 0.2418435 -0.3837922 -0.8557482 0.3469849 -0.2418463 -0.9396923 0.2418441 -0.3831208 -0.8561812 0.3466588 -0.2418454 -0.9396926 0.2418445 -0.3835369 -0.8557493 0.3472644 -0.2418453 -0.9396925 0.2418446 -0.3847247 -0.8549947 0.3478088 -0.2418451 -0.9396927 0.241844 -0.3823128 -0.8565687 0.3465933 -0.2418435 -0.9396927 0.2418459 -0.3832706 -0.8559644 0.3470283 -0.2418447 -0.9396926 0.2418447 -0.382229 -0.8562825 0.3473921 -0.2418454 -0.9396928 0.2418437 -0.2418449 -0.9396928 0.2418441 -0.3843431 -0.8549188 0.3484169 -0.2418439 -0.9396928 0.2418447 -0.3812937 -0.856577 0.3476939 -0.2418427 -0.9396927 0.2418466 -0.3842554 -0.8546084 0.3492738 -0.2418462 -0.9396926 0.2418434 -0.3808171 -0.8564978 0.3484106 -0.2418475 -0.9396929 0.2418413 -0.3837364 -0.8544956 0.3501195 -0.241842 -0.9396926 0.2418475 -0.3809327 -0.8558493 0.3498746 -0.3834417 -0.8540766 0.3514624 -0.2418467 -0.9396924 0.2418439 -0.3815941 -0.8547265 0.3518927 -0.2418459 -0.9396923 0.2418449 -0.2418447 -0.9396923 0.2418456 -0.37428 -0.8587216 0.3500167 -0.2418451 -0.9396926 0.2418446 -0.2418439 -0.9396924 0.2418463 -0.3819122 -0.8544654 0.3521815 -0.2418473 -0.9396923 0.2418433 -0.3635855 -0.8641429 0.3479405 -0.241847 -0.9396923 0.2418437 -0.344769 -0.8807207 0.3247545 -0.3692479 -0.8622435 0.3466874 -0.3808336 -0.8520541 0.3591232 -0.241844 -0.939693 0.2418441 -0.3634722 -0.8613752 0.354853 -0.2418417 -0.9396929 0.2418468 -0.3592325 -0.8675986 0.343838 -0.377185 -0.8520134 0.3630492 -0.2418451 -0.9396928 0.2418436 -0.3585678 -0.8624652 0.3571876 -0.2418453 -0.9396929 0.2418434 -0.3601013 -0.8641897 0.3514302 -0.3744707 -0.8505583 0.3692184 -0.2418429 -0.9396927 0.2418457 -0.3633917 -0.855509 0.3688507 -0.2418438 -0.9396929 0.2418444 -0.3672752 -0.8546081 0.3670886 -0.2418428 -0.9396922 0.2418487 -0.3561957 -0.8590703 0.3675907 -0.2418448 -0.9396928 0.2418441 -0.3589271 -0.8596048 0.363663 -0.3654725 -0.8514086 0.3762091 -0.2418496 -0.939693 0.2418384 -0.3554153 -0.8573144 0.3724137 -0.3628786 -0.8510131 0.3795994 -0.2418383 -0.9396927 0.2418504 -0.3588986 -0.8516216 0.3820109 -0.2418453 -0.9396924 0.2418456 -0.3500706 -0.8569612 0.3782435 -0.2418458 -0.9396924 0.2418445 -0.3569967 -0.8535955 0.3793786 -0.2418456 -0.9396924 0.2418451 -0.3366843 -0.8640434 0.3742628 -0.3640213 -0.8410131 0.4002319 -0.2418456 -0.9396922 0.2418451 -0.3736308 -0.8055974 0.4597966 -0.2418534 -0.9396954 0.2418254 -0.3189903 -0.860691 0.3968076 -0.2418455 -0.9396923 0.2418451 -0.3417619 -0.850613 0.3995701 -0.2418362 -0.9396911 0.2418592 -0.4130612 -0.4880426 0.768892 -0.241847 -0.9396926 0.2418423 -0.2849521 -0.8633044 0.4165427 -0.3135251 -0.8573008 0.408335 -0.2418409 -0.9396924 0.2418497 -0.2664266 -0.8749207 0.4043894 -0.2936193 -0.8182414 0.4942354 -0.241846 -0.9396917 0.2418469 -0.2656978 -0.8633196 0.42905 -0.2418465 -0.9396921 0.241845 -0.2654054 -0.8641377 0.4275817 -0.2418457 -0.9396916 0.2418474 -0.2712575 -0.8761319 0.3985126 -0.2418413 -0.9396913 0.2418534 -0.2992237 -0.8498339 0.4338752 -0.2712608 -0.8761147 0.3985483 -0.2418447 -0.9396974 0.2418264 -0.2821815 -0.9012157 0.328913 -0.2418457 -0.939691 0.2418501 -0.2418423 -0.9396927 0.2418466 -0.3376228 -0.8542461 0.3953156 -0.3055455 -0.8626528 0.4030784 -0.2418447 -0.9396932 0.2418426 -0.3745896 -0.8340165 0.4050915 -0.3146367 -0.8833028 0.3475341 -0.2418547 -0.9396873 0.2418555 -0.3771941 -0.8480251 0.3722609 -0.2418442 -0.9396933 0.2418428 -0.3412188 -0.8752118 0.3428906 -0.2418414 -0.9396952 0.241838 -0.3729061 -0.8625641 0.3419419 -0.3821454 -0.8552711 0.3499662 0.7753833 -0.3356338 -0.5349118 0.7749527 -0.3372929 -0.5344921 0.7744037 -0.3393329 -0.5339964 0.7750777 -0.3368189 -0.5346099 0.7754995 -0.3352037 -0.5350133 0.7742506 -0.3400006 -0.5337936 -0.00458765 -0.995085 0.09891808 0.7735078 -0.3431222 -0.5328722 -0.09847617 -0.9843106 0.1464074 -0.05167478 -0.9902864 0.1290835 -0.1205322 -0.9810885 0.1514509 -0.01713538 -0.9960969 0.08658742 -0.1290467 -0.9805755 0.1477119 -0.02575385 -0.9970798 0.07189303 -0.1296196 -0.9819212 0.1379476 -0.0423758 -0.9969066 0.06619173 -0.1262537 -0.9840492 0.1253275 -0.05833107 -0.9962676 0.06362789 -0.1188989 -0.986837 0.1096168 -0.07803285 -0.9945626 0.06896436 -0.1057062 -0.9904792 0.088189 -0.1236854 -0.9869222 0.1033757 -0.1006843 -0.991514 0.08223479 -0.08935564 -0.9942877 0.05837398 -0.1226373 -0.9878854 0.09509223 -0.1177969 -0.9886056 0.09371775 -0.1016783 -0.9925719 0.06680256 -0.1246136 -0.9877833 0.09357213 -0.1201457 -0.988605 0.09069305 -0.1182856 -0.9893824 0.08444517 -0.125099 -0.9878412 0.09230357 -0.1201843 -0.9889322 0.08699959 -0.1249404 -0.9879221 0.09165138 -0.1238671 -0.9882004 0.09009408 -0.1237221 -0.9882366 0.08989596 -0.1253742 -0.9878829 0.09148138 -0.125037 -0.9879096 0.0916537 -0.1171373 -0.9899529 0.07919716 -0.07438796 -0.9970251 0.02018088 -0.1311361 -0.9872121 0.09063971 -0.1221379 -0.9888678 0.08498752 -0.1076616 -0.9928173 0.05218148 -0.8000286 0.2267239 0.5554734 -0.7750303 0.3370235 0.5345494 -0.7750002 0.3370966 0.534547 -0.8072733 0.1475988 0.5714232 -0.7549561 0.4058011 0.5151376 -0.7482069 0.33936 0.5701063 -0.7434247 0.3573389 0.5653571 -0.6811226 0.5157679 0.5196687 -0.7434505 0.349295 0.5703284 -0.7788164 0.1502608 0.6089884 -0.7434762 0.3399933 0.5758888 -0.6808423 0.5192253 0.5165838 -0.7436778 0.339607 0.5758562 -0.5809794 -0.05938422 -0.8117491 -0.5214657 0.1281824 -0.8435892 -0.7458364 0.3391743 0.5733139 -0.6828469 0.5193926 0.5137621 -0.6873288 0.5064196 0.5206901 -0.747735 0.338914 0.5709902 -0.689085 0.5093644 0.5154704 -0.7459009 0.3399888 0.5727472 -0.7492823 0.3387746 0.5690411 -0.6867349 0.5179379 0.5100349 -0.7478585 0.3398988 0.5702424 -0.6885652 0.5104324 0.5151085 -0.7505227 0.3387343 0.5674282 -0.6934649 0.5054302 0.5134655 -0.749464 0.3397555 0.5682165 -0.7515971 0.3385959 0.566087 -0.6898206 0.5159538 0.5078772 -0.7507402 0.3395529 0.5666506 -0.6889408 0.5148566 0.5101795 -0.7523339 0.3387694 0.5650035 -0.6901819 0.5168295 0.5064939 -0.7517142 0.3392876 0.5655172 -0.6917575 0.5120997 0.5091418 -0.7527126 0.3389193 0.5644089 -0.6911695 0.5155279 0.5064738 -0.752368 0.3390938 0.5647634 -0.6917937 0.5139254 0.5072496 -0.752757 0.3389855 0.5643098 -0.6912438 0.5154963 0.5064048 -0.7527179 0.3390075 0.5643489 -0.7524747 0.3390878 0.5646248 -0.6913915 0.5146141 0.5070998 -0.752752 0.3389188 0.5643567 -0.690809 0.5163568 0.5061212 -0.7518749 0.3392227 0.5653426 -0.6888442 0.519059 0.5060349 -0.7524514 0.338842 0.5648034 -0.750991 0.3393771 0.5664238 -0.6899443 0.5148002 0.5088788 -0.7518246 0.3387896 0.5656689 -0.690063 0.5165817 0.5069087 -0.7498332 0.33955 0.5678521 -0.6891839 0.5140921 0.510622 -0.7509056 0.3387596 0.5669063 -0.6864492 0.5214927 0.506787 -0.7484279 0.3397397 0.5695897 -0.6859368 0.5184094 0.5106295 -0.7497074 0.3387708 0.5684831 -0.7467555 0.3400542 0.5715937 -0.6868959 0.5128201 0.5149657 -0.7481905 0.3384446 0.5706716 -0.6836463 0.5229183 0.5091015 -0.7449222 0.3401529 0.5739226 -0.6796394 0.5250363 0.5122764 -0.7461424 0.3384699 0.573332 -0.7429425 0.3400179 0.5765624 -0.6831651 0.5128777 0.5198482 -0.7437438 0.3387616 0.5762689 -0.680863 0.5226076 0.5131345 -0.7401463 0.3408253 0.5796737 -0.6800109 0.5143322 0.5225394 -0.7410255 0.3393254 0.5794303 -0.6745628 0.5282384 0.5156832 -0.7367269 0.3414421 0.583653 -0.6748059 0.5189202 0.5247465 -0.7383201 0.339057 0.5830299 -0.7331508 0.3415619 0.5880692 -0.6755445 0.5094541 0.5330067 -0.7351214 0.3385135 0.5873714 -0.6696736 0.529027 0.5212177 -0.729314 0.3416606 0.5927639 -0.6691455 0.5155948 0.5351696 -0.7310821 0.3388828 0.5921803 -0.6619945 0.5340321 0.5259022 -0.7252326 0.341774 0.5976856 -0.6639121 0.5185209 0.5388476 -0.7268313 0.3392689 0.5971709 -0.7209151 0.3419275 0.6027992 -0.6636591 0.5095965 0.5476022 -0.7224317 0.3395863 0.6023069 -0.654784 0.5361611 0.5327187 -0.7169257 0.3400946 0.6085665 -0.6475901 0.5358125 0.541786 -0.7172959 0.3394187 0.6085076 -0.7118227 0.3419495 0.6134972 -0.6542804 0.510784 0.5576888 -0.6501606 0.5307723 0.5436653 -0.7067372 0.3430091 0.6187626 -0.629802 0.5541272 0.5443276 -0.7113617 0.3387193 0.6158197 -0.6936954 0.3550274 0.6266916 -0.6415706 0.5069332 0.5756787 -0.6957679 0.350571 0.6269026 -0.7051309 0.3387595 0.6229224 -0.645092 0.5241523 0.5559862 -0.6779647 0.3554226 0.6434583 -0.6455542 0.457764 0.6113199 -0.6851422 0.3431015 0.6425431 -0.6920121 0.3407629 0.6363961 -0.6712092 0.4348855 0.6002939 -0.6152234 0.5480045 0.5667375 -0.6622521 0.3539355 0.660418 -0.6146147 0.4967058 0.6128066 -0.6774974 0.3252322 0.659713 -0.6108965 0.5336453 0.5848318 -0.6465886 0.3517967 0.6768767 -0.6052244 0.4798592 0.6351681 -0.6585844 0.3295886 0.6764895 -0.6146977 0.4965186 0.6128751 -0.5852313 0.5351597 0.6091867 -0.6310806 0.3500692 0.6922347 -0.589033 0.4808546 0.6494759 -0.6412634 0.3325878 0.691496 -0.5647686 0.5494534 0.6157413 -0.6163371 0.3483927 0.7062231 -0.5695437 0.4923482 0.6581894 -0.6256259 0.3344163 0.7048106 -0.548177 0.5528132 0.6276142 -0.6019775 0.3475494 0.7189107 -0.5502464 0.5046277 0.6652667 -0.6117298 0.3356375 0.7163338 -0.5349901 0.5469549 0.6439145 -0.5778744 0.3525855 0.7360331 -0.5155137 0.5342046 0.6699784 -0.5984976 0.3344424 0.7279759 -0.5320443 0.3510535 0.7705131 -0.499861 0.4559934 0.7363485 -0.5739752 0.3300005 0.7494347 -0.498401 0.5680483 0.654918 -0.4636989 0.342863 0.8169629 -0.4537739 0.3787878 0.8066034 -0.4669232 0.338354 0.8170063 -0.5291255 0.3307979 0.7814083 -0.3657287 0.6955415 0.6184374 -0.3682842 0.3478015 0.8622069 -0.194393 0.7633262 0.6160718 -0.4014773 0.3140079 0.8603574 -0.263295 0.330066 0.9064946 -0.2402617 0.4110125 0.8793993 -0.3177772 0.2877938 0.9034336 -0.2838931 0.6210078 0.7305848 -0.1877094 0.2971783 0.9361892 0.01389825 0.8325663 0.5537511 -0.2181266 0.2691167 0.9380816 -0.1512397 0.272633 0.9501566 -0.102 0.4494705 0.8874526 -0.1490125 0.2756721 0.9496315 -0.1530705 0.5230621 0.8384364 -0.137203 0.2796137 0.9502586 -0.06739377 0.5211793 0.8507821 -0.1491778 0.2882941 0.9458501 -0.09424209 0.480844 0.8717268 -0.146827 0.2909483 0.9454051 -0.09258174 0.4572707 0.8844954 -0.1928458 0.284071 0.9392094 -0.1938726 0.2800415 0.9402076 -0.2641185 0.2857607 0.9211853 -0.1809909 0.5556595 0.8114707 -0.2067281 0.3169945 0.925623 -0.1951693 0.2760952 0.9411059 -0.3575129 0.2978979 0.8851222 -0.3840336 0.1772646 0.9061432 -0.3051919 0.3368362 0.8907296 -0.4543032 0.3107453 0.8348928 -0.3537301 0.6018045 0.7160352 -0.4148325 0.3477059 0.8408415 -0.4045534 0.09470516 0.9095975 -0.5430239 0.3197854 0.7764421 -0.5611818 0.2360133 0.7933302 -0.5118874 0.3563852 0.7816399 -0.6220278 0.3267288 0.7115685 -0.5115897 0.618299 0.5966426 -0.598937 0.3602367 0.715195 -0.5525348 0.2694566 0.7887322 -0.690087 0.3330543 0.6425378 -0.5853089 0.6049203 0.5398935 -0.6759589 0.3578546 0.6442203 -0.6831753 0.2254905 0.6945686 -0.7203317 0.07290625 0.6897875 -0.7621852 0.2470629 0.5983591 -0.6503888 -0.002843499 0.7595961 -0.6333479 0.4280312 0.6447168 -0.4176439 0.6089665 0.6743394 -0.468068 0.07743674 0.8802931 -0.5550343 0.2575088 0.7909654 -0.1033489 0.8144392 0.570971 -0.2567276 0.1003415 0.961261 -0.3963934 0.1438092 0.9067475 -0.2064467 0.03012949 0.9779939 -0.1793841 0.3366212 0.9243958 -0.1815198 0.1400051 0.97337 -0.1898595 0.07613426 0.9788549 -0.2766375 -0.01362437 0.9608778 -0.3271138 0.2486741 0.9116785 -0.3028255 -0.1326796 0.9437653 -0.4665101 -0.2320713 0.8535288 -0.4917817 0.229635 0.839892 -0.4542145 -0.0999341 0.8852698 -0.5785114 -0.1663501 0.7985312 -0.6064299 0.1599618 0.7788806 -0.552608 0.1252308 0.8239792 -0.6281855 0.1841419 0.7559596 -0.6249556 0.0458166 0.7793147 -0.6437693 0.1673926 0.7466865 -0.6465496 0.1058033 0.7554994 -0.6581986 0.158499 0.7359706 -0.660009 0.1307848 0.7397861 -0.6714022 0.1719886 0.7208599 -0.6734284 0.1457337 0.7247454 -0.6824201 0.2099531 0.700159 -0.6885089 0.1352669 0.7125016 -0.6953917 0.2390453 0.6777077 -0.7033601 0.1143106 0.7015823 -0.7186753 0.1593868 0.6768321 -0.7132254 0.138264 0.6871628 -0.7251239 0.156828 0.6705224 -0.7260366 0.1174961 0.6775439 -0.7324267 0.1462262 0.664958 -0.7365576 0.1659419 0.655703 -0.7354673 0.1248667 0.6659553 -0.7434265 0.1592866 0.6495729 -0.7446213 0.1236245 0.6559392 -0.7512087 0.1414912 0.6447215 -0.7547831 0.1573783 0.636816 -0.7514014 0.1400224 0.6448175 -0.759081 0.1571221 0.6317505 -0.7597128 0.1271318 0.63771 -0.7646278 0.142001 0.6286335 -0.7669547 0.1585474 0.6218063 -0.7652027 0.1376036 0.6289119 -0.7707242 0.1539051 0.6183021 -0.7711213 0.1323071 0.6227896 -0.7742393 0.1457397 0.6158844 -0.7758407 0.1558085 0.6113876 -0.7752903 0.1379442 0.6163574 -0.7786226 0.1508516 0.60909 -0.7790667 0.1383444 0.6114866 -0.7808198 0.1489998 0.6067285 -0.7820737 0.1525907 0.6042157 -0.7817441 0.1421965 0.6071708 -0.7842816 0.1412298 0.6041163 -0.7843948 0.1503062 0.6017748 -0.7834241 0.1481493 0.6035715 -0.7850053 0.1505776 0.6009104 -0.785066 0.145814 0.6020047 -0.7855151 0.1484926 0.6007629 -0.7854271 0.1493259 0.6006712 -0.7854153 0.1492652 0.6007019 -0.7851527 0.1487733 0.601167 -0.7851113 0.1514049 0.6005639 -0.7842894 0.1516194 0.6015827 -0.7837734 0.1474595 0.6032869 -0.7840726 0.1531912 0.601467 -0.7824007 0.1491848 0.604643 -0.7821003 0.1567509 0.6031156 -0.7807265 0.1504642 0.6064871 -0.7793192 0.1448418 0.6096575 -0.779466 0.1590608 0.6059147 -0.7768752 0.1464415 0.6123886 -0.7762585 0.160509 0.6096388 -0.5809795 -0.05939108 -0.8117485 -0.6293051 -0.4144613 -0.6574168 -0.6000321 -0.2477623 -0.7606415 -0.4163955 -0.1246165 -0.9006028 -0.2948111 0.2380854 -0.9254198 -0.2948109 0.2380943 -0.9254176 -0.4444171 0.3048223 -0.8423638 -0.3119787 0.4891499 -0.8144947 -0.4142362 0.3380556 -0.8450601 -0.4163958 -0.124616 -0.9006028 -0.4767919 -0.4690066 -0.7434396 0.3328263 -0.314455 -0.8890133 0.3729001 -0.1291357 -0.9188414 0.3328338 -0.314466 -0.8890066 0.5158311 -0.3356205 -0.7882114 0.5143769 0.5128204 -0.6873366 0.5707708 -0.1476586 -0.8077237 -0.0452944 -0.2380345 -0.9702 0.04902762 0.1330152 -0.9899006 -0.04529368 -0.2380356 -0.9701997 0.3389737 0.2529572 -0.9061509 0.3993646 0.06219929 -0.9146798 0.04903066 0.1329959 -0.989903 -0.1329622 -0.57412 -0.8079029 -0.4767855 -0.4690267 -0.743431 0.2173815 -0.6449135 -0.7326881 -0.1329672 -0.5740987 -0.8079174 0.5162848 -0.3431078 -0.7846827 0.4611845 -0.512322 -0.7244551 0.2056881 -0.472747 -0.8568563 0.8320339 -0.3379187 -0.4399212 0.8613133 -0.1838985 -0.473625 0.8335329 -0.3288346 -0.443949 0.8158562 -0.3236426 -0.4792016 0.8345168 -0.2321403 -0.4996926 0.8655729 -0.02927148 -0.4999266 0.8315662 0.2023184 -0.5172668 0.7943503 -0.316997 -0.5181894 0.8254261 -0.009318292 -0.5644333 0.8055682 -0.3512946 -0.4771289 0.7700693 -0.3084146 -0.5584567 0.7713233 -0.302881 -0.559753 0.7750278 -0.3676202 -0.5139917 0.8188563 0.07230901 -0.5694257 0.7429354 -0.3021559 -0.5972845 0.7302228 -0.3537936 -0.5844696 0.7400333 -0.3841668 -0.5520567 0.7750785 0.1506967 -0.6136317 0.7130893 -0.3073055 -0.6301324 0.720216 -0.2738458 -0.6374146 0.7046741 -0.3919464 -0.5914494 0.7479916 0.1040029 -0.6555089 0.6829438 -0.3248378 -0.6542692 0.7204422 0.002019047 -0.693512 0.6758763 -0.3807191 -0.631066 0.6565759 -0.3426133 -0.6719556 0.6853464 -0.1988039 -0.700555 0.6542103 -0.3597897 -0.6652522 0.7201368 -0.0750218 -0.6897643 0.6388772 -0.3413972 -0.6894083 0.6646647 -0.217533 -0.7147729 0.6928289 0.04391795 -0.7197633 0.626049 -0.3343264 -0.7044776 0.6680191 -0.04401415 -0.7428414 0.6342344 -0.3527446 -0.687981 0.6143108 -0.3338735 -0.7149481 0.6426115 -0.1909081 -0.7420273 0.6171696 -0.3531545 -0.7031242 0.668216 -0.0327363 -0.7432467 0.6042141 -0.3358876 -0.7225682 0.6477091 -0.0437321 -0.7606316 0.6048587 -0.3501268 -0.7152321 0.5958734 -0.3385019 -0.7282522 0.6284379 -0.171209 -0.7587841 0.5958255 -0.3460747 -0.7247237 0.6473123 -0.05654978 -0.7601243 0.5891919 -0.340819 -0.732595 0.6296157 -0.1104182 -0.7690201 0.5891371 -0.3423255 -0.7319362 0.5847494 -0.3396272 -0.7366964 0.6326641 0.03591871 -0.773593 0.5813491 -0.3387647 -0.7397781 0.6165701 -0.1540565 -0.7720803 0.5835886 -0.3418095 -0.7366075 0.6256075 -0.1357318 -0.7682397 0.5786617 -0.3388093 -0.7418618 0.6189184 -0.1107965 -0.7776017 0.5796154 -0.3414378 -0.7399095 0.5766614 -0.3391393 -0.7432671 0.6221501 -0.04844641 -0.7813975 0.577008 -0.3407122 -0.7422782 0.5752704 -0.3394467 -0.7442042 0.6110715 -0.1520466 -0.7768356 0.5753563 -0.3400669 -0.7438545 0.6163406 -0.1333299 -0.7761105 0.574383 -0.3396276 -0.7448068 0.6111533 -0.1448826 -0.7781392 0.574384 -0.3396409 -0.7447999 0.5739763 -0.3394762 -0.7451893 0.6119235 -0.1348873 -0.7793298 0.5738885 -0.3395271 -0.7452338 0.6121613 -0.1322295 -0.7795985 0.573917 -0.3395609 -0.7451965 0.5737439 -0.3391668 -0.745509 0.6095564 -0.1517086 -0.7780909 0.5738908 -0.3395243 -0.7452332 0.6104778 -0.1488385 -0.7779229 0.5719559 -0.3386656 -0.7471092 0.609781 -0.1347115 -0.7810378 0.5723413 -0.3403943 -0.7460277 0.5679631 -0.3390884 -0.7499579 0.6139349 -0.04804646 -0.7878931 0.5681382 -0.3405154 -0.7491784 0.5616269 -0.3411911 -0.7537665 0.6100546 0.1401062 -0.7798742 0.5614885 -0.3389466 -0.7548814 0.555152 -0.3366129 -0.7605906 0.5894301 -0.1618348 -0.7914428 0.6090978 -0.1023504 -0.786463 0.5459226 -0.3342407 -0.7682784 0.5895381 -0.0776273 -0.8040017 0.550515 -0.3425226 -0.7613222 0.5335438 -0.3327179 -0.7775796 0.582374 0.1724927 -0.7944096 0.5361495 -0.343945 -0.7708733 0.3258331 -0.7866988 -0.5243451 0.4970913 -0.5069129 -0.7042297 0.3812567 -0.7032283 -0.6000944 0.5005114 -0.5230617 -0.6898514 0.4589882 -0.6262434 -0.6301975 0.4045078 -0.7230749 -0.5599431 0.5160312 -0.5154604 -0.6841143 0.5038591 -0.529416 -0.6825282 0.5158862 -0.5159024 -0.6838905 0.5109658 -0.5289389 -0.6775969 0.5184103 -0.513514 -0.6837794 0.5140397 -0.5211183 -0.6813214 0.5130328 -0.5308134 -0.6745625 0.4834713 -0.6007214 -0.6367019 0.5276111 -0.5119948 -0.6778553 0.5169116 -0.5239608 -0.6769546 0.4855216 -0.6150518 -0.6212729 0.5462998 -0.4982884 -0.6732498 0.5162013 -0.5480992 -0.6581212 0.5506049 -0.5124058 -0.658995 0.4968899 -0.6185267 -0.6087078 0.558645 -0.5240972 -0.6428359 0.6127071 -0.4251074 -0.6662385 0.5052182 -0.6395045 -0.5794728 0.6424083 -0.4004254 -0.6534302 0.5080336 -0.675064 -0.5349678 0.6707836 -0.397686 -0.6260153 0.5457174 -0.6600093 -0.5163142 0.6987488 -0.410772 -0.585676 0.5883741 -0.6418923 -0.4917218 0.6287975 -0.6331365 -0.4513887 0.7252641 -0.504387 -0.4685998 0.6847421 -0.5255497 -0.5049017 0.8020067 -0.3638778 -0.4736858 0.6071637 -0.7077735 -0.3611218 0.7817572 -0.4803916 -0.3975921 0.5849567 -0.7649146 -0.2696877 0.774807 -0.3356242 -0.5357524 0.7752171 -0.3357116 -0.5351039 0.6311829 -0.7142049 -0.302522 0.7725783 -0.348772 -0.5305477 0.7742491 -0.3407866 -0.5332943 0.371649 -0.9189924 -0.1316435 0.4811583 -0.8524018 -0.2046896 0.1763473 -0.9842442 -0.01284468 0.591414 0.6802642 -0.4329782 0.668623 0.5789024 -0.4667069 0.6015713 0.6679852 -0.4380727 0.7595655 0.4135307 -0.5020483 0.8068331 0.2851994 -0.5173795 0.8303009 0.2035337 -0.5188202 0.7885084 0.3408374 -0.5119417 0.8563755 0.03783816 -0.5149652 0.497542 0.5939196 -0.6322273 0.3872877 0.599408 -0.7005128 0.5146067 0.5964636 -0.6159638 0.5003179 0.5870407 -0.6364473 0.5199775 0.5929092 -0.6148838 0.5180291 0.5887025 -0.6205443 0.5210156 0.5950942 -0.611887 0.5205017 0.5917394 -0.6155668 0.524201 0.5989584 -0.6053612 0.5242593 0.5879066 -0.6160503 0.5295496 0.6041466 -0.5954697 0.5319581 0.5820913 -0.6149718 0.5368109 0.6106919 -0.5821421 0.5436747 0.5743248 -0.6120204 0.5457192 0.6184489 -0.5654304 0.5595472 0.5645083 -0.6068257 0.555979 0.6272127 -0.5454279 0.5797443 0.5524104 -0.5989486 0.5670784 0.6369314 -0.5222457 0.6040773 0.5384681 -0.5874884 0.5786894 0.6471316 -0.4963259 0.632281 0.5228972 -0.5716636 0.5903301 0.6575765 -0.4680851 0.6635478 0.5065493 -0.5505563 0.6965469 0.4907677 -0.523421 0.5782194 0.2412095 -0.7794101 0.6056498 0.243646 -0.7575124 0.5790684 0.2337862 -0.7810403 0.6117933 0.2397119 -0.7538217 0.6067803 0.2353045 -0.7592427 0.6147009 0.2422111 -0.7506507 0.6119892 0.238306 -0.7541084 0.6219257 0.2465781 -0.7432414 0.615883 0.2338328 -0.7523366 0.6333463 0.2526378 -0.7314687 0.6247638 0.2271332 -0.7470479 0.6486822 0.2605703 -0.7150625 0.6386265 0.2183055 -0.7379016 0.6675261 0.2703591 -0.6937686 0.657437 0.2073444 -0.7244204 0.6893948 0.2815982 -0.667411 0.6810995 0.1939195 -0.7060443 0.7133644 0.2948939 -0.6357269 0.7091504 0.1791545 -0.6819161 0.7384575 0.309904 -0.5988657 0.7409153 0.1638135 -0.6513138 0.7638307 0.3254439 -0.5573589 0.7754599 0.1480975 -0.6137827 0.8113502 0.1333232 -0.5691534 -0.086214 0.7767982 -0.6238202 -0.2096114 0.6578814 -0.7233637 -0.1685233 0.9819134 0.08629006 -0.213695 0.9696769 0.1185798 -0.3156492 0.9269358 0.2028687 -0.4518257 0.8328325 0.3197556 -0.4857494 0.8033097 0.3445882 -0.5776673 0.6977289 0.4236447 -0.4836493 0.8037062 0.3466117 -0.4831091 0.8042032 0.3462122 -0.2119669 0.969842 0.1203183 -0.2114678 0.9699959 0.1199551 -0.4869116 0.8045163 0.3401039 -0.4891355 0.8042008 0.3376502 -0.488226 0.8033136 0.3410609 -0.4907209 0.8039144 0.3360279 -0.4900847 0.8033334 0.3383376 -0.4916565 0.8036743 0.3352333 -0.4913086 0.8033779 0.3364519 -0.4919033 0.8035193 0.335243 -0.491862 0.8034869 0.3353813 -0.4914934 0.8034118 0.3361008 -0.4917858 0.8036265 0.3351585 -0.4904372 0.8033418 0.3378066 -0.4910866 0.8037831 0.3358073 -0.4886438 0.8033829 0.3402987 -0.4896804 0.8040333 0.3372589 -0.4862004 0.8034395 0.3436483 -0.4876592 0.8042839 0.339582 -0.4830092 0.8035833 0.3477874 -0.4849275 0.8046066 0.342715 -0.4791783 0.8036939 0.3527952 -0.4815961 0.8048821 0.3467418 -0.4746009 0.8038461 0.3585879 -0.4775605 0.8051858 0.3515847 -0.4692202 0.8040691 0.36511 -0.4727631 0.8055476 0.357195 -0.4631479 0.8042275 0.3724409 -0.4673218 0.8058344 0.3636499 -0.4561323 0.8045261 0.3803697 -0.4609844 0.8062495 0.3707493 -0.4484604 0.8046653 0.3890975 -0.4540334 0.8064993 0.3786985 -0.4398311 0.8049008 0.3983507 -0.4461712 0.806832 0.3872382 -0.4305902 0.8048734 0.4083762 -0.4377339 0.806901 0.3966103 -0.4202941 0.8049837 0.4187529 -0.4282806 0.8070952 0.4064148 -0.4092297 0.8049392 0.4296557 -0.4180876 0.8071267 0.4168325 -0.3972027 0.8049235 0.4408267 -0.4069502 0.8071761 0.4276192 -0.3844799 0.8046025 0.4525374 -0.3951747 0.8069369 0.4389645 -0.3710588 0.8042417 0.4642313 -0.3824982 0.8065958 0.4506644 -0.34921 0.8022848 0.4841399 -0.3690808 0.8062586 0.4623055 -0.2955324 0.7963535 0.5277136 -0.3451814 0.8064938 0.4800182 -0.1935524 0.7829137 0.5912559 -0.2885864 0.8041101 0.5197353 -0.05296891 0.7614817 0.6460186 -0.1849709 0.793962 0.579146 0.01562935 0.7541562 0.6565091 -0.04749119 0.7704039 0.6357849 -0.02419203 0.7649868 0.6435915 0.01607078 0.7549738 0.6555581 -0.1628925 0.7881369 0.5935539 -0.02704721 0.7601392 0.6491971 -0.3111444 0.8032972 0.5078414 -0.1675695 0.7819072 0.6004512 -0.413161 0.8066142 0.4226955 -0.3144944 0.7996479 0.5115238 -0.4148845 0.8049301 0.4242151 -0.2135934 0.9700714 0.115496 -0.2152054 0.969894 0.1139836 -0.215265 0.9695592 0.1166871 -0.2163375 0.9697597 0.1129786 -0.216355 0.9695423 0.1147971 -0.2170348 0.9696563 0.1125284 -0.2170307 0.9695478 0.1134668 -0.217306 0.9695823 0.1126424 -0.2173045 0.9695739 0.112718 -0.2170943 0.9695553 0.1132809 -0.2171226 0.9696384 0.1125134 -0.2164022 0.9695721 0.1144546 -0.216491 0.9697397 0.1128559 -0.2153366 0.9695971 0.1162388 -0.2155193 0.9698423 0.1138299 -0.213767 0.9696646 0.1185502 -0.2140805 0.9699822 0.1153439 -0.2117232 0.9697603 0.1214013 -0.2122061 0.970144 0.1174276 -0.2091829 0.9698827 0.1247802 -0.2098777 0.9703285 0.1200586 -0.2061375 0.9700245 0.1286854 -0.2070891 0.9705293 0.1232357 -0.2026149 0.9701686 0.1331172 -0.2038667 0.9707285 0.1269831 -0.1985356 0.970326 0.1380254 -0.2001377 0.9709401 0.131226 -0.1939073 0.9704841 0.1433901 -0.1959052 0.9711498 0.1359754 -0.1888048 0.970604 0.1492674 -0.1912479 0.9713222 0.1412704 -0.1830872 0.9707198 0.155506 -0.1860162 0.9714896 0.146989 -0.1767991 0.9708017 0.1621299 -0.1802655 0.9716238 0.1531385 -0.1699352 0.9708395 0.1690935 -0.1739766 0.9717152 0.1596929 -0.1625981 0.9707842 0.1764649 -0.1672543 0.9717174 0.1667071 -0.1545928 0.9706987 0.1839705 -0.1598799 0.9716863 0.1739658 -0.1459826 0.9705356 0.1917022 -0.151964 0.971584 0.1814703 -0.1369668 0.9702821 0.1994817 -0.1435329 0.9713745 0.1892876 -0.1227983 0.9691721 0.2136026 -0.1345817 0.9711138 0.1970426 -0.08762317 0.9656988 0.2444343 -0.1178566 0.9709541 0.2082261 -0.01962894 0.957143 0.2889499 -0.07931846 0.9689998 0.2339827 0.07521128 0.9425842 0.3253895 -0.009871661 0.9619814 0.2729365 0.1217319 0.9367812 0.3280583 0.08092319 0.9467662 0.311585 0.09525549 0.9436001 0.3170888 0.122174 0.9371854 0.3267369 0.002917051 0.9590077 0.2833652 0.09233129 0.9413093 0.3246714 -0.09616696 0.9691265 0.2270367 -0.002619504 0.9561125 0.2929885 -0.1644304 0.9715155 0.1706466 -0.1001421 0.9676026 0.231769 -0.1666358 0.9707868 0.1726424 0.3098983 -0.8018745 -0.5108429 0.1460353 -0.7777341 -0.6113947 0.3400762 -0.8010908 -0.4925462 0.313667 -0.7971535 -0.5159066 0.3355041 -0.8061646 -0.4873764 0.3439127 -0.8034243 -0.4860386 0.3431263 -0.8042907 -0.4851605 0.3495589 -0.8009975 -0.4860162 0.3449303 -0.8060837 -0.4808868 0.3610559 -0.7975118 -0.4833362 0.3501451 -0.8093998 -0.4714556 0.3784001 -0.7928706 -0.4776709 0.3588232 -0.8139129 -0.4569375 0.401746 -0.7866972 -0.4687298 0.3706725 -0.8195058 -0.4370493 0.4307112 -0.7790204 -0.4556481 0.3854969 -0.8257544 -0.4117303 0.4650046 -0.7695044 -0.4377596 0.4025483 -0.8325406 -0.3805667 0.5038 -0.7580614 -0.41416 0.4213216 -0.8392586 -0.343705 0.5460128 -0.7444651 -0.3842416 0.4411229 -0.8452766 -0.3015262 0.5893262 -0.729532 -0.3470989 0.4614308 -0.849761 -0.2549273 0.1676013 -0.9848108 -0.04535949 0.3308058 -0.9304361 -0.1576583 0.1587374 -0.9843619 -0.07638168 0.2913218 -0.9398595 -0.1783137 0.1501501 -0.9830371 -0.1053222 0.2537778 -0.9477788 -0.1931641 0.1420616 -0.9810828 -0.131511 0.2199856 -0.9540635 -0.2033945 0.1346918 -0.978785 -0.154395 0.1908028 -0.958903 -0.2099986 0.1283807 -0.9763912 -0.1737198 0.166619 -0.9625391 -0.2139081 0.1233686 -0.9741402 -0.1892911 0.1474863 -0.9652266 -0.2158368 0.1198312 -0.9722363 -0.2009899 0.1332463 -0.9672002 -0.2162617 0.1180022 -0.9707971 -0.2088743 0.1236627 -0.9686515 -0.2154573 0.1176532 -0.9700424 -0.2125449 0.118643 -0.9696667 -0.2137063 0.1112425 -0.970788 -0.2125928 0.117185 -0.9685084 -0.2196797 0.1004225 -0.9663442 -0.2368422 0.09560352 -0.9684767 -0.2300275 -0.6220422 -0.4547587 -0.6373838 -0.6110024 -0.6064727 -0.5087896 -0.5687215 -0.7374951 -0.3642208 -0.06466805 0.302915 0.9508209 -0.7519095 -0.2450594 0.6120278 -0.1181285 0.2639294 0.9572811 -0.6087763 -0.6021171 0.5165716 -0.753751 -0.2379127 0.6125822 -0.6155816 -0.5917603 0.5204603 -0.6139173 -0.5918525 0.5223181 -0.6134996 -0.5926043 0.5219562 -0.7517795 -0.2384228 0.6148026 -0.7516994 -0.2388647 0.614729 -0.6171051 -0.5918635 0.5185354 -0.6160318 -0.5935099 0.5179293 -0.618292 -0.5922009 0.5167332 -0.6175216 -0.5933783 0.5163034 -0.6190681 -0.5924644 0.5155004 -0.6185867 -0.5931982 0.5152341 -0.6193425 -0.5928075 0.514776 -0.6192319 -0.5929756 0.5147151 -0.6192487 -0.5930171 0.5146473 -0.6193577 -0.5928512 0.5147073 -0.6187641 -0.5931193 0.515112 -0.6190952 -0.5926145 0.5152953 -0.617819 -0.5932239 0.516125 -0.618422 -0.5923023 0.5164613 -0.6164299 -0.5933015 0.5176944 -0.6172637 -0.5920222 0.5181652 -0.6145717 -0.593389 0.5197991 -0.6156358 -0.5917482 0.52041 -0.6123115 -0.5933599 0.5224928 -0.6135053 -0.5915076 0.5231922 -0.6095772 -0.593318 0.5257275 -0.6109412 -0.591185 0.5265465 -0.6063858 -0.5932347 0.5294988 -0.6078717 -0.5908898 0.5304163 -0.6027089 -0.5931307 0.5337958 -0.6043059 -0.5905834 0.5348137 -0.5984559 -0.5931503 0.538538 -0.6002218 -0.5902994 0.539704 -0.5937755 -0.5930367 0.5438182 -0.5955221 -0.5901781 0.5450167 -0.5886365 -0.5928266 0.5496035 -0.5903588 -0.5899634 0.5508356 -0.5828183 -0.5928791 0.5557132 -0.5847012 -0.5896944 0.5571221 -0.5767102 -0.5925392 0.5624078 -0.5783341 -0.5897388 0.5636824 -0.5697633 -0.5927416 0.5692339 -0.5716449 -0.5894269 0.5707874 -0.5623956 -0.5927723 0.5764827 -0.5640943 -0.5897097 0.5779621 -0.5546517 -0.5925458 0.584167 -0.556097 -0.5898712 0.5854982 -0.546117 -0.5928478 0.5918511 -0.5477121 -0.5898112 0.593409 -0.5370966 -0.5931442 0.5997558 -0.5385316 -0.5903285 0.6012455 -0.5209595 -0.5958858 0.6111639 -0.524032 -0.5895293 0.6146915 -0.4830383 -0.6000369 0.6376753 -0.4875866 -0.5891381 0.6443413 -0.4141184 -0.6084361 0.6769871 -0.4186359 -0.5931193 0.6877161 -0.3222437 -0.6203628 0.7150588 -0.323751 -0.6084294 0.7245682 -0.2798591 -0.6246807 0.7290082 -0.2799015 -0.623776 0.7297662 -0.3083696 -0.6152938 0.7254803 -0.3077241 -0.6217439 0.7202364 -0.4026162 -0.5980747 0.6929697 -0.4002188 -0.6069993 0.6865689 -0.5010985 -0.5904474 0.6326707 -0.498869 -0.5954937 0.629696 -0.5681104 -0.5896172 0.5741098 -0.5667723 -0.5920045 0.5729745 -0.6821193 -0.2374534 0.6916135 -0.6826373 -0.2349749 0.6919487 -0.5804891 -0.2429592 0.7771764 -0.5814045 -0.2366372 0.7784419 -0.4326265 -0.2602611 0.8631908 -0.4331424 -0.2497396 0.8660356 -0.2938688 -0.2827975 0.9130535 -0.2935317 -0.275231 0.9154709 -0.2521924 -0.2866816 0.9242362 -0.2522888 -0.287988 0.9238036 -0.3170495 -0.2651548 0.910589 -0.3174901 -0.2799003 0.906011 -0.4577155 -0.2428371 0.8552933 -0.4565969 -0.2604076 0.8507099 -0.5611821 -0.2356429 0.7934401 -0.5595087 -0.2483743 0.7907341 -0.6164966 -0.2357423 0.7512373 -0.6153562 -0.2425435 0.7500063 -0.6387844 -0.2361571 0.7322459 -0.6381521 -0.2396333 0.7316677 -0.6522566 -0.236115 0.7202854 -0.6517138 -0.2389637 0.7198371 -0.6650965 -0.2352606 0.7087306 -0.6643149 -0.2391965 0.708146 -0.6769838 -0.2351135 0.6974342 -0.6762729 -0.2385656 0.6969515 -0.6879804 -0.2354959 0.6864582 -0.6873192 -0.2385979 0.6860492 -0.6982346 -0.2354478 0.676042 -0.6974352 -0.2390857 0.6755902 -0.7076301 -0.2356086 0.6661443 -0.7068425 -0.2390986 0.6657367 -0.7162407 -0.2356305 0.6568696 -0.7154026 -0.239258 0.6564715 -0.7239587 -0.2360249 0.6482098 -0.7232037 -0.2392259 0.6478791 -0.7309393 -0.2362819 0.6402332 -0.7301613 -0.2395194 0.639918 -0.7370809 -0.2367422 0.6329809 -0.7363803 -0.2396109 0.632717 -0.7424916 -0.2371165 0.6264838 -0.7418108 -0.2398644 0.6262441 -0.7471555 -0.2374878 0.6207723 -0.7465307 -0.2399798 0.6205655 -0.7510836 -0.237896 0.6158563 -0.750538 -0.24005 0.6156855 -0.7542857 -0.2383679 0.6117465 -0.7538393 -0.240116 0.6116132 -0.7568302 -0.2386603 0.6084811 -0.7564342 -0.2402011 0.6083673 -0.7586649 -0.2390256 0.6060482 -0.7583956 -0.2400684 0.605973 -0.7598499 -0.2392933 0.604456 -0.7596727 -0.2399771 0.6044075 -0.7603549 -0.2395992 0.603699 -0.7603151 -0.2397526 0.6036883 -0.7601915 -0.239917 0.6037788 -0.7602909 -0.2395336 0.6038058 -0.7593954 -0.2400998 0.6047073 -0.7596046 -0.2392919 0.6047646 -0.7579599 -0.2402098 0.6064619 -0.7582995 -0.2388947 0.606557 -0.7558487 -0.2403451 0.6090378 -0.7563511 -0.2383893 0.6091827 -0.01043522 0.8424787 0.5386286 0.1310858 0.7376107 0.6623798 0.2126095 0.6544767 0.7255738 0.07041317 0.9971079 0.02859944 0.07407391 0.9969072 0.02624899 0.252015 0.962332 -0.102008 0.2826803 0.9513819 -0.1223286 0.3522759 0.9197573 -0.1730548 0.494474 0.823581 -0.2778663 0.4726385 0.8411538 -0.2628176 0.6732532 -0.3007035 -0.6755054 0.6320183 0.6711355 -0.3874661 0.6564379 0.6361549 -0.4054581 0.594868 0.6723132 -0.4405987 0.5948145 0.6723878 -0.4405571 0.4431862 0.8408837 -0.3106453 0.4427911 0.8412041 -0.3103417 0.2615782 0.9518705 -0.1597484 0.2609341 0.9521288 -0.1592615 0.0614435 0.9981073 0.002566516 0.06106638 0.9981297 0.0028463 0.6240947 0.6682899 -0.4048389 0.6135489 0.6693332 -0.4189878 0.6213799 0.6720155 -0.4028425 0.6036331 0.6708804 -0.4307515 0.6107411 0.6732085 -0.416876 0.595618 0.671614 -0.4406517 0.6017256 0.6735261 -0.4292886 0.5891816 0.6722375 -0.4482877 0.5941116 0.6737142 -0.4394776 0.5846149 0.6726748 -0.453579 0.588148 0.6736846 -0.4474717 0.5820739 0.6734076 -0.4557545 0.5837644 0.6738688 -0.4529018 0.5820959 0.6732847 -0.4559081 0.5821512 0.673299 -0.4558163 0.5824372 0.6734651 -0.4552051 0.5820372 0.6733672 -0.4558612 0.5828924 0.673528 -0.4545288 0.5824633 0.6734284 -0.455226 0.5825671 0.6732447 -0.4553649 0.5830235 0.6733439 -0.4546335 0.5807527 0.6731424 -0.457827 0.5823985 0.6734816 -0.4552301 0.5778383 0.6731188 -0.4615343 0.5804144 0.6736186 -0.4575556 0.5734934 0.6736707 -0.4661256 0.5769917 0.6743121 -0.4608511 0.5682895 0.6738136 -0.4722524 0.5728308 0.6746064 -0.4655867 0.5620113 0.6738704 -0.4796271 0.5676001 0.6747907 -0.4716859 0.5545341 0.6739196 -0.4881848 0.5612329 0.6749786 -0.4789797 0.545709 0.6741505 -0.4977176 0.5535437 0.6753371 -0.4873492 0.5358002 0.6740902 -0.5084493 0.5448426 0.6753982 -0.4969747 0.5246115 0.6739832 -0.5201244 0.5348761 0.675431 -0.5076423 0.5119268 0.6740126 -0.5325768 0.523501 0.6756075 -0.5191351 0.4980913 0.6736732 -0.5459572 0.5109832 0.6754056 -0.5317175 0.4825514 0.6736782 -0.5597336 0.4968156 0.6755757 -0.5447676 0.4655343 0.6729726 -0.574792 0.4816103 0.6750978 -0.5588333 0.4324717 0.6701603 -0.6032028 0.4644806 0.6745831 -0.5737554 0.3603382 0.6633342 -0.6558538 0.4299754 0.6740832 -0.6006106 0.2359318 0.6467853 -0.7252621 0.3568115 0.6692457 -0.6517636 0.08956253 0.6245063 -0.7758675 0.2315709 0.6550742 -0.7192028 0.03832769 0.6179444 -0.785287 0.08739155 0.6294006 -0.7721513 0.09839874 0.6315362 -0.7690772 0.0382772 0.6180657 -0.785194 0.2574795 0.6561688 -0.7093283 0.100311 0.6272988 -0.7722914 0.4131295 0.6716139 -0.6150276 0.2597281 0.6520152 -0.7123325 0.5201731 0.6752411 -0.522943 0.4144905 0.6694433 -0.6164765 0.5211914 0.6737477 -0.5238548 0.469601 0.8369185 -0.2811444 0.4605071 0.8377943 -0.2933154 0.4637151 0.8415847 -0.2769541 0.4521788 0.8386828 -0.3035548 0.4553391 0.8419266 -0.2895271 0.4450272 0.8394698 -0.3118352 0.447919 0.8421144 -0.300353 0.4392282 0.840155 -0.318148 0.4416828 0.842181 -0.309269 0.4348001 0.8408938 -0.3222522 0.4366298 0.8422715 -0.3161219 0.4324166 0.841495 -0.3238856 0.4333101 0.8421114 -0.3210774 0.4320726 0.8417401 -0.3237082 0.432098 0.8417559 -0.3236331 0.4322791 0.8418959 -0.3230263 0.4320492 0.8417592 -0.3236895 0.4328461 0.8417718 -0.3225904 0.4325983 0.8416349 -0.3232791 0.4325613 0.8416359 -0.3233259 0.4328386 0.8417779 -0.3225845 0.4310635 0.8415657 -0.3255015 0.4320685 0.8420388 -0.3229356 0.4285833 0.841572 -0.3287444 0.430199 0.8422737 -0.3248134 0.4254156 0.8414337 -0.3331831 0.427658 0.842332 -0.3280022 0.4208009 0.8417038 -0.3383214 0.4237661 0.8427932 -0.3318464 0.4156598 0.8415868 -0.3449035 0.4194028 0.8428612 -0.3371739 0.4089525 0.841929 -0.3520134 0.4135282 0.8433615 -0.3431264 0.401591 0.8419199 -0.3604102 0.4070669 0.843509 -0.3504127 0.3928517 0.8421352 -0.3694262 0.3992834 0.8438689 -0.3584105 0.3833331 0.8420072 -0.3795782 0.390808 0.8438774 -0.3676139 0.372388 0.8420522 -0.3902246 0.3809475 0.844063 -0.377408 0.3604291 0.8418653 -0.4016886 0.370146 0.8440077 -0.3881274 0.3474373 0.8414151 -0.4138936 0.3583664 0.8436903 -0.3997001 0.3325956 0.8410549 -0.4266227 0.3450853 0.8435294 -0.4115511 0.3048673 0.8382635 -0.4520734 0.3301792 0.8432654 -0.4241288 0.2436851 0.8317064 -0.4988808 0.299718 0.8431574 -0.4463797 0.1371101 0.8168246 -0.5603556 0.2363156 0.8393803 -0.4894851 0.0103603 0.7979079 -0.6026903 0.1289178 0.8270859 -0.5470915 -0.03482145 0.7940503 -0.6068537 0.006228685 0.8046439 -0.593725 0.01640707 0.8063088 -0.5912674 -0.03471124 0.7938511 -0.6071207 0.1525068 0.8280214 -0.5395576 0.0194633 0.8014619 -0.5977291 0.2863822 0.8407694 -0.4594478 0.1571037 0.822506 -0.5466282 0.3787749 0.8433994 -0.3810605 0.2896211 0.8376229 -0.4631495 0.3803034 0.8420764 -0.3824614 0.2829094 0.9491397 -0.1381884 0.2753005 0.9500458 -0.1470463 0.2755493 0.952029 -0.1330915 0.2685799 0.9507667 -0.1546208 0.2691632 0.9524714 -0.1426512 0.2627971 0.9513731 -0.1607078 0.2635534 0.9527666 -0.1509155 0.2582577 0.9518035 -0.1654488 0.2590432 0.9528758 -0.1578742 0.2547145 0.9522371 -0.1684192 0.2553748 0.9529632 -0.163232 0.2528473 0.9525271 -0.1695887 0.253196 0.9528504 -0.1672365 0.2524399 0.9526844 -0.1693115 0.2524461 0.9526895 -0.1692744 0.2527161 0.9526888 -0.1688745 0.2526115 0.9526152 -0.1694459 0.2533118 0.9525631 -0.1686913 0.2532006 0.9524929 -0.1692536 0.2531426 0.9524953 -0.1693262 0.2532841 0.9525744 -0.1686696 0.2519991 0.9524959 -0.1710199 0.2525144 0.9527494 -0.1688344 0.250165 0.9525179 -0.1735715 0.251023 0.9528913 -0.1702514 0.2476456 0.9525566 -0.1769396 0.2488884 0.9530366 -0.1725572 0.2443338 0.9526337 -0.1810801 0.2460269 0.9532167 -0.1756383 0.2401052 0.9527769 -0.1859186 0.2423198 0.9534587 -0.1794369 0.2353559 0.9528088 -0.1917363 0.238142 0.9535861 -0.1842878 0.2294514 0.9529731 -0.197975 0.232878 0.9538378 -0.1896345 0.223128 0.9529333 -0.2052612 0.2272554 0.9538934 -0.1960675 0.2155818 0.9530044 -0.2128545 0.2204771 0.954056 -0.2028964 0.2072791 0.9529614 -0.2211334 0.2130153 0.9541046 -0.2104967 0.1980081 0.9528712 -0.2298459 0.2046352 0.9541109 -0.2186253 0.1878501 0.9526652 -0.2390422 0.1954262 0.9540119 -0.2273103 0.1766528 0.9522409 -0.2490603 0.1854631 0.9537399 -0.2366084 0.155521 0.950475 -0.269092 0.1737083 0.9535947 -0.2459322 0.1090719 0.9456537 -0.3063368 0.1499553 0.9531574 -0.2626868 0.02719372 0.9345659 -0.3547493 0.100937 0.9500629 -0.2952829 -0.07072579 0.9196407 -0.3863401 0.01857119 0.9405425 -0.3391677 -0.1056477 0.9160923 -0.3867989 -0.07483047 0.9237441 -0.3756291 -0.06629121 0.9251273 -0.3738248 -0.1054505 0.9158635 -0.3873941 0.03799349 0.9417616 -0.3341281 -0.06321829 0.922179 -0.3815615 0.1406269 0.9516623 -0.2730621 0.04291546 0.9385459 -0.3424761 0.2114905 0.9538568 -0.2131408 0.1441025 0.9499397 -0.2772164 0.2134503 0.9530124 -0.2149566 0.07513695 0.9970505 0.01564627 0.0704025 0.9974679 0.01006633 0.06979387 0.9973758 0.0192424 0.06616538 0.9977944 0.005340456 0.06589633 0.997739 0.0132153 0.06254118 0.9980413 0.001534223 0.06250816 0.9980126 0.007979571 0.05958062 0.9982227 -0.001328647 0.05969178 0.9982101 0.003645241 0.05736964 0.9983481 -0.003162622 0.05752974 0.9983438 2.22265e-4 0.05613011 0.9984163 -0.003804326 0.05623477 0.998415 -0.002292215 0.05582153 0.9984344 -0.0035609 0.05582106 0.9984345 -0.003565788 0.05605596 0.998422 -0.003332316 0.05601626 0.998423 -0.003711163 0.05624812 0.9984121 -0.003076791 0.05620318 0.9984135 -0.003445804 0.05614697 0.9984163 -0.00350368 0.05621099 0.9984143 -0.003048241 0.05552119 0.9984467 -0.004662096 0.05575752 0.9984392 -0.003203332 0.05442869 0.9984976 -0.006328523 0.05483812 0.9984867 -0.004131853 0.0527904 0.9985702 -0.008406281 0.05340337 0.9985578 -0.005524694 0.05075991 0.9986494 -0.01107937 0.05162698 0.9986383 -0.007481992 0.0481702 0.9987385 -0.01418215 0.04933321 0.998733 -0.009926855 0.04505759 0.9988269 -0.01774179 0.04656016 0.9988328 -0.01285535 0.04151195 0.9988998 -0.02181744 0.04339915 0.9989241 -0.01634299 0.03729343 0.9989612 -0.02618896 0.03961402 0.9990113 -0.02017384 0.03269982 0.9989811 -0.03110581 0.03550034 0.9990671 -0.02458959 0.02742469 0.9989657 -0.03626579 0.03074693 0.9990975 -0.02930593 0.02166092 0.9988905 -0.04181641 0.02554655 0.9990791 -0.03447198 0.01527535 0.9987498 -0.04759651 0.01977324 0.9990063 -0.0399425 0.00821495 0.9985121 -0.05390894 0.01350617 0.9988608 -0.04576563 -0.004881918 0.9977436 -0.06696307 0.006189465 0.9986428 -0.05171453 -0.03416502 0.9952896 -0.09072703 -0.00905478 0.998034 -0.06201851 -0.08587491 0.9888647 -0.121541 -0.04007124 0.9958026 -0.08228921 -0.1475986 0.9789538 -0.14094 -0.09182351 0.9897083 -0.1097534 -0.1692436 0.9755305 -0.1403447 -0.1501777 0.9796746 -0.1329823 -0.1443419 0.9807246 -0.1316996 -0.1691251 0.9754878 -0.1407845 -0.07888197 0.9911607 -0.1066685 -0.1423444 0.98021 -0.1375734 -0.01446616 0.9975443 -0.06852769 -0.07536977 0.990719 -0.1131163 0.0300635 0.9990668 -0.03100878 -0.01189845 0.9973554 -0.0716992 0.03142148 0.9989851 -0.03227186 0.6217287 -0.4196869 0.661299 0.5823071 -0.2995675 -0.755763 0.6077109 -0.6213191 0.4946209 0.5702134 -0.7342417 0.3684367 0.5812941 -0.305219 -0.7542802 0.8196346 -0.03614854 -0.571745 0.7707754 -0.3044039 -0.5596815 0.8182144 -0.0511139 -0.5726366 0.1662939 0.2643989 -0.9499682 0.6687895 -0.5429599 -0.5078535 0.7692527 -0.3090646 -0.5592222 0.5186645 -0.7448842 -0.4196839 0.6674515 -0.5451872 -0.5072274 0.5216668 -0.7418614 -0.421314 0.5084093 -0.7375915 -0.4443859 0.5078094 -0.7383014 -0.4438925 0.6446841 -0.5381348 -0.5429487 0.6447202 -0.538062 -0.5429779 0.7372416 -0.3013505 -0.6047006 0.7370386 -0.30217 -0.6045391 0.7793265 -0.04434341 -0.6250471 0.7793227 -0.04444766 -0.6250444 0.7050995 -0.04279112 -0.7078161 0.7051952 -0.04108446 -0.7078219 0.5981509 -0.04683631 -0.8000136 0.5981976 -0.04379433 -0.8001511 0.442672 -0.06335651 -0.8944426 0.4424026 -0.05744099 -0.8949751 0.2839341 -0.08890205 -0.9547135 0.283401 -0.08405882 -0.9553105 0.2228444 -0.09900581 -0.9698135 0.222787 -0.09858292 -0.9698697 0.2720803 -0.08505558 -0.9585081 0.2728202 -0.09145843 -0.9577079 0.4174353 -0.05833947 -0.906832 0.4180709 -0.06959253 -0.9057448 0.542929 -0.04630571 -0.8385009 0.5429786 -0.05391234 -0.8380142 0.6158981 -0.04264068 -0.786671 0.6157793 -0.04799091 -0.7864557 0.649707 -0.04223293 -0.7590106 0.6496145 -0.04486745 -0.7589387 0.6668277 -0.04235291 -0.7440074 0.6667674 -0.0437988 -0.7439777 0.6821378 -0.04202193 -0.7300152 0.6820373 -0.04412567 -0.7299849 0.6961079 -0.04155206 -0.7167336 0.6959798 -0.04397135 -0.7167138 0.7086925 -0.04206258 -0.7042624 0.7086025 -0.04361867 -0.7042585 0.7200635 -0.04129427 -0.6926783 0.7198842 -0.04418933 -0.6926861 0.7300784 -0.04178708 -0.6820845 0.7299724 -0.04340469 -0.682097 0.7388892 -0.04180794 -0.6725287 0.7387493 -0.04383921 -0.672553 0.7464541 -0.04241645 -0.6640837 0.7463585 -0.04375147 -0.6641047 0.7528856 -0.04230648 -0.6567903 0.7527456 -0.04419821 -0.6568261 0.7581201 -0.04268985 -0.6507161 0.7580305 -0.04386919 -0.650742 0.7621893 -0.04322856 -0.6459093 0.76213 -0.04399359 -0.6459275 0.765163 -0.04412525 -0.6423228 0.7651533 -0.04424792 -0.6423258 0.7671747 -0.04405736 -0.6399235 0.767113 -0.04482978 -0.6399438 0.7677814 -0.04464006 -0.6391549 0.7678089 -0.04429793 -0.6391457 0.7671323 -0.0439881 -0.6399789 0.7671017 -0.04437363 -0.6399891 0.7664934 -0.04389888 -0.6407501 0.7665065 -0.04373508 -0.6407458 0.7668524 -0.04367607 -0.6403357 0.7668237 -0.0440368 -0.6403453 0.7689676 -0.04355317 -0.6378023 0.7688874 -0.04455488 -0.63783 0.7733392 -0.04343944 -0.6325026 0.7731739 -0.04545825 -0.6325627 0.7796553 -0.04354292 -0.6246933 0.7794191 -0.04634428 -0.6247863 0.7875918 -0.04337579 -0.6146688 0.7872416 -0.04739511 -0.6148205 0.7969399 -0.04402875 -0.6024519 0.7965592 -0.04823249 -0.6026335 0.8074943 -0.04438745 -0.5882028 0.806976 -0.04987394 -0.5884745 0.5173346 -0.7409247 -0.4282468 0.5214299 -0.7366676 -0.4306179 0.5131732 -0.7404234 -0.4340813 0.5168398 -0.7365466 -0.4363206 0.5097005 -0.7397905 -0.4392214 0.5125163 -0.7367683 -0.4410211 0.5069861 -0.7390226 -0.4436334 0.5089812 -0.7368525 -0.4449567 0.5042006 -0.7391674 -0.4465572 0.5063179 -0.7368421 -0.448002 0.5032151 -0.7382277 -0.4492155 0.5036711 -0.7377231 -0.4495329 0.5027943 -0.7377623 -0.4504492 0.5029479 -0.7375919 -0.450557 0.5027441 -0.7376893 -0.4506251 0.5027544 -0.7376778 -0.4506323 0.5031771 -0.7375298 -0.4504029 0.5028492 -0.7378935 -0.450173 0.5033629 -0.7376223 -0.4500433 0.5032804 -0.737714 -0.4499855 0.502691 -0.7380342 -0.4501194 0.5032403 -0.7374244 -0.4505047 0.5016051 -0.7382618 -0.4509564 0.5023105 -0.7374768 -0.4514556 0.5001749 -0.7383806 -0.4523484 0.5009959 -0.7374624 -0.4529374 0.4985244 -0.7382401 -0.4543951 0.4993047 -0.7373611 -0.4549652 0.4964628 -0.7380164 -0.4570083 0.4973452 -0.7370128 -0.457668 0.4938164 -0.7378761 -0.4600915 0.4949252 -0.7366003 -0.4609435 0.4905063 -0.7379769 -0.4634584 0.4919171 -0.7363321 -0.4645777 0.4869378 -0.7378179 -0.4674572 0.4881938 -0.7363312 -0.4684903 0.482348 -0.73827 -0.4714847 0.4841558 -0.7360932 -0.4730328 0.4778892 -0.7379966 -0.4764273 0.47909 -0.7365218 -0.4775024 0.4726467 -0.738029 -0.4815789 0.4740722 -0.7362373 -0.4829183 0.4670751 -0.7378498 -0.4872562 0.4682636 -0.7363168 -0.488433 0.4606196 -0.7381663 -0.4928893 0.4620919 -0.7362124 -0.4944316 0.4534693 -0.7384557 -0.4990479 0.4548234 -0.7365989 -0.5005575 0.4383949 -0.7404102 -0.5095122 0.4414894 -0.735865 -0.51341 0.4075693 -0.7436803 -0.529931 0.4116026 -0.7367015 -0.5365206 0.3559022 -0.7500097 -0.5575115 0.3593755 -0.7413434 -0.5667973 0.2971268 -0.7581094 -0.5805047 0.2981112 -0.7529446 -0.5866892 0.2775514 -0.7601792 -0.587446 0.2775426 -0.7602541 -0.5873533 0.3037323 -0.7532057 -0.5834618 0.302916 -0.7570497 -0.5788934 0.3706068 -0.7416245 -0.5591455 0.3683307 -0.7467828 -0.553758 0.434517 -0.7366938 -0.5181479 0.432731 -0.7394112 -0.5157665 0.4779349 -0.7364508 -0.4787676 0.4771454 -0.7374269 -0.4780521 0.6604702 -0.54355 -0.5180084 0.664777 -0.5361642 -0.5201917 0.6540911 -0.5421366 -0.5274968 0.6577164 -0.5357986 -0.5294612 0.6484788 -0.5408189 -0.5357148 0.6513915 -0.5356374 -0.5373841 0.6433195 -0.5404989 -0.5422187 0.6460247 -0.5356196 -0.5438416 0.6398397 -0.5392215 -0.5475814 0.6412676 -0.5366173 -0.5484685 0.6369298 -0.5392073 -0.550977 0.6383315 -0.5366317 -0.5518689 0.636102 -0.5382675 -0.5528494 0.6362104 -0.5380678 -0.552919 0.636093 -0.5379183 -0.5531994 0.6359917 -0.5381051 -0.5531341 0.6366004 -0.5377905 -0.5527397 0.6363419 -0.538267 -0.5525736 0.6366776 -0.5384839 -0.5519753 0.6368644 -0.5381401 -0.552095 0.636336 -0.5382553 -0.5525918 0.6363994 -0.5381387 -0.5526325 0.6349084 -0.538352 -0.5541377 0.6354892 -0.5372771 -0.554515 0.6328381 -0.5383483 -0.5565043 0.6335915 -0.5369457 -0.5570019 0.629929 -0.5386059 -0.5595474 0.6310187 -0.5365615 -0.5602832 0.6264817 -0.5384399 -0.5635631 0.6275302 -0.5364531 -0.5642907 0.6219185 -0.5389229 -0.5681369 0.6234577 -0.5359714 -0.5692408 0.6170736 -0.5384764 -0.5738148 0.6182364 -0.536214 -0.574681 0.6110914 -0.5387476 -0.5799296 0.6126903 -0.5355825 -0.581173 0.6047127 -0.5381573 -0.5871194 0.6059259 -0.5357066 -0.5881091 0.5970574 -0.5385529 -0.5945445 0.5987465 -0.535061 -0.5959969 0.5888545 -0.5383509 -0.6028504 0.5902248 -0.535444 -0.604098 0.5795143 -0.5388348 -0.6114084 0.5811315 -0.5353019 -0.6129748 0.5697047 -0.5384998 -0.6208499 0.5708479 -0.5359174 -0.6220331 0.5580011 -0.5398351 -0.6302483 0.559768 -0.5356894 -0.6322158 0.5348072 -0.5428557 -0.6475252 0.5378221 -0.5351879 -0.6513995 0.4864047 -0.5476585 -0.6807942 0.4902067 -0.5358227 -0.6874529 0.404093 -0.5584934 -0.7244267 0.4072957 -0.5422821 -0.7348743 0.3098039 -0.5709009 -0.7603247 0.3102814 -0.561607 -0.7670223 0.2778612 -0.573866 -0.7703706 0.2778611 -0.573946 -0.7703111 0.3187285 -0.5616165 -0.7635437 0.3182244 -0.5693233 -0.7580266 0.4245293 -0.5434 -0.7242178 0.4225608 -0.5521699 -0.7187147 0.5265364 -0.5363721 -0.6595942 0.524933 -0.5406375 -0.6573861 0.5966833 -0.5349741 -0.5981404 0.595292 -0.5378724 -0.596926 0.7595716 -0.3080451 -0.5728517 0.7624871 -0.2988384 -0.5738547 0.7507372 -0.3068817 -0.5849936 0.75312 -0.2991976 -0.5859106 0.7430256 -0.3054028 -0.5955184 0.7448353 -0.2994488 -0.5962809 0.7363976 -0.3046226 -0.6040891 0.7379329 -0.2994846 -0.6047842 0.7314326 -0.3029664 -0.6109156 0.7322642 -0.3001427 -0.6113129 0.7278352 -0.3023846 -0.6154832 0.7285277 -0.3000091 -0.6158262 0.726202 -0.301841 -0.6176752 0.7264355 -0.3010374 -0.6177929 0.7261026 -0.3012415 -0.6180847 0.725986 -0.301643 -0.6180257 0.7267892 -0.3007556 -0.617514 0.7265372 -0.3016237 -0.6173872 0.7272498 -0.3012379 -0.6167363 0.7272715 -0.3011632 -0.616747 0.7265434 -0.3016459 -0.6173691 0.7267729 -0.3008553 -0.6174845 0.7247646 -0.3017955 -0.6193833 0.725122 -0.3005596 -0.619566 0.7219784 -0.3022956 -0.6223862 0.7225754 -0.3002173 -0.6226992 0.7183898 -0.3024116 -0.6264691 0.7189962 -0.3002818 -0.6267976 0.7139052 -0.3021213 -0.6317136 0.7145096 -0.2999718 -0.6320545 0.7083635 -0.3020725 -0.6379448 0.7091206 -0.2993372 -0.6383927 0.7017112 -0.3023572 -0.6451215 0.7026219 -0.299008 -0.6456908 0.6942807 -0.3018208 -0.6533594 0.6950062 -0.2990944 -0.6538416 0.6856016 -0.3018292 -0.6624572 0.6864926 -0.2983933 -0.6630909 0.6760342 -0.3012703 -0.6724686 0.676768 -0.2983546 -0.6730303 0.665089 -0.3017144 -0.6830997 0.6660425 -0.2977955 -0.6838899 0.6531812 -0.3016537 -0.694521 0.6539606 -0.2983261 -0.6952244 0.639912 -0.3026039 -0.7063593 0.6408467 -0.2984389 -0.7072834 0.6252431 -0.3029754 -0.7192198 0.6259755 -0.2995424 -0.7200201 0.5957168 -0.3064243 -0.7424458 0.5973266 -0.2979826 -0.7445853 0.5328695 -0.3132951 -0.7860637 0.5348665 -0.2992494 -0.7901693 0.4257655 -0.3261801 -0.8439965 0.4267625 -0.3089506 -0.8499549 0.301675 -0.3434865 -0.889387 0.3012118 -0.3323809 -0.8937529 0.2591351 -0.3476557 -0.9011018 0.2591655 -0.3480572 -0.900938 0.3115525 -0.3332831 -0.8898637 0.311809 -0.3411967 -0.8867694 0.4486611 -0.3102743 -0.8381128 0.4479464 -0.319661 -0.8349615 -0.9951845 0 -0.09801906 -0.9569397 0 -0.2902867 -0.8819203 0 -0.4713984 -0.7730094 0 -0.6343945 -0.634392 0 -0.7730116 -0.4713941 0 -0.8819227 -0.290283 0 -0.9569408 -0.09801548 0 -0.995185 0.0980187 0 -0.9951846 0.2902871 0 -0.9569396 0.4713989 0 -0.8819202 0.6343936 0 -0.7730101 0.7730119 0 -0.6343915 0.881922 0 -0.4713954 0.9569408 0 -0.2902829 0.9951848 0 -0.0980165 0.9951844 0 0.09802013 0.9569392 0 0.2902886 0.8819209 0 0.4713973 0.7730085 0 0.6343956 0.6343913 0 0.7730122 0.4713944 0 0.8819225 0.2902829 0 0.9569409 0.0980165 0 0.9951848 -0.09802389 0 0.9951841 -0.2902886 0 0.9569392 -0.4713982 0 0.8819205 -0.6343954 0 0.7730087 -0.7730118 0 0.6343917 -0.8819229 0 0.4713937 -3.17653e-6 1 -6.25723e-7 -0.995185 0 0.09801465 -0.9569416 0 0.2902806 0 -1 3.17638e-6 0 -1 0 -0.81914 0 -0.5735938 0 -1 0 -0.5735221 -0.01062607 -0.8191213 0 -1 0 -0.6834896 0 -0.7299602 -0.3570635 -0.07007688 -0.9314478 -0.4995071 -0.03622448 -0.865552 -0.6361448 -0.005687773 -0.7715486 0 -1 0 -0.9659249 0 -0.2588222 0 -1 0 0 -1 0 0 -1 0 -0.8933951 0 -0.4492719 -0.8595395 -0.005562663 -0.511039 -0.8176866 -0.01738393 -0.5754013 -0.8784221 -0.002087593 -0.4778811 -0.7557836 -0.04701638 -0.6531315 0 -1 0 -0.9961879 0 0.08723318 0 -1 0 -0.9659249 0 -0.2588222 0 -1 0 -0.9063231 0 0.4225854 0 -1 0 -0.9961879 0 0.08723318 -0.7071068 0 0.7071068 -0.9063231 0 0.4225854 -0.4225922 0 0.9063198 -0.7071068 0 0.7071068 -0.08722412 0 0.9961887 -0.4225922 0 0.9063198 0 -1 0 0.2588243 0 0.9659244 0 -1 0 -0.08722412 0 0.9961887 0 -1 0 0.5735614 -0.01061642 0.8190938 0 -1 0 0 -1 0 0.2588243 0 0.9659244 0.4610955 0 0.8873505 0 -1 0 0.8191674 0 0.5735545 0 -1 0 0.357156 -0.07005614 0.9314138 0.4989331 -0.03636932 0.865877 0.6361506 -0.005708754 0.7715438 0.683655 0 0.7298054 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0 -1 0 0 -1 0 0.893602 0 0.4488602 0.7557774 -0.04704064 0.6531369 0.8593177 -0.005634307 0.5114111 0.8177586 -0.01736962 0.5752992 0.8784545 -0.002113282 0.4778213 0 -1 0 0.9961942 0 -0.08716166 0 -1 0 0.9659211 0 0.2588369 0 -1 0 0.9063198 0 -0.4225922 0 -1 0 0.9961942 0 -0.08716166 0.7070775 0 -0.7071361 0.9063198 0 -0.4225922 0.4226078 0 -0.9063127 0.7070775 0 -0.7071361 0.08716994 0 -0.9961934 0.4226078 0 -0.9063127 0 -1 0 -0.2588369 0 -0.9659211 0 -1 0 0.08716994 0 -0.9961934 0 -1 0 0 -1 0 -0.2588369 0 -0.9659211 -0.4609354 0 -0.8874337 0.4999817 0 0.866036 0.8660537 0 0.4999511 0.8660537 0 0.4999511 0 0 1 0.4999817 0 0.866036 -0.4999817 0 0.866036 0 0 1 -0.8660231 0 0.5000042 -0.4999817 0 0.866036 -1 0 0 -0.8660231 0 0.5000042 -0.8660441 0 -0.4999678 -1 0 0 -0.4999372 0 -0.8660618 -0.8660441 0 -0.4999678 0 0 -1 -0.4999372 0 -0.8660618 0.4999729 0 -0.8660411 0 0 -1 0.8660389 0 -0.4999766 0.4999729 0 -0.8660411 1 0 0 0.8660389 0 -0.4999766 1 0 0 0 1 0 -0.5735545 0 -0.8191674 0 1 0 -0.8191092 0.008663177 -0.5735722 0 1 0 -0.9816569 0.1415085 -0.1277698 -0.9584861 0.1072542 -0.2641988 -0.8285142 0.02425849 -0.5594424 -0.7850577 0.008889913 -0.619359 -0.7504475 0.00245893 -0.6609255 -0.7220276 0 -0.6918643 0 1 0 0 1 0 0 1 0 0 1 0 -0.6462897 0.04281824 -0.76189 -0.5510026 0.0105974 -0.8344362 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.8191365 0.008688986 0.5735328 0 1 0 0 1 0 0 1 0 0.5735938 0 0.81914 0 1 0 0.7219615 0 0.6919333 0.9816371 0.1414593 0.1279761 0.9585961 0.1073725 0.263751 0.8282997 0.02417093 0.5597639 0.7849586 0.008851826 0.619485 0.7507074 0.00248754 0.6606302 0 1 0 0 1 0 0 1 0 0 1 0 0.6463042 0.04280614 0.7618784 0.5510128 0.01058137 0.8344297 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4619306 -0.7964566 0.3902269 -0.2418212 -0.9397037 0.2418254 -0.7527827 -0.3264684 0.571609 -0.3838487 -0.8553493 0.3479048 -0.6330184 -0.594274 0.496111 -0.6646183 0.3420861 0.6642737 -0.8119053 0.03813701 0.5825423 -0.7789322 -0.2409562 0.5789685 -0.6646167 0.3419233 0.6643591 -0.6638476 0.3419303 0.6651241 -0.6641563 0.342087 0.6647351 -0.5054956 0.8045904 0.3116223 -0.6641556 0.3412541 0.6651639 -0.7078543 0.5280983 0.4690996 -0.7143629 0.5133348 0.4755766 -0.01547026 0.9985108 -0.05231261 -0.5079064 0.8021967 0.3138654 -0.2309078 0.9684029 0.09421962 0.2418333 0.9396987 -0.2418324 0.08596938 0.9873956 -0.1328884 0.2418138 0.9397078 -0.2418169 0.2416788 0.9396899 -0.2420209 0.2418519 0.93969 -0.2418477 0.241842 0.9396939 -0.2418426 -0.2417623 0.939691 0.2419338 -0.2418109 0.9397078 0.2418196 -0.2418491 0.9396908 0.2418471 -0.2418289 0.9396988 0.241836 -0.2418534 0.9396883 0.2418534 -0.6644579 -0.3420399 0.6644579 -0.6648871 -0.341983 0.6640578 0.241458 -0.9396801 -0.2422793 -0.6633315 -0.342028 0.6655885 0.2409695 -0.9396868 -0.2427396 0.2418622 -0.939684 -0.2418608 0.2418566 -0.9396874 -0.241853 -0.2418559 -0.9396861 0.241859 -0.2425903 -0.939687 0.2411191 -0.2418537 -0.9396874 0.2418559 0.4619124 -0.7964705 -0.3902198 0.2418485 -0.9396909 -0.2418476 0.7527768 -0.3264696 -0.5716159 0.3335638 -0.8868054 -0.3198618 0.5189928 -0.7390947 -0.4294012 0.664218 -0.5403606 -0.5165509 0.6643127 0.3420243 -0.6646112 0.8117072 0.03798604 -0.5828279 0.7603757 -0.3038223 -0.5740391 0.8092667 -0.04722565 -0.58554 0.6642985 0.3420527 -0.6646107 0.6648313 0.3421291 -0.6640383 0.6645234 0.3419727 -0.6644271 0.5037125 0.8051416 -0.3130825 0.664561 0.3424335 -0.6641521 0.7077248 0.5251682 -0.4725718 0.6243304 0.6698848 -0.4018282 0.01728153 0.9984045 0.05375725 0.4660715 0.8393574 -0.2797439 0.280812 0.9505268 -0.1328284 -0.2419 0.9396666 0.2418902 -0.1386439 0.9756374 0.1700279 0.06806498 0.9976139 0.01155328 0.2418602 0.9396847 -0.2418602 0.6644605 -0.3420302 -0.6644605 0.6645213 -0.3420222 -0.6644036 -0.2418331 -0.9396986 0.2418331 0.6644621 -0.3420236 -0.6644621 -0.7748999 -0.3375172 0.5344271 -0.241866 0.9396851 0.241853 -0.2418479 0.9396915 0.2418461 -0.2418494 0.939691 0.2418465 -0.2418521 0.9396903 0.2418464 -0.2418398 0.939692 0.2418519 -0.241846 0.9396922 0.2418451 -0.4919027 0.7720436 0.402468 -0.4964769 0.7680223 0.40454 -0.7750207 -0.3370477 0.534548 -0.7750192 -0.3370774 0.5345315 -0.7751431 -0.3365028 0.5347142 -0.7749838 -0.3373496 0.5344112 -0.7751158 -0.3366752 0.534645 -0.774979 -0.3372145 0.5345034 -0.775279 -0.336014 0.5348243 -0.7747343 -0.3382141 0.5342267 -0.7749927 -0.337169 0.5345124 -0.7750187 -0.3370612 0.5345425 -0.7749277 -0.3374474 0.534431 -0.1418125 0.9759387 0.1656286 -0.1305622 0.9815126 0.1399519 -0.1617149 0.9703912 0.1794132 -0.1422463 0.981029 0.1317116 -0.1809268 0.966749 0.1807258 -0.1832419 0.9695861 0.1622502 -0.1644471 0.9801517 0.1107231 -0.1916269 0.9662536 0.1721425 -0.2418349 0.9396955 0.2418436 -0.2081197 0.9637588 0.1668981 -0.2418621 0.9396885 0.2418432 -0.1953494 0.9752684 0.1033927 -0.2097849 0.962876 0.1698825 -0.2418509 0.939691 0.2418453 -0.2175873 0.9656001 0.1423807 -0.2418308 0.9396941 0.2418529 -0.2170642 0.96969 0.1121807 -0.2211539 0.9631475 0.1530935 -0.2418531 0.9396917 0.2418398 -0.222028 0.9676778 0.1195961 -0.2418398 0.9396924 0.2418504 -0.2230761 0.9669128 0.1237604 -0.2418475 0.9396914 0.2418466 -0.2192244 0.9685326 0.1178357 -0.2418424 0.9396924 0.2418478 -0.2211157 0.9684813 0.114681 -0.2418443 0.939692 0.2418477 -0.1797 0.9836591 -0.01107424 -0.2418439 0.939692 0.2418479 -0.2075709 0.9692624 0.1320794 -0.2062381 0.9750536 0.08207494 -0.2418386 0.9396926 0.241851 -0.1302404 0.9912587 -0.02106148 -0.241848 0.939692 0.2418441 -0.1909629 0.9711682 0.1427083 -0.1503871 0.988389 0.02170282 -0.2418474 0.9396919 0.2418447 -0.1351711 0.9883189 0.07038956 -0.2418506 0.9396917 0.2418428 -0.1753849 0.9732038 0.1487092 -0.2418481 0.939692 0.2418439 -0.1574876 0.9820744 0.1035733 -0.2418361 0.939693 0.2418519 -0.1665078 0.975135 0.1462427 -0.142151 0.9836789 0.1103121 -0.2418512 0.9396923 0.2418396 -0.1590883 0.976929 0.1424803 -0.2418449 0.9396926 0.2418446 -0.1620702 0.9754576 0.1490498 -0.2418473 0.9396923 0.2418435 -0.1537721 0.9785893 0.1368105 -0.2418445 0.9396926 0.2418449 -0.1518732 0.9783769 0.1404035 -0.241842 0.9396929 0.2418469 -0.1583119 0.9758111 0.150765 -0.156847 0.9768349 0.1455774 -0.241849 0.939692 0.2418429 -0.159404 0.9749441 0.1551592 -0.2418428 0.9396928 0.2418461 -0.1510124 0.9780353 0.1436742 -0.2418447 0.9396923 0.241846 -0.1588428 0.9745971 0.1578911 -0.1484421 0.978206 0.1451827 -0.2418424 0.9396927 0.2418464 -0.1579703 0.9743291 0.1604002 -0.2418463 0.9396924 0.2418443 -0.1471094 0.9780412 0.1476288 -0.2418435 0.9396929 0.2418456 -0.155323 0.9746114 0.1612676 -0.1470195 0.9775521 0.1509214 -0.2418471 0.9396923 0.2418434 -0.1557207 0.97395 0.1648406 -0.2418425 0.9396926 0.2418467 -0.1481776 0.9763448 0.1574626 -0.1507769 0.9759648 0.1573502 -0.2418461 0.9396924 0.2418445 -0.1534537 0.9741652 0.1656926 -0.2418465 0.9396923 0.2418443 -0.1438 0.9772722 0.1557587 -0.2418431 0.9396922 0.2418479 -0.1522884 0.9741259 0.1669933 -0.241844 0.9396922 0.2418472 -0.1445394 0.9765084 0.1598119 -0.148784 0.9755198 0.1619398 -0.2418474 0.939692 0.2418445 -0.1456023 0.9758188 0.1630259 -0.2418457 0.9396922 0.2418453 -0.2418436 0.9396923 0.2418471 -0.1452155 0.9761193 0.161566 -0.2418448 0.9396924 0.2418457 -0.1450216 0.9759243 0.1629124 -0.2418464 0.9396921 0.2418452 -0.2418473 0.939692 0.2418446 -0.1449893 0.9759427 0.1628308 -0.1527521 0.9737647 0.1686685 -0.2418432 0.9396931 0.2418446 -0.1440301 0.9762251 0.161988 -0.2418487 0.9396924 0.2418417 -0.1434558 0.9763948 0.1614733 -0.1430795 0.976476 0.1613165 -0.1405298 0.9771659 0.1593671 -0.241843 0.9396929 0.2418453 -0.151798 0.9737153 0.1698111 -0.2418434 0.9396929 0.2418451 -0.2418424 0.9396929 0.2418461 -0.1417867 0.9767721 0.1606635 -0.1449837 0.9759611 0.1627256 -0.2418432 0.9396933 0.2418432 -0.1539573 0.9725305 0.1745897 -0.2418423 0.9396936 0.2418435 -0.2418454 0.9396936 0.2418409 -0.1394394 0.9769155 0.1618419 -0.1490625 0.9744946 0.1677512 -0.2418466 0.9396922 0.2418442 -0.1526032 0.9722366 0.1773928 -0.2418406 0.9396932 0.2418466 -0.1394718 0.9760642 0.1668718 -0.14313 0.975522 0.1669453 -0.2418456 0.9396923 0.2418453 -0.1483737 0.9726816 0.1785374 -0.2418429 0.939693 0.2418453 -0.2418478 0.9396918 0.2418448 -0.2418349 0.9396946 0.241847 -0.2418743 0.9396871 0.2418368 -0.2418451 0.939692 0.2418472 -0.1319411 0.9775014 0.1645678 -0.001127362 0.8454493 0.5340547 -0.1734045 0.9089676 0.3790893 -0.1415225 0.9744718 0.1742873 -0.04526418 0.8249554 0.5633823 -0.1555646 0.8016229 0.5772351 -0.04590165 0.8018397 0.5957736 -0.2617061 0.7746872 0.5756472 -0.1993453 0.7479358 0.6331298 -0.3819859 0.708272 0.5936644 -0.4243684 0.7394679 0.5225884 -0.3522617 0.7433044 0.5686917 -0.4929943 0.6202558 0.6101142 -0.4388576 0.7397629 0.5100538 -0.4440699 0.7135012 0.5419574 -0.4504715 0.7245826 0.5215895 -0.4433138 0.7371456 0.5099895 -0.4473326 0.7291935 0.5178517 -0.4427503 0.7375658 0.5098715 -0.4444375 0.7352878 0.5116906 -0.442494 0.7397598 0.5069066 -0.4442596 0.7355443 0.5114763 -0.4487315 0.7323111 0.5122113 -0.4461027 0.7400931 0.5032439 -0.4552371 0.7229915 0.5196563 -0.4548008 0.7320994 0.5071358 -0.4533712 0.7400438 0.4967792 -0.4703162 0.7103406 0.5236591 -0.467048 0.728876 0.5006058 -0.459247 0.7489614 0.4776495 -0.4921229 0.694154 0.5253241 -0.4936869 0.7131997 0.4976136 -0.4723909 0.7531737 0.4577951 -0.5064163 0.6960226 0.5090139 -0.4861425 0.7477216 0.4523029 -0.5346888 0.679988 0.5017213 -0.5149856 0.7252847 0.4568938 -0.4967017 0.7581016 0.4225747 -0.5364354 0.7000592 0.4713323 -0.5567463 0.6944561 0.4558116 0.2418595 -0.939685 -0.2418594 0.3135868 -0.9023764 -0.2956015 0.3369964 -0.887194 -0.3151512 0.2418559 -0.9396876 -0.2418528 -0.7745889 -0.3387156 0.5341196 0.2419568 -0.9396306 -0.2419732 0.2418244 -0.9397066 -0.2418113 -0.7750326 -0.3370063 0.534557 -0.7751133 -0.3367149 0.5346236 -0.77486 -0.3376528 0.5343992 -0.7752625 -0.3361443 0.5347662 -0.7748323 -0.3377658 0.534368 -0.7750888 -0.3367878 0.5346133 0.2418467 -0.9396927 -0.2418425 -0.01796197 -0.9978349 -0.06326848 0.2418462 -0.939677 -0.2419041 0.2418487 -0.9396927 -0.2418407 0.2418506 -0.9396988 -0.2418146 0.2418422 -0.9396845 -0.2418788 0.2418556 -0.9396968 -0.2418175 0.2418404 -0.9396901 -0.2418591 0.2418553 -0.9396923 -0.2418353 0.241843 -0.9396929 -0.2418456 0.2418236 -0.9396963 -0.2418517 -0.775141 -0.3365288 0.5347006 -0.1522517 -0.9882701 0.01190179 0.2418434 -0.9396929 -0.2418451 -0.01384681 -0.9989989 -0.04253882 0.2418418 -0.9396917 -0.2418511 0.2418469 -0.939694 -0.2418372 0.2418419 -0.9396926 -0.2418478 0.2418455 -0.9396932 -0.2418416 0.2418443 -0.9396932 -0.2418433 0.2418372 -0.9396927 -0.2418519 -0.1217978 -0.9923303 0.02111554 0.2418422 -0.9396927 -0.2418469 -0.01189655 -0.999724 -0.0202586 0.2418413 -0.9396924 -0.2418491 0.2418408 -0.9396923 -0.2418501 0.2418444 -0.9396926 -0.2418451 0.2418479 -0.9396927 -0.2418413 -0.1021638 -0.9940895 0.03672665 0.2418476 -0.939693 -0.2418401 -0.006209313 -0.9999798 -0.001396954 0.2418408 -0.9396917 -0.2418522 0.2418529 -0.9396923 -0.2418377 -0.09910291 -0.9928408 0.06667649 0.2418441 -0.9396926 -0.2418456 0.001527607 -0.9999146 0.01297783 0.2418454 -0.9396929 -0.2418432 0.2418494 -0.939693 -0.2418389 -0.08966964 -0.9916806 0.09235233 0.2418423 -0.9396929 -0.2418461 -0.00383675 -0.9992967 0.03730064 0.2418411 -0.9396928 -0.2418478 -0.0566439 -0.9943481 0.08979594 0.2418439 -0.9396925 -0.2418461 -0.01318031 -0.9979808 0.06213343 0.2418453 -0.9396926 -0.2418444 0.2418484 -0.9396922 -0.241843 0.004941225 -0.9987002 0.05073052 0.2418478 -0.9396921 -0.2418439 -0.02315258 -0.9969105 0.07505548 0.2418433 -0.9396924 -0.2418471 -0.0221799 -0.9956007 0.09103488 0.2418438 -0.9396925 -0.241846 0.2418459 -0.9396917 -0.241847 0.00380516 -0.9980389 0.0624811 0.2418466 -0.9396924 -0.2418439 -3.93433e-4 -0.9980775 0.06197696 0.2418484 -0.9396921 -0.2418429 0.003695726 -0.9979796 0.06342774 0.001651942 -0.9978426 0.06563013 0.2418416 -0.9396919 -0.2418508 0.003533601 -0.9980028 0.06306976 0.241843 -0.9396926 -0.2418466 0.2418485 -0.939692 -0.2418432 -0.0168516 -0.9955196 0.09304124 0.2418448 -0.9396919 -0.2418475 0.01399028 -0.9977153 0.06609529 0.2418472 -0.9396922 -0.2418438 0.002780497 -0.9978041 0.06617611 0.2418474 -0.939692 -0.2418447 -0.1081557 -0.9605973 0.2560372 0.2418464 -0.9396917 -0.2418469 0.2418332 -0.9396888 -0.2418715 0.07677513 -0.9907062 0.1122798 0.2418438 -0.9396926 -0.2418459 0.01743793 -0.9972167 0.07248902 0.241842 -0.9396908 -0.2418544 0.1883534 -0.9740456 0.1255319 0.08075213 -0.9851605 0.1514524 0.2418362 -0.9396899 -0.2418638 0.294512 -0.947143 0.1272116 0.2380334 -0.9513169 0.1957966 0.2418308 -0.9396893 -0.2418719 0.417224 -0.8940358 0.163169 0.312071 -0.9397984 -0.1392511 0.3848433 -0.9140986 0.1277471 0.4422296 -0.8924104 0.08964657 0.5147315 -0.8046279 0.2960157 0.4367107 -0.894986 0.09101629 0.3305243 -0.8945297 -0.3009492 0.3382461 -0.8900836 -0.3055171 0.3277162 -0.8947945 -0.3032243 0.3471908 -0.883481 -0.3145155 0.3246343 -0.8953748 -0.3048222 0.3372815 -0.8886658 -0.3106671 0.3388933 -0.8867155 -0.3144631 0.3332877 -0.888769 -0.3146568 0.3372399 -0.8869979 -0.3154425 0.3341981 -0.8877686 -0.3165103 0.3197884 -0.8975682 -0.3034908 0.3340378 -0.8880634 -0.3158515 0.3341964 -0.8877695 -0.3165091 0.3348191 -0.8874098 -0.3168599 0.3360177 -0.8865275 -0.3180584 0.3345701 -0.8875625 -0.3166951 0.3267471 -0.8922879 -0.3115424 0.330729 -0.8901541 -0.313439 0.3338136 -0.8880516 -0.3161216 0.3343306 -0.8875023 -0.3171164 0.3250178 -0.8925869 -0.3124931 0.3307939 -0.8895483 -0.3150861 0.3357874 -0.8857855 -0.3203604 0.3226795 -0.8930883 -0.3134822 0.3292749 -0.8896548 -0.3163738 0.3345516 -0.8854011 -0.3227076 0.3271885 -0.8887683 -0.3209963 0.3322816 -0.8861826 -0.3229079 0.3213173 -0.8916034 -0.3190588 0.3232603 -0.891597 -0.3171084 0.3323473 -0.8841221 -0.3284406 0.3204796 -0.8909042 -0.3218426 0.3323439 -0.8828626 -0.331815 0.3195731 -0.8903021 -0.3244 0.3305332 -0.8827936 -0.3338016 0.3186502 -0.8897395 -0.3268421 0.3291065 -0.8822895 -0.3365324 0.3202047 -0.8873104 -0.3318875 0.3260877 -0.8828961 -0.3378774 0.3190169 -0.8870644 -0.3336839 0.3132944 -0.8902308 -0.3306596 0.3255052 -0.8812968 -0.3425816 0.3268211 -0.8754197 -0.3561299 0.3032358 -0.8924673 -0.3339915 0.3255869 -0.8766248 -0.3542912 0.3500877 -0.8313727 -0.4315763 0.2907455 -0.8936926 -0.3417317 0.3225517 -0.8674712 -0.3787533 0.3120012 -0.8511766 -0.4220824 0.2727817 -0.8974401 -0.3466864 0.3318086 -0.8093092 -0.4846871 0.270579 -0.8811607 -0.3877407 0.2581685 -0.8984646 -0.3551201 0.2738978 -0.8679961 -0.4142014 0.2581422 -0.895448 -0.3626779 0.2635271 -0.8926967 -0.3655763 0.2582194 -0.8950254 -0.3636649 0.2733419 -0.8897669 -0.3655118 0.2597677 -0.9092166 -0.3253396 0.2812783 -0.8934767 -0.3501169 0.265197 -0.9198293 -0.2891101 0.3104391 -0.8827819 -0.3525955 0.2823693 -0.8985366 -0.3360053 0.2805789 -0.9142231 -0.2923555 0.3274279 -0.8838515 -0.3340622 0.3057689 -0.8924403 -0.3317468 0.3478304 -0.8749619 -0.3368321 0.301137 -0.9047189 -0.3013308 0.7975839 0.2296335 -0.5577889 0.7750354 0.3369926 -0.5345617 0.7750247 0.3370185 -0.5345608 0.7998605 0.2121697 -0.561433 0.7546905 0.4066025 -0.5148948 0.7374366 0.4567922 -0.4975219 0.7542591 0.3388434 -0.5623863 0.7535916 0.3188155 -0.5748533 0.76818 0.248085 -0.5902144 0.7054239 0.4591056 -0.5399991 0.7792558 0.2140933 -0.589003 0.7809456 0.3447847 -0.5208144 0.7402656 0.4678497 -0.4828287 0.7843964 0.3360705 -0.5213242 0.580998 -0.05943089 0.8117322 0.5431191 0.06772041 0.8369203 0.7608134 0.3541457 -0.5438233 0.7700398 0.3180519 -0.5530656 0.7706666 0.3303085 -0.5449488 0.7994816 0.278562 -0.5321959 0.7116835 0.5136511 -0.4792382 0.7565065 0.32691 -0.5664166 0.7128819 0.4654016 -0.5245957 0.7569292 0.3258965 -0.5664361 0.728766 0.4455755 -0.5199641 0.747624 0.3408627 -0.5699746 0.7158348 0.4435159 -0.5393276 0.697942 0.4987849 -0.5138975 0.7424433 0.3415369 -0.5763076 0.691857 0.4924142 -0.528074 0.7447361 0.3382942 -0.5752611 0.7378621 0.3418214 -0.5819946 0.7035265 0.4515061 -0.5488103 0.7406378 0.3383533 -0.5804935 0.7010257 0.4712944 -0.5352052 0.7341158 0.341665 -0.5868043 0.7007315 0.4489485 -0.5544553 0.7368714 0.3387607 -0.5850315 0.6890437 0.4848916 -0.5386083 0.7312942 0.3412176 -0.5905755 0.6925298 0.4631466 -0.5530802 0.7336784 0.3392933 -0.5887241 0.6883096 0.4751606 -0.5481354 0.7297196 0.340622 -0.5928626 0.6900666 0.4651444 -0.5544805 0.7311806 0.339936 -0.5914545 0.7290908 0.3405619 -0.59367 0.6918421 0.4587898 -0.5575541 0.7296401 0.3400797 -0.5932715 0.6892862 0.46697 -0.5539165 0.7292364 0.3403111 -0.593635 0.6921469 0.4581935 -0.5576661 0.7290586 0.3404439 -0.5937772 0.7300302 0.3401669 -0.5927413 0.6962966 0.4490048 -0.5599694 0.7292991 0.3406094 -0.5933869 0.6969763 0.4461883 -0.5613734 0.730671 0.3402665 -0.5918942 0.700479 0.4392278 -0.5625016 0.7300874 0.3405237 -0.5924662 0.7309022 0.3403745 -0.5915464 0.6938065 0.4581873 -0.5556049 0.7306945 0.3404479 -0.5917609 0.6932684 0.4576371 -0.5567288 0.7307409 0.3403995 -0.5917314 0.6917891 0.4631152 -0.5540325 0.7308982 0.3403435 -0.5915691 0.6920347 0.4623513 -0.5543637 0.7301605 0.3405027 -0.592388 0.6903517 0.4654538 -0.5538659 0.7307266 0.3402981 -0.5918073 0.7290604 0.3408185 -0.5935602 0.6931459 0.4554013 -0.5587116 0.7291607 0.3406432 -0.5935376 0.730129 0.3402963 -0.5925454 0.6895508 0.4673397 -0.5532751 0.7273617 0.3408962 -0.5955961 0.6906713 0.457594 -0.5599828 0.7278019 0.3401365 -0.5954926 0.686232 0.4706627 -0.5545831 0.7251763 0.3410522 -0.5981663 0.687317 0.460893 -0.5614028 0.725691 0.3401822 -0.5980374 0.7225348 0.3412947 -0.6012166 0.688041 0.4521168 -0.5676177 0.7231619 0.3402664 -0.6010454 0.6813232 0.4750297 -0.5569072 0.7194803 0.3415781 -0.6047086 0.6715347 0.4872383 -0.5582473 0.7202887 0.3403081 -0.6044622 0.7160721 0.3419277 -0.6085444 0.6801398 0.456667 -0.5734676 0.7171466 0.3403294 -0.6081747 0.6804935 0.4660619 -0.5654335 0.7123488 0.3422672 -0.6127092 0.6773945 0.4543758 -0.5785149 0.7137429 0.3403404 -0.6121596 0.666343 0.4880025 -0.5637734 0.713696 0.3210069 -0.6225694 0.6682136 0.4684718 -0.5779488 0.707143 0.3375728 -0.6212837 0.7054747 0.3374345 -0.6232522 0.6705412 0.4511793 -0.5889073 0.6585637 0.4905366 -0.570673 0.6936619 0.3485378 -0.6303607 0.6887993 0.3664448 -0.6255186 0.6531829 0.4840342 -0.5822911 0.6802023 0.3449665 -0.6467788 0.6645581 0.3999372 -0.6311995 0.6806715 0.3438832 -0.6468622 0.6944722 0.3398937 -0.6341773 0.6379343 0.4987132 -0.586792 0.6648445 0.3476067 -0.6611741 0.6305314 0.4576436 -0.6268912 0.6688017 0.3395626 -0.6613634 0.6406747 0.4645151 -0.6113604 0.6502639 0.3483166 -0.6751536 0.620723 0.4450739 -0.6454552 0.65647 0.3375054 -0.6746387 0.6387117 0.4361205 -0.6339135 0.6078448 0.4834977 -0.6298846 0.6366755 0.3477742 -0.6882569 0.595108 0.4778897 -0.6461175 0.6441048 0.3369898 -0.6867073 0.6240121 0.3465286 -0.7003762 0.5935085 0.4468672 -0.6693709 0.6320753 0.3371216 -0.6977319 0.5938797 0.4808416 -0.6450568 0.6123742 0.3450767 -0.7112805 0.5864201 0.4325545 -0.6848418 0.6206034 0.3377433 -0.7076588 0.5609022 0.5218791 -0.6426749 0.6006391 0.3443371 -0.7215709 0.5355406 0.5347363 -0.6536463 0.609839 0.3382052 -0.7167382 0.5814322 0.340379 -0.7389714 0.5576079 0.4225377 -0.7145175 0.5775954 0.3463455 -0.739208 0.5986132 0.337653 -0.726397 0.553253 0.4954189 -0.6696799 0.5399522 0.3515834 -0.7647489 0.5417947 0.3446263 -0.7666103 0.5508912 0.337654 -0.7632225 0.4473502 0.6441677 -0.6204239 0.4819805 0.3522083 -0.8022743 0.3591522 0.6641749 -0.6556535 0.5156468 0.32633 -0.7922229 0.4142643 0.3374011 -0.845308 0.4180434 0.322859 -0.8491182 0.4186757 0.3327586 -0.8449748 0.4704238 0.3266916 -0.8197402 0.366913 0.6511813 -0.6643326 0.3348003 0.332502 -0.8816753 0.1033767 0.8469947 -0.521453 0.3669638 0.311073 -0.8766819 0.2517417 0.3181523 -0.9140051 0.2552986 0.3045159 -0.9176561 0.3014497 0.2959603 -0.906386 0.2023748 0.7127573 -0.6715814 0.1857193 0.3009679 -0.9353751 0.04832243 0.7077313 -0.7048272 0.2285327 0.2839248 -0.931214 0.147709 0.2873345 -0.9463725 0.1268177 0.3650852 -0.9222961 0.1706741 0.2761237 -0.9458468 0.09071516 0.6215571 -0.7780988 0.1373185 0.2794627 -0.9502865 0.09555083 0.430662 -0.897441 0.1401187 0.2774314 -0.9504728 0.151212 0.2811623 -0.9476721 0.1076911 0.4377096 -0.8926438 0.1463478 0.2856817 -0.9470841 0.1194781 0.3621692 -0.9244234 0.192198 0.2876758 -0.9382444 0.1931897 0.2838006 -0.9392204 0.1873903 0.2923542 -0.9377707 0.2627028 0.2927652 -0.9193888 0.1956583 0.5162128 -0.8338118 0.2494363 0.304534 -0.9192609 0.2661041 0.02062869 -0.9637235 0.3581379 0.2974106 -0.8850334 0.3746457 0.2258763 -0.8992332 0.3238187 0.3225638 -0.8894348 0.4556536 0.3075451 -0.8353418 0.3697037 0.5673364 -0.7358319 0.4009628 0.3369568 -0.8518737 0.4487774 -0.1793631 -0.8754585 0.5412977 0.3292157 -0.7737014 0.5639409 0.2244201 -0.7947366 0.5453239 0.3237468 -0.7731817 0.4732208 0.3410211 -0.8122602 0.6248853 0.3173287 -0.7133167 0.5059847 0.6295715 -0.5895924 0.6014085 0.3469912 -0.7196562 0.5944062 0.04278594 -0.803026 0.6954092 0.3135215 -0.6466145 0.5966978 0.5846005 -0.5497218 0.6545514 0.357942 -0.6659129 0.7045742 0.05591893 -0.7074238 0.7051985 0.3553996 -0.6135033 0.7476693 0.07988375 -0.659249 0.6850118 0.5091648 -0.5210665 0.5749632 0.5710366 -0.5859476 0.6433955 0.10569 -0.7582032 0.625115 0.4634755 -0.62803 0.40515 0.6763941 -0.6150972 0.518917 0.1031646 -0.8485766 0.4604381 0.5816143 -0.6706128 0.3608011 0.4691715 -0.8060401 -0.01573616 0.9527581 -0.3033224 0.2874854 0.1384479 -0.9477259 0.3820972 0.30863 -0.8710622 0.0585609 0.6829624 -0.7281025 0.1861612 0.1186481 -0.9753289 0.1974299 0.3300538 -0.923085 0.1690333 0.1583963 -0.9727992 0.1642402 0.1874443 -0.9684472 0.1993269 0.1562008 -0.9674038 0.3303316 -0.4586257 -0.8249507 0.323759 0.199823 -0.9247977 0.2305556 0.1412774 -0.9627486 0.4336647 -0.3822672 -0.8159698 0.4359678 0.2610243 -0.8612772 0.4266237 -0.2102014 -0.8796633 0.5133407 0.09780538 -0.8525934 0.5348894 -0.4231044 -0.7313523 0.5749655 0.2275946 -0.7858852 0.5214954 0.1700745 -0.8361324 0.6224581 -0.1775701 -0.7622432 0.6237227 0.218535 -0.7504747 0.5946627 0.2048973 -0.7774274 0.6335116 0.2270933 -0.7396565 0.6413036 0.1273786 -0.7566401 0.6485647 0.1990609 -0.734669 0.6508435 0.2518839 -0.7162103 0.6566061 0.1532401 -0.7385026 0.6632602 0.2492501 -0.705663 0.6733667 0.149069 -0.7241241 0.6780772 0.2358137 -0.6961345 0.6851211 0.1749799 -0.7071005 0.6902329 0.2393996 -0.682837 0.6957908 0.1958391 -0.6910297 0.6985408 0.2646228 -0.6648425 0.7079256 0.1955461 -0.6786775 0.7053813 0.2935992 -0.645164 0.7207618 0.1792829 -0.669597 0.7187328 0.2876123 -0.6330105 0.7306478 0.1749623 -0.659956 0.7395615 0.211791 -0.6389001 0.7318255 0.2247105 -0.6433791 0.7411662 0.2235378 -0.6330116 0.7441269 0.1862155 -0.6415599 0.7474244 0.2022836 -0.6328017 0.7471953 0.2232234 -0.6259956 0.7482358 0.1974849 -0.6333584 0.750429 0.2184427 -0.6238102 0.7526143 0.1971595 -0.6282514 0.7531064 0.214535 -0.6219369 0.7538954 0.2191811 -0.6193556 0.7545862 0.2061992 -0.622962 0.7562423 0.2092105 -0.6199423 0.756473 0.2117469 -0.6187987 0.7565019 0.2077039 -0.6201322 0.7570708 0.208864 -0.6190474 0.7565867 0.2110087 -0.6189119 0.7566734 0.2112112 -0.6187367 0.7538337 0.2253714 -0.6172053 0.7539086 0.2246568 -0.6173744 0.752633 0.2281382 -0.6176541 0.7534452 0.221136 -0.6192088 0.7529876 0.2263329 -0.6178861 0.7544832 0.2174947 -0.6192343 0.7561969 0.2160679 -0.6176415 0.7558498 0.2096708 -0.6202656 0.7577586 0.2211348 -0.6139228 0.7601223 0.1948692 -0.619871 0.7638323 0.2001382 -0.6136001 0.7636271 0.2265689 -0.6045992 0.7649816 0.1931102 -0.6144197 0.7755178 0.1673771 -0.6087339 0.7741094 0.2429956 -0.5845578 0.7708944 0.1988704 -0.6051219 0.7722083 0.3240745 -0.5465071 0.7528622 0.3360421 -0.5659278 0.7939341 0.1570649 -0.5873665 0.7977125 0.2780079 -0.5351321 0.8042292 0.1646348 -0.571061 0.5809982 -0.05943912 0.8117316 0.6293109 -0.4144952 0.65739 0.5852984 -0.1909334 0.7880167 0.8128919 0.196386 -0.5483058 0.4163792 -0.1246848 0.900601 0.2947914 0.2380406 0.9254376 0.2947902 0.2381495 0.9254099 0.4443575 0.3048453 0.8423869 0.3145903 0.4860619 0.8153385 0.6739171 -0.2980446 -0.6760215 0.4478089 0.280182 0.8490967 0.4164547 -0.1245459 0.9005852 0.4768491 -0.4690247 0.7433913 -0.332829 -0.3145076 0.8889937 -0.3993754 0.06220942 0.9146744 -0.3328317 -0.3145117 0.8889914 -0.5233721 -0.3362563 0.7829516 -0.5480636 0.3932208 0.7382438 -0.5894545 0.0477603 0.8063884 0.04531097 -0.2379827 0.9702119 -0.04902929 0.1331368 0.9898842 0.04522937 -0.238106 0.9701855 -0.399343 0.06232821 0.9146805 -0.04906076 0.1329365 0.9899095 0.1329237 -0.5742144 0.8078423 0.4768208 -0.4691147 0.7433527 -0.217441 -0.6448161 0.7327563 0.1329764 -0.5739827 0.8079982 -0.5222184 -0.3498757 0.777737 -0.3932231 -0.6703177 0.6293249 -0.2174451 -0.6449151 0.7326678 -0.820809 -0.2809737 0.4973194 -0.8290042 -0.236712 0.5066748 -0.8136618 -0.3322199 0.4770582 -0.7909635 -0.2952956 0.5358893 -0.8176024 -0.0642994 0.5721817 -0.7900407 -0.3567605 0.4985556 -0.8126137 0.1927878 0.5499925 -0.8160604 0.177848 0.5499231 -0.8241121 0.138431 0.5492505 -0.8380085 0.03710478 0.5443943 -0.8424779 -0.07949113 0.5328341 -0.7627879 -0.300834 0.5724103 -0.7910888 -0.06862103 0.6078403 -0.7423587 -0.423834 0.5189109 -0.7833238 0.2015863 0.5880193 -0.7231203 -0.3541249 0.5930367 -0.7657843 -0.01062232 0.6430098 -0.7144988 -0.3958323 0.5768954 -0.7547008 0.1962742 0.6260216 -0.7032393 -0.3308495 0.6292798 -0.7347292 0.1148051 0.6685752 -0.6820581 -0.313824 0.6605386 -0.7171166 -0.01604008 0.6967686 -0.6779333 -0.3959353 0.619388 -0.731493 0.13817 0.6677027 -0.6529583 -0.3335699 0.6799829 -0.6942706 0.01740723 0.7195035 -0.6456025 -0.3876358 0.6579786 -0.690529 0.1982611 0.6956021 -0.6233671 -0.3653275 0.6913388 -0.6734102 0.07588434 0.7353641 -0.6256333 -0.3515743 0.696404 -0.6153545 -0.3301585 0.7157752 -0.6585146 0.01318639 0.7524525 -0.6645465 0.156536 0.7306671 -0.6011117 -0.3325167 0.7267033 -0.6447725 0.09776186 0.7580971 -0.6001583 -0.3623909 0.7130798 -0.5883599 -0.3414869 0.7329524 -0.6363711 0.02928572 0.7708268 -0.5874457 -0.3505027 0.7294211 -0.6430878 0.116834 0.7568276 -0.5813847 -0.3389523 0.7396643 -0.62925 0.07318979 0.7737491 -0.5766882 -0.3370227 0.7442086 -0.6247102 0.04197484 0.7797276 -0.5782204 -0.3459565 0.7389014 -0.6281164 0.08985924 0.7729135 -0.5732063 -0.3387374 0.7461178 -0.6219624 0.04830592 0.7815558 -0.5731529 -0.3428576 0.7442744 -0.5717692 -0.3394179 0.7469106 -0.6207655 0.06667733 0.7811558 -0.5717429 -0.339753 0.7467784 -0.572067 -0.3397586 0.7465276 -0.6211606 0.04756295 0.7822386 -0.6214285 0.04878902 0.7819503 -0.5722678 -0.3376904 0.7473117 -0.620867 0.05013889 0.782311 -0.5725005 -0.3389241 0.7465746 -0.566729 -0.3327447 0.7537236 -0.6145667 0.03703743 0.787995 -0.5671907 -0.3454846 0.7476197 -0.6187425 0.08853256 0.7805893 -0.551842 -0.3299453 0.7659024 -0.6006146 0.06977885 0.7964879 -0.5510944 -0.350529 0.7572479 -0.4275075 -0.6584591 0.6194101 -0.3175663 -0.7968138 0.5140421 -0.4264405 -0.6837828 0.5921061 -0.435447 -0.6745315 0.5961487 -0.4185961 -0.6980115 0.5809969 -0.435472 -0.6736394 0.5971383 -0.4413762 -0.6672188 0.6000051 -0.4310764 -0.6818138 0.5910187 -0.4323629 -0.6909925 0.5793028 -0.4654322 -0.6523965 0.5981236 -0.427536 -0.6992403 0.5729537 -0.4870152 -0.641047 0.5931904 -0.418877 -0.73606 0.5317499 -0.4435806 -0.7395732 0.5062289 -0.520619 -0.6676892 0.5321156 -0.4804638 -0.6830584 0.550078 -0.5874852 -0.6101406 0.5315915 -0.47705 -0.7347662 0.4822262 -0.6388691 -0.5794497 0.5060477 -0.5013876 -0.7461758 0.4379867 -0.6625918 -0.6000941 0.4481731 -0.5480266 -0.7270174 0.4136577 -0.6394019 -0.6735762 0.3707564 -0.6251831 -0.6623756 0.4128011 -0.6843119 -0.6298353 0.367457 -0.558288 -0.774856 0.2965005 -0.7749846 -0.3373579 0.5344048 -0.7749807 -0.3374281 0.5343662 -0.7750806 -0.3365845 0.534753 -0.7767177 -0.3292323 0.5369503 -0.7748128 -0.3379455 0.5342826 -0.6364991 0.6078829 0.4747078 -0.742711 0.4169235 0.5239803 -0.7931902 0.2745797 0.543558 0.7744818 -0.3391332 -0.5340099 0.2418428 0.9396937 -0.2418429 0.2418397 0.9396946 -0.2418422 0.2418518 0.9396918 -0.2418409 0.2418422 0.9396921 -0.2418497 0.2418434 0.9396928 -0.2418454 0.4354242 0.8288478 -0.3513076 0.4082998 0.8482341 -0.3373278 0.7750209 -0.337044 -0.5345503 0.7750254 -0.3370304 -0.5345523 0.7750344 -0.3369888 -0.5345656 0.7749938 -0.3372728 -0.5344452 0.7756307 -0.3318481 -0.5369114 0.7735033 -0.3491548 -0.5289459 0.7758593 -0.3337414 -0.5354056 0.7748533 -0.3377066 -0.5343748 0.7749186 -0.337449 -0.534443 0.7756248 -0.3345864 -0.5352179 0.774911 -0.3374897 -0.5344284 0.7749768 -0.3372165 -0.5345054 0.7755842 -0.3345925 -0.5352729 0.09085959 0.9878481 -0.1260979 0.08425539 0.991799 -0.09610271 0.1137393 0.9833955 -0.1414093 0.1006792 0.9913911 -0.08371067 0.1414517 0.9800168 -0.139851 0.1468393 0.9829597 -0.1105823 0.2418339 0.9396948 -0.2418472 0.1335268 0.9895601 -0.05423659 0.1609379 0.9788061 -0.1266397 0.2418463 0.9396933 -0.2418403 0.1838575 0.9769037 -0.1088839 0.2418582 0.9396898 -0.2418424 0.1776432 0.9831173 -0.04385495 0.2418425 0.9396933 -0.2418441 0.1908811 0.9741267 -0.1210023 0.2418355 0.9396939 -0.2418491 0.201812 0.9766641 -0.07347881 0.2418374 0.9396936 -0.2418482 0.2058069 0.9772479 -0.05128431 0.2088035 0.9735521 -0.09272336 0.2418501 0.9396927 -0.2418389 0.210459 0.9761474 -0.05332177 0.2418493 0.9396927 -0.2418398 0.208841 0.9767662 -0.04809653 0.2418417 0.9396925 -0.2418481 0.2052589 0.9769632 -0.05840849 0.2418424 0.9396924 -0.2418479 0.2086156 0.976858 -0.04720324 0.2418409 0.9396926 -0.2418486 0.1538051 0.9856095 0.07012754 0.2418466 0.9396923 -0.2418447 0.1795662 0.980499 -0.07985991 0.183136 0.9829764 -0.0147807 0.2418476 0.9396921 -0.2418436 0.1588782 0.9839124 -0.08169549 0.1043843 0.9932699 0.05018961 0.2418434 0.9396926 -0.2418465 0.1316646 0.9887765 -0.07060652 0.2418466 0.9396921 -0.2418449 0.2418428 0.9396925 -0.2418469 0.1374199 0.9852424 -0.1020451 0.1131951 0.9924955 -0.04625487 0.2418513 0.9396924 -0.2418388 0.1267386 0.9867632 -0.1011722 0.1064759 0.9918549 -0.06990647 0.2418418 0.9396932 -0.2418459 0.1202482 0.9876961 -0.09998351 0.2418494 0.9396923 -0.2418413 0.1125523 0.98961 -0.08946508 0.2418437 0.939693 -0.2418443 0.1166255 0.9880086 -0.1011804 0.1128817 0.98892 -0.09641087 0.241842 0.9396929 -0.2418465 0.1146619 0.9878588 -0.1048213 0.2418415 0.9396929 -0.2418469 0.1116476 0.9885843 -0.1011725 0.2418463 0.9396927 -0.2418429 0.1144317 0.987268 -0.1104866 0.1079984 0.9888044 -0.1029669 0.2418422 0.9396929 -0.241846 0.114403 0.9866007 -0.1163228 0.241846 0.9396927 -0.2418432 0.102971 0.9893196 -0.1031692 0.2418438 0.939693 -0.2418444 0.1120628 0.986455 -0.1197847 0.2418433 0.939693 -0.2418447 0.09932017 0.9895477 -0.104551 0.2418469 0.9396927 -0.2418422 0.10355 0.9876506 -0.1175738 0.2418442 0.939693 -0.2418439 0.1008685 0.9887387 -0.1105499 0.2418428 0.9396927 -0.2418463 0.1078478 0.986065 -0.1266676 0.2418443 0.9396926 -0.2418452 0.09474813 0.9890843 -0.1128494 0.1108463 0.9861168 -0.1236399 0.241846 0.9396927 -0.2418431 0.1061022 0.9858375 -0.1298722 0.2418437 0.939693 -0.2418443 0.2418454 0.939693 -0.2418428 0.09513324 0.9882642 -0.1195135 0.09868985 0.9879046 -0.1196019 0.2418457 0.9396922 -0.2418453 0.09561294 0.9874833 -0.1254386 0.2418448 0.9396924 -0.2418457 0.2418416 0.9396926 -0.2418481 0.09350669 0.9882677 -0.1207615 0.241845 0.9396926 -0.2418448 0.09361881 0.9874567 -0.1271401 0.2418433 0.9396929 -0.2418453 0.2418441 0.9396927 -0.2418449 0.2418499 0.9396924 -0.2418402 0.09181165 0.9880799 -0.1235679 0.1094155 0.98467 -0.1358427 0.2418456 0.9396927 -0.2418435 0.09529459 0.986869 -0.1304168 0.2418617 0.9396894 -0.2418405 0.2418321 0.9396944 -0.2418509 0.2418538 0.9396918 -0.2418388 0.2418416 0.9396923 -0.2418488 0.09094142 0.9877716 -0.1266365 0.09199935 0.9876865 -0.1265369 0.1060426 0.9849758 -0.1363001 0.2418448 0.9396924 -0.2418456 0.0901252 0.9878303 -0.1267623 0.241851 0.9396909 -0.2418453 0.2418385 0.9396933 -0.2418479 0.241841 0.939693 -0.241847 0.2418454 0.9396927 -0.2418437 0.09099066 0.9876466 -0.1275728 0.09261906 0.9873716 -0.1285257 0.241846 0.9396917 -0.2418466 0.08035838 0.9898514 -0.1172041 0.2418249 0.9396992 -0.2418389 0.2418492 0.9396911 -0.2418464 0.2418592 0.9396879 -0.241849 0.241838 0.9396943 -0.2418447 0.2418432 0.9396929 -0.2418455 0.24185 0.9396912 -0.241845 0.2418431 0.9396923 -0.2418475 0.2418434 0.9396923 -0.2418473 0.09208375 0.9875652 -0.1274186 0.09130239 0.9876331 -0.127455 0.08693879 0.9884093 -0.1244534 0.001102447 0.8454309 -0.5340838 0.1313142 0.8978497 -0.4202648 0.09781551 0.9867815 -0.1292062 0.07693564 0.990419 -0.1146784 0.04521548 0.8249483 -0.5633968 0.1555613 0.8015954 -0.5772741 0.04585123 0.8018015 -0.595829 0.2617343 0.7746824 -0.5756407 0.1993321 0.7479146 -0.6331591 0.3819063 0.7083334 -0.5936424 0.3379137 0.856144 -0.3909372 0.2296843 0.8583313 -0.4588164 0.3742145 0.8168144 -0.4390647 0.5058374 0.5887037 -0.6305207 0.3441833 0.8569123 -0.3837175 0.3576073 0.8375272 -0.4131166 0.3502692 0.8520663 -0.3889657 0.3649362 0.8376584 -0.4063864 0.3863452 0.8142448 -0.4332929 0.3489125 0.8555881 -0.382399 0.3521505 0.8510367 -0.3895211 0.3493815 0.8552066 -0.3828241 0.349107 0.8554605 -0.3825069 0.3513272 0.8533344 -0.385214 0.349195 0.8556106 -0.3820909 0.3495233 0.8550867 -0.3829624 0.3508425 0.8542094 -0.3837133 0.3569155 0.8484392 -0.3908482 0.349868 0.8560438 -0.3805015 0.3533635 0.8519149 -0.3864908 0.3535974 0.853021 -0.3838281 0.3718795 0.8352537 -0.4050393 0.3523014 0.8562358 -0.377815 0.3538553 0.8531492 -0.3833053 0.374891 0.8352984 -0.402161 0.3539707 0.8576818 -0.3729432 0.3615993 0.8482875 -0.3868518 0.3950152 0.8196357 -0.4149219 0.3602742 0.8564922 -0.3696264 0.3610642 0.8525054 -0.3779777 0.353884 0.8647761 -0.35627 0.3898105 0.830067 -0.3987939 0.3661258 0.8579678 -0.3603376 0.3971924 0.8296702 -0.3922825 0.3844641 0.8474075 -0.3661801 0.3669567 0.8655807 -0.3407534 0.3891111 0.8436264 -0.3699827 0.3635449 0.8717504 -0.3284603 0.4246823 0.820792 -0.3820283 0.3775594 0.8658493 -0.3282591 0.4639046 0.7960547 -0.388702 -0.2418702 -0.9397011 0.2417858 -0.1624438 -0.984514 0.06591224 -0.2418442 -0.9396915 0.2418496 -0.2418454 -0.9396915 0.241849 0.2538747 -0.8489086 -0.4635751 -0.1330454 -0.9873946 0.08573639 -0.2418284 -0.9396909 0.2418677 -0.1883323 -0.9740439 -0.1255766 -0.09964144 -0.9297651 -0.3544131 -0.08077007 -0.9851523 -0.1514958 -0.2418227 -0.93969 0.2418772 -0.2944968 -0.9471466 -0.1272198 -0.2379935 -0.951318 -0.19584 -0.242026 -0.9397143 0.2415795 -0.4173219 -0.893982 -0.1632137 -0.3468375 -0.9340861 0.08477616 -0.3848441 -0.9141065 -0.1276882 -0.4418514 -0.8925779 -0.08984446 -0.4941158 -0.8381208 -0.2310912 -0.3891066 -0.8506118 0.353632 -0.377268 -0.8590922 0.3458749 -0.2418463 -0.9396916 0.241847 -0.3892112 -0.8507496 0.3531848 -0.2418481 -0.9396919 0.2418441 -0.388776 -0.8513128 0.3523066 -0.2418461 -0.9396917 0.2418472 -0.3884216 -0.8513885 0.3525142 -0.2418453 -0.939692 0.2418465 -0.3847221 -0.8546816 0.3485803 -0.2418462 -0.9396921 0.2418452 -0.3843793 -0.8548499 0.3485457 -0.241844 -0.9396928 0.241845 -0.3826948 -0.8565261 0.3462771 -0.2418441 -0.9396928 0.2418448 -0.2418397 -0.9396927 0.2418496 -0.3816472 -0.857144 0.3459039 -0.2418457 -0.9396922 0.2418453 -0.3837153 -0.855804 0.3469325 -0.2418482 -0.9396927 0.2418408 -0.3830835 -0.8562113 0.3466256 -0.2418465 -0.9396923 0.2418442 -0.3834413 -0.8558204 0.3471946 -0.2418457 -0.9396923 0.2418453 -0.3846268 -0.8550676 0.3477379 -0.2418491 -0.9396929 0.2418395 -0.3822203 -0.8566431 0.3465112 -0.2418426 -0.9396926 0.2418469 -0.3831429 -0.8560614 0.34693 -0.2418404 -0.9396926 0.2418491 -0.382234 -0.8562738 0.3474078 -0.2418431 -0.939693 0.2418448 -0.2418473 -0.939693 0.2418406 -0.384373 -0.854894 0.3484446 -0.2418453 -0.9396932 0.2418421 -0.381312 -0.8565656 0.3477019 -0.2418411 -0.9396926 0.2418484 -0.3842228 -0.854631 0.3492545 -0.2418448 -0.9396933 0.2418423 -0.380789 -0.8565189 0.3483895 -0.2418443 -0.9396931 0.2418431 -0.3837498 -0.8544883 0.3501225 -0.2418394 -0.9396932 0.2418479 -0.3808948 -0.8558767 0.3498491 -0.383417 -0.8540946 0.3514453 -0.2418485 -0.9396924 0.2418419 -0.3815521 -0.8547609 0.3518546 -0.2418497 -0.9396923 0.2418406 -0.2418443 -0.9396929 0.2418442 -0.3743395 -0.8586766 0.3500635 -0.2418429 -0.9396922 0.2418479 -0.2418449 -0.9396924 0.241845 -0.3819605 -0.8544258 0.3522254 -0.241845 -0.9396924 0.2418451 -0.3635547 -0.8641644 0.3479194 -0.2418472 -0.9396927 0.2418418 -0.344702 -0.8807696 0.3246932 -0.3692281 -0.8622596 0.3466684 -0.3808265 -0.8520596 0.3591179 -0.2418419 -0.9396929 0.2418469 -0.3633502 -0.8614704 0.3547468 -0.2418417 -0.9396928 0.2418472 -0.3591254 -0.8676798 0.3437451 -0.3770655 -0.8521111 0.3629438 -0.2418497 -0.9396926 0.2418399 -0.3585729 -0.862466 0.3571804 -0.2418457 -0.9396924 0.2418446 -0.3598859 -0.8643611 0.3512292 -0.374307 -0.850689 0.3690834 -0.2418429 -0.939693 0.2418451 -0.3633856 -0.8555148 0.3688434 -0.2418438 -0.939693 0.2418439 -0.3672755 -0.8546134 0.3670756 -0.2418428 -0.9396922 0.2418487 -0.3563072 -0.8589714 0.3677138 -0.2418452 -0.9396929 0.2418431 -0.3589269 -0.8596053 0.3636626 -0.3654925 -0.851383 0.3762475 -0.2418496 -0.939693 0.2418384 -0.3555194 -0.857219 0.372534 -0.3629978 -0.8509021 0.3797345 -0.2418383 -0.9396927 0.2418504 -0.3590078 -0.8515166 0.3821426 -0.2418497 -0.9396938 0.2418351 -0.3500919 -0.856951 0.378247 -0.2418449 -0.9396924 0.2418452 -0.3570124 -0.8535878 0.379381 -0.2418352 -0.9396919 0.2418574 -0.3367247 -0.8639882 0.3743538 -0.3641579 -0.8408657 0.400417 -0.2418497 -0.9396924 0.2418407 -0.3736145 -0.8056271 0.4597579 -0.2418438 -0.939692 0.2418475 -0.3189594 -0.8607041 0.3968037 -0.2418447 -0.9396924 0.2418451 -0.3417663 -0.850611 0.3995706 -0.2418488 -0.9396934 0.2418376 -0.4128337 -0.4903714 0.7675313 -0.241846 -0.939693 0.241842 -0.2849555 -0.863294 0.416562 -0.3135325 -0.8572885 0.4083548 -0.241838 -0.9396926 0.2418516 -0.2664217 -0.8749295 0.4043735 -0.2936209 -0.8182377 0.4942407 -0.2418454 -0.9396929 0.2418431 -0.2656987 -0.8633146 0.4290594 -0.2418445 -0.9396923 0.2418463 -0.2654007 -0.8641482 0.4275632 -0.241844 -0.9396926 0.2418462 -0.2712581 -0.8761258 0.3985257 -0.2418533 -0.9396932 0.2418337 -0.2993077 -0.8496869 0.4341048 -0.2712715 -0.8760533 0.3986757 -0.2418406 -0.9396895 0.2418611 -0.2822679 -0.9011011 0.3291527 -0.2418398 -0.9396941 0.2418437 -0.2418435 -0.9396951 0.2418363 -0.3376101 -0.8542668 0.3952816 -0.3055455 -0.8626691 0.4030435 -0.2418395 -0.9396944 0.241843 -0.374599 -0.8340037 0.4051092 -0.3146519 -0.883288 0.347558 -0.2418473 -0.9396919 0.2418448 -0.3771746 -0.8480428 0.3722402 -0.2418445 -0.9396935 0.2418415 -0.3412139 -0.8752173 0.3428816 -0.2418505 -0.93969 0.2418491 -0.372888 -0.8625758 0.3419319 -0.3822672 -0.8551709 0.3500778 0.7753347 -0.3358262 -0.5348616 0.774941 -0.3373355 -0.5344823 0.7757586 -0.3342694 -0.535222 0.7749145 -0.3374437 -0.5344523 0.7750372 -0.3369759 -0.5345695 0.7752273 -0.336243 -0.5347554 -0.004649281 -0.9950811 0.09895515 0.7751595 -0.3365342 -0.5346704 -0.0985167 -0.9843022 0.1464362 -0.05173695 -0.9902785 0.1291199 -0.1205421 -0.9810861 0.1514587 -0.01715791 -0.9960951 0.08660328 -0.129029 -0.9805797 0.1476987 -0.02576202 -0.9970792 0.07189899 -0.1295989 -0.9819269 0.1379267 -0.04231464 -0.9969128 0.06613755 -0.1262645 -0.9840466 0.1253382 -0.0583353 -0.9962669 0.0636326 -0.1188678 -0.9868442 0.1095852 -0.07804411 -0.994561 0.06897509 -0.1056677 -0.9904871 0.08814597 -0.1236941 -0.9869203 0.1033831 -0.1006728 -0.9915161 0.08222383 -0.08943545 -0.9942746 0.058474 -0.1226246 -0.9878888 0.09507399 -0.1177812 -0.9886091 0.09369927 -0.101659 -0.9925757 0.06677502 -0.1246711 -0.9877687 0.09364873 -0.1202094 -0.98859 0.09077256 -0.1183313 -0.9893719 0.08450472 -0.1250826 -0.9878451 0.09228497 -0.120188 -0.9889314 0.08700281 -0.1249219 -0.9879268 0.09162461 -0.1238743 -0.9881985 0.0901044 -0.1236764 -0.9882479 0.08983409 -0.1253885 -0.9878793 0.09149992 -0.1250516 -0.987906 0.09167259 -0.1171557 -0.9899488 0.07922196 -0.07443994 -0.9970198 0.02025175 -0.1311022 -0.9872211 0.09058976 -0.1220973 -0.9888774 0.08493375 -0.1076312 -0.9928228 0.05213725 -0.8001288 0.2260873 0.5555884 -0.7750088 0.337105 0.5345293 -0.7750142 0.3370919 0.5345298 -0.807309 0.1473407 0.5714393 -0.7549679 0.4057631 0.5151504 -0.7482087 0.3393563 0.5701062 -0.7435331 0.3569467 0.5654622 -0.6811331 0.5157226 0.5196999 -0.7434456 0.3493049 0.5703285 -0.7788396 0.1499868 0.6090262 -0.7434649 0.3400247 0.5758848 -0.6808673 0.5191635 0.516613 -0.7436648 0.3396417 0.5758525 -0.5809883 -0.05936157 -0.8117444 -0.5214936 0.128147 -0.8435775 -0.7458481 0.3391978 0.5732849 -0.6829317 0.5192383 0.5138052 -0.6874391 0.5061846 0.5207732 -0.7477314 0.338915 0.5709943 -0.6891072 0.5093085 0.5154961 -0.7459103 0.3399822 0.572739 -0.7492985 0.3387392 0.5690408 -0.6867122 0.5180011 0.5100012 -0.7478526 0.339881 0.5702608 -0.6885561 0.5104408 0.5151123 -0.7504976 0.3387625 0.5674445 -0.6933224 0.5057217 0.5133709 -0.749484 0.3397401 0.5681992 -0.751582 0.3386685 0.5660637 -0.6898263 0.515947 0.5078763 -0.7507264 0.3396239 0.5666264 -0.6889426 0.5148442 0.5101897 -0.7523379 0.3387926 0.5649844 -0.6901298 0.5169651 0.5064266 -0.7516941 0.3393308 0.565518 -0.6917336 0.5121522 0.5091215 -0.7527102 0.3389146 0.5644149 -0.6912176 0.5154136 0.5065246 -0.7523689 0.3390875 0.5647661 -0.6917499 0.514047 0.5071862 -0.7527634 0.3389739 0.5643084 -0.6912994 0.5153787 0.5064483 -0.7527153 0.3390008 0.5643564 -0.75248 0.3390675 0.5646299 -0.6912996 0.5148182 0.5070179 -0.7527576 0.3388983 0.5643615 -0.6907451 0.5164761 0.5060865 -0.7518695 0.3391879 0.5653706 -0.688694 0.5193623 0.5059284 -0.7524548 0.3388015 0.5648233 -0.7509875 0.3394221 0.5664013 -0.6900475 0.5145878 0.5089539 -0.751828 0.33883 0.5656403 -0.6901665 0.5163693 0.5069842 -0.7498282 0.3395711 0.5678461 -0.6891332 0.5142067 0.5105752 -0.7508991 0.3387818 0.5669016 -0.6864352 0.5215061 0.506792 -0.7484318 0.3397312 0.5695898 -0.6858888 0.5185192 0.5105826 -0.7496992 0.3387716 0.5684936 -0.7467465 0.3400463 0.5716103 -0.6869592 0.5126544 0.5150462 -0.7481923 0.3384245 0.5706814 -0.6836637 0.5228985 0.5090983 -0.7449395 0.3401488 0.5739024 -0.6798068 0.5247027 0.512396 -0.7461434 0.3384884 0.5733198 -0.7429311 0.340008 0.5765829 -0.6830977 0.5130013 0.5198147 -0.7437426 0.3387356 0.5762858 -0.6807892 0.5227522 0.513085 -0.7401334 0.3408681 0.579665 -0.6800292 0.5142874 0.5225598 -0.7410384 0.3393242 0.5794146 -0.674565 0.5282356 0.5156832 -0.7367398 0.3414221 0.5836484 -0.6748386 0.5188626 0.5247613 -0.7382974 0.3390903 0.5830391 -0.7331529 0.3415548 0.5880706 -0.6754986 0.5095602 0.5329635 -0.7351332 0.3384915 0.5873694 -0.6696294 0.5291203 0.5211797 -0.7293089 0.3416544 0.5927739 -0.6691035 0.5156758 0.535144 -0.7310804 0.3388711 0.5921891 -0.6619313 0.5341623 0.5258495 -0.7252524 0.3417446 0.5976786 -0.6638934 0.5185878 0.5388063 -0.7268323 0.3392688 0.5971696 -0.7208954 0.3419626 0.602803 -0.663662 0.5095671 0.5476261 -0.7224528 0.3395583 0.6022974 -0.6547361 0.53628 0.532658 -0.7169411 0.340061 0.6085671 -0.6476526 0.5356909 0.5418317 -0.7172745 0.3394524 0.6085142 -0.7117973 0.3419309 0.6135371 -0.6542546 0.5107803 0.5577225 -0.6501165 0.5308594 0.5436331 -0.7067581 0.3430646 0.618708 -0.6300861 0.5536032 0.5445319 -0.7113509 0.3388041 0.6157854 -0.6937159 0.3549461 0.6267148 -0.6415793 0.5069096 0.5756897 -0.6957804 0.3505064 0.6269249 -0.7051182 0.3387262 0.6229549 -0.6451036 0.5241426 0.5559818 -0.6779742 0.3553609 0.6434824 -0.6455374 0.4577912 0.6113171 -0.685125 0.3430848 0.6425702 -0.6920383 0.3407313 0.6363844 -0.6712213 0.4348477 0.6003077 -0.6152051 0.5480301 0.5667325 -0.6622742 0.3539145 0.6604071 -0.6147043 0.496522 0.6128658 -0.6775076 0.3252331 0.6597022 -0.6109943 0.5334396 0.5849172 -0.6465802 0.3517834 0.6768919 -0.6051929 0.4799118 0.6351584 -0.6585999 0.3295289 0.6765035 -0.6145811 0.4968001 0.6127641 -0.5851197 0.5354105 0.6090736 -0.6310821 0.3500691 0.6922334 -0.5890327 0.4808595 0.6494725 -0.6412606 0.3325954 0.6914949 -0.564777 0.549435 0.61575 -0.6163343 0.3483968 0.7062235 -0.5695381 0.4923577 0.6581871 -0.6256268 0.3344149 0.7048105 -0.5481653 0.5528368 0.6276037 -0.6019791 0.3475472 0.7189103 -0.550248 0.5046266 0.6652662 -0.6117269 0.335641 0.7163347 -0.5349928 0.5469511 0.6439157 -0.5778911 0.3525186 0.736052 -0.515512 0.534206 0.6699786 -0.5984879 0.3343985 0.728004 -0.532015 0.351071 0.7705253 -0.4998592 0.4559313 0.7363881 -0.5740017 0.3299902 0.7494188 -0.4984011 0.5680464 0.6549196 -0.4637171 0.3429167 0.8169299 -0.4538533 0.3786234 0.8066359 -0.46692 0.3384383 0.8169733 -0.5291057 0.3308813 0.7813864 -0.3658579 0.695329 0.6185997 -0.3683072 0.3477143 0.8622322 -0.1943842 0.763341 0.6160562 -0.401408 0.3140147 0.8603874 -0.2632948 0.3300632 0.9064955 -0.2402545 0.4110319 0.8793922 -0.3178361 0.2877443 0.9034287 -0.2838804 0.621034 0.7305674 -0.1877079 0.2971811 0.9361886 0.01389795 0.8325659 0.5537517 -0.218128 0.2691164 0.9380813 -0.151254 0.2726161 0.9501593 -0.1020117 0.4494543 0.8874595 -0.1490122 0.2756754 0.9496307 -0.1530804 0.5230383 0.8384494 -0.1371964 0.2796085 0.9502611 -0.0673862 0.5211963 0.8507723 -0.1491779 0.2882962 0.9458495 -0.09425866 0.4807949 0.871752 -0.1468268 0.2909508 0.9454044 -0.09259808 0.4572265 0.8845166 -0.1927943 0.284079 0.9392175 -0.1937857 0.2801887 0.9401816 -0.2641544 0.2858001 0.9211627 -0.1811158 0.5554491 0.811587 -0.2067067 0.3170704 0.9256018 -0.1952975 0.2755869 0.9412283 -0.3574551 0.2979372 0.8851323 -0.3839784 0.1773018 0.9061593 -0.3051925 0.3368313 0.8907312 -0.4543205 0.3108138 0.8348579 -0.3536739 0.6019904 0.7159066 -0.4148306 0.3477885 0.8408083 -0.4045345 0.09458982 0.9096179 -0.5430446 0.3197147 0.7764567 -0.561109 0.2364161 0.7932617 -0.5118325 0.3564035 0.7816674 -0.6220223 0.3267385 0.7115689 -0.5116023 0.6182709 0.596661 -0.5989754 0.3601843 0.7151893 -0.5525378 0.2695445 0.7887 -0.6900845 0.3330642 0.6425353 -0.585445 0.604671 0.5400251 -0.675955 0.3578664 0.6442178 -0.6832199 0.2252932 0.6945887 -0.7203342 0.07285064 0.6897909 -0.7621912 0.2469769 0.598387 -0.6504104 -0.002648651 0.7595785 -0.6333522 0.4280107 0.6447263 -0.4173574 0.6094627 0.6740683 -0.4681147 0.07725703 0.880284 -0.5550867 0.2572535 0.7910116 -0.1033505 0.8144342 0.5709776 -0.256727 0.1003352 0.9612617 -0.3963963 0.1438007 0.9067476 -0.2064496 0.03011745 0.9779936 -0.1793899 0.3365968 0.9244035 -0.1815208 0.1400029 0.9733701 -0.1898608 0.07612705 0.9788552 -0.2766356 -0.01361316 0.9608786 -0.3271088 0.2488992 0.9116189 -0.3028249 -0.1326726 0.9437665 -0.4664496 -0.231327 0.8537638 -0.4918367 0.229459 0.8399079 -0.4542282 -0.1001597 0.8852372 -0.5785105 -0.1663569 0.7985305 -0.6064526 0.1599768 0.7788597 -0.5526071 0.12523 0.8239799 -0.6281399 0.1843084 0.7559568 -0.6249369 0.04616814 0.7793089 -0.6437678 0.1673912 0.7466882 -0.6465478 0.1058094 0.7555 -0.6582407 0.1581541 0.736007 -0.6600282 0.1307359 0.7397776 -0.6714076 0.171939 0.7208666 -0.6734517 0.1454069 0.7247894 -0.6824221 0.2099456 0.7001593 -0.6885128 0.1352167 0.7125073 -0.6953355 0.2394313 0.6776291 -0.7033449 0.1143937 0.7015839 -0.7186036 0.1598314 0.6768034 -0.71318 0.13879 0.6871037 -0.7251013 0.157217 0.6704558 -0.7260274 0.1176386 0.6775287 -0.7323797 0.1466543 0.6649155 -0.7365025 0.1662327 0.655691 -0.7354264 0.1253007 0.6659186 -0.7434363 0.1593011 0.649558 -0.7446326 0.1235907 0.6559327 -0.751187 0.1415812 0.6447269 -0.7547866 0.1574876 0.6367847 -0.7513888 0.1400436 0.6448276 -0.7590615 0.1573238 0.6317237 -0.7596976 0.1273826 0.637678 -0.7646026 0.1422266 0.6286131 -0.7669575 0.1585839 0.6217936 -0.7652046 0.1376254 0.6289048 -0.7707084 0.1539137 0.6183196 -0.7711039 0.1324847 0.6227734 -0.7742593 0.145664 0.615877 -0.7758142 0.1559934 0.611374 -0.7752687 0.1381821 0.6163313 -0.7786412 0.1507188 0.6090992 -0.7790808 0.138316 0.6114751 -0.7808277 0.1488754 0.6067489 -0.7820668 0.1525744 0.6042289 -0.7817369 0.1421796 0.607184 -0.7842884 0.1411402 0.6041285 -0.7844145 0.150249 0.6017633 -0.7834308 0.1480634 0.6035839 -0.7849919 0.1506408 0.6009119 -0.7850518 0.1459861 0.6019816 -0.7855144 0.148504 0.6007608 -0.7854192 0.1493638 0.6006723 -0.7854098 0.1493151 0.6006968 -0.7851708 0.148565 0.6011949 -0.7851284 0.1512778 0.6005735 -0.7842965 0.1514489 0.6016165 -0.7837882 0.1473414 0.6032963 -0.784084 0.1529911 0.6015031 -0.7823992 0.1493923 0.6045936 -0.78211 0.1566657 0.603125 -0.7806932 0.1506954 0.6064727 -0.7793369 0.1447372 0.6096598 -0.7794846 0.1589345 0.6059236 -0.7768821 0.1463137 0.6124104 -0.7762618 0.1604821 0.6096417 -0.5809895 -0.05942696 -0.8117387 -0.6293047 -0.414499 -0.6573935 -0.6000389 -0.2478088 -0.7606208 -0.4163793 -0.1246583 -0.9006046 -0.2947772 0.2381011 -0.9254266 -0.2947765 0.2381651 -0.9254103 -0.4443839 0.3048889 -0.8423573 -0.3120762 0.4890401 -0.8145233 -0.4141296 0.3382567 -0.845032 -0.416413 -0.1245962 -0.9005976 -0.4768193 -0.4690229 -0.7434117 0.3328491 -0.3144636 -0.8890019 0.3729079 -0.1292387 -0.9188237 0.3328592 -0.3144785 -0.8889928 0.5158253 -0.3356397 -0.788207 0.5143643 0.5128694 -0.6873096 0.5707623 -0.1477563 -0.8077119 -0.04531443 -0.2380388 -0.970198 0.04902321 0.1330854 -0.9898914 -0.04530447 -0.2380539 -0.9701948 0.3389726 0.2530035 -0.9061385 0.3993485 0.06230902 -0.9146794 0.04903674 0.1329997 -0.9899023 -0.1329571 -0.5741046 -0.8079149 -0.4768175 -0.4690287 -0.7434092 0.2173953 -0.6449314 -0.7326682 -0.1329544 -0.5741161 -0.8079071 0.5162769 -0.3430914 -0.7846951 0.4612455 -0.5121396 -0.7245451 0.2056921 -0.4726545 -0.8569063 0.832031 -0.3379339 -0.439915 0.8613065 -0.1839687 -0.4736102 0.8335405 -0.3287854 -0.443971 0.8158527 -0.3236566 -0.479198 0.8345168 -0.2321403 -0.4996926 0.8654123 -0.02553105 -0.5004095 0.831529 0.2025079 -0.5172524 0.7943475 -0.3170082 -0.5181871 0.8254261 -0.009318232 -0.5644333 0.8055652 -0.3513065 -0.4771253 0.7700693 -0.3084146 -0.5584567 0.7713364 -0.3028223 -0.5597667 0.7750278 -0.3676224 -0.5139899 0.8188509 0.07235687 -0.5694275 0.7429327 -0.3021368 -0.5972976 0.7301677 -0.3539724 -0.5844303 0.7400301 -0.3841741 -0.5520559 0.7750735 0.1507337 -0.6136289 0.7131039 -0.3072699 -0.6301333 0.720145 -0.2742356 -0.6373273 0.7046951 -0.3918817 -0.5914674 0.74804 0.103545 -0.6555262 0.6829434 -0.3248417 -0.6542677 0.720445 0.001674652 -0.6935101 0.6758772 -0.3807135 -0.6310684 0.656574 -0.3426179 -0.6719549 0.6852976 -0.1991372 -0.7005081 0.6542082 -0.3597954 -0.6652511 0.7201212 -0.07533943 -0.689746 0.6388784 -0.341402 -0.6894049 0.6646676 -0.21753 -0.7147711 0.6928284 0.04374533 -0.7197745 0.6260491 -0.3343304 -0.7044755 0.6680207 -0.04399496 -0.742841 0.6342353 -0.3527499 -0.6879775 0.6143087 -0.3338344 -0.7149682 0.6426205 -0.1907607 -0.7420575 0.617173 -0.3531516 -0.7031226 0.6682209 -0.03247243 -0.7432539 0.6042352 -0.3358365 -0.7225743 0.6477083 -0.04392319 -0.7606213 0.6048793 -0.3500505 -0.7152521 0.59588 -0.3385044 -0.7282457 0.6284438 -0.1712237 -0.7587759 0.5958324 -0.3460417 -0.7247337 0.6473148 -0.0566008 -0.7601184 0.5891886 -0.3408068 -0.7326032 0.6296223 -0.1102764 -0.769035 0.5891332 -0.3423342 -0.7319354 0.5847555 -0.3396177 -0.7366958 0.6326668 0.03569418 -0.7736011 0.5813366 -0.3387953 -0.7397739 0.6165566 -0.1541235 -0.7720777 0.5835745 -0.3418381 -0.7366055 0.6256024 -0.1357836 -0.7682347 0.5786607 -0.338823 -0.7418562 0.6189015 -0.1109909 -0.7775873 0.5796142 -0.3414509 -0.7399045 0.5766645 -0.3391415 -0.7432638 0.6221398 -0.04867357 -0.7813917 0.5770122 -0.3407198 -0.7422715 0.5752671 -0.3394598 -0.7442008 0.6111016 -0.151812 -0.7768579 0.5753521 -0.3400743 -0.7438544 0.6163592 -0.1331258 -0.7761307 0.574377 -0.3395925 -0.7448275 0.6111835 -0.1445103 -0.7781847 0.5743819 -0.3396537 -0.7447958 0.5739875 -0.3394476 -0.7451939 0.611918 -0.1349672 -0.7793205 0.5738849 -0.3395391 -0.745231 0.6121699 -0.1321519 -0.779605 0.5739058 -0.3395637 -0.7452037 0.5737412 -0.3391734 -0.7455083 0.6095216 -0.1519701 -0.7780671 0.5738893 -0.3395339 -0.7452301 0.6104546 -0.1490658 -0.7778976 0.5719605 -0.3386572 -0.7471094 0.6097487 -0.1350075 -0.7810119 0.5723474 -0.340393 -0.7460234 0.5679646 -0.3390997 -0.7499518 0.6139168 -0.04841864 -0.7878844 0.5681376 -0.3405099 -0.7491815 0.5616267 -0.3411398 -0.7537898 0.6100168 0.1405359 -0.7798264 0.5614922 -0.3389579 -0.7548735 0.5551776 -0.3365804 -0.7605863 0.5894593 -0.1617611 -0.7914361 0.6090871 -0.1023968 -0.7864654 0.545929 -0.3342452 -0.7682721 0.5895617 -0.07744055 -0.8040025 0.5505174 -0.3425198 -0.7613217 0.533537 -0.3327003 -0.7775917 0.5823327 0.1730331 -0.7943226 0.5361492 -0.3439561 -0.7708685 0.3258192 -0.7867177 -0.5243253 0.4971213 -0.5068409 -0.7042604 0.3812766 -0.7031954 -0.6001205 0.5005435 -0.5229969 -0.6898772 0.4590655 -0.6260944 -0.6302893 0.4044948 -0.7231003 -0.5599197 0.5160303 -0.5154646 -0.6841118 0.5038654 -0.5294114 -0.6825271 0.5159276 -0.5157776 -0.6839534 0.5108927 -0.5291165 -0.6775133 0.5183548 -0.5136441 -0.6837238 0.5139943 -0.5212286 -0.6812713 0.5129492 -0.5310253 -0.6744592 0.4834423 -0.6007812 -0.6366676 0.5276238 -0.5119487 -0.6778803 0.5169318 -0.5239086 -0.6769796 0.4854941 -0.6151029 -0.6212438 0.5462962 -0.4982924 -0.6732497 0.5161995 -0.5480983 -0.6581234 0.5505809 -0.5124653 -0.658969 0.4968665 -0.6185714 -0.6086815 0.5586218 -0.5241583 -0.6428062 0.6127147 -0.4250911 -0.6662419 0.505223 -0.6394976 -0.5794762 0.6425075 -0.4001024 -0.6535306 0.5081061 -0.6749449 -0.5350493 0.6708706 -0.3974012 -0.626103 0.545842 -0.6598109 -0.516436 0.6987579 -0.4107477 -0.5856822 0.588455 -0.6417667 -0.4917888 0.6288173 -0.6331033 -0.4514079 0.7252507 -0.5044185 -0.4685867 0.6847296 -0.5255771 -0.5048902 0.8020256 -0.3638134 -0.4737033 0.607182 -0.7077497 -0.3611376 0.7817578 -0.4803797 -0.3976053 0.5850272 -0.7648419 -0.2697406 0.7752413 -0.3385891 -0.5332524 0.7749381 -0.3373531 -0.5344753 0.6310431 -0.7143695 -0.3024252 0.7779223 -0.3221315 -0.5395073 0.7750231 -0.3370401 -0.5345496 0.3715513 -0.9190414 -0.1315773 0.481154 -0.8524054 -0.2046843 0.1763154 -0.9842502 -0.01282328 0.5914576 0.6802078 -0.4330072 0.6687068 0.5787769 -0.4667426 0.6014651 0.668111 -0.4380269 0.7598288 0.4129384 -0.5021376 0.8048816 0.2916005 -0.5168509 0.830303 0.2035245 -0.5188206 0.7884907 0.3408843 -0.5119378 0.8564535 0.03690826 -0.5149029 0.4975016 0.594021 -0.6321638 0.3872487 0.5994986 -0.7004569 0.5146062 0.5964593 -0.6159681 0.5003204 0.5870367 -0.636449 0.5199608 0.5929508 -0.6148577 0.5180104 0.5887401 -0.6205243 0.5210181 0.5950877 -0.6118912 0.5205045 0.5917379 -0.6155659 0.5242177 0.5989251 -0.6053797 0.5242767 0.5878666 -0.6160737 0.5295125 0.6042212 -0.5954269 0.5319214 0.5821754 -0.614924 0.5368115 0.610691 -0.5821424 0.543676 0.574321 -0.6120226 0.5457177 0.6184542 -0.5654261 0.5595464 0.5645106 -0.6068243 0.5559622 0.62724 -0.5454136 0.5797262 0.5524514 -0.5989282 0.5670882 0.6369159 -0.522254 0.6040861 0.5384497 -0.5874963 0.5786883 0.6471337 -0.4963244 0.6322824 0.5228933 -0.5716656 0.5902917 0.6576326 -0.4680544 0.6635245 0.506596 -0.5505413 0.6963881 0.4910869 -0.5233328 0.5782144 0.2412777 -0.7793928 0.6056594 0.2435326 -0.7575412 0.5790834 0.2336766 -0.781062 0.6117949 0.2397193 -0.753818 0.6067743 0.2353047 -0.7592475 0.6147186 0.2420762 -0.7506798 0.6120101 0.2381744 -0.7541329 0.621904 0.2467305 -0.743209 0.6158608 0.2339811 -0.7523087 0.6333398 0.2526809 -0.7314596 0.624759 0.2271794 -0.7470381 0.6487296 0.2602882 -0.7151222 0.6386658 0.2180318 -0.7379486 0.6675211 0.2703863 -0.6937627 0.6574303 0.2073591 -0.7244222 0.6893301 0.2819002 -0.6673502 0.6810517 0.1942452 -0.7060009 0.7132849 0.2952133 -0.635668 0.7090983 0.1795348 -0.6818702 0.7384576 0.309902 -0.5988665 0.7409164 0.1638395 -0.6513059 0.7638485 0.3253915 -0.5573651 0.7754694 0.1480352 -0.6137856 0.8113403 0.1333839 -0.5691535 -0.0862475 0.7767693 -0.6238515 -0.2095886 0.6579052 -0.7233487 -0.1684803 0.9819237 0.08625698 -0.2136795 0.9696821 0.1185653 -0.3162002 0.9266514 0.2033092 -0.4517868 0.8328701 0.3197124 -0.4857692 0.8032984 0.3445868 -0.5776566 0.6977522 0.4236209 -0.4835944 0.8037568 0.3465712 -0.4829929 0.8043099 0.3461263 -0.2119669 0.969842 0.1203183 -0.2114101 0.9700137 0.1199131 -0.486926 0.8044996 0.3401227 -0.4891345 0.8041989 0.3376558 -0.4882246 0.8033114 0.3410682 -0.4908308 0.8038079 0.3361218 -0.4901963 0.8032287 0.3384246 -0.4916765 0.803662 0.3352336 -0.4913217 0.8033598 0.3364759 -0.4918838 0.8035313 0.3352427 -0.4918495 0.8035042 0.3353582 -0.4914495 0.8034591 0.3360519 -0.4917337 0.8036683 0.3351347 -0.4903213 0.8034481 0.3377221 -0.4909749 0.8038921 0.3357097 -0.4887016 0.8033328 0.340334 -0.4897367 0.8039821 0.3372989 -0.4861489 0.803484 0.3436169 -0.4876114 0.8043304 0.3395406 -0.4830244 0.8035691 0.3477991 -0.4849413 0.8045912 0.3427315 -0.4791237 0.8037464 0.3527498 -0.4815397 0.8049337 0.3467004 -0.474566 0.8038787 0.3585614 -0.4775266 0.8052189 0.3515549 -0.4692742 0.804021 0.3651467 -0.4728154 0.8054993 0.3572346 -0.463081 0.8042913 0.3723865 -0.4672546 0.8058988 0.3635934 -0.456085 0.8045783 0.3803161 -0.4609271 0.8063039 0.3707025 -0.448398 0.8047277 0.3890407 -0.4539733 0.806563 0.3786349 -0.4397576 0.8049711 0.3982897 -0.4460982 0.8069036 0.3871728 -0.4304928 0.8049774 0.4082736 -0.4376316 0.8069983 0.3965253 -0.4202551 0.8050224 0.4187179 -0.4282483 0.8071361 0.4063676 -0.4092297 0.8049392 0.4296557 -0.4180881 0.8071269 0.4168316 -0.3971941 0.8049328 0.4408176 -0.4069408 0.8071853 0.4276108 -0.3844522 0.8046318 0.4525086 -0.3951529 0.8069591 0.4389432 -0.3710671 0.8042333 0.4642394 -0.3825081 0.8065872 0.4506711 -0.3492024 0.8022928 0.4841321 -0.3690725 0.806267 0.4622974 -0.2956322 0.7962302 0.5278438 -0.3453127 0.8063576 0.4801527 -0.1935649 0.7828949 0.5912769 -0.288595 0.8040906 0.5197606 -0.0529856 0.7614542 0.6460496 -0.1849905 0.7939346 0.5791773 0.01562982 0.7541562 0.6565092 -0.04749119 0.7704039 0.6357849 -0.02407979 0.7652106 0.6433295 0.01618742 0.7551885 0.6553078 -0.1628475 0.7881706 0.5935215 -0.02706575 0.7601424 0.6491926 -0.3113043 0.8031243 0.5080167 -0.1677069 0.7816962 0.6006876 -0.4131739 0.8066076 0.4226958 -0.3144534 0.7996933 0.5114779 -0.4148012 0.8050175 0.4241306 -0.2135781 0.9700756 0.1154892 -0.2152652 0.9698757 0.1140261 -0.2153246 0.9695403 0.1167337 -0.2163119 0.9697668 0.1129665 -0.2163295 0.9695501 0.1147791 -0.2170634 0.9696478 0.1125456 -0.2170593 0.9695383 0.113493 -0.2172539 0.9695976 0.112611 -0.2172525 0.9695901 0.1126784 -0.2171007 0.9695535 0.1132847 -0.2171288 0.9696359 0.1125231 -0.2164618 0.9695539 0.1144969 -0.2165504 0.9697216 0.1128971 -0.2153469 0.969594 0.1162466 -0.2155294 0.9698392 0.1138371 -0.2137794 0.9696605 0.1185625 -0.2140933 0.9699782 0.1153533 -0.2117344 0.9697564 0.1214134 -0.2122176 0.97014 0.1174393 -0.2091634 0.969889 0.1247636 -0.2098577 0.9703341 0.1200479 -0.206188 0.9700083 0.1287256 -0.2071409 0.9705137 0.1232716 -0.2026206 0.9701665 0.1331235 -0.2038731 0.9707262 0.1269902 -0.1985814 0.9703103 0.1380702 -0.2001864 0.9709247 0.131265 -0.1940158 0.9704489 0.143481 -0.1960138 0.9711147 0.1360692 -0.1887993 0.9706057 0.1492635 -0.1912414 0.9713237 0.1412695 -0.1831163 0.9707092 0.1555383 -0.186048 0.9714795 0.1470156 -0.1769117 0.9707641 0.1622326 -0.1803761 0.9715875 0.153239 -0.1699537 0.9708331 0.1691114 -0.1739943 0.9717085 0.1597137 -0.1625937 0.9707857 0.1764608 -0.1672492 0.9717188 0.1667041 -0.1545963 0.9706972 0.1839756 -0.1598843 0.9716848 0.1739699 -0.1459986 0.9705302 0.1917175 -0.1519737 0.9715805 0.1814811 -0.1369632 0.9702833 0.199478 -0.1435292 0.9713759 0.1892836 -0.1228405 0.9691575 0.2136446 -0.1346275 0.971098 0.1970894 -0.08757299 0.9657201 0.2443679 -0.117792 0.9709777 0.2081519 -0.01953852 0.9571962 0.2887796 -0.07921957 0.9690388 0.2338548 0.07522916 0.9426003 0.3253388 -0.009853124 0.9619963 0.2728847 0.1217914 0.9368363 0.3278791 0.08098906 0.9468157 0.3114175 0.09520995 0.9435672 0.3172 0.1221331 0.9371487 0.3268575 0.002916932 0.9590076 0.2833654 0.0923264 0.941308 0.3246768 -0.09615796 0.9691291 0.2270296 -0.002610504 0.9561172 0.2929728 -0.164485 0.9714966 0.1707017 -0.1002083 0.9675759 0.2318513 -0.1665827 0.9708035 0.1726002 0.3098352 -0.8019486 -0.5107647 0.1460174 -0.7777766 -0.6113448 0.3400946 -0.801073 -0.4925624 0.3135951 -0.7972398 -0.5158167 0.3354299 -0.806249 -0.4872879 0.3439295 -0.8034052 -0.4860582 0.3431437 -0.8042711 -0.4851809 0.3495194 -0.8010418 -0.4859714 0.3449474 -0.8060656 -0.4809048 0.3609986 -0.7975755 -0.4832735 0.3501053 -0.8094424 -0.4714121 0.378407 -0.7928632 -0.4776778 0.3587656 -0.8139727 -0.4568762 0.4017421 -0.7867026 -0.4687241 0.3706798 -0.8194993 -0.4370552 0.4307237 -0.7790025 -0.4556668 0.385491 -0.8257571 -0.4117304 0.4648755 -0.7696537 -0.4376344 0.4025532 -0.832539 -0.3805649 0.5037848 -0.7580826 -0.4141397 0.4212171 -0.8393501 -0.3436099 0.5459955 -0.7444853 -0.3842272 0.4411127 -0.845285 -0.3015177 0.5893275 -0.7295299 -0.3471012 0.4614124 -0.8497745 -0.2549153 0.1676105 -0.984809 -0.0453661 0.3307812 -0.9304476 -0.157642 0.1587392 -0.9843614 -0.07638388 0.2913416 -0.9398502 -0.1783301 0.1501406 -0.9830396 -0.1053135 0.2537762 -0.9477795 -0.1931621 0.1420105 -0.9810969 -0.1314609 0.2199702 -0.9540709 -0.2033761 0.1346926 -0.9787849 -0.1543962 0.1907346 -0.9589313 -0.2099313 0.1283788 -0.9763923 -0.1737155 0.1666162 -0.9625407 -0.2139028 0.1233854 -0.9741342 -0.189311 0.1474877 -0.9652255 -0.21584 0.1198671 -0.9722228 -0.2010342 0.1332663 -0.9671916 -0.2162878 0.1180152 -0.9707922 -0.2088894 0.1236971 -0.9686383 -0.215497 0.1176986 -0.9700248 -0.2126002 0.1186563 -0.9696611 -0.2137241 0.1112409 -0.970788 -0.2125939 0.1172305 -0.9684898 -0.2197368 0.1004237 -0.9663433 -0.2368453 0.09558552 -0.9684844 -0.2300034 -0.6220184 -0.453633 -0.6382085 -0.6109734 -0.6065741 -0.5087035 -0.5687138 -0.7374994 -0.3642243 -0.06394219 0.3033074 0.9507449 -0.7519449 -0.2449077 0.6120451 -0.116816 0.2656563 0.9569644 -0.6087968 -0.6020858 0.516584 -0.7537801 -0.237782 0.6125971 -0.6155465 -0.591814 0.5204409 -0.6137579 -0.5921215 0.5222006 -0.6135268 -0.5925374 0.5220004 -0.7518422 -0.2380847 0.6148568 -0.7516986 -0.2388782 0.6147248 -0.6171858 -0.5917322 0.518589 -0.6159953 -0.5935589 0.5179167 -0.6182687 -0.5922412 0.5167148 -0.617605 -0.5932557 0.5163446 -0.6189979 -0.5925745 0.515458 -0.6185632 -0.5932373 0.5152176 -0.6194689 -0.5926079 0.5148535 -0.6191595 -0.5930793 0.514683 -0.6192687 -0.5929836 0.5146619 -0.619485 -0.5926542 0.5147811 -0.618816 -0.5930378 0.5151437 -0.6191155 -0.5925812 0.5153093 -0.6178513 -0.5931656 0.5161533 -0.6184717 -0.5922173 0.5164992 -0.616418 -0.5933142 0.5176941 -0.6172966 -0.591966 0.5181903 -0.6146624 -0.5932486 0.5198523 -0.6156254 -0.5917635 0.5204051 -0.6123223 -0.5933397 0.522503 -0.6135947 -0.591365 0.5232486 -0.6095501 -0.5933547 0.5257175 -0.6109513 -0.5911636 0.5265588 -0.6064484 -0.59314 0.5295329 -0.6078481 -0.5909311 0.5303972 -0.6026993 -0.593151 0.5337841 -0.6043681 -0.5904891 0.5348476 -0.5984596 -0.5931401 0.5385452 -0.6002089 -0.5903161 0.5397002 -0.593819 -0.5929637 0.5438504 -0.5955268 -0.5901684 0.5450223 -0.5887179 -0.5926783 0.5496758 -0.5903971 -0.5898861 0.5508772 -0.5829193 -0.5926972 0.5558015 -0.5847813 -0.5895464 0.5571947 -0.5765556 -0.5927973 0.5622943 -0.5784342 -0.589558 0.5637688 -0.5697714 -0.592746 0.5692213 -0.5715028 -0.5896967 0.5706509 -0.5623956 -0.5927726 0.5764822 -0.5640914 -0.5897153 0.5779591 -0.5544258 -0.5929788 0.5839419 -0.5561043 -0.5898746 0.5854879 -0.5461177 -0.5928481 0.5918502 -0.5474851 -0.5902466 0.5931855 -0.5371155 -0.5931301 0.5997529 -0.5385416 -0.5903319 0.6012333 -0.5209451 -0.5959136 0.6111491 -0.5240391 -0.5895127 0.6147014 -0.4830461 -0.600022 0.6376833 -0.4875766 -0.5891662 0.6443232 -0.4141839 -0.6081612 0.6771939 -0.4186226 -0.5931038 0.6877375 -0.3222383 -0.6204589 0.7149779 -0.323795 -0.6081281 0.7248015 -0.2798571 -0.6246809 0.7290087 -0.2798958 -0.6238576 0.7296986 -0.3083431 -0.6155582 0.7252674 -0.3077235 -0.6217439 0.7202365 -0.4026358 -0.5980652 0.6929664 -0.4001672 -0.6072503 0.6863769 -0.5012147 -0.5901447 0.6328611 -0.498856 -0.5954856 0.6297139 -0.5681446 -0.5895531 0.574142 -0.5669273 -0.5917258 0.5731092 -0.6820465 -0.2378721 0.6915414 -0.6826496 -0.2349894 0.6919318 -0.5804873 -0.242973 0.7771735 -0.5813392 -0.2370949 0.7783513 -0.4326282 -0.260276 0.8631857 -0.4331442 -0.2497537 0.8660307 -0.2938688 -0.282792 0.9130552 -0.2935327 -0.2752464 0.9154661 -0.2521782 -0.2865811 0.9242714 -0.2522818 -0.2879849 0.9238067 -0.3170902 -0.2656208 0.9104391 -0.317512 -0.2797667 0.9060446 -0.4577158 -0.2428375 0.8552931 -0.4565675 -0.260843 0.8505922 -0.5611794 -0.2356641 0.7934356 -0.5595087 -0.2483743 0.7907341 -0.6165009 -0.2357229 0.75124 -0.6153532 -0.2425668 0.7500013 -0.6387336 -0.2365183 0.7321738 -0.6381657 -0.239638 0.7316544 -0.6523606 -0.2355028 0.7203916 -0.6516349 -0.2393127 0.7197924 -0.6650887 -0.2352319 0.7087475 -0.6644232 -0.2385872 0.7082499 -0.6769829 -0.2351132 0.6974353 -0.6762772 -0.23854 0.6969561 -0.68795 -0.2356238 0.6864446 -0.6873162 -0.2385969 0.6860524 -0.6982157 -0.2355824 0.6760146 -0.697416 -0.2392197 0.6755625 -0.7076169 -0.2356907 0.6661292 -0.7068173 -0.2392325 0.6657154 -0.7162204 -0.2357097 0.6568633 -0.715382 -0.2393371 0.6564649 -0.7239955 -0.2358773 0.6482226 -0.7231864 -0.2393077 0.6478682 -0.7309306 -0.2362765 0.6402451 -0.7301887 -0.239365 0.6399445 -0.7370595 -0.2368686 0.6329587 -0.7363883 -0.2396157 0.6327058 -0.7424858 -0.2371621 0.6264736 -0.7417849 -0.2399903 0.6262267 -0.7471439 -0.2375277 0.6207709 -0.746519 -0.2400202 0.6205641 -0.751033 -0.2381227 0.6158303 -0.7505334 -0.2400949 0.6156737 -0.7543254 -0.2382388 0.6117479 -0.7537878 -0.2403433 0.6115872 -0.7568092 -0.2387173 0.6084849 -0.7564635 -0.2400624 0.6083856 -0.758659 -0.2390475 0.6060469 -0.7583795 -0.2401298 0.6059688 -0.7598488 -0.2393021 0.6044537 -0.7596679 -0.2400004 0.6044042 -0.7602975 -0.2398514 0.6036711 -0.7603196 -0.2397667 0.6036772 -0.760242 -0.2397142 0.6037957 -0.7602254 -0.2397778 0.6037913 -0.7593852 -0.2401114 0.6047153 -0.7596511 -0.2390848 0.6047881 -0.7579117 -0.2404351 0.6064327 -0.7583032 -0.2389202 0.6065422 -0.7558819 -0.2402185 0.6090465 -0.7562961 -0.2386066 0.6091659 -0.01046967 0.8425 0.5385946 0.1310701 0.7376298 0.6623616 0.2124168 0.6546993 0.7254295 0.0703957 0.9971087 0.02861231 0.07403212 0.9969096 0.02627754 0.251973 0.9623474 -0.1019656 0.2824493 0.9514723 -0.1221587 0.3518846 0.9199633 -0.172756 0.4945597 0.8235054 -0.277938 0.4730417 0.8408367 -0.2631069 0.67324 -0.3007617 -0.6754927 0.6319969 0.6711614 -0.3874564 0.6564741 0.6360965 -0.4054912 0.5951356 0.6719242 -0.4408304 0.594803 0.6723886 -0.440571 0.4432026 0.8408704 -0.3106579 0.4428092 0.8411893 -0.3103556 0.2613542 0.9519609 -0.1595752 0.2608938 0.9521455 -0.159227 0.06152588 0.9981023 0.002498924 0.06113326 0.9981257 0.002790212 0.6240848 0.6683202 -0.404804 0.6132418 0.6697604 -0.4187548 0.6210841 0.6724357 -0.4025977 0.6037928 0.6706625 -0.4308667 0.6109022 0.6729885 -0.4169952 0.5956639 0.6715443 -0.440696 0.6017785 0.6734579 -0.4293218 0.5893034 0.6720553 -0.4484006 0.5942343 0.6735381 -0.4395816 0.58468 0.672577 -0.4536405 0.5882065 0.6735916 -0.4475348 0.5821448 0.6733079 -0.4558112 0.5838319 0.6737676 -0.4529651 0.5820526 0.6733404 -0.4558811 0.5821111 0.6733553 -0.4557843 0.5825096 0.6733591 -0.455269 0.5821091 0.6732609 -0.4559262 0.5829334 0.6734716 -0.4545599 0.5825011 0.6733712 -0.4552622 0.5826468 0.6731194 -0.4554482 0.5831116 0.6732211 -0.4547021 0.5807445 0.6731692 -0.457798 0.5823724 0.6735051 -0.4552289 0.5776663 0.6733604 -0.4613971 0.5802515 0.6738629 -0.4574025 0.5735906 0.6735218 -0.4662213 0.5770963 0.6741639 -0.4609371 0.5685181 0.6734914 -0.4724367 0.5730537 0.6742806 -0.4657846 0.5621759 0.6736081 -0.4798024 0.5677815 0.6745364 -0.4718315 0.554641 0.6737617 -0.4882811 0.5613272 0.6748173 -0.4790964 0.5458065 0.6740099 -0.4978012 0.5536403 0.6751946 -0.4874368 0.53585 0.6740143 -0.5084974 0.5448878 0.6753331 -0.4970135 0.5245807 0.6740105 -0.5201201 0.5348535 0.6754601 -0.5076273 0.5121484 0.6736823 -0.5327816 0.5237203 0.6752694 -0.5193536 0.4980961 0.6736505 -0.5459811 0.5109969 0.6753829 -0.5317331 0.4827467 0.6733886 -0.5599139 0.4970065 0.6752761 -0.5449649 0.4653289 0.6733208 -0.5745503 0.4813907 0.6754335 -0.5586166 0.4321021 0.6707581 -0.602803 0.4641098 0.6751819 -0.573351 0.3603773 0.6632751 -0.655892 0.4300257 0.674019 -0.6006467 0.2358204 0.6469874 -0.725118 0.356759 0.66934 -0.6516954 0.08976513 0.6239891 -0.7762602 0.2318518 0.654533 -0.719605 0.03832894 0.617941 -0.7852896 0.0873714 0.6293875 -0.7721642 0.0984193 0.6314859 -0.7691159 0.03829532 0.6180217 -0.7852278 0.2574835 0.6561627 -0.7093325 0.1003173 0.6272795 -0.7723063 0.4131187 0.6716132 -0.6150354 0.2597289 0.6520153 -0.7123321 0.5203874 0.6749273 -0.523135 0.4146369 0.6691913 -0.6166518 0.5211908 0.6737483 -0.5238544 0.4700058 0.8365846 -0.2814618 0.4604829 0.837819 -0.2932825 0.4636835 0.8416001 -0.2769602 0.4519906 0.8388436 -0.3033908 0.4551465 0.8420844 -0.289371 0.4446819 0.8397611 -0.3115434 0.4475755 0.8423969 -0.3000724 0.4389031 0.840427 -0.3178782 0.4413613 0.84245 -0.3089957 0.4345979 0.8410646 -0.3220791 0.4364305 0.8424392 -0.3159503 0.4324724 0.8414474 -0.3239354 0.433369 0.8420687 -0.3211101 0.4319597 0.8418347 -0.3236123 0.4319818 0.8418487 -0.3235466 0.4322794 0.8418953 -0.3230277 0.4320511 0.84176 -0.3236848 0.4329905 0.8416522 -0.3227088 0.4327436 0.8415156 -0.3233953 0.4324531 0.8417217 -0.3232476 0.4327319 0.8418636 -0.3225042 0.431113 0.8415257 -0.3255396 0.4321157 0.8419975 -0.3229804 0.4286952 0.841479 -0.3288365 0.4303128 0.8421812 -0.3249027 0.4253697 0.8414744 -0.3331387 0.4276085 0.8423717 -0.3279649 0.4208058 0.8417056 -0.3383107 0.4237679 0.8427944 -0.3318406 0.4154482 0.8417626 -0.3447296 0.4191993 0.8430353 -0.336992 0.4089516 0.8419302 -0.3520114 0.4135265 0.8433619 -0.3431274 0.4015921 0.8419203 -0.3604083 0.4070674 0.843509 -0.350412 0.3930072 0.8419943 -0.3695821 0.3994514 0.8437287 -0.3585532 0.3833048 0.8420327 -0.37955 0.3907623 0.8439085 -0.3675913 0.3723748 0.8420639 -0.3902122 0.3809346 0.8440752 -0.3773939 0.3604295 0.8418654 -0.401688 0.370146 0.8440077 -0.3881274 0.347324 0.8415167 -0.413782 0.3582474 0.8437957 -0.3995842 0.3327046 0.8409472 -0.4267499 0.3452084 0.8434187 -0.4116748 0.3049992 0.8381389 -0.4522154 0.3303187 0.8431308 -0.4242874 0.2436785 0.8317143 -0.4988709 0.29971 0.8431668 -0.4463672 0.1371201 0.816833 -0.5603409 0.2363094 0.8393876 -0.4894756 0.01034957 0.7978889 -0.6027156 0.1289424 0.8270754 -0.5471015 -0.03480613 0.7940243 -0.6068887 0.006225526 0.804613 -0.593767 0.01653343 0.8060824 -0.5915723 -0.03456842 0.7935938 -0.6074651 0.1525253 0.8279985 -0.5395874 0.01945769 0.8014435 -0.5977539 0.2863681 0.8407825 -0.4594326 0.1570921 0.8225192 -0.5466116 0.3788197 0.8433597 -0.3811038 0.2896612 0.8375833 -0.4631962 0.3803146 0.8420656 -0.382474 0.2826698 0.9492346 -0.1380268 0.2754361 0.9499905 -0.1471495 0.2756855 0.9519758 -0.1331903 0.2686206 0.9507492 -0.1546571 0.2692044 0.9524545 -0.1426867 0.263019 0.9512811 -0.1608884 0.2637705 0.9526802 -0.1510819 0.2582801 0.9517946 -0.1654649 0.2590644 0.9528653 -0.157903 0.2548454 0.9521839 -0.1685222 0.2555068 0.9529108 -0.1633324 0.2529262 0.9524933 -0.1696614 0.2532764 0.9528178 -0.1673001 0.2524508 0.9526802 -0.169319 0.2524554 0.9526837 -0.1692926 0.2528364 0.9526399 -0.1689697 0.2527325 0.9525663 -0.1695398 0.2530779 0.9526588 -0.1685013 0.252965 0.952588 -0.1690703 0.2531422 0.9524951 -0.169328 0.2532854 0.952575 -0.1686635 0.2520647 0.95247 -0.1710682 0.2525792 0.9527229 -0.1688872 0.2501744 0.952513 -0.1735851 0.2510344 0.9528873 -0.170257 0.2476261 0.9525658 -0.1769169 0.2488657 0.9530445 -0.1725455 0.244294 0.9526506 -0.1810449 0.2459881 0.9532337 -0.1756001 0.2401241 0.9527681 -0.1859392 0.2423412 0.9534506 -0.1794515 0.2352789 0.9528423 -0.1916648 0.2380605 0.9536186 -0.1842249 0.2295234 0.9529442 -0.1980313 0.2329461 0.9538109 -0.1896861 0.2229226 0.9530209 -0.2050772 0.2270535 0.9539787 -0.195886 0.21564 0.9529785 -0.2129116 0.2205446 0.9540277 -0.202956 0.2072791 0.9529614 -0.2211334 0.2130141 0.9541043 -0.2104994 0.1979086 0.9529168 -0.2297433 0.2045291 0.9541566 -0.2185247 0.1878893 0.9526475 -0.2390822 0.1954718 0.9539932 -0.22735 0.176681 0.9522271 -0.2490933 0.1854928 0.9537267 -0.2366387 0.1556685 0.9503998 -0.2692725 0.1738547 0.953527 -0.2460908 0.1090428 0.9456715 -0.3062924 0.1499161 0.953173 -0.2626525 0.02719193 0.9345763 -0.354722 0.1009304 0.9500681 -0.2952688 -0.07075923 0.9196628 -0.3862814 0.01855057 0.9405649 -0.3391069 -0.1056258 0.9160844 -0.3868238 -0.07482928 0.9237316 -0.37566 -0.06639194 0.9252218 -0.3735731 -0.105526 0.9159687 -0.3871249 0.03799045 0.9417628 -0.3341249 -0.06321656 0.9221763 -0.3815688 0.1407352 0.9516068 -0.2731997 0.04302591 0.9384717 -0.3426655 0.2114335 0.9538818 -0.2130852 0.1440477 0.9499648 -0.2771594 0.2134128 0.9530293 -0.2149189 0.07509475 0.9970531 0.01567918 0.07038116 0.9974693 0.01008164 0.06977248 0.9973769 0.0192613 0.06617003 0.9977941 0.0053339 0.06590086 0.9977387 0.0132125 0.06253933 0.9980413 0.001534521 0.06251037 0.9980124 0.007974624 0.05957806 0.9982227 -0.001320958 0.05968904 0.9982104 0.003646254 0.05734634 0.9983494 -0.003144621 0.05750674 0.9983451 2.45376e-4 0.05610042 0.998418 -0.00377947 0.05620563 0.9984167 -0.002269804 0.05582648 0.9984341 -0.00356549 0.0558263 0.9984341 -0.003567934 0.05599546 0.9984257 -0.003286421 0.0559557 0.9984266 -0.003665268 0.05625581 0.9984117 -0.003081679 0.05621063 0.998413 -0.00345236 0.05621165 0.9984125 -0.003557145 0.05627632 0.9984104 -0.003097355 0.05552679 0.9984463 -0.004662513 0.05576193 0.998439 -0.003210425 0.05435144 0.9985022 -0.006268143 0.05476129 0.9984912 -0.004068374 0.05278587 0.9985705 -0.008401513 0.05339848 0.9985581 -0.005521118 0.05073171 0.9986512 -0.0110504 0.05159723 0.9986401 -0.007457137 0.0481587 0.998739 -0.01417756 0.04932093 0.9987338 -0.009910821 0.04507941 0.9988256 -0.01776015 0.0465815 0.9988315 -0.01287788 0.04149341 0.998901 -0.02180117 0.043383 0.998925 -0.0163294 0.03735804 0.9989572 -0.02624636 0.03967648 0.9990078 -0.02022767 0.0326187 0.998986 -0.03102964 0.03541654 0.9990719 -0.02451455 0.02742433 0.9989658 -0.03626656 0.03074735 0.9990975 -0.02930504 0.02167165 0.9988898 -0.0418269 0.025559 0.9990784 -0.03448492 0.01527595 0.99875 -0.04759389 0.01977246 0.9990063 -0.0399416 0.008215427 0.9985122 -0.05390733 0.01350682 0.998861 -0.04576319 -0.004895508 0.9977443 -0.06695204 0.00618577 0.9986432 -0.05170851 -0.0341168 0.9952848 -0.09079778 -0.009001791 0.9980302 -0.0620864 -0.08587229 0.9888652 -0.1215388 -0.0400722 0.9958026 -0.08229005 -0.1475964 0.9789517 -0.1409572 -0.09181511 0.9897081 -0.109763 -0.1692284 0.975526 -0.1403947 -0.1501693 0.979671 -0.1330182 -0.1443778 0.9807342 -0.1315885 -0.1691591 0.9755011 -0.1406512 -0.07888227 0.9911606 -0.1066686 -0.1423429 0.9802104 -0.1375726 -0.01445949 0.9975436 -0.06854015 -0.0753569 0.9907174 -0.1131401 0.03010463 0.9990644 -0.03105002 -0.01186358 0.9973524 -0.07174628 0.03148412 0.9989811 -0.03233313 0.6217168 -0.4196295 0.6613466 0.58228 -0.2996155 -0.7557649 0.6077396 -0.6211431 0.4948071 0.5700826 -0.7345123 0.3680996 0.5813902 -0.3045856 -0.7544622 0.819656 -0.03608691 -0.5717183 0.7708728 -0.304098 -0.5597137 0.8181829 -0.05158174 -0.5726397 0.1666026 0.2639607 -0.9500361 0.6686484 -0.5431962 -0.5077866 0.7691768 -0.3092898 -0.5592022 0.518854 -0.7446902 -0.4197942 0.6675142 -0.5450837 -0.5072559 0.52162 -0.7419046 -0.4212958 0.5081636 -0.737872 -0.4442012 0.5078346 -0.7382611 -0.4439307 0.6446549 -0.5381736 -0.5429452 0.644505 -0.5384755 -0.5428237 0.7372484 -0.3013253 -0.6047047 0.7371419 -0.3017557 -0.60462 0.7793319 -0.04425382 -0.6250467 0.7793282 -0.04435592 -0.6250441 0.7050971 -0.04279458 -0.7078183 0.7051976 -0.04100215 -0.7078244 0.5981423 -0.04749041 -0.7999815 0.5981997 -0.04379683 -0.8001493 0.4426952 -0.06334853 -0.8944316 0.44246 -0.05816763 -0.8948998 0.2840098 -0.08958649 -0.954627 0.2834014 -0.08405387 -0.9553108 0.2228617 -0.09912961 -0.9697969 0.2228803 -0.09926694 -0.9697785 0.2721073 -0.08503735 -0.9585021 0.2728632 -0.09157985 -0.9576841 0.417434 -0.05833429 -0.9068329 0.4180686 -0.06956845 -0.9057477 0.5429453 -0.04671525 -0.8384677 0.5429913 -0.05390709 -0.8380062 0.6158981 -0.04263943 -0.7866711 0.6157681 -0.04845517 -0.786436 0.6497027 -0.04276418 -0.7589846 0.6496285 -0.04486703 -0.7589268 0.6668288 -0.04235655 -0.7440063 0.6667456 -0.04434168 -0.7439652 0.6821514 -0.04138326 -0.730039 0.682021 -0.04412633 -0.7300002 0.6961051 -0.04155135 -0.7167365 0.6960116 -0.04332548 -0.7167223 0.708716 -0.0416513 -0.7042633 0.7086025 -0.04361867 -0.7042585 0.7200376 -0.04175591 -0.6926776 0.7199127 -0.04377204 -0.6926829 0.7300613 -0.04216688 -0.6820795 0.7299491 -0.04387325 -0.682092 0.7388752 -0.04211115 -0.6725252 0.7387292 -0.04422229 -0.67255 0.7464633 -0.04237878 -0.6640757 0.7463428 -0.04405707 -0.6641019 0.7528546 -0.04283183 -0.6567916 0.7527561 -0.0441606 -0.6568167 0.7581199 -0.04277783 -0.6507105 0.7579967 -0.04439753 -0.6507456 0.7621689 -0.04349362 -0.6459156 0.7621232 -0.04408174 -0.6459296 0.7651591 -0.04425746 -0.6423183 0.7651387 -0.04451555 -0.6423249 0.7671987 -0.04369992 -0.6399192 0.7670984 -0.04495739 -0.6399523 0.7678017 -0.04427772 -0.6391558 0.7678288 -0.04393851 -0.6391466 0.7670797 -0.0447027 -0.6399926 0.7671343 -0.04401689 -0.6399744 0.7664989 -0.04403567 -0.6407341 0.7664657 -0.04445493 -0.6407451 0.7668209 -0.04416877 -0.6403397 0.7668208 -0.04417014 -0.6403397 0.768983 -0.04325687 -0.637804 0.7688397 -0.04504323 -0.6378532 0.7733425 -0.0435329 -0.6324921 0.7732082 -0.04517537 -0.6325411 0.7796896 -0.04294598 -0.6246918 0.779397 -0.04642713 -0.624808 0.7875774 -0.04358136 -0.6146727 0.7872963 -0.04681342 -0.6147951 0.796965 -0.04372817 -0.6024407 0.7965386 -0.04843777 -0.6026443 0.8074417 -0.04485481 -0.5882398 0.8069962 -0.04956597 -0.5884727 0.5172128 -0.7410531 -0.4281722 0.5213841 -0.7367179 -0.4305873 0.513172 -0.7404235 -0.4340825 0.5167188 -0.736674 -0.4362488 0.5096338 -0.739863 -0.4391766 0.5125153 -0.7367706 -0.4410184 0.5067518 -0.7392977 -0.4434428 0.5089188 -0.7369419 -0.4448801 0.5044351 -0.7389016 -0.4467323 0.506076 -0.7370993 -0.4478522 0.5030618 -0.7384045 -0.4490965 0.5039088 -0.7374677 -0.4496858 0.5028144 -0.7377386 -0.4504657 0.5027914 -0.7377642 -0.4504496 0.5027282 -0.7377008 -0.4506238 0.5027734 -0.7376507 -0.4506556 0.50306 -0.7376645 -0.4503128 0.502837 -0.7379121 -0.4501565 0.503198 -0.7378215 -0.4499014 0.5031676 -0.7378551 -0.4498801 0.5027617 -0.7379491 -0.4501798 0.5030674 -0.7376098 -0.4503942 0.50167 -0.7381872 -0.4510065 0.5023823 -0.7373941 -0.4515106 0.5003275 -0.7382054 -0.4524657 0.5010592 -0.7373865 -0.4529908 0.4987465 -0.737983 -0.454569 0.4994554 -0.7371839 -0.455087 0.4964985 -0.7379571 -0.4570652 0.4975624 -0.7367464 -0.4578606 0.4937626 -0.7379472 -0.4600352 0.4949764 -0.7365507 -0.460968 0.490475 -0.7380158 -0.4634294 0.4918612 -0.7364002 -0.4645292 0.4867615 -0.7380324 -0.4673024 0.488165 -0.7363716 -0.4684568 0.4827001 -0.7378455 -0.471789 0.4839784 -0.7363055 -0.4728837 0.4779043 -0.737965 -0.4764611 0.4794313 -0.7360882 -0.4778281 0.4726128 -0.7380725 -0.4815456 0.4740956 -0.7362087 -0.4829388 0.4670641 -0.7378638 -0.4872456 0.46823 -0.73636 -0.4884001 0.4605964 -0.738199 -0.4928623 0.4620821 -0.7362271 -0.4944186 0.453288 -0.7387195 -0.4988222 0.4548097 -0.7366338 -0.5005185 0.4382255 -0.7406591 -0.5092962 0.4413066 -0.7361372 -0.513177 0.4075855 -0.7436528 -0.5299571 0.4114652 -0.7369419 -0.5362957 0.3559044 -0.7500239 -0.5574911 0.359395 -0.7413145 -0.5668227 0.2971069 -0.7582123 -0.5803806 0.2981079 -0.7529616 -0.5866689 0.2775401 -0.7604614 -0.587086 0.2775539 -0.7603455 -0.5872297 0.3037689 -0.7530222 -0.5836797 0.3028531 -0.7573336 -0.5785549 0.3705316 -0.7417838 -0.5589841 0.3683879 -0.7466417 -0.5539103 0.434327 -0.7370154 -0.5178496 0.4326245 -0.7396036 -0.5155799 0.4779656 -0.7364127 -0.4787955 0.4769014 -0.7377281 -0.4778308 0.6604091 -0.5436611 -0.5179695 0.6648393 -0.5360637 -0.5202156 0.6539512 -0.5423788 -0.5274211 0.6576508 -0.5359137 -0.5294259 0.6482006 -0.5413397 -0.5355253 0.6512621 -0.5358991 -0.5372802 0.6434971 -0.5401986 -0.5423073 0.6457453 -0.5361447 -0.543656 0.6395993 -0.5396407 -0.5474492 0.6414355 -0.5362924 -0.54859 0.6372331 -0.5386584 -0.5511634 0.6381006 -0.5370639 -0.5517154 0.6360648 -0.5383232 -0.552838 0.6365072 -0.5375075 -0.5531225 0.6361334 -0.5378286 -0.5532401 0.6359541 -0.5381594 -0.5531246 0.6367111 -0.5375837 -0.5528138 0.6363862 -0.5381823 -0.552605 0.6368573 -0.5381557 -0.5520881 0.6369771 -0.5379351 -0.5521648 0.6363704 -0.5381579 -0.5526472 0.6365665 -0.5377963 -0.5527733 0.6349245 -0.5383208 -0.5541495 0.6355339 -0.5371928 -0.5545452 0.6327579 -0.5385025 -0.5564463 0.6336098 -0.536917 -0.5570089 0.6298853 -0.5386945 -0.5595113 0.6309401 -0.5367164 -0.5602234 0.6262521 -0.5388838 -0.5633938 0.6274882 -0.5365433 -0.5642516 0.6219902 -0.5388036 -0.5681717 0.6232318 -0.5364236 -0.5690622 0.6168798 -0.538874 -0.5736499 0.6183082 -0.536096 -0.5747139 0.611224 -0.5384789 -0.5800396 0.6124867 -0.5359795 -0.5810216 0.6045734 -0.5384325 -0.5870106 0.6060549 -0.5354396 -0.5882194 0.5972247 -0.5382013 -0.5946948 0.5986108 -0.5353356 -0.5958867 0.5888559 -0.5383518 -0.6028482 0.59039 -0.5350959 -0.604245 0.5796828 -0.5384357 -0.6116002 0.581119 -0.5352969 -0.6129911 0.5695356 -0.5389134 -0.6206462 0.5710332 -0.5355307 -0.6221961 0.5581585 -0.5394677 -0.6304236 0.5595898 -0.5361098 -0.6320172 0.5349267 -0.5424892 -0.6477336 0.5379478 -0.5347978 -0.651616 0.4863113 -0.5479395 -0.6806348 0.4903128 -0.5354817 -0.6876428 0.4041473 -0.5582228 -0.7246049 0.407249 -0.5425217 -0.7347233 0.3098035 -0.5709019 -0.7603241 0.3102916 -0.5613892 -0.7671775 0.2778617 -0.5733936 -0.7707223 0.2778611 -0.5739456 -0.7703115 0.3187058 -0.5616478 -0.7635301 0.318235 -0.5688584 -0.7583711 0.4244382 -0.5439099 -0.7238883 0.4225737 -0.5522078 -0.718678 0.5267108 -0.5359039 -0.6598353 0.5247569 -0.541102 -0.6571445 0.5964664 -0.5354259 -0.5979524 0.5954985 -0.5374423 -0.5971075 0.7596336 -0.3078615 -0.5728684 0.7624177 -0.2990699 -0.573826 0.750817 -0.3065908 -0.5850434 0.7531728 -0.2989883 -0.5859494 0.7430413 -0.3053818 -0.5955093 0.7449265 -0.299177 -0.5963034 0.7365172 -0.3041678 -0.6041725 0.7379289 -0.2994396 -0.6048113 0.7313702 -0.303197 -0.6108757 0.7323975 -0.299708 -0.6113663 0.7278664 -0.302229 -0.6155226 0.7284492 -0.3002299 -0.6158115 0.7263223 -0.3014307 -0.617734 0.7264779 -0.3008946 -0.6178125 0.7260996 -0.3012084 -0.6181043 0.7260954 -0.3012226 -0.6181023 0.7266724 -0.3012017 -0.617434 0.7265543 -0.3016078 -0.6173746 0.7272273 -0.3013535 -0.6167063 0.7271532 -0.301608 -0.6166692 0.7264824 -0.3018414 -0.6173453 0.7267386 -0.3009597 -0.6174741 0.7247346 -0.3019173 -0.6193592 0.7250689 -0.3007614 -0.6195301 0.7220135 -0.3021771 -0.6224029 0.7225422 -0.3003368 -0.6226801 0.7184716 -0.3020918 -0.6265294 0.7190219 -0.3001581 -0.6268274 0.713945 -0.3019782 -0.6317371 0.7145971 -0.2996574 -0.6321048 0.7083553 -0.302084 -0.6379482 0.7091554 -0.2991931 -0.6384215 0.7018992 -0.3016607 -0.6452429 0.7026163 -0.299021 -0.6456909 0.6943168 -0.3015954 -0.6534253 0.6951702 -0.2983831 -0.6539922 0.6856038 -0.3018487 -0.6624459 0.6865544 -0.298182 -0.6631218 0.6759026 -0.3017917 -0.672367 0.6767642 -0.2983712 -0.6730266 0.6650012 -0.3021872 -0.6829761 0.6659436 -0.2983203 -0.6837573 0.6530608 -0.3021572 -0.6944152 0.6538478 -0.2988035 -0.6951255 0.640143 -0.3015871 -0.7065849 0.6407373 -0.2989362 -0.7071725 0.6252335 -0.3029379 -0.7192438 0.6261746 -0.2985189 -0.720272 0.5957028 -0.3064224 -0.7424578 0.597319 -0.2979469 -0.7446057 0.5328789 -0.3133211 -0.7860471 0.5348795 -0.299251 -0.79016 0.4257469 -0.3264815 -0.8438894 0.4267612 -0.3089763 -0.8499462 0.3017284 -0.3440511 -0.8891506 0.3012521 -0.3325934 -0.8936603 0.2591351 -0.3476563 -0.9011017 0.2592092 -0.3486338 -0.9007025 0.3115545 -0.3333103 -0.8898529 0.3118099 -0.3411905 -0.8867715 0.4487102 -0.3095922 -0.8383387 0.4479435 -0.3196876 -0.834953 -0.9951848 0 -0.0980165 -0.9569395 0 -0.2902874 -0.8819202 0 -0.4713987 -0.7730091 0 -0.6343949 -0.634392 0 -0.7730116 -0.4713946 0 -0.8819224 -0.2902834 0 -0.9569408 -0.09801501 0 -0.995185 0.0980187 0 -0.9951846 0.2902866 0 -0.9569397 0.4713985 0 -0.8819202 0.6343948 0 -0.7730093 0.7730114 0 -0.6343921 0.8819223 0 -0.4713948 0.956941 0 -0.2902822 0.995185 0 -0.09801506 0.9951846 0 0.09801912 0.9569395 0 0.2902873 0.8819197 0 0.4713996 0.7730097 0 0.6343942 0.634391 0 0.7730123 0.4713954 0 0.881922 0.2902795 0 0.9569419 0.09801524 0 0.995185 -0.09801894 0 0.9951846 -0.2902886 0 0.9569392 -0.4713996 0 0.8819198 -0.6343935 0 0.7730103 -0.7730136 0 0.6343894 -0.8819243 0 0.471391 -1.58832e-6 1 -6.25718e-7 -0.9951853 0 0.09801238 -0.9569402 0 0.2902851 0 -1 3.17648e-6 -0.9951846 0 -0.09801906 -0.9569398 0 -0.2902867 -0.8819204 0 -0.4713985 -0.7730094 0 -0.6343945 -0.634392 0 -0.7730116 -0.4713941 0 -0.8819227 -0.290283 0 -0.9569408 -0.09801548 0 -0.9951849 0.0980187 0 -0.9951846 0.2902871 0 -0.9569396 0.4713989 0 -0.8819202 0.6343936 0 -0.7730102 0.7730119 0 -0.6343915 0.881922 0 -0.4713954 0.9569408 0 -0.2902829 0.9951848 0 -0.0980165 0.9951844 0 0.09802013 0.9569392 0 0.2902886 0.8819209 0 0.4713973 0.7730086 0 0.6343957 0.6343913 0 0.7730121 0.4713944 0 0.8819225 0.2902829 0 0.9569409 0.0980165 0 0.9951847 -0.09802389 0 0.995184 -0.2902886 0 0.9569392 -0.4713982 0 0.8819204 -0.6343954 0 0.7730087 -0.7730118 0 0.6343917 -0.8819229 0 0.4713937 -1.2279e-6 1 -1.18588e-6 1.24458e-7 1 -6.25714e-7 1.22789e-6 1 -1.18587e-6 0 1 -6.65285e-7 6.75306e-7 1 -9.56982e-7 -2.04894e-7 1 -4.86508e-7 0 1 -6.02821e-7 0 1 0 -2.09247e-7 1 -1.05196e-6 -1.79982e-7 1 -9.55486e-7 -4.43004e-7 1 -7.66342e-7 0 1 -4.50959e-7 -6.11e-7 1 -9.98747e-7 -2.4434e-6 1 0 -2.60718e-7 1 -3.90197e-7 1.33777e-7 1 -6.53789e-7 7.66345e-7 1 4.43014e-7 -3.91068e-7 1 -1.28919e-6 -4.25374e-7 1 -1.94907e-7 -6.9491e-7 1 2.29079e-6 -1.44624e-7 1 -4.75656e-7 0 1 -5.37702e-7 1.9713e-7 1 -8.37997e-7 0 1 -6.5917e-7 0 1 -6.25226e-7 1.84059e-7 1 -6.06751e-7 0 1 -6.06751e-7 0 1 -5.94289e-7 3.75041e-7 1 -9.56873e-7 -0.9951849 0 0.09801465 -0.9569416 0 0.2902806 0 -1 0 0 -1 0 0 -1 9.90722e-7 0 -1 9.90725e-7 0 -1 7.36174e-7 0 -1 7.36174e-7 0 -1 4.02776e-7 0 -1 4.02776e-7 0 -1 5.29551e-7 0 -1 5.29553e-7 0 -1 8.13399e-7 0 -1 8.13397e-7 0 -1 4.69283e-7 0 -1 4.69288e-7 0 -1 7.82139e-7 0 -1 7.8214e-7 0 -1 4.88039e-7 0 -1 4.88038e-7 0 -1 8.82588e-7 0 -1 8.8259e-7 0 -1 6.04162e-7 0 -1 6.04163e-7 0 -1 4.90783e-7 0 -1 4.90783e-7 0 -1 9.90724e-7 0 -1 9.90724e-7 0 -1 0 0 -1 0 0 -1 0 -0.9951848 0 -0.0980165 -0.9569395 0 -0.2902874 -0.8819202 0 -0.4713987 -0.7730091 0 -0.6343949 -0.634392 0 -0.7730116 -0.4713946 0 -0.8819224 -0.2902834 0 -0.9569408 -0.09801501 0 -0.995185 0.0980187 0 -0.9951846 0.2902866 0 -0.9569397 0.4713986 0 -0.8819203 0.6343948 0 -0.7730093 0.7730114 0 -0.634392 0.8819223 0 -0.4713948 0.9569411 0 -0.2902822 0.9951849 0 -0.09801506 0.9951846 0 0.09801912 0.9569396 0 0.2902873 0.8819198 0 0.4713996 0.7730097 0 0.6343942 0.634391 0 0.7730123 0.4713954 0 0.881922 0.2902795 0 0.9569419 0.09801524 0 0.995185 -0.09801888 0 0.9951846 -0.2902886 0 0.9569392 -0.4713996 0 0.8819198 -0.6343935 0 0.7730103 -0.7730136 0 0.6343894 -0.8819244 0 0.471391 -1.2279e-6 1 -1.18588e-6 1.24456e-7 1 -6.25714e-7 -1.70684e-6 1 0 -3.98372e-7 1 -7.29712e-7 1.79862e-7 1 -7.51766e-7 2.41005e-7 1 -7.84447e-7 -3.05406e-7 1 -4.19349e-7 0 1 0 -3.13863e-7 1 -1.57793e-6 0 1 -4.60022e-7 -9.72964e-7 1 -1.40265e-6 -1.32623e-7 1 -8.41154e-7 -1.43564e-6 1 -9.23541e-7 -1.67979e-6 1 -3.03842e-7 4.43021e-7 1 -7.66351e-7 -4.83058e-7 1 -1.47567e-7 -4.63274e-7 1 1.5272e-6 0 1 -1.10268e-6 -1.45968e-7 1 -4.24209e-7 0 1 -6.37249e-7 0 1 -6.38451e-7 -6.94908e-7 1 -2.29082e-6 0 1 -8.61545e-7 0 1 -5.97218e-7 0 1 -6.44019e-7 1.88778e-7 1 -6.22309e-7 0 1 -6.22309e-7 0 1 -6.17902e-7 2.34391e-7 1 -7.9668e-7 -0.9951853 0 0.09801238 -0.9569402 0 0.2902851 0 -1 0 0 -1 0 0 -1 9.90721e-7 0 -1 9.90724e-7 0 -1 4.90783e-7 0 -1 4.90783e-7 0 -1 6.04161e-7 0 -1 6.0416e-7 0 -1 5.29554e-7 0 -1 5.29553e-7 0 -1 8.13398e-7 0 -1 8.134e-7 0 -1 3.12856e-7 0 -1 3.12858e-7 0 -1 9.38567e-7 0 -1 9.38567e-7 0 -1 3.2536e-7 0 -1 3.25359e-7 0 -1 1.0591e-6 0 -1 1.05911e-6 0 -1 4.02775e-7 0 -1 4.02775e-7 0 -1 7.36174e-7 0 -1 7.36175e-7 0 -1 6.60483e-7 0 -1 6.60482e-7 0 -1 0 0 -1 0 0 -1 0 -1 -7.94729e-7 0 0 -7.94729e-7 -1 1 0 0 0 7.94729e-7 1 3.17891e-7 -1 8.26518e-7 -3.49681e-7 1 -8.58307e-7 -1 -7.94729e-7 0 0 -7.94729e-7 -1 1 0 0 0 7.94729e-7 1 3.49681e-7 -1 8.58307e-7 -3.17891e-7 1 -8.26518e-7 -1 -3.8147e-7 0 0 -5.08626e-7 -1 1 3.8147e-7 0 0 1.01725e-6 1 2.54313e-7 -1 7.15256e-7 -3.17892e-7 1 -8.10623e-7 -1 -3.17891e-7 0 0 -5.08626e-7 -1 1 3.17891e-7 0 0 1.01725e-6 1 5.08626e-7 -1 8.10623e-7 -3.17891e-7 1 -8.10623e-7 -0.7071066 6.67572e-7 0.707107 -0.7071071 -6.35783e-7 -0.7071065 0.7071061 -6.7435e-7 -0.7071076 0.7071068 6.7435e-7 0.7071068 3.52161e-7 -1 9.7968e-7 -3.12824e-7 1 -9.68441e-7 -0.7071056 0 -0.7071079 0.7071067 0 -0.707107 0.707107 0 0.7071067 -0.7071072 0 0.7071064 3.29682e-7 -1 6.16282e-7 -3.44668e-7 1 -6.48125e-7 -0.7071068 0 0.7071068 -0.7071072 0 -0.7071064 0.7071062 0 -0.7071074 0.7071069 0 0.7071067 2.99711e-7 -1 9.64695e-7 -3.12824e-7 1 -9.68441e-7 -0.7071056 0 -0.707108 0.7071067 0 -0.7071069 0.707107 0 0.7071066 -0.7071072 0 0.7071064 3.14697e-7 -1 6.6873e-7 -3.5216e-7 1 -6.21902e-7 -0.7071049 2.22723e-7 0.7071087 0.7071096 4.93364e-7 0.7071039 0.7071061 0 -0.7071074 -0.7071104 -4.21207e-7 -0.7071033 0.6672638 0.3309306 -0.6672661 -0.6894164 -0.222274 0.6894195 0.7071082 4.70828e-7 0.7071053 0.7071072 5.20896e-7 0.7071064 0.707102 2.89993e-7 0.7071117 0.7071051 4.19692e-7 0.7071086 0.7071067 1.69253e-6 0.7071069 0.7071064 4.83472e-7 0.7071073 0.7071079 1.14927e-6 0.7071057 0.7071068 0 0.7071068 0.7071084 5.77985e-7 0.7071052 0.7071877 4.65984e-6 0.7070258 0.707102 2.00185e-7 0.7071116 0.7072384 5.29796e-7 0.7069752 0.7071068 0 0.7071068 0.7071244 1.16172e-6 0.7070893 0.7071084 1.16558e-6 0.7071053 0.7071087 1.00029e-6 0.707105 0.7071128 7.40535e-7 0.7071008 0.7071068 5.4012e-7 0.7071068 0.7071095 5.11138e-7 0.7071041 0.7071727 3.14492e-6 0.7070408 0.7071067 1.18712e-6 0.7071069 0.7071041 3.51201e-7 0.7071095 0.707107 5.38966e-7 0.7071067 0.7070338 0 0.7071798 0.7071069 5.29816e-7 0.7071067 0.7071068 5.39436e-7 0.7071068 0.7071153 8.12527e-7 0.7070983 0.7070987 3.98197e-6 0.7071149 0.707104 -1.31508e-7 0.7071095 0.7071089 1.27859e-7 0.7071048 0.7071041 1.45791e-6 0.7071095 0.707107 1.00028e-6 0.7071065 0.707109 0 0.7071045 0.7071095 4.90836e-7 0.7071041 0.7071025 5.39437e-7 0.707111 0.7071068 8.1094e-7 0.7071068 0.7071068 5.39485e-7 0.7071068 0 1 0 0.4999542 0.7071139 0.4999542 0.5000153 0.7070528 0.5000153 0.7071011 2.63846e-7 0.7071126 0.7071068 8.10904e-7 0.7071068 0.7071046 4.31549e-7 0.7071091 0.7071068 1.21303e-6 0.7071068 0 -1 0 0.4999848 -0.7070834 0.4999848 0.4999848 -0.7070834 0.4999848 0.7071076 8.4573e-7 0.707106 0.7071101 1.5037e-6 0.7071035 0.7071068 6.9095e-7 0.7071068 0.7071068 0 0.7071068 0.7071068 5.39913e-7 0.7071068 0.7071068 6.48244e-7 0.7071068 0.7071372 1.64757e-6 0.7070763 0.7071922 4.31549e-7 0.7070214 0.7071067 5.39486e-7 0.7071067 0.7071068 1.21641e-6 0.7071068 0 0 0 0.7070959 -0.005536675 0.7070959 0.7071173 3.23651e-7 0.7070963 0.7071031 2.02834e-6 0.7071106 0.7071068 1.22377e-6 0.7071068 0.7071083 4.67282e-7 0.7071053 0.7071027 -7.85863e-7 0.7071108 0.7069504 0.0197736 0.7069866 0.707125 3.50704e-6 0.7070887 0.7071083 1.71973e-6 0.7071053 0.7071068 0 0.7071068 0.7071067 3.0776e-4 0.7071067 0.7070989 1.7365e-7 0.7071146 0.7071068 5.39335e-7 0.7071068 0.7071068 5.38427e-7 0.7071068 0.7070763 1.02052e-6 0.7071372 0.7071068 5.38336e-7 0.7071068 0.7071067 5.38258e-7 0.7071067 0.7070788 -6.87274e-7 0.7071347 0 -1 0 0.7075734 3.23442e-7 0.7066399 0.7071124 4.30306e-7 0.7071012 0.7072327 2.02742e-6 0.7069808 0.7070886 -6.7019e-4 0.7071247 0.7071068 3.23342e-7 0.7071068 0.7071068 6.46064e-7 0.7071068 0.7071055 1.42486e-6 0.7071082 0 0 0 0.7071179 1.74366e-6 0.7070958 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071227 -0.005845487 0.7070668 0.7071245 -8.7817e-4 0.7070884 0.7071068 0 0.7071068 0.7071069 6.29741e-7 0.7071067 0.7071132 1.78115e-7 0.7071003 0.7070414 1.07829e-6 0.7071721 0.7071068 0 0.7071068 0.7071067 3.24361e-7 0.7071069 0.7071068 6.48284e-7 0.7071068 0.7069184 9.75956e-6 0.7072952 0.7072274 -3.07753e-6 0.7069862 0.7070925 5.16284e-7 0.707121 0.7071073 7.53736e-7 0.7071063 0.7071255 5.03393e-4 0.7070878 0.7071068 6.46522e-7 0.7071068 0.707111 1.21642e-6 0.7071027 0.7071083 4.4774e-7 0.7071053 0.7071006 5.21513e-4 0.7071127 0.7071158 4.1103e-6 0.7070978 0.7071059 9.58213e-7 0.7071077 0.7071126 1.25504e-6 0.7071009 0.707109 1.03319e-6 0.7071045 0.7071096 5.75366e-7 0.7071039 0.7071177 2.5791e-7 0.7070959 0.7071068 0 0.7071068 0.7071107 5.75366e-7 0.7071029 0.7071209 1.45133e-7 0.7070928 0.7071057 5.97196e-7 0.7071079 0.707109 9.19701e-7 0.7071045 0.7071031 5.16246e-7 0.7071104 0.7071092 7.53738e-7 0.7071045 0.7071083 9.5173e-7 0.7071053 0.7071068 5.15144e-7 0.7071068 0.7071091 4.9368e-7 0.7071046 0.7071068 1.8993e-6 0.7071068 0.7067412 1.09516e-5 0.7074723 0.7071635 1.03911e-5 0.7070501 0.7067521 1.03316e-5 0.7074613 0.7068091 9.55004e-6 0.7074045 0.7067358 1.47462e-5 0.7074775 0.7067466 1.07915e-5 0.7074669 0.7067604 1.0682e-5 0.707453 0.7067496 9.71363e-6 0.7074638 0.7071015 0 0.707112 0.7071039 7.37469e-7 0.7071098 0.7065418 1.11298e-5 0.7076714 0.6991987 2.33699e-4 0.7149273 0.6992096 2.33198e-4 0.7149167 0.6991608 2.31454e-4 0.7149645 0.6991994 2.33681e-4 0.7149268 0.6992278 2.33491e-4 0.7148988 0.6991978 2.3584e-4 0.7149283 0.6992063 2.33477e-4 0.71492 0.6992086 2.33244e-4 0.7149177 0.6992061 2.32184e-4 0.7149201 0.707109 1.10517e-5 0.7071045 0.707107 1.07642e-5 0.7071066 0.7071055 1.05844e-5 0.7071081 0.7070568 1.17896e-5 0.7071568 0.707112 1.24841e-5 0.7071016 0.7071093 1.15751e-5 0.7071042 0.7071062 1.11298e-5 0.7071074 0.707106 1.07918e-5 0.7071077 0.7071173 1.10167e-5 0.7070963 0.694866 5.7807e-4 0.719139 0.6948555 5.78298e-4 0.7191492 0.6948664 5.77766e-4 0.7191386 0.6948686 5.769e-4 0.7191364 0.6948652 5.77383e-4 0.7191397 0.6948698 5.77037e-4 0.7191355 0.6948799 5.77908e-4 0.7191256 0.694981 5.78218e-4 0.7190279 0.7070997 2.33543e-4 0.7071139 0.7071122 2.33588e-4 0.7071014 0.7071067 2.31476e-4 0.7071067 0.7071067 2.33496e-4 0.7071067 0.7073768 2.25217e-4 0.7068367 0.7071083 2.34728e-4 0.7071052 0.7071037 2.3397e-4 0.7071098 0 -1 0 0.7001235 7.75103e-4 0.7140213 0.7001366 7.75032e-4 0.7140086 0.7002734 7.77584e-4 0.7138743 0.7001616 7.75996e-4 0.7139841 0.7001363 7.75037e-4 0.7140088 0.700115 7.74947e-4 0.7140297 0.7001299 7.74963e-4 0.714015 0.7001233 7.73625e-4 0.7140214 0.7001218 7.75749e-4 0.7140231 0.7071178 5.77692e-4 0.7070956 0.7071067 5.77575e-4 0.7071067 0.7071341 5.77525e-4 0.7070794 0.7070622 5.77791e-4 0.7071512 0.7070768 5.77863e-4 0.7071365 0.7068091 5.78302e-4 0.7074041 0.7071081 5.79735e-4 0.7071051 0 -1 0 0.5001068 -0.7069308 0.5000763 0.5001373 -0.7069002 0.5001373 0.7071067 5.78976e-4 0.7071067 0.7071331 5.92102e-4 0.7070802 0.7172767 0.002368092 0.6967845 0.7172806 4.83497e-4 0.6967843 0.7173049 4.82765e-4 0.6967593 0.7173056 4.83719e-4 0.6967587 0.7173261 4.83816e-4 0.6967374 0.7173405 4.83014e-4 0.6967226 0 1 0 0.5001373 -0.7068392 0.5001984 0.08758813 -0.9922788 0.08761864 0.5048372 -0.7052217 0.4977264 0.7070312 7.76818e-4 0.7071818 0.7071061 7.75293e-4 0.7071071 0.7172773 4.76691e-4 0.6967878 0.7173093 4.7902e-4 0.6967548 0.7171839 -0.01930916 0.6966164 0.7172966 4.83989e-4 0.696768 0.7071188 -5.83166e-4 0.7070946 0.7071146 7.75022e-4 0.7070986 0.7071058 7.75318e-4 0.7071074 0.7071059 7.74923e-4 0.7071073 0.7071187 7.74966e-4 0.7070944 0.7071212 7.7514e-4 0.707092 -0.7071068 0 -0.7071068 0.7069368 7.75149e-4 0.7072762 0.705967 7.76032e-4 0.7082443 0.7071051 7.75719e-4 0.7071081 0 0 0 0.7071065 7.76453e-4 0.7071065 0.7070886 7.76462e-4 0.7071247 0.721166 8.01515e-5 0.6927623 0.7211694 8.0206e-5 0.6927587 0.7212906 7.59509e-5 0.6926325 0.7211627 8.04693e-5 0.6927657 0.7211754 8.03843e-5 0.6927524 0.7211731 -4.29085e-5 0.6927549 0.7211796 8.214e-5 0.6927481 0.720338 -0.0237118 0.6932179 0.721165 8.07544e-5 0.6927632 0.7211701 8.08454e-5 0.692758 0.7070949 2.98906e-4 0.7071187 0.7070853 -7.80583e-4 0.7071279 0.7071413 0.002010047 0.7070694 0.707107 4.83566e-4 0.7071064 0.707113 4.83773e-4 0.7071005 0.7070802 4.83066e-4 0.7071332 0.7071067 4.83796e-4 0.7071067 0.7075018 4.71839e-4 0.7067114 0.7071067 4.83051e-4 0.7071067 0.7071067 4.84595e-4 0.7071067 0 0 0 0.7071396 4.99176e-4 0.7070738 0.7069928 8.13849e-5 0.7072206 0.7071036 8.02628e-5 0.70711 0.7071393 8.09378e-5 0.7070742 0.7099419 4.33967e-5 0.7042604 0.7099123 4.40812e-7 0.7042902 0.7099076 2.87681e-7 0.7042949 0.7098958 0 0.7043067 0.7099142 1.28505e-7 0.7042883 0.707077 8.08747e-5 0.7071366 0.709909 -9.29672e-7 0.7042934 0.7099086 -1.13458e-6 0.704294 0.7099218 1.88157e-6 0.7042805 0.7073762 5.39406e-5 0.7068372 0.7099436 8.41712e-7 0.7042585 0.7071265 8.03675e-5 0.707087 0.7071561 8.07707e-5 0.7070574 0.7070922 8.29872e-5 0.7071213 0.7071197 7.67298e-5 0.7070939 0.7099112 4.29283e-7 0.7042912 0.7070975 8.00809e-5 0.7071161 0.7071078 3.92491e-7 0.7071058 0.7071065 3.91918e-7 0.707107 -0.7071022 -4.92835e-7 -0.7071112 -0.707107 -4.35789e-7 -0.7071065 -0.7071078 -5.15144e-7 -0.7071057 -0.7071235 -5.15142e-7 -0.7070902 -0.7071057 -2.33067e-6 -0.7071079 -0.7071062 -3.36067e-7 -0.7071074 -0.7071243 -6.50046e-7 -0.7070892 -0.7072592 -3.89844e-6 -0.7069544 -0.7071062 -5.90745e-7 -0.7071073 -0.7071067 -6.12808e-7 -0.707107 -0.7070977 -4.27487e-7 -0.707116 -0.7071072 -6.47451e-7 -0.7071064 -0.707118 -1.24876e-6 -0.7070955 -0.7071032 1.97556e-6 -0.7071103 -0.7071068 0 -0.7071068 -0.7071114 0 -0.7071022 -0.7071079 -1.81181e-6 -0.7071056 -0.7071113 -1.55354e-6 -0.7071022 -0.7071068 -6.48895e-7 -0.7071068 -0.707123 -5.47908e-7 -0.7070906 -0.7071064 -1.36546e-6 -0.7071071 -0.7046473 1.13715e-4 -0.7095577 -0.7071236 -1.21504e-6 -0.70709 -0.7071068 -6.49527e-7 -0.7071068 -0.707054 4.02542e-7 -0.7071596 -0.7071068 -8.62714e-7 -0.7071068 -0.7070735 4.67508e-7 -0.7071402 -0.7071065 -1.36548e-6 -0.7071071 -0.706853 7.83878e-6 -0.7073605 -0.7071068 -6.4892e-7 -0.7071068 -0.7070989 -1.56617e-6 -0.7071147 -0.7070559 -1.87233e-5 -0.7071576 -0.7071267 0 -0.7070869 -0.7071067 -2.07201e-6 -0.7071067 -0.7071065 -8.61315e-7 -0.707107 -0.7069206 0 -0.707293 -0.7071068 0 -0.7071068 -0.7073605 1.31425e-4 -0.706853 -0.7070878 -1.55501e-6 -0.7071258 -0.7071068 -1.58624e-6 -0.7071068 -0.7071068 -6.48965e-7 -0.7071068 -0.7071068 -4.32145e-7 -0.7071068 -0.7063623 1.20833e-5 -0.7078504 -0.7071071 -2.1888e-7 -0.7071065 -0.7071068 -4.32876e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071228 -2.82339e-7 -0.7070908 -0.707123 -2.80156e-7 -0.7070907 -0.7071595 -1.60145e-6 -0.707054 -0.7071068 -6.49177e-7 -0.7071068 -0.7071185 -7.26858e-7 -0.707095 -0.7071238 2.45437e-6 -0.7070897 -0.7070899 -9.59861e-7 -0.7071238 -0.7071226 4.9643e-6 -0.7070909 -0.707152 0 -0.7070617 -0.7071068 0 -0.7071068 -0.7071452 -6.80746e-7 -0.7070683 -0.7071247 -4.32407e-7 -0.7070888 -0.7067565 0 -0.707457 -0.7071068 -2.37646e-6 -0.7071068 -0.7070957 -1.58626e-6 -0.7071178 -0.7071068 -1.58624e-6 -0.7071068 -0.7071068 -2.16344e-7 -0.7071068 -0.7071014 -5.16869e-7 -0.7071122 -0.7071122 -2.0539e-7 -0.7071014 -0.7071068 0 -0.7071068 -0.707077 -6.49213e-7 -0.7071366 -0.7071068 -4.32849e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071164 -2.16404e-7 -0.7070971 -0.7071129 -1.76504e-7 -0.7071007 -0.7071146 -2.56817e-6 -0.707099 -0.7070875 0 -0.7071262 -0.7071083 0 -0.7071053 -0.7071014 -1.90212e-6 -0.7071122 -0.707077 -1.80025e-5 -0.7071366 -0.7071068 -1.58624e-6 -0.7071068 -0.7071099 -7.93115e-7 -0.7071038 -0.7070997 -8.65605e-7 -0.7071139 -0.7071014 -4.68492e-7 -0.7071122 -0.7070466 0 -0.7071671 -0.7071068 -6.49168e-7 -0.7071068 -0.7071068 -2.16454e-7 -0.7071068 -0.7071134 -5.53775e-7 -0.7071002 -0.7072129 3.85452e-6 -0.7070006 -0.7071123 -6.49189e-7 -0.7071013 -0.7071299 -8.87775e-6 -0.7070837 -0.7071068 0 -0.7071068 -0.7071068 6.97199e-7 -0.7071068 -0.7071122 1.44333e-6 -0.7071014 -0.7071068 -7.93118e-7 -0.7071068 -0.7071068 -7.93118e-7 -0.7071068 -0.7071264 6.04367e-7 -0.7070872 -0.7071295 6.21497e-7 -0.707084 -0.7071068 -5.38989e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071066 0 -0.7071069 -0.7071031 -6.53749e-7 -0.7071105 -0.7070349 -9.1766e-7 -0.7071785 -0.7071107 -3.99692e-7 -0.7071029 -0.7070932 -8.65357e-7 -0.7071203 -0.7071068 1.40128e-6 -0.7071068 -0.7071008 -5.9981e-7 -0.7071127 -0.707099 -7.78938e-7 -0.7071145 -0.7071068 0 -0.7071068 -0.7071295 -1.19185e-5 -0.7070841 -0.7071106 -1.31445e-6 -0.7071029 -0.7071062 -6.95615e-7 -0.7071074 -0.7071083 -7.93116e-7 -0.7071053 -0.7071055 -4.29328e-7 -0.7071081 -0.7070965 -7.72024e-7 -0.707117 -0.7071079 -1.17734e-6 -0.7071057 -0.7071007 -6.50235e-7 -0.7071129 -0.7071561 1.8992e-6 -0.7070574 -0.7071081 1.37593e-6 -0.7071055 -0.7071064 -3.99695e-7 -0.7071071 -0.7071172 -3.14993e-7 -0.7070964 -0.7071068 -9.17753e-7 -0.7071068 -0.7071068 -6.95615e-7 -0.7071068 -0.7071105 -4.93679e-7 -0.707103 -0.707109 -4.94356e-7 -0.7071045 -0.7071021 -6.45934e-7 -0.7071114 -0.707108 -4.88596e-7 -0.7071056 -0.7070997 1.68237e-6 -0.7071139 -0.7071067 -5.75367e-7 -0.7071068 -0.7071146 -2.32206e-7 -0.7070989 -0.7070952 -8.20154e-7 -0.7071183 -0.7071077 -3.6788e-7 -0.7071058 -0.7071061 -8.26052e-7 -0.7071076 -0.707109 1.36164e-7 -0.7071045 -0.7071027 0 -0.7071109 -0.7071065 3.76844e-7 -0.707107 -0.7071062 -6.33207e-7 -0.7071073 -0.7071067 -6.47494e-7 -0.707107 -0.7071068 -5.39266e-7 -0.7071068 -0.7071158 -4.32847e-7 -0.7070978 -0.7071068 -5.39426e-7 -0.7071068 -0.7071067 -6.47856e-7 -0.707107 -0.7071355 1.02279e-6 -0.7070781 -0.707041 -2.34854e-6 -0.7071726 -0.7071067 3.83518e-7 -0.7071069 -0.70703 0 -0.7071835 -0.7071393 -8.26042e-7 -0.7070743 -0.7071068 -8.62376e-7 -0.7071068 -0.7071068 -8.64403e-7 -0.7071068 -0.7071068 4.00737e-7 -0.7071068 -0.7071068 3.88802e-7 -0.7071068 -0.7070987 3.08903e-6 -0.7071148 -0.7071068 1.02711e-6 -0.7071068 -0.7071143 0 -0.7070992 -0.7071048 4.18676e-7 -0.7071087 -0.7071114 -1.0345e-6 -0.7071023 -0.7071233 0 -0.7070903 -0.7071095 -5.31079e-7 -0.707104 -0.7071096 -4.99245e-7 -0.7071041 -0.7071028 -5.51994e-7 -0.7071109 -0.7071524 1.07276e-6 -0.7070612 -0.7071068 -8.6252e-7 -0.7071068 -0.7071068 -8.62493e-7 -0.7071068 -0.7070987 -6.57351e-7 -0.7071149 -0.706942 -8.10751e-7 -0.7072715 -0.7070905 -5.91372e-7 -0.7071231 -0.7071124 -5.39431e-7 -0.7071012 -0.707135 4.12269e-7 -0.7070785 -0.7071149 -1.90193e-6 -0.7070987 -0.7070994 2.40405e-6 -0.7071141 -0.707106 -8.42177e-7 -0.7071076 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071177 -0.001721739 -0.7070937 -0.7071191 0.006651937 -0.7070633 -0.7071068 -1.0345e-6 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 -6.47712e-7 -0.7071068 -0.7071068 -5.39336e-7 -0.7071068 -0.7071122 -3.94143e-7 -0.7071014 -0.7071067 -5.39909e-7 -0.7071067 -0.7070916 -1.32104e-6 -0.707122 -0.7070946 -1.4368e-6 -0.707119 -0.7071068 -8.6216e-7 -0.7071068 -0.7071068 -1.21641e-6 -0.7071068 -0.7070963 -5.39651e-7 -0.7071173 -0.7071657 -8.11008e-7 -0.7070479 -0.7071068 -5.39436e-7 -0.7071068 -0.7071068 -5.39421e-7 -0.7071068 -0.7071042 4.70709e-7 -0.7071095 -0.7071068 -4.05285e-7 -0.7071068 -0.7071068 -1.21641e-6 -0.7071068 -0.7071083 -1.14422e-6 -0.7071053 -0.7071041 8.6717e-7 -0.7071095 -0.7071068 0 -0.7071068 -0.7071083 -1.03643e-6 -0.7071052 -0.7071189 -2.33537e-6 -0.7070947 -0.7071194 0 -0.7070941 -0.7071095 -3.62197e-7 -0.7071041 -0.7070698 -2.17191e-6 -0.7071438 -0.7070987 -7.81946e-7 -0.7071149 -0.7071126 -5.39426e-7 -0.7071011 -0.7071068 -1.21641e-6 -0.7071068 -0.707118 -6.47323e-7 -0.7070956 -0.7071169 -3.70341e-6 -0.7070967 -0.7071068 0 -0.7071068 -0.7071099 -2.6118e-7 -0.7071038 -0.7071027 -1.03643e-6 -0.707111 -0.7071096 2.8934e-7 -0.7071039 -0.7071067 -1.03642e-6 -0.7071067 -0.70721 -5.78315e-6 -0.7070036 -0.7071068 -3.24968e-7 -0.7071068 -0.7071508 -2.09734e-6 -0.7070629 -0.7071067 -6.47277e-7 -0.7071067 -0.707107 -6.46921e-7 -0.7071066 -0.7071364 -1.67376e-6 -0.7070772 -0.7071068 -3.1789e-7 -0.7071068 -0.7070338 0 -0.7071798 -0.7071068 -8.63464e-7 -0.7071068 -0.707097 0 -0.7071166 -0.7070987 -2.36628e-6 -0.7071149 -0.7071068 0 -0.7071068 -0.7071122 4.98621e-7 -0.7071014 -0.7070987 -3.33858e-6 -0.7071149 -0.7071073 -2.00057e-6 -0.7071063 -0.707109 -1.03642e-6 -0.7071045 -0.7071084 -5.20581e-7 -0.7071052 -0.707112 3.52416e-7 -0.7071015 -0.7071152 -8.04988e-7 -0.7070984 -0.7071065 -3.79275e-7 -0.7071071 -0.7071081 -1.38981e-6 -0.7071055 -0.7070846 6.47449e-7 -0.707129 -0.7071079 -3.3945e-7 -0.7071057 -0.7071068 0 -0.7071068 -0.7071071 -3.18415e-7 -0.7071065 -0.7071069 -3.1789e-7 -0.7071067 -0.7071068 0 -0.7071068 -0.7071078 -3.61241e-7 -0.7071058 -0.7071079 0 -0.7071056 -0.7071087 -1.02614e-6 -0.7071049 -0.7071065 -4.7712e-7 -0.7071071 -0.6912856 0.2103408 0.6912893 -0.4786194 0.7361019 0.4786202 -0.1013849 0.9896678 0.1013837 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.1925806 0.962198 -0.1925817 0.419377 0.8051363 -0.4193785 0.6368716 -0.4345108 -0.6368635 0.5090725 -0.6940503 -0.5090572 0.1883646 -0.9638658 -0.1883653 -0.00605911 -0.9999633 0.00605911 -0.02794915 -0.9990673 0.03291589 -0.006942629 -0.999303 0.03667992 0.03836226 -0.9992232 0.009015262 0.04342377 -0.999025 -0.007970571 0.02401846 -0.9996657 -0.009572684 0.001110613 -0.9999994 -4.63763e-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.1821449 -0.9662536 0.1821459 -0.5224954 -0.6737909 0.5224981 0.7071052 0 -0.7071084 -0.7071059 1.43842e-7 0.7071077 -0.6799221 -0.274605 0.679925 0.6952258 0.1825323 -0.6952288 0.6964952 -0.1725873 -0.696497 0.5293532 -0.663 -0.5293545 0.1238292 -0.9845468 -0.1238297 0.1234626 -0.9846389 -0.123463 0.1238292 -0.9845468 -0.1238297 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.232125 -0.9445822 0.2321256 -0.4743033 -0.7416613 0.4743153 -0.4743787 -0.7415716 0.47438 -0.4743068 -0.7416632 0.4743089 -0.6581356 0.3656675 0.6581373 -0.5561605 0.6175405 0.5561738 -0.5562157 0.6174508 0.5562181 -0.5561656 0.6175405 0.5561685 -0.2271821 0.9469826 0.2271831 0.007288217 0.9999468 -0.007282078 -1.84615e-4 1 -1.84619e-4 0.03724908 0.9985979 -0.03761541 -0.00114113 0.9999987 -0.001141011 -0.00114113 0.9999987 -0.001141011 -0.001141071 0.9999987 -0.001141071 0.02562355 0.9992816 -0.02792507 -0.001832127 0.9999967 -0.001832067 -0.01983803 0.9996722 0.01617765 -0.001371383 0.9999982 -0.001371383 -0.03277277 0.9990108 0.03005623 -5.52092e-4 0.9999997 -5.52092e-4 -2.2859e-5 1 -2.28557e-5 -0.02108424 0.999578 0.0199806 -2.28574e-5 1 -2.28574e-5 -9.61196e-4 0.9999991 9.12841e-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.21949 0.950604 -0.2194905 0.2194791 0.9506089 -0.21948 0.2199785 0.9503782 -0.2199791 0.5677012 0.5961778 -0.5677036 0.7071049 -1.44498e-7 -0.7071086 -0.707105 1.40886e-7 0.7071087 -0.6799203 -0.2746107 0.6799244 0.6952269 0.1825307 -0.6952281 0.6964942 -0.1725894 -0.6964976 0.5293487 -0.6630069 -0.5293503 0.1240458 -0.9844928 -0.1240429 0.1236308 -0.9845972 -0.1236279 0.1239386 -0.9845195 -0.123938 0.1238494 -0.9845419 -0.1238487 0.1243875 -0.9844064 -0.1243864 0.1236956 -0.9845808 -0.1236944 0.1238427 -0.9845439 -0.1238397 0.1238558 -0.9845401 -0.1238564 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2321527 -0.9445689 0.2321525 -0.2323763 -0.9444583 0.2323786 -0.232143 -0.9445732 0.2321442 -0.4742231 -0.7417725 0.4742214 -0.4743296 -0.7416307 0.4743366 -0.4743687 -0.7415831 0.474372 -0.4742518 -0.7417331 0.4742544 -0.474341 -0.7416182 0.4743448 -0.6581335 0.3656722 0.6581369 -0.5563507 0.6171757 0.5563884 -0.5563457 0.6172178 0.5563467 -0.5561933 0.6174818 0.5562061 -0.556199 0.6174818 0.5562005 -0.227307 0.9469161 0.2273352 -0.2273175 0.9469177 0.2273182 -0.2271912 0.9469785 0.2271915 0.7071068 0 0.7071068 -1.84617e-4 1 -1.84617e-4 -1.84617e-4 1 -1.84617e-4 -1.84617e-4 0.9999999 -1.84617e-4 0.03719604 0.9986017 -0.03756505 -0.001141071 0.9999988 -0.001141071 -0.001141071 0.9999988 -0.001141071 -0.001141071 0.9999986 -0.001141071 0.02571934 0.9992765 -0.02801609 -0.001832067 0.9999966 -0.001832067 -0.001832008 0.9999967 -0.001832127 -0.01993894 0.9996688 0.01627361 -0.01983183 0.9996725 0.01616895 -0.001371383 0.9999981 -0.001371383 -0.001371383 0.999998 -0.001371443 -0.03277474 0.9990116 0.03002864 -0.002570509 0.9999934 -0.002570569 -5.53855e-4 0.9999997 -5.53846e-4 -0.02130556 0.999569 0.02019613 -7.71912e-4 0.9999994 -7.71836e-4 -2.28571e-5 1 -2.28576e-5 -2.28573e-5 1 -2.28573e-5 -8.96203e-4 0.9999992 8.51122e-4 0 1 0 -0.5000458 0.7070834 -0.4999237 -0.5000153 0.7071444 -0.4998627 -0.4999542 0.7071444 -0.4999542 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.4999848 -0.7070834 0.4999848 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2193732 0.9506579 -0.2193738 0.2194098 0.950641 -0.219411 0.2199618 0.9503858 -0.219963 0.2199589 0.9503872 -0.2199597 0.5676952 0.5961888 -0.5676982 0.7071046 -2.8089e-7 -0.7071089 0.7071043 0 -0.7071093 -0.7071064 2.13039e-7 0.7071071 -0.7071062 0 0.7071074 -0.6799207 -0.2746102 0.6799244 0.6952251 0.1825323 -0.6952294 0.6964969 -0.1725756 -0.6964982 0.6964938 -0.1725907 -0.6964977 0.7823966 -0.5982782 -0.172971 0.5295547 -0.6626783 -0.5295557 0.5293515 -0.6630017 -0.5293543 0.1238411 -0.9845439 -0.1238417 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2321376 -0.9445757 0.2321394 -0.2321417 -0.9445739 0.2321429 -0.2321383 -0.9445757 0.2321387 -0.4743481 -0.7416104 0.4743498 -0.6581377 0.3656589 0.65814 -0.6581372 0.3656631 0.6581383 -0.5561817 0.6175118 0.5561845 -0.2271643 0.946993 0.2271575 -0.2271633 0.9469918 0.2271641 -0.2272011 0.9469735 0.2272023 0.0072999 0.9999467 -0.007292091 -1.83894e-4 1 -1.83894e-4 -1.84026e-4 1 -1.84026e-4 0.03730243 0.9985926 -0.0377016 -0.001159369 0.9999986 -0.001159369 0.02554714 0.9992854 -0.02785903 -0.001835405 0.9999966 -0.001835405 -0.01618361 0.9997905 0.01253449 -0.02007222 0.9996642 0.01639246 -0.001374363 0.9999982 -0.001374304 -9.40016e-4 0.9999991 -9.40016e-4 -0.0329321 0.9990017 0.03018617 -5.60875e-4 0.9999997 -5.60855e-4 -0.02137666 0.9995667 0.02023684 -3.31976e-5 1 -3.31976e-5 -6.7165e-4 0.9999996 6.37862e-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.2199133 0.9504085 -0.2199133 0.2199315 0.9503998 -0.2199329 0.5678305 0.5959334 -0.567831 0.5677852 0.5960168 -0.5677887 0.56769 0.5961981 -0.5676935 0.7071058 -2.16758e-7 -0.7071077 -0.7071062 0 0.7071074 -0.7071061 0 0.7071074 -0.6799224 -0.274584 0.6799331 -0.6799225 -0.274607 0.6799237 0.695227 0.1825274 -0.6952288 0.696496 -0.1725763 -0.696499 0.5293315 -0.6630356 -0.5293315 0.5294862 -0.6627873 -0.5294877 0.5292785 -0.6631184 -0.5292809 0.1239655 -0.9845147 -0.1239487 0.1238582 -0.9845396 -0.1238585 0.1237967 -0.984555 -0.1237969 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.7070834 0 -0.7070834 -0.4999848 -0.7070834 -0.4999848 -0.4999848 -0.7070834 -0.4999848 0 -1 0 0 -1 0 0 -1 0 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.98769e-4 -0.9999999 2.19671e-4 0 -1 0 1.04509e-5 -1 1.04507e-5 1.04508e-5 -1 1.04508e-5 1.04511e-5 -1 1.04505e-5 1.04506e-5 -1 1.04509e-5 1.0468e-5 -1 1.0468e-5 1.04803e-5 -1 1.04829e-5 1.06252e-5 -1 1.03199e-5 1.0638e-5 -1 1.03326e-5 1.04677e-5 -1 1.04683e-5 1.04875e-5 -1 1.04879e-5 1.04859e-5 -1 1.04847e-5 1.04878e-5 -1 1.04877e-5 1.06572e-5 -1 1.03119e-5 1.04876e-5 -1 1.04879e-5 1.0498e-5 -1 1.04973e-5 1.04659e-5 -1 1.05388e-5 0 -1 0 1.07333e-5 -1 1.03103e-5 -0.2321069 -0.9445953 0.2320907 -0.2322099 -0.9445405 0.2322107 -0.232173 -0.9445535 0.2321945 -0.4101719 -0.7388343 0.5346801 -0.4743285 -0.7416356 0.4743302 -0.6581349 0.3656691 0.6581373 -0.5561832 0.617509 0.5561861 -0.2267681 0.9471907 0.2267293 -0.2277638 0.9466908 0.2278165 -0.2271574 0.9469983 0.2271425 -0.2270492 0.9470548 0.2270156 -0.2272421 0.9469539 0.2272433 -0.2272419 0.946954 0.2272428 0.007369279 0.9999457 -0.007377982 -1.94103e-4 1 -1.94095e-4 0.03712004 0.9986069 -0.03750163 -0.001144409 0.9999987 -0.001144468 0.0256825 0.9992789 -0.02796953 -0.001825809 0.9999967 -0.001825511 -0.001861572 0.9999966 -0.001787662 -0.001823425 0.9999966 -0.001827418 -0.001851379 0.9999967 -0.001799106 -0.001859724 0.9999967 -0.001789689 -0.001826167 0.9999967 -0.001826047 -0.01950341 0.9996842 0.01584649 -0.02045971 0.9996488 0.01684689 -0.002476632 0.9999939 -0.002476572 -0.001388311 0.9999982 -0.001348555 -0.03290551 0.9990029 0.03017157 -5.57238e-4 0.9999997 -5.57238e-4 -0.02098101 0.9995822 0.01988184 -2.25302e-5 1 -2.25302e-5 0.2132548 0.9525479 0.2171977 0.02632272 0.999248 0.02847063 -0.1195159 0.9855657 -0.1199014 -0.004458189 0.9999867 -0.002583146 -9.46018e-4 0.9999991 9.0096e-4 0 1 0 0 1 0 0 1 0 0 1 0 -0.7070834 0 -0.7070834 -0.4999848 0.7070834 -0.4999848 -0.4999848 0.7070834 -0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2199258 0.9504024 -0.2199268 0.637026 -0.06867724 0.7677769 0.5676472 0.5962746 -0.5676559 0.5677345 0.5961218 -0.5677293 0.5676919 0.5961965 -0.5676933 0.5677151 0.5961407 -0.5677287 0.5677098 0.5961616 -0.5677123 -0.7071068 -6.9387e-7 -0.7071068 -0.7071033 8.38722e-7 0.7071102 0.7071078 6.90708e-7 0.7071059 0.7071065 -9.07358e-7 -0.707107 0.6672647 0.3309326 0.6672641 -0.6894184 -0.2222714 -0.6894184 -0.7071065 8.92097e-7 0.7071071 -0.7071073 8.25065e-7 0.7071062 -0.7071038 8.24128e-7 0.7071098 -0.7071092 5.98721e-7 0.7071044 -0.7071049 4.8691e-7 0.7071086 -0.7071123 4.4596e-7 0.7071012 -0.7071058 9.22079e-7 0.7071077 -0.7071031 1.96172e-6 0.7071105 -0.7071056 1.01147e-6 0.707108 -0.7070664 3.34496e-6 0.7071471 -0.7071112 6.24706e-7 0.7071024 -0.707019 8.47814e-7 0.7071946 -0.7071032 1.92688e-6 0.7071105 -0.7070717 2.32574e-6 0.7071419 -0.7071035 7.97649e-7 0.7071101 -0.7071066 6.66864e-7 0.7071069 -0.7071756 -1.44183e-6 0.707038 -0.7071068 8.62987e-7 0.7071068 -0.7071068 8.63178e-7 0.7071068 -0.7071071 2.3742e-6 0.7071065 -0.7072261 -1.15307e-6 0.7069874 -0.7071068 8.63204e-7 0.7071068 -0.7071176 8.97718e-7 0.7070959 -0.7071069 7.91501e-7 0.7071067 -0.7071069 8.47708e-7 0.7071067 -0.7071068 8.63098e-7 0.7071068 -0.7071068 1.62203e-6 0.7071068 -0.7071014 5.85207e-7 0.7071122 -0.7071068 2.38829e-6 0.7071068 -0.7071068 6.99451e-7 0.7071068 -0.7071068 6.93731e-7 0.7071068 -0.7071066 6.66864e-7 0.707107 -0.7071068 6.90958e-7 0.7071068 -0.7071123 8.80123e-7 0.7071014 -0.7071067 8.63098e-7 0.7071067 -0.7070698 8.10983e-7 0.7071438 -0.7070981 1.38481e-6 0.7071155 -0.7071239 9.18041e-7 0.7070896 -0.707101 1.35355e-6 0.7071126 -0.7071676 -1.33302e-6 0.7070459 -0.7071132 8.63091e-7 0.7071005 -0.70708 -1.06237e-5 0.7071335 -0.7071005 8.10948e-7 0.7071131 -0.7071068 2.43236e-6 0.7071068 -0.7071122 -1.33867e-6 0.7071014 -0.7071126 6.90952e-7 0.7071011 -0.7071068 6.90958e-7 0.7071068 -0.7071122 5.70379e-7 0.7071014 -0.7071014 1.27618e-6 0.7071123 -0.7071068 1.62188e-6 0.7071068 -0.7071068 8.63098e-7 0.7071068 -0.7071068 6.47383e-7 0.7071068 -0.7071641 8.10875e-7 0.7070496 -0.70721 -3.35156e-6 0.7070035 -0.7071068 8.63081e-7 0.7071068 -0.7070963 6.4732e-7 0.7071172 -0.7071068 8.14195e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071177 -2.09749e-6 0.707096 -0.7070826 1.59278e-6 0.7071309 -0.7071068 0 0.7071068 -0.7071053 6.90324e-7 0.7071083 -0.7072651 0 0.7069485 -0.7071068 8.62081e-7 0.7071068 -0.7071068 8.65902e-7 0.7071068 -0.7071068 8.62724e-7 0.7071068 -0.7071068 8.62173e-7 0.7071068 -0.7071068 1.62174e-6 0.7071068 -0.7071068 8.6101e-7 0.7071068 -0.7071068 8.6307e-7 0.7071068 -0.706995 6.05304e-6 0.7072187 -0.7058497 6.0721e-5 0.7083616 -0.7071068 6.47311e-7 0.7071068 -0.707118 7.90554e-7 0.7070956 -0.7073585 0 0.7068549 -0.7071167 4.24824e-7 0.7070969 -0.7067777 6.46986e-7 0.7074357 -0.7071068 4.31095e-7 0.7071068 -0.7070959 -2.45534e-6 0.7071176 -0.7064481 8.11695e-7 0.7077649 -0.7071053 8.83039e-7 0.7071083 -0.7071038 -1.72181e-4 0.7071097 -0.70713 0.001377105 0.7070823 -0.7070825 -0.001314461 0.7071298 -0.7071068 2.36913e-4 0.7071068 -0.7071291 0.002236485 0.707081 -0.7071053 0 0.7071083 -0.7071065 1.26151e-6 0.7071071 -0.707094 5.719e-7 0.7071197 -0.7071063 7.54017e-7 0.7071073 -0.7071263 1.69931e-6 0.7070874 -0.7071068 8.59212e-7 0.7071068 -0.7071188 1.21976e-6 0.7070948 -0.7072325 5.99633e-6 0.7069811 -0.7071062 7.53478e-7 0.7071073 -0.7070769 1.11407e-6 0.7071366 -0.7071064 7.53736e-7 0.7071073 -0.7071166 8.14232e-7 0.707097 -0.7070814 -5.59549e-7 0.7071321 -0.7071178 8.10928e-7 0.7070958 -0.7071068 0 0.7071068 -0.7071068 1.38932e-6 0.7071068 -0.7070918 7.63287e-6 0.7071218 -0.7071224 6.38801e-7 0.7070911 -0.7071071 1.3147e-6 0.7071065 -0.7071083 0 0.7071053 -0.7071289 1.29455e-6 0.7070847 -0.7071052 6.51907e-7 0.7071084 -0.7071074 3.76317e-7 0.7071061 -0.7071082 8.63049e-7 0.7071053 -0.7070885 0 0.707125 -0.7071079 5.97153e-7 0.7071057 -0.7071104 1.32436e-6 0.7071032 -0.7071064 5.93737e-7 0.7071072 -0.7071064 7.53736e-7 0.7071073 -0.7071068 5.96451e-7 0.7071068 -0.7071037 8.58533e-7 0.7071098 -0.7071068 8.15645e-7 0.7071068 -0.7071052 8.9853e-6 0.7071083 -0.7074595 1.08655e-5 0.7067539 -0.7071064 8.15645e-7 0.7071073 -0.7074638 1.09813e-5 0.7067497 -0.70743 9.53915e-6 0.7067835 -0.7074647 1.12356e-5 0.7067487 -0.7074548 1.13909e-5 0.7067586 -0.7074739 1.15424e-5 0.7067395 -0.7074621 1.04041e-5 0.7067511 -0.7071055 9.4947e-7 0.707108 -0.7071078 2.45822e-7 0.7071059 -0.707368 1.07814e-5 0.7068455 -0.7148938 2.33232e-4 0.6992331 -0.7149354 2.33505e-4 0.6991905 -0.7149218 2.34275e-4 0.6992045 -0.7149274 2.34123e-4 0.6991986 -0.7149226 2.34288e-4 0.6992037 -0.7149321 2.38218e-4 0.699194 -0.7149239 2.33866e-4 0.6992023 -0.7149347 2.34971e-4 0.6991912 -0.7149233 2.34251e-4 0.699203 -0.7071037 2.35158e-4 0.7071098 -0.7071065 1.09306e-5 0.707107 -0.7071082 1.10173e-5 0.7071054 -0.7070364 9.63287e-6 0.7071771 -0.7071095 9.77961e-6 0.707104 -0.7071061 1.09245e-5 0.7071074 -0.7071071 1.0782e-5 0.7071064 -0.7071099 1.12297e-5 0.7071036 -0.7070969 1.04044e-5 0.7071167 -0.7191338 5.78156e-4 0.6948713 -0.7191492 5.78504e-4 0.6948555 -0.7191294 5.78289e-4 0.694876 -0.7191339 5.78277e-4 0.6948714 -0.719133 5.7931e-4 0.6948722 -0.7191383 5.77688e-4 0.6948667 -0.7191289 5.78455e-4 0.6948766 -0.7191236 5.7785e-4 0.6948819 -0.707096 2.33713e-4 0.7071174 -0.7071068 2.33714e-4 0.7071067 -0.7071068 2.3429e-4 0.7071068 -0.707117 2.34001e-4 0.7070965 -0.7069718 2.3116e-4 0.7072418 -0.7071066 5.78179e-4 0.7071066 -0.7071068 2.35159e-4 0.7071068 -0.7071067 2.35169e-4 0.7071067 -0.714016 7.75937e-4 0.7001289 -0.7140184 7.76185e-4 0.7001266 -0.7139598 7.77412e-4 0.7001862 -0.7141077 7.75272e-4 0.7000355 -0.7141262 7.78927e-4 0.7000166 -0.7140297 7.75698e-4 0.700115 -0.7139937 7.7678e-4 0.7001517 -0.7140188 7.7562e-4 0.7001261 -0.7140197 7.75288e-4 0.7001252 -0.7071003 5.78368e-4 0.707113 -0.7071067 5.78873e-4 0.7071067 -0.7071067 5.77953e-4 0.7071067 -0.7072457 5.78549e-4 0.7069676 -0.7071067 5.78873e-4 0.7071067 -0.7071067 5.77953e-4 0.7071067 -0.7071066 7.75664e-4 0.7071066 -0.7071094 5.78117e-4 0.707104 -0.7071365 5.78183e-4 0.7070769 -0.7070934 5.85537e-4 0.7071199 -0.6967499 4.84328e-4 0.717314 -0.696757 4.84448e-4 0.717307 -0.6979508 4.62176e-4 0.7161455 -0.6967608 4.84268e-4 0.7173035 -0.6967895 4.84228e-4 0.7172756 -0.6968801 4.8409e-4 0.7171875 -0.696769 4.84096e-4 0.7172954 -0.7072301 7.79305e-4 0.7069831 -0.7072082 7.7875e-4 0.707005 -0.7063358 7.54492e-4 0.7078766 -0.6967695 4.84459e-4 0.7172949 -0.6967858 4.90706e-4 0.7172791 -0.6967657 4.84512e-4 0.7172986 -0.6967687 4.84039e-4 0.7172957 -0.7070884 7.7548e-4 0.7071247 -0.7070945 7.7594e-4 0.7071186 -0.7071344 7.7605e-4 0.7070787 -0.7071024 7.75756e-4 0.7071108 -0.7071375 7.76535e-4 0.7070757 -0.7071139 7.75911e-4 0.7070993 -0.7072554 7.76486e-4 0.7069576 -0.7072771 7.76231e-4 0.706936 -0.7053924 7.75317e-4 0.7088167 -0.7071052 4.85399e-4 0.7071082 -0.707112 7.74401e-4 0.7071012 -0.7070997 7.79079e-4 0.7071135 -0.7071065 7.75669e-4 0.7071065 -0.6927784 8.1524e-5 0.7211505 -0.6927171 7.93854e-5 0.7212094 -0.6927269 7.9654e-5 0.7212001 -0.6927562 8.03686e-5 0.7211718 -0.6927557 8.00956e-5 0.7211723 -0.6927658 7.79437e-5 0.7211627 -0.6927663 7.87525e-5 0.7211621 -0.6930558 -4.31563e-5 0.720884 -0.6927444 8.07542e-5 0.7211833 -0.6927557 8.07822e-5 0.7211725 -0.7071068 5.5447e-4 0.7071068 -0.7071102 2.19881e-4 0.7071033 -0.7071007 5.57225e-4 0.7071127 -0.7070903 4.84874e-4 0.7071231 -0.7071067 4.84312e-4 0.7071067 -0.7071067 4.84125e-4 0.7071067 -0.7071959 4.86649e-4 0.7070174 -0.7071067 4.84125e-4 0.7071067 -0.7071068 8.16424e-5 0.7071068 -0.7071067 4.85388e-4 0.7071067 -0.7071067 4.842e-4 0.7071067 -0.7071074 4.83884e-4 0.707106 -0.7071873 8.09475e-5 0.7070264 -0.7070933 8.02801e-5 0.7071203 -0.7070999 7.98267e-5 0.7071136 -0.7042747 4.29617e-7 0.7099276 -0.7042931 1.53892e-5 0.7099093 -0.7042956 7.22056e-7 0.7099068 -0.7042908 8.36788e-7 0.7099116 -0.7042936 8.19032e-7 0.709909 -0.7071363 8.12699e-5 0.7070773 -0.7042941 -1.78187e-7 0.7099083 -0.7043144 -7.6551e-6 0.7098882 -0.7042841 1.99759e-6 0.7099183 -0.7071064 8.06224e-5 0.7071072 -0.7042884 8.77738e-7 0.7099139 -0.7071083 8.03675e-5 0.7071053 -0.7071949 8.07706e-5 0.7070186 -0.7071011 8.00801e-5 0.7071125 -0.7071065 8.13306e-5 0.707107 -0.7042915 8.39576e-7 0.7099109 -0.7071068 8.16357e-5 0.7071068 -0.7071061 8.06302e-7 0.7071076 -0.7071096 8.8383e-7 0.7071039 0.707108 -8.378e-7 -0.7071055 0.7071081 -7.40246e-7 -0.7071055 0.7071052 -7.4073e-7 -0.7071084 0.7071015 -8.58579e-7 -0.7071121 0.7071118 -2.17208e-6 -0.7071019 0.7071081 -7.73215e-7 -0.7071054 0.7071035 -8.12562e-7 -0.7071101 0.7070168 -2.89544e-6 -0.7071968 0.7071002 -1.05833e-6 -0.7071134 0.7071105 -6.75857e-7 -0.707103 0.7071112 -8.54968e-7 -0.7071024 0.7071036 -1.03139e-6 -0.7071101 0.7070995 -1.58205e-6 -0.7071141 0.7071135 1.4565e-6 -0.7071001 0.707108 -6.45096e-7 -0.7071056 0.7071068 -1.00782e-6 -0.7071068 0.7070994 6.43187e-7 -0.7071141 0.7071046 -1.3676e-6 -0.707109 0.7070987 -2.13514e-4 -0.7071148 0.7071068 -7.57323e-7 -0.7071068 0.7072114 2.48746e-6 -0.7070022 0.7070947 -1.21267e-6 -0.7071189 0.7071152 -2.58024e-7 -0.7070984 0.7071148 -8.14715e-7 -0.7070987 0.7070282 -3.67511e-6 -0.7071853 0.7070984 -8.11948e-7 -0.7071151 0.7071067 -7.57242e-7 -0.7071067 0.7070807 -1.91773e-7 -0.7071329 0.7067259 -5.40802e-7 -0.7074874 0.7071312 0 -0.7070825 0.7071068 0 -0.7071068 0.707095 -0.003306329 -0.7071109 0.7071068 -1.04372e-6 -0.7071068 0.7071068 0 -0.7071068 0.707107 -8.54973e-7 -0.7071066 0.7071068 0 -0.7071068 0.7071027 3.32831e-7 -0.7071109 0 0 0 0.7071068 0 -0.7071068 0.7071068 -1.18968e-6 -0.7071068 0.7071189 -7.86356e-7 -0.7070947 0.7071068 -1.08121e-6 -0.7071067 0.7071068 -1.04373e-6 -0.7071068 0.7071068 -8.65347e-7 -0.7071068 0.7071068 -8.65594e-7 -0.7071068 0.7071068 -1.04389e-6 -0.7071068 0.7071068 -7.57106e-7 -0.7071068 0.7070987 -5.72617e-7 -0.7071149 0.7071332 -5.90927e-7 -0.7070804 0.7071068 -8.65678e-7 -0.7071068 0.7071009 -1.12157e-6 -0.7071127 0.7071028 1.91302e-4 -0.7071108 0.7071095 0 -0.7071041 0.7070948 6.46519e-4 -0.7071185 0.7071068 0 -0.7071068 0.7071069 -1.0441e-6 -0.7071067 0.7071068 -5.40652e-7 -0.7071068 0.7071068 -5.40511e-7 -0.7071068 0.7070193 -1.04385e-6 -0.7071943 0.7071068 -1.1887e-6 -0.7071068 0.7071067 -1.18968e-6 -0.7071067 0.7071068 -1.18968e-6 -0.7071068 0 1 0 0.7071068 -5.40583e-7 -0.7071067 0.7071068 -7.57056e-7 -0.7071068 0.7071068 3.49121e-7 -0.7071068 0.7072458 -1.08188e-6 -0.7069677 0.7071067 -5.41065e-7 -0.7071067 0.7071293 0 -0.7070844 0.7070865 -8.6563e-7 -0.7071272 0.7071099 -8.85394e-7 -0.7071037 0.7071068 3.48813e-7 -0.7071068 0 -1 0 0.7071068 3.48604e-7 -0.7071068 0.7071068 -1.18979e-6 -0.7071068 0 0 0 0.7071068 -1.18968e-6 -0.7071068 0.7071045 0 -0.707109 0.7071113 -7.57402e-7 -0.7071023 0.7070987 -8.93702e-7 -0.707115 0.7071068 -6.97849e-7 -0.7071068 0.707115 -9.82394e-7 -0.7070987 0.5000153 -0.7070528 -0.5000153 0 -1 0 0.4999542 -0.7071444 -0.4999542 0.7070968 -7.22814e-7 -0.7071167 0.7071068 -6.97907e-7 -0.7071068 0 1 0 0.7071067 3.45919e-7 -0.7071067 0 1 0 0.7071045 -5.9171e-7 -0.707109 0.7071022 1.2289e-6 -0.7071114 0.7071068 0 -0.7071068 0.7071068 -1.18968e-6 -0.7071068 0.7071053 -1.52998e-6 -0.7071082 0.7071068 -8.65494e-7 -0.7071068 0.7071247 -1.08955e-6 -0.707089 0.7070538 0 -0.7071598 0.7071105 -1.10306e-6 -0.7071031 0.7071068 -5.42124e-7 -0.7071068 0.7071062 -6.11836e-7 -0.7071074 0.7071062 -6.99466e-7 -0.7071075 0.4999542 -0.7071139 -0.4999542 0 -1 0 0.4999542 -0.7071139 -0.4999848 0.7071068 -1.7433e-6 -0.7071068 0.707124 -2.41072e-6 -0.7070894 0.7071009 0 -0.7071128 0.7071046 -6.97851e-7 -0.7071091 0.707109 3.41634e-7 -0.7071046 0.7071011 -2.34754e-6 -0.7071125 0.7071128 -6.95609e-7 -0.7071007 0.707106 -1.18968e-6 -0.7071076 0.7071047 -1.22822e-6 -0.7071089 0.7070869 0 -0.7071266 0.707118 2.99312e-6 -0.7070955 0.7071044 -8.66977e-7 -0.7071092 0.7071002 -6.09483e-7 -0.7071135 0.7071072 -1.62743e-6 -0.7071064 0.7070697 -6.99502e-7 -0.707144 0.707123 -1.12091e-6 -0.7070906 0.7071365 -6.1181e-7 -0.707077 0.7069557 -6.95763e-7 -0.7072578 0.7071083 -9.01501e-7 -0.7071052 0.7071053 -8.37111e-7 -0.7071083 0.7071095 -8.37107e-7 -0.7071042 0.707105 -7.16709e-7 -0.7071086 0.7071064 1.84469e-7 -0.7071071 0.7071056 -8.6305e-7 -0.707108 0.7070797 2.56379e-7 -0.7071339 0.7071079 -5.97153e-7 -0.7071057 0.7071095 -1.69224e-6 -0.7071041 0.7071063 -8.26052e-7 -0.7071074 0.7071068 -7.53042e-7 -0.7071068 0.7071045 -6.38817e-7 -0.7071091 0.7071063 -7.53829e-7 -0.7071073 0.7071065 -1.25964e-6 -0.7071071 0.707094 -5.719e-7 -0.7071197 0.7071068 0 -0.7071068 0.7071188 -1.00436e-6 -0.7070948 0.7071068 -8.63077e-7 -0.7071068 0.707107 -8.63515e-7 -0.7071065 0.7069905 1.8315e-6 -0.7072229 0.7073686 -1.16497e-5 -0.7068449 0.7072325 -5.99633e-6 -0.7069811 0.7071062 -7.53736e-7 -0.7071073 0.7070771 -8.26086e-7 -0.7071365 0.707115 2.21087e-4 -0.7070985 0.7071068 -4.31199e-7 -0.7071068 0.7071068 -8.08128e-7 -0.7071068 0.7071026 2.02142e-7 -0.7071111 0.7070837 -0.004435479 -0.7071159 0.707116 6.9491e-4 -0.7070972 0.7071224 -6.38801e-7 -0.7070911 0.7071071 -1.3147e-6 -0.7071065 0.7071083 0 -0.7071053 0.7071068 0 -0.7071068 0.7071068 -8.62619e-7 -0.7071068 0.7071068 -8.61957e-7 -0.7071068 0.7071068 -8.6257e-7 -0.7071068 0.7071068 -1.62174e-6 -0.7071068 0.706995 -5.04713e-7 -0.7072187 0.7071067 0 -0.7071067 0.7071068 -8.62393e-7 -0.7071068 0.7070513 -8.11004e-7 -0.7071623 0.7071068 0 -0.7071068 0.7071068 -6.47316e-7 -0.7071068 0.7071068 -8.64269e-7 -0.7071067 0.7071068 0 -0.7071068 0.7071099 7.30773e-7 -0.7071037 0.7071053 -1.55909e-6 -0.7071083 0.7071094 -8.16498e-5 -0.7071042 0.7071059 -0.001610755 -0.7071059 0.7071124 8.47889e-4 -0.7071006 0.7071157 -0.003615677 -0.7070887 0.7071052 0 -0.7071084 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071008 -9.00896e-7 -0.7071128 0.7071014 -8.2574e-7 -0.7071123 0.7071122 -8.28488e-7 -0.7071014 0.7071068 -1.62174e-6 -0.7071068 0.7071068 -6.47185e-7 -0.7071068 0.7070214 3.21095e-6 -0.7071922 0 -1 0 0.7070963 -7.90858e-7 -0.7071172 0.7068712 0 -0.7073424 0.707102 -8.63104e-7 -0.7071115 0.707208 -5.69025e-6 -0.7070056 0.7071041 -1.6793e-6 -0.7071095 0.7071019 -2.36746e-6 -0.7071116 0.7071444 -8.10896e-7 -0.707069 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 -6.90958e-7 -0.7071068 0.7071068 0 -0.7071068 0.7071068 -8.62646e-7 -0.7071068 0.7071122 -8.81802e-7 -0.7071014 0.7071438 -2.57734e-6 -0.7070697 0.707096 -5.83923e-7 -0.7071177 0.7071126 -8.81643e-7 -0.7071011 0.7070754 -8.10975e-7 -0.7071382 0.7071068 -8.63098e-7 -0.7071068 0.7071068 -8.10842e-7 -0.7071068 0 -0.9999695 0 0.4999848 -0.7070834 -0.4999848 0.4999542 -0.7071444 -0.4999542 0.7071068 -8.1197e-7 -0.7071068 0.7071101 -6.90954e-7 -0.7071035 0 -1 0 0.4999848 0.7070834 -0.4999848 0.4999848 0.7070834 -0.4999848 0.7071068 -6.90958e-7 -0.7071068 0.7071068 -8.62987e-7 -0.7071068 0.7071002 -1.05776e-6 -0.7071133 0.7071071 -2.3747e-6 -0.7071065 0.7071067 -8.63098e-7 -0.7071067 0.7071176 -8.97718e-7 -0.7070959 0.7072262 1.15254e-6 -0.7069874 0.707107 -1.07178e-6 -0.7071067 0.7071069 -7.91502e-7 -0.7071067 0.7071068 -8.63673e-7 -0.7071068 0.7071025 -8.10944e-7 -0.707111 0.7071014 -5.85207e-7 -0.7071123 0.7071068 -2.43058e-6 -0.7071068 0.7071068 -6.87251e-7 -0.7071068 0.7071068 -6.93731e-7 -0.7071068 0.7071066 -6.66864e-7 -0.707107 0.7071068 -6.90958e-7 -0.7071068 0.7071061 -8.68154e-7 -0.7071075 0.7071049 -4.8691e-7 -0.7071086 0.7071094 -6.58391e-7 -0.7071041 0.7071124 -5.1473e-7 -0.7071012 0.7071058 -9.22079e-7 -0.7071077 0.7070717 -2.32574e-6 -0.7071419 0.7071299 5.95563e-7 -0.7070837 0.707104 -2.20285e-6 -0.7071096 0.7071112 -6.24706e-7 -0.7071024 0.707019 -8.47814e-7 -0.7071946 0.7071036 -2.45677e-6 -0.7071101 0.7071073 -1.01147e-6 -0.7071062 0.7070038 -7.91618e-7 -0.7072098 0.7071056 -6.67496e-7 -0.707108 0.7071048 -8.67802e-7 -0.7071089 -0.691287 0.2103427 -0.6912874 -0.4786193 0.7361028 -0.4786193 -0.1013881 0.9896669 -0.1013898 8.79129e-7 1 -8.79129e-7 8.79129e-7 1 -8.79129e-7 8.79129e-7 1 -8.79129e-7 -1.26048e-6 1 -3.01874e-6 8.79129e-7 1 -8.79129e-7 8.7913e-7 1 -8.79126e-7 -1.26049e-6 1 -3.01874e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.52097e-6 1 -6.03748e-6 1.75826e-6 1 -1.75826e-6 1.75826e-6 1 -1.75826e-6 0.1925798 0.9621987 0.1925793 0.4193777 0.8051372 0.4193763 0.6368682 -0.4345114 0.6368665 0.5090557 -0.6940643 0.5090548 0.1883645 -0.9638659 0.1883645 -0.006029188 -0.9999637 -0.006029188 -0.03293377 -0.9990655 -0.02799171 -0.03665423 -0.999304 -0.006916999 -0.02368348 -0.999439 0.02368348 -0.01773828 -0.9996852 0.01773834 -0.007212698 -0.999948 0.007212698 -3.11147e-4 -0.9999999 3.11147e-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.1821266 -0.9662608 -0.1821266 -0.5224969 -0.6737908 -0.5224969 0.7071068 4.33488e-7 0.7071068 -0.7071068 -7.19209e-7 -0.7071069 -0.6799238 -0.2746037 -0.6799238 0.6952255 0.182546 0.6952255 0.6964963 -0.1725859 0.6964963 0.5293538 -0.6630001 0.5293538 0.1238295 -0.9845468 0.1238295 0.1242119 -0.9844505 0.1242119 0.1238295 -0.9845468 0.1238295 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2321254 -0.9445822 -0.2321254 -0.4743145 -0.7416613 -0.4743041 -0.4743767 -0.7415751 -0.4743767 -0.4743093 -0.7416614 -0.4743093 -0.6581443 0.3656396 -0.6581443 -0.5561601 0.6175528 -0.5561604 -0.556159 0.6175552 -0.556159 -0.5561604 0.6175527 -0.5561604 -0.2272389 0.9469556 -0.2272389 0.007455229 0.9999445 0.007448911 1.95163e-4 1 -1.9517e-4 0.0376262 0.9985978 0.03723883 0.001151621 0.9999987 -0.001151621 0.001151621 0.9999986 -0.001151621 0.001151621 0.9999987 -0.001151621 0.02792412 0.9992816 0.02562266 0.001832008 0.9999967 -0.001832127 -0.01617753 0.9996724 -0.01983797 0.001371443 0.9999982 -0.001371383 -0.03036403 0.9989899 -0.03312206 5.6442e-4 0.9999997 -5.64381e-4 1.84617e-4 0.9999999 -1.84617e-4 -0.02018958 0.9995689 -0.02131789 2.28566e-5 1 -2.28581e-5 -8.67208e-4 0.9999992 -9.13149e-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.2201432 0.9503021 0.2201432 0.2201432 0.9503021 0.2201432 0.2199681 0.950383 0.2199681 0.5677024 0.5961778 0.5677024 0.7071068 4.33488e-7 0.7071068 -0.7071068 -2.90058e-7 -0.7071068 -0.6799225 -0.2746132 -0.6799215 0.6952264 0.1825394 0.6952264 0.6964965 -0.1725824 0.6964969 0.5293489 -0.6630069 0.5293501 0.1238782 -0.9845347 0.1238778 0.1236991 -0.9845798 0.1236987 0.1239579 -0.9845144 0.1239593 0.1238522 -0.9845409 0.1238535 0.1241171 -0.9844742 0.1241188 0.1236826 -0.9845838 0.1236826 0.1238566 -0.98454 0.1238566 0.1238399 -0.9845438 0.1238434 -1.75824e-6 -1 1.75827e-6 -1.75826e-6 -1 1.75826e-6 -1.75859e-6 -1 1.75794e-6 -1.75821e-6 -1 1.75831e-6 -1.75821e-6 -1 1.75831e-6 -1.75826e-6 -1 1.75826e-6 -1.75826e-6 -1 1.75826e-6 -1.75827e-6 -1 1.75824e-6 -1.75818e-6 -1 1.75833e-6 -1.75835e-6 -1 1.75816e-6 -1.75841e-6 -1 1.75813e-6 -1.75824e-6 -1 1.75827e-6 -1.75807e-6 -1 1.75849e-6 -1.75826e-6 -1 1.75826e-6 -1.75827e-6 -1 1.75824e-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.7070834 0 -0.7070834 0.4999542 -0.7071139 -0.4999848 0 -1 0 6.8524e-6 -1 8.46798e-6 -8.79141e-7 -1 8.79113e-7 -8.7831e-7 -1 8.79947e-7 -8.79142e-7 -1 8.79115e-7 -8.79115e-7 -1 8.79142e-7 -0.2321516 -0.9445695 -0.2321511 -0.2322641 -0.9445144 -0.2322624 -0.2321522 -0.9445695 -0.2321505 -0.4741954 -0.741802 -0.4742031 -0.4743772 -0.7415784 -0.474371 -0.4743418 -0.7416205 -0.4743405 -0.4742859 -0.7416922 -0.4742845 -0.4743524 -0.7416076 -0.4743499 -0.6581377 0.365663 -0.6581377 -0.5563378 0.6172599 -0.5563079 -0.5563228 0.6172599 -0.5563228 -0.5561689 0.6175433 -0.5561622 -0.5561655 0.6175432 -0.5561655 -0.227144 0.9469937 -0.2271749 -0.2271596 0.9469938 -0.2271596 -0.2273042 0.9469243 -0.2273042 -0.7071068 0 0.7071068 -2.77805e-4 1 2.77805e-4 1.95167e-4 1 -1.95167e-4 1.9516e-4 1 -1.95173e-4 0.03757351 0.9986018 0.03718346 0.001151621 0.9999986 -0.001151621 0.001151084 0.9999988 -0.001152157 0.001151621 0.9999987 -0.001151621 0.0280168 0.9992765 0.02572011 0.7070834 0 -0.7070834 0.492233 0.7089755 -0.5049898 0.5072177 0.7104709 -0.4877773 0.001832008 0.9999967 -0.001832127 -0.01597964 0.9996796 -0.01962971 -0.01616841 0.9996726 -0.01983141 0.001371383 0.9999981 -0.001371383 0.001371383 0.9999981 -0.001371383 -0.03034758 0.9989915 -0.03309053 5.644e-4 0.9999997 -5.644e-4 5.644e-4 0.9999997 -5.644e-4 -0.02019441 0.999569 -0.02130401 2.28573e-5 1 -2.28573e-5 2.28573e-5 1 -2.28573e-5 2.28573e-5 1 -2.28573e-5 -8.95977e-4 0.9999991 -9.43439e-4 0 1 0 0.7070834 0 -0.7070834 0.5000153 0.7071139 -0.4999542 0.4999848 0.7070834 -0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.22065 0.9500669 0.22065 0.22065 0.9500669 0.22065 0.2199922 0.950372 0.2199923 0.2199922 0.950372 0.2199922 0.5676981 0.5961861 0.5676981 0.7071068 4.68097e-7 0.7071068 0.7071077 9.49467e-7 0.7071058 -0.7071078 -7.45399e-7 -0.7071057 -0.7071077 -6.64492e-7 -0.7071058 -0.6799241 -0.2746081 -0.6799218 0.6952259 0.1825428 0.6952259 0.6964967 -0.1725925 0.6964943 0.6964969 -0.1725866 0.6964955 0.2992559 -0.6339483 0.7131308 0.5294389 -0.6628643 0.5294389 0.5293556 -0.6629988 0.5293537 0.123841 -0.9845439 0.123841 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -8.78374e-7 -1 8.78374e-7 -8.78658e-7 -1 8.78658e-7 -8.78366e-7 -1 8.78383e-7 -8.78374e-7 -1 8.78374e-7 -8.78651e-7 -1 8.78664e-7 -8.78655e-7 -1 8.78662e-7 -8.78658e-7 -1 8.78658e-7 -0.2321333 -0.9445796 -0.2321285 -0.2321463 -0.9445725 -0.232144 -0.2321417 -0.9445743 -0.2321417 -0.4743425 -0.7416205 -0.4743399 -0.6581382 0.3656617 -0.6581381 -0.6581386 0.3656631 -0.6581369 -0.5561831 0.6175131 -0.5561816 -0.2273076 0.9469274 -0.2272881 -0.2272982 0.9469274 -0.2272976 -0.2272009 0.9469739 -0.2272003 0.007466495 0.9999443 0.007458388 0 1 0 1.96295e-4 1 -1.96295e-4 0.03749924 0.9986072 0.03711438 0.001147091 0.9999986 -0.00114715 0.02805018 0.9992748 0.02574849 0.001835405 0.9999966 -0.001835405 -0.0168277 0.9996483 -0.02049726 -0.01609563 0.9996752 -0.01975983 0.001354336 0.9999982 -0.001394331 5.50393e-4 0.9999997 -5.50374e-4 -0.03018581 0.9990016 -0.03293174 5.50368e-4 0.9999997 -5.50396e-4 -0.02024728 0.9995667 -0.02136617 2.27142e-5 1 -2.27142e-5 -9.11251e-4 0.9999992 -9.59523e-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.2198331 0.9504457 0.2198325 0.2200115 0.9503632 0.2200109 0.5677801 0.5960307 0.5677792 0.5678013 0.5959891 0.5678018 0.5676918 0.5961996 0.5676903 0.7071074 7.2247e-7 0.7071062 -0.7071077 -7.19207e-7 -0.7071058 -0.7071077 -8.12557e-7 -0.7071059 -0.6799368 -0.2745752 -0.6799224 -0.6799243 -0.2746056 -0.6799225 0.6952261 0.182546 0.6952249 0.6964955 -0.17259 0.6964961 0.5293336 -0.6630312 0.529335 0.5293395 -0.6630241 0.5293381 0.5294368 -0.6628673 0.5294373 0.1238213 -0.9845503 0.1238103 0.1238772 -0.9845349 0.1238769 0.1239311 -0.9845213 0.1239308 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.5000153 -0.7070528 -0.5000153 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.7070834 0 -0.7070834 0.4495682 -0.6560259 -0.6061586 0.4999848 -0.7070834 -0.4999848 0 -1 0 -0.2320879 -0.9445964 -0.2321054 -0.2322092 -0.9445412 -0.2322086 -0.2320756 -0.9446068 -0.2320752 -0.3737348 -0.7346113 -0.566276 -0.474329 -0.7416368 -0.4743278 -0.6581374 0.3656676 -0.6581357 -0.5561875 0.6175047 -0.5561865 -0.2267217 0.9471942 -0.2267607 -0.2278079 0.9466943 -0.2277569 -0.2271144 0.9470112 -0.2271318 -0.2272483 0.946949 -0.2272576 -0.2272415 0.9469545 -0.2272411 -0.2271209 0.9470074 -0.227141 0.007378101 0.9999457 0.007369399 1.90197e-4 0.9999999 -1.98001e-4 0.03750133 0.9986069 0.03711986 0.001121461 0.9999987 -0.001167476 0.02796775 0.9992789 0.02568084 0.001825749 0.9999967 -0.001825571 0 1 0 0.001799046 0.9999966 -0.001851439 0.00179845 0.9999967 -0.001852035 0.001788854 0.9999967 -0.001860678 0.001826107 0.9999967 -0.001826107 -0.01675438 0.9996517 -0.02039176 -0.01604121 0.9996771 -0.01971006 0.001369416 0.9999981 -0.001369476 0.001348555 0.9999982 -0.001388251 -0.03017193 0.9990029 -0.03290593 5.4915e-4 0.9999997 -5.65327e-4 -0.02019596 0.9995684 -0.02133673 3.41593e-5 1 -3.51644e-5 0.1767814 0.9682387 -0.1768118 0.00228101 0.9999889 -0.00412327 -0.09552609 0.9911686 0.0919758 -0.1003741 0.9898515 0.1005929 -0.001056671 0.9999988 -0.001125991 0 1 0 0 1 0 0 1 0 0 1 0 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.2562639 -0.926725 -0.2746971 0.4999848 0.7070834 -0.4999848 0.4999848 0.7070834 -0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2199882 0.9503739 0.2199878 -0.4738413 0.20153 0.8572398 0.5677137 0.596153 0.5677172 0.5677214 0.5961359 0.5677273 0.5676955 0.5961911 0.5676955 0.5676989 0.5961802 0.5677034 0.567706 0.5961719 0.567705 0.7071062 -5.6995e-7 -0.7071074 -0.7071087 0 -0.7071048 -0.7071068 5.91239e-7 0.7071068 0.7071069 0 0.7071066 -0.6672646 0.3309314 0.6672646 0.6894178 -0.2222751 -0.6894178 -0.7071056 -1.23903e-7 -0.707108 -0.707109 0 -0.7071045 -0.7071058 0 -0.7071077 -0.707107 0 -0.7071065 -0.7071083 -1.3262e-6 -0.7071052 -0.7071093 0 -0.7071042 -0.7071064 -4.67725e-7 -0.7071073 -0.7071068 0 -0.7071068 -0.7071064 -1.44496e-7 -0.7071073 -0.7071068 0 -0.7071068 -0.7071064 -3.18413e-7 -0.7071071 -0.7072383 0 -0.7069754 -0.7071068 0 -0.7071068 -0.7070897 -1.04125e-6 -0.7071239 -0.7071068 0 -0.7071068 -0.7070877 0 -0.7071258 -0.7070036 -3.67359e-6 -0.70721 -0.7070916 -7.2532e-7 -0.707122 -0.7071041 0 -0.7071095 -0.7071069 -1.18735e-6 -0.7071066 -0.7071962 1.458e-6 -0.7070174 -0.7071149 0 -0.7070987 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071002 0 -0.7071134 -0.7071068 0 -0.7071068 -0.7071122 -1.03683e-6 -0.7071014 -0.7071014 1.0432e-6 -0.7071122 -0.7071068 -1.19328e-6 -0.7071068 -0.7070763 1.38824e-5 -0.7071372 -0.7071149 -1.26823e-6 -0.7070987 -0.7071068 0 -0.7071068 -0.7071091 -1.03642e-6 -0.7071045 -0.7071122 0 -0.7071014 -0.7071068 0 -0.7071068 -0.7070512 -1.21651e-6 -0.7071623 -0.7071068 0 -0.7071068 -0.7071154 0 -0.7070982 -0.7071126 0 -0.7071011 -0.7071982 1.99934e-6 -0.7070155 -0.7071163 0 -0.7070973 -0.7071268 -8.56804e-6 -0.7070868 -0.7071163 0 -0.7070972 -0.707109 0 -0.7071045 -0.7071041 -2.05408e-6 -0.7071095 -0.7071183 0 -0.7070952 -0.7071076 -1.03642e-6 -0.707106 -0.7071041 -3.62197e-7 -0.7071095 -0.7070987 -1.89563e-7 -0.7071149 -0.7072169 2.77647e-6 -0.7069967 -0.7070503 0 -0.7071632 -0.7071149 0 -0.7070987 -0.7070209 0 -0.7071927 -0.7071068 0 -0.7071068 -0.707113 0 -0.7071006 -0.707112 0 -0.7071015 -0.7071095 -1.39304e-6 -0.7071042 -0.7071067 0 -0.7071067 -0.7071046 1.12379e-6 -0.7071091 -0.7071095 5.25714e-7 -0.7071041 -0.7071189 -2.40274e-7 -0.7070947 -0.7070887 -3.50704e-6 -0.707125 -0.7071068 0 -0.7071068 -0.7070277 -1.03629e-6 -0.7071859 -0.707199 -2.94791e-7 -0.7070145 -0.7071292 1.03356e-6 -0.7070845 -0.7071014 -2.50636e-7 -0.7071123 -0.7071149 2.68794e-7 -0.7070987 -0.7070916 -1.31434e-6 -0.707122 -0.7070891 -1.14796e-6 -0.7071246 -0.7070993 -2.48604e-7 -0.7071142 -0.7070788 -1.62117e-6 -0.7071347 -0.7061621 -4.50315e-5 -0.7080502 -0.7080378 0 -0.7061746 -0.707118 -1.43541e-7 -0.7070956 -0.7071697 -8.10868e-7 -0.7070438 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071149 -2.84972e-6 -0.7070987 -0.7071068 0 -0.7071068 -0.7071083 0 -0.7071053 -0.7071101 -3.76646e-5 -0.7071034 -0.7071068 1.56001e-4 -0.7071068 -0.7071068 -2.75008e-4 -0.7071068 -0.707129 -0.004075586 -0.707073 -0.7070881 0.001422822 -0.7071241 -0.707109 -1.03617e-6 -0.7071045 -0.7071068 0 -0.7071068 -0.7071035 1.81162e-7 -0.7071101 -0.7071073 7.54017e-7 -0.7071063 -0.7071019 2.08814e-7 -0.7071116 -0.7071068 0 -0.7071068 -0.7071068 -2.1547e-7 -0.7071068 -0.7071067 -3.83518e-7 -0.7071069 -0.7070468 2.10379e-6 -0.7071667 -0.7071068 0 -0.7071068 -0.7072603 0 -0.7069532 -0.7071019 1.91521e-7 -0.7071117 -0.7070814 9.92556e-7 -0.7071321 -0.7071068 0 -0.7071068 -0.7071068 -3.93896e-7 -0.7071068 -0.7071068 1.0444e-6 -0.7071068 -0.7070764 -1.24797e-5 -0.7071371 -0.7070984 9.58201e-7 -0.7071152 -0.7071085 1.4047e-6 -0.7071051 -0.707106 1.03319e-6 -0.7071075 -0.7071148 -2.15757e-7 -0.7070989 -0.7071068 0 -0.7071068 -0.7071025 -1.37984e-6 -0.707111 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.707096 3.22454e-7 -0.7071174 -0.7071068 0 -0.7071068 -0.7070989 3.15762e-7 -0.7071146 -0.7070996 0 -0.7071139 -0.707109 7.22009e-7 -0.7071046 -0.7071052 0 -0.7071083 -0.7071083 -1.28785e-7 -0.7071053 -0.707109 8.97313e-6 -0.7071045 -0.706762 9.55569e-6 -0.7074515 -0.7071087 -1.28785e-7 -0.7071049 -0.7067454 1.01144e-5 -0.707468 -0.706758 9.7345e-6 -0.7074553 -0.706761 5.84997e-6 -0.7074523 -0.7067723 9.99217e-6 -0.7074411 -0.706775 9.97114e-6 -0.7074384 -0.7067489 9.79248e-6 -0.7074645 -0.7071095 0 -0.7071042 -0.7070996 -3.11137e-6 -0.7071141 -0.7068963 1.04344e-5 -0.7073172 -0.6992446 2.32403e-4 -0.7148824 -0.6991878 2.32768e-4 -0.7149381 -0.699203 2.34252e-4 -0.7149232 -0.6992133 2.32429e-4 -0.7149131 -0.6991748 2.33069e-4 -0.7149507 -0.6991842 2.41773e-4 -0.7149415 -0.6991984 2.33925e-4 -0.7149277 -0.6991908 2.34683e-4 -0.7149352 -0.6992014 2.34228e-4 -0.7149247 -0.7071083 2.33171e-4 -0.7071052 -0.7071091 9.96297e-6 -0.7071045 -0.7071231 9.22543e-6 -0.7070906 -0.7071967 8.76326e-6 -0.7070168 -0.7071122 1.37612e-5 -0.7071014 -0.7071015 1.00936e-5 -0.7071121 -0.707104 1.04342e-5 -0.7071096 -0.7070999 1.02217e-5 -0.7071137 -0.7071161 9.79249e-6 -0.7070975 -0.6948713 5.77284e-4 -0.7191338 -0.694891 5.76853e-4 -0.7191148 -0.6948904 5.7802e-4 -0.7191155 -0.6948661 5.77283e-4 -0.7191389 -0.6948707 5.77947e-4 -0.7191345 -0.694882 5.79292e-4 -0.7191236 -0.6948593 5.77478e-4 -0.7191454 -0.6949149 5.79642e-4 -0.7190917 -0.7071068 2.3328e-4 -0.7071068 -0.7071068 2.33064e-4 -0.7071067 -0.7071067 2.3429e-4 -0.7071067 -0.7071271 2.32483e-4 -0.7070864 -0.7069718 2.37419e-4 -0.7072418 -0.7071066 5.78972e-4 -0.7071066 -0.7071068 2.33177e-4 -0.7071068 -0.7071241 2.41783e-4 -0.7070894 -0.7001344 7.75474e-4 -0.7140108 -0.7001168 7.75107e-4 -0.714028 -0.7000991 7.75834e-4 -0.7140453 -0.7000594 7.7527e-4 -0.7140842 -0.7003483 7.68407e-4 -0.7138009 -0.7001327 7.75052e-4 -0.7140123 -0.7001324 7.76441e-4 -0.7140127 -0.7001289 7.75476e-4 -0.714016 -0.7001259 7.76337e-4 -0.714019 -0.7071194 5.76996e-4 -0.707094 -0.707112 5.77995e-4 -0.7071012 -0.7071067 5.79014e-4 -0.7071067 -0.7068283 5.77575e-4 -0.7073849 -0.7071066 5.78008e-4 -0.7071066 -0.7068088 5.79726e-4 -0.7074043 -0.7071066 7.75664e-4 -0.7071066 -0.7071066 5.77393e-4 -0.7071066 -0.7070769 5.78976e-4 -0.7071365 -0.7070538 5.52716e-4 -0.7071597 -0.7173373 4.82944e-4 -0.6967259 -0.717307 4.8347e-4 -0.696757 -0.7125662 3.95831e-4 -0.7016047 -0.7172661 4.83513e-4 -0.6967992 -0.7172756 4.83249e-4 -0.6967894 -0.7173405 4.84447e-4 -0.6967226 -0.7173117 4.83089e-4 -0.6967523 -0.7071065 7.75428e-4 -0.7071065 -0.7070822 7.76016e-4 -0.7071309 -0.7071066 7.75285e-4 -0.7071066 -0.7173007 4.81909e-4 -0.6967636 -0.7173025 4.81653e-4 -0.6967617 -0.717323 4.82729e-4 -0.6967407 -0.717295 4.85421e-4 -0.6967694 -0.7070945 7.75754e-4 -0.7071186 -0.7071065 7.75134e-4 -0.7071065 -0.7071058 7.75318e-4 -0.7071074 -0.7070863 7.74832e-4 -0.7071268 -0.7070654 7.75703e-4 -0.7071478 -0.7071066 7.75582e-4 -0.7071066 -0.7071066 7.75316e-4 -0.7071066 -0.7073339 7.75149e-4 -0.7068791 -0.7071066 7.75316e-4 -0.7071066 -0.7071067 4.85386e-4 -0.7071067 -0.7070958 7.73121e-4 -0.7071174 -0.7071135 7.79866e-4 -0.7070996 -0.7071065 7.75669e-4 -0.7071065 -0.7211551 7.97964e-5 -0.6927737 -0.7211585 8.034e-5 -0.6927702 -0.7211071 8.27124e-5 -0.6928235 -0.7211812 7.97229e-5 -0.6927466 -0.7211752 7.88939e-5 -0.6927527 -0.7211781 8.25117e-5 -0.6927498 -0.721172 8.0725e-5 -0.6927561 -0.7218366 3.66126e-4 -0.6920633 -0.7211652 8.00827e-5 -0.6927632 -0.7211715 8.00958e-5 -0.6927565 -0.7070948 -4.44753e-4 -0.7071186 -0.706965 -0.006812572 -0.7072157 -0.7071068 2.63185e-4 -0.7071068 -0.7071068 4.83341e-4 -0.7071068 -0.707113 4.83557e-4 -0.7071005 -0.7070801 4.84478e-4 -0.7071332 -0.7070474 4.85268e-4 -0.7071661 -0.7075024 4.73239e-4 -0.7067109 -0.7071053 7.92979e-5 -0.7071083 -0.7076138 4.85388e-4 -0.7065993 -0.7071121 4.86195e-4 -0.7071013 -0.7071059 4.83436e-4 -0.7071076 -0.7070598 8.02991e-5 -0.7071539 -0.7071105 7.97021e-5 -0.7071031 -0.7071395 8.02527e-5 -0.7070741 -0.7099401 -6.07153e-7 -0.7042623 -0.7099078 1.64509e-5 -0.7042946 -0.7099063 1.45552e-7 -0.7042963 -0.7098919 -2.01125e-7 -0.7043107 -0.7099136 0 -0.7042888 -0.7070969 8.00164e-5 -0.7071168 -0.7099077 5.81062e-7 -0.7042948 -0.7098944 -4.34187e-6 -0.7043082 -0.7099052 0 -0.7042973 -0.7071127 7.92381e-5 -0.7071009 -0.7099009 0 -0.7043015 -0.7071162 7.97262e-5 -0.7070973 -0.7071563 8.00852e-5 -0.7070572 -0.7071109 7.94185e-5 -0.7071027 -0.7071065 8.04267e-5 -0.7071071 -0.7099044 0 -0.7042979 -0.7071068 7.93033e-5 -0.7071068 -0.7071056 -1.31109e-7 -0.707108 -0.7071053 0 -0.7071082 0.7071087 0 0.7071049 0.7071053 0 0.7071082 0.7071079 0 0.7071056 0.7071034 0 0.7071102 0.7071167 1.56407e-6 0.7070969 0.7071135 0 0.7071003 0.7071114 0 0.7071021 0.7071589 -1.14149e-6 0.7070547 0.7070892 6.5109e-7 0.7071244 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7070963 2.40882e-7 0.7071173 0.7071004 1.9407e-7 0.7071132 0.7071148 -2.94407e-6 0.7070989 0.7070975 5.16085e-7 0.7071161 0.7071068 0 0.7071068 0.7071027 -1.63967e-6 0.7071109 0.7071068 0 0.7071068 0.7071144 -0.001105725 0.7070984 0.7071149 0 0.7070987 0.7072111 -3.51176e-6 0.7070024 0.7070906 3.18656e-7 0.7071229 0.70709 3.48845e-7 0.7071236 0.7071068 0 0.7071068 0.7070018 3.5339e-6 0.7072119 0.7071233 0 0.7070902 0.7071148 0 0.7070988 0.7070544 -2.99198e-7 0.7071592 0.7076138 4.32098e-7 0.7065994 0.7071392 -1.5176e-6 0.7070744 0.7070989 -2.45955e-4 0.7071147 0.7071068 0 0.7071068 0.7071194 -6.95837e-7 0.7070941 0.7071367 -2.78005e-6 0.7070769 0.7071068 0 0.7071068 0.7070137 0 0.7071999 0.7071014 -1.23802e-6 0.7071122 0 -1 0 0.4999848 -0.7070834 0.4999848 0.4999848 -0.7070834 0.4999848 0.7071164 0 0.7070971 0.7071052 0 0.7071083 0.7071068 4.32592e-7 0.7071068 0.7070903 7.17343e-7 0.7071233 0.7071596 -2.29756e-6 0.707054 0.7070902 7.18964e-7 0.7071233 0.7071068 2.16438e-7 0.7071068 0.7071068 -6.95504e-7 0.7071068 0.7071068 4.32518e-7 0.7071068 0.7071068 4.32463e-7 0.7071068 0.7071596 -2.29728e-6 0.707054 0.7071265 2.16516e-7 0.707087 0.7071186 -5.09722e-7 0.7070951 0.7071133 0.002048194 0.7070974 0.7071122 -1.31193e-6 0.7071014 0.7071144 7.88811e-4 0.7070986 0.707152 -6.97895e-7 0.7070617 0.707061 1.29209e-6 0.7071526 0.7071068 4.3247e-7 0.7071068 0.7071068 4.32409e-7 0.7071068 0.7067565 -6.9548e-7 0.7074569 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0 -1 0 0.7071307 3.71153e-7 0.7070829 0.7071068 0 0.7071068 0.7071334 -9.83241e-7 0.7070803 0.7068285 2.16657e-7 0.7073851 0.7071068 0 0.7071068 0.7071517 -6.97895e-7 0.7070619 0.7070932 2.16414e-7 0.7071204 0.7070946 -5.12249e-7 0.7071191 0.7071036 -7.62222e-7 0.70711 0 -1 0 0.7071068 -2.09468e-6 0.7071068 0.707104 -1.74503e-6 0.7071095 0 -1 0 0.707134 0 0.7070796 0.7071068 0 0.7071068 0.7071068 2.16401e-7 0.7071068 0.7071122 0 0.7071014 0.7071369 0 0.7070767 0.7071122 -3.54976e-7 0.7071014 0.4999848 -0.7070834 0.4999848 0 1 0 0.5000153 -0.7070528 0.5000153 0.7071002 -5.27859e-7 0.7071134 0.7071067 -6.97908e-7 0.7071067 0.4998932 -0.7071139 0.5000763 0 -0.9999695 0 0.4999542 -0.7071444 0.4999542 0.7071068 -1.39255e-6 0.7071068 0 -1 0 0.4999848 0.7071139 0.4999542 0.4999848 0.7070834 0.4999848 0.7071052 -7.69068e-7 0.7071082 0.7071006 -3.22056e-6 0.7071129 0.7071127 0 0.7071008 0.7071068 0 0.7071068 0.7071073 -6.11132e-7 0.7071062 0.7071295 8.53052e-7 0.7070841 0.707089 -3.31661e-7 0.7071246 0.707073 -1.67053e-6 0.7071406 0.7071068 -2.10636e-7 0.7071068 0.7071213 6.65128e-7 0.7070922 0.7072037 0 0.7070099 0.7071065 1.99847e-7 0.707107 -0.6893126 -0.2230894 -0.6892599 0.7071029 -1.78238e-6 0.7071107 0.7071198 0 0.7070937 0.7071033 -1.7009e-6 0.7071104 0.7071068 0 0.7071068 0.7071155 -3.79821e-6 0.7070981 0.7071029 5.53915e-7 0.7071108 0.7071068 0 0.7071068 0.7071083 0 0.7071052 0.7071024 2.88998e-7 0.7071112 0.7070953 -4.13882e-7 0.7071184 0.7070996 1.12761e-6 0.7071139 0.7071046 1.44499e-7 0.7071091 0.7070953 -4.10289e-7 0.7071183 0.7071118 2.13029e-6 0.7071017 0.707107 1.99847e-7 0.7071067 0.7071318 3.95721e-7 0.7070819 0.7070866 0 0.707127 0.7072079 0 0.7070057 0.7071076 0 0.7071061 0.7071068 0 0.7071068 0.7071086 0 0.707105 0.7071166 1.98293e-7 0.707097 0.7071139 -1.68237e-6 0.7070997 0.7071145 2.15756e-7 0.7070991 0.707094 -6.72407e-7 0.7071197 0.7071062 -2.98536e-7 0.7071073 0.7071046 -1.88353e-6 0.7071091 0.7071068 0 0.7071068 0.7071105 7.53038e-7 0.707103 0.707106 6.38809e-7 0.7071076 0.7070844 6.45851e-7 0.7071292 0.7071068 2.09966e-7 0.7071068 0.7070969 -3.26805e-7 0.7071166 0.7071091 -0.003253996 0.7070971 0.7071068 -2.15484e-7 0.7071068 0.7071068 0 0.7071068 0.7071124 0 0.7071012 0.707135 1.77567e-6 0.7070785 0.7070405 -1.59313e-6 0.707173 0.7071065 1.14896e-6 0.7071071 0.7071062 7.53736e-7 0.7071073 0.7070922 0 0.7071214 0.7070944 3.32274e-4 0.7071192 0.7071321 9.91033e-7 0.7070814 0.7071068 8.08128e-7 0.7071068 0.7071087 1.2497e-6 0.707105 0.7071144 -0.001091659 0.7070983 0.7071159 -7.00208e-4 0.7070972 0.7071074 6.38807e-7 0.7071062 0.7071029 8.36372e-7 0.7071107 0.707106 1.03452e-6 0.7071075 0.7070754 -0.002943813 0.7071321 0.7071122 2.23269e-7 0.7071014 0.7071096 3.63125e-7 0.7071041 0.7070987 0 0.7071148 0.7071068 0 0.7071068 0.7071068 -3.23445e-7 0.7071068 0.7071065 9.28152e-4 0.7071065 0.7070987 2.04603e-7 0.7071149 0.7071623 8.10877e-7 0.7070513 0.7071179 0.001758933 0.7070935 0.7071186 -2.15786e-7 0.7070951 0.7070785 -1.1676e-6 0.7071351 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071047 4.65006e-4 0.7071087 0.7071148 -1.17062e-5 0.7070988 0.7071026 -0.001114666 0.7071101 0.707093 -0.002832472 0.7071149 0.7071076 1.03451e-6 0.707106 0.7070895 0 0.7071241 0.7070572 0.01492607 0.7069987 0.7070978 -2.67043e-7 0.7071158 0.7071122 0 0.7071014 0.7071067 -3.23268e-7 0.7071067 0.7070916 7.06176e-7 0.707122 0.7071068 -3.24228e-7 0.7071068 0.7071068 -3.25186e-7 0.7071068 -0.440962 -0.7586291 0.4795373 0.4999848 -0.7070834 0.4999848 0.4999848 -0.7070834 0.4999848 0.7070963 -1.80157e-7 0.7071173 0.7069889 0 0.7072246 0.707102 -2.15769e-7 0.7071115 0.7072586 6.91714e-6 0.706955 0.7071068 0 0.7071068 0.7071141 -2.3333e-6 0.7070995 0.7070503 1.21651e-6 0.7071633 0.7071068 1.21707e-6 0.7071068 0.7071081 -2.6015e-7 0.7071054 0.7071068 0 0.7071068 0.7070641 1.03649e-6 0.7071495 0.7071068 0 0.7071068 0.7071152 4.02388e-7 0.7070983 0.7071014 0 0.7071122 0.7071068 0 0.7071068 0.7071122 -1.8364e-7 0.7071014 0.7071011 1.97202e-7 0.7071126 0.707154 1.21633e-6 0.7070596 0.7071022 -2.15769e-7 0.7071113 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071084 0 0.7071052 0 1 0 0.7071099 1.03642e-6 0.7071038 0.7071068 0 0.7071068 0.7071002 0 0.7071133 0.7071068 3.96047e-7 0.7071067 0.7071376 4.2221e-7 0.707076 0.7070902 2.70552e-7 0.7071233 0.7071069 3.95883e-7 0.7071067 0.7071134 0 0.7071001 0.7070583 1.18733e-6 0.7071554 0.7071113 -2.16278e-7 0.7071023 0.7071025 0 0.7071111 0.7071122 1.84469e-6 0.7071014 0.7071075 2.55849e-7 0.707106 0.7071068 1.03085e-6 0.7071068 0.7071041 2.70987e-7 0.7071095 0.7071087 1.00028e-6 0.7071048 0.7071045 0 0.707109 0.7071077 0 0.7071058 0.707113 1.8038e-6 0.7071005 0.7070871 9.20307e-7 0.7071263 0.7071092 -1.56294e-7 0.7071043 0.707104 -2.24507e-6 0.7071097 0.7071396 -1.71651e-6 0.707074 0.7070993 4.68861e-7 0.7071143 0.7071139 -2.57884e-6 0.7070997 0.7071071 -3.18413e-7 0.7071064 0.7070631 -2.11874e-7 0.7071506 0.7071074 8.0287e-7 0.7071062 0.707107 0 0.7071066 0.7070554 1.18734e-6 0.7071582 0.7071083 1.00978e-6 0.7071053 0.7071068 0 0.7071068 0.6912866 0.2103428 -0.6912878 0.4786198 0.7361012 -0.478621 0.1013851 0.9896676 -0.1013861 0 1 0 2.1396e-6 1 -2.13961e-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 4.27923e-6 1 -4.27923e-6 0 1 0 0 1 0 -0.19258 0.9621984 0.1925799 -0.4193789 0.8051351 0.4193789 -0.6368699 -0.4345036 0.6368699 -0.5090556 -0.694064 0.5090556 -0.1883448 -0.9638736 0.1883448 0 -1 0 -0.002461016 -0.9999939 -0.002461016 -0.01486349 -0.999779 -0.01486349 -0.02368175 -0.999439 -0.02368181 -0.01772612 -0.9996858 -0.01772618 -0.007242679 -0.9999479 -0.007182717 -3.23451e-4 -0.9999999 -3.23453e-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.182146 -0.9662533 -0.1821465 0.5224952 -0.6737924 -0.5224966 -0.7071065 7.22481e-7 0.707107 0.7071059 -5.03446e-7 -0.7071077 0.6799228 -0.2746087 -0.6799228 -0.695226 0.1825371 0.6952272 -0.6964946 -0.1725913 0.6964965 -0.5293841 -0.6629506 0.5293855 -0.1238366 -0.9845466 0.1238247 -0.123442 -0.9846441 0.1234423 -0.1238304 -0.9845467 0.1238307 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321254 -0.9445823 -0.2321254 0.4743088 -0.7416613 -0.4743097 0.4743713 -0.7415819 -0.4743713 0.4743123 -0.7416576 -0.4743123 0.6581357 0.3656676 -0.6581373 0.5562164 0.6174508 -0.5562174 0.5562139 0.6174548 -0.5562154 0.5561651 0.6175428 -0.5561665 0.227182 0.946983 -0.227182 -0.00737214 0.9999458 0.007361829 1.84616e-4 1 1.84619e-4 -0.03698348 0.9986164 0.03738355 0.001151621 0.9999988 0.00115168 0.00115168 0.9999986 0.001151561 0.001151621 0.9999988 0.001151621 -0.0256232 0.9992815 0.02792811 0.001833796 0.9999966 0.001833796 0.01988762 0.9996706 -0.01622474 0.001371383 0.9999982 0.001371383 0.0329647 0.9989991 -0.03023862 5.52079e-4 0.9999997 5.52107e-4 1.84612e-4 1 1.84622e-4 0.02111506 0.9995767 -0.02001136 2.28577e-5 1 2.28569e-5 9.39796e-4 0.9999991 -8.92518e-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.2199907 0.9503767 0.219973 -0.2194902 0.950604 0.2194902 -0.2199783 0.9503781 0.2199793 -0.5677009 0.5961805 0.5677009 -0.7071068 3.57978e-7 0.7071068 0.7071058 -8.63051e-7 -0.7071077 0.6799209 -0.2746152 -0.6799221 -0.6952254 0.1825394 0.6952273 -0.6964966 -0.1725838 0.6964966 -0.5293467 -0.6630104 0.529348 -0.123938 -0.9845195 0.1239386 -0.123699 -0.9845796 0.1236997 -0.1239534 -0.9845157 0.1239537 -0.1238377 -0.9845448 0.123838 -0.1242216 -0.9844481 0.1242219 -0.1237069 -0.9845777 0.1237077 -0.1238398 -0.9845447 0.1238359 -0.1238555 -0.9845403 0.1238558 0 -1 0 0 -1 0 0 -1 0 -0.4999542 0.7070834 -0.5000153 -0.4999848 -0.7070834 -0.4999848 -0.4999848 -0.7070834 -0.4999848 0 -1 0 0 -1 0 -7.66001e-6 -1 7.66003e-6 -7.66e-6 -1 7.66004e-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 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2323775 -0.9444582 -0.2323775 0.2324887 -0.9444031 -0.23249 0.2321521 -0.9445689 -0.2321531 0.4743224 -0.7416439 -0.4743232 0.4742513 -0.7417341 -0.4742534 0.4743412 -0.7416205 -0.4743412 0.4742594 -0.7417235 -0.4742619 0.4743549 -0.7416025 -0.4743556 0.658133 0.3656767 -0.6581348 0.5563223 0.6172599 -0.5563234 0.5563223 0.6172599 -0.5563234 0.5562056 0.61747 -0.5562071 0.556203 0.6174758 -0.556203 0.2273098 0.9469216 -0.2273098 0.2273098 0.9469216 -0.2273098 0.2271996 0.9469744 -0.2272 -0.007476449 0.9999442 0.007474005 -2.86598e-4 0.9999999 -2.86593e-4 1.84624e-4 1 1.84611e-4 1.84626e-4 1 1.84608e-4 -0.03719228 0.998602 0.03756141 0.001141071 0.9999988 0.001141071 0.001141071 0.9999988 0.001141071 0.001141071 0.9999988 0.001141071 -0.02550226 0.9992879 0.02780973 0.4999848 -0.7070834 0.4999848 0.5057222 0.7079378 0.4929655 0.4876857 0.7107456 0.5069125 0.001832067 0.9999967 0.001832067 0.01976519 0.9996749 -0.01610839 0.01982796 0.9996725 -0.0161733 0.001371443 0.9999982 0.001371383 0.001371383 0.9999981 0.001371443 0.6774947 -0.2463617 0.6930418 5.5386e-4 0.9999997 5.53841e-4 5.53851e-4 0.9999998 5.53851e-4 0.02130413 0.999569 -0.02019691 3.51657e-5 1 3.51646e-5 3.51647e-5 1 3.51655e-5 3.51654e-5 1 3.51648e-5 0.001098394 0.9999989 -0.00104314 0 1 0 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 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.2194537 0.9506523 0.2193179 -0.219361 0.9506637 0.2193616 -0.2199708 0.9503857 0.219954 -0.2199578 0.9503879 0.2199578 -0.5676974 0.5961861 0.5676988 -0.7071063 7.48948e-7 0.7071073 -0.7071068 1.26597e-6 0.7071068 0.7071062 -4.25941e-7 -0.7071074 0.7071068 -4.42992e-7 -0.7071068 0.6799218 -0.2746108 -0.679923 -0.6952281 0.1825258 0.6952282 -0.6964951 -0.1725857 0.6964975 -0.6964967 -0.1725831 0.6964967 -0.5293551 -0.6629987 0.5293542 -0.5293048 -0.6630769 0.5293067 -0.5293537 -0.6630016 0.5293519 -0.1238416 -0.9845439 0.1238412 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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.35638e-5 -1 1.70773e-5 0 -1 0 -1.56543e-5 -1 1.56543e-5 1.75677e-6 -1 1.75672e-6 0 -1 0 0 -1 0 0 -1 0 0.2321428 -0.9445737 -0.2321428 0.2321456 -0.9445725 -0.2321453 0.2321381 -0.9445758 -0.2321389 0.4743434 -0.7416182 -0.4743425 0.6600103 0.3656631 -0.6562598 0.6581369 0.365666 -0.6581369 0.5561851 0.617509 -0.5561842 0.2271732 0.9469872 -0.2271729 0.2271758 0.946986 -0.2271758 0.2271848 0.9469818 -0.2271844 -0.007407903 0.9999452 0.007394611 0 1 0 1.84028e-4 1 1.84024e-4 -0.03721088 0.9986002 0.03759098 0.001147091 0.9999988 0.001147091 -0.02558386 0.9992841 0.02787339 0.001824855 0.9999966 0.001824915 0.02047514 0.9996488 -0.01682651 0.01979625 0.9996736 -0.01615071 0.001383721 0.9999982 0.001343965 5.60866e-4 0.9999997 5.60866e-4 0.03305125 0.9989935 -0.03032624 5.60857e-4 0.9999997 5.60877e-4 0.02121472 0.9995729 -0.02010345 2.27141e-5 1 2.27141e-5 9.36417e-4 0.9999991 -8.89307e-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.2199092 0.9504103 0.2199091 -0.2199263 0.9504024 0.2199263 -0.5676913 0.596192 0.5676986 -0.5678015 0.595989 0.5678015 -0.5676965 0.596189 0.5676965 -0.7071068 5.77985e-7 0.7071068 0.7071072 -4.31525e-7 -0.7071063 0.7071067 -6.50046e-7 -0.7071067 0.6799141 -0.2746546 -0.679913 0.6799243 -0.2746013 -0.6799243 -0.6952273 0.1825323 0.6952273 -0.6964974 -0.1725818 0.6964961 -0.5293356 -0.663029 0.5293356 -0.5294504 -0.6628443 0.5294523 -0.5292723 -0.663131 0.5292713 -0.1238174 -0.9845503 0.1238141 -0.1238783 -0.9845345 0.1238783 -0.1237947 -0.9845556 0.1237952 0 -1 0 -1.07681e-4 -1 1.28731e-4 -1.42784e-4 -1 1.63823e-4 1.05254e-5 -1 1.05246e-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.5003204 -0.7067782 -0.5001068 -0.7070834 7.62963e-4 -0.7070834 -0.4984893 -0.70571 -0.5034028 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.4999848 0.7070834 0.4999848 0.6063112 -0.6559038 0.4495682 0.4999848 -0.7070834 0.4999848 0 -1 0 0.2320861 -0.9446015 -0.2320861 0.2321979 -0.9445419 -0.2322173 0.2321792 -0.9445535 -0.2321886 0.42164 -0.7396836 -0.5244883 0.4743374 -0.7416259 -0.4743366 0.6581394 0.365657 -0.6581394 0.5561615 0.6175507 -0.5561615 0.2275075 0.9468219 -0.227527 0.5269728 -0.4298465 0.7331656 0.2274391 0.9468547 -0.2274588 0.2272893 0.9469291 -0.2272989 0.2273532 0.9469007 -0.2273532 0.2272424 0.946954 -0.2272424 -0.007247269 0.9999474 0.00726211 1.97998e-4 1 1.902e-4 -0.03720593 0.9986006 0.03758329 9.78189e-4 0.9999986 0.001331686 -0.02568715 0.9992786 0.02797383 0.001825809 0.9999967 0.001825511 0 1 0 0.001851856 0.9999967 0.001798629 0.001851856 0.9999967 0.001798629 0.001863121 0.9999967 0.001786291 0.001826107 0.9999967 0.001826047 0.7005236 -0.1137346 0.7045077 0.02058982 0.9996439 -0.01697343 0.001369476 0.999998 0.001369416 0.001388311 0.9999982 0.001348555 0.03290712 0.9990028 -0.03017306 5.6533e-4 0.9999997 5.49144e-4 0.02110278 0.9995774 -0.01999729 2.28568e-5 1 2.22035e-5 -0.2118439 0.9531826 -0.2157894 -0.02611964 0.999259 -0.02826762 0.09901475 0.9901476 0.09901475 -0.06066763 0.9963126 -0.06066763 9.81923e-4 0.9999991 -9.36863e-4 0 1 0 0 1 0 0 1 0 0 1 0 0.5000153 -0.7070834 0.4999542 0 -0.9999695 0 0.4999848 0.7070834 0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2947478 -0.9019441 0.3155919 0.4999848 0.7070834 0.4999848 0.4999848 0.7070834 0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2199295 0.9504008 0.2199298 -0.5676531 0.5962755 0.5676491 -0.5676926 0.5961965 0.5676926 -0.5676119 0.59632 0.5676436 -0.5676926 0.5961965 0.5676926 -0.567717 0.5961539 0.567713 -0.5677171 0.5961506 0.5677161 0.7071068 9.41657e-7 0.7071068 0.7071073 -2.46681e-7 -0.7071062 -0.7071058 -1.03467e-6 -0.7071077 -0.7071127 1.4866e-7 0.7071008 -0.6672648 0.3309286 -0.667266 0.6894181 -0.2222735 0.6894181 0.7071109 -1.48677e-7 -0.7071025 0.7071041 -1.74382e-7 -0.7071095 0.7071034 0 -0.7071101 0.7071163 -5.35002e-7 -0.7070973 0.7071086 -4.86903e-7 -0.7071049 0.7071017 1.75048e-7 -0.7071118 0.7071077 -9.22085e-7 -0.7071059 0.7071087 4.82255e-7 -0.7071049 0.7071104 -1.44491e-7 -0.707103 0.7071067 -5.73094e-7 -0.7071068 0.707107 -2.12312e-7 -0.7071066 0.7071069 -2.11927e-7 -0.7071068 0.707104 2.98667e-6 -0.7071096 0.7070763 1.10726e-6 -0.7071373 0.7071079 0 -0.7071056 0.707109 0 -0.7071046 0.7071008 2.00602e-7 -0.7071127 0.7071068 0 -0.7071068 0.7071122 -5.92372e-7 -0.7071014 0.7071069 7.91106e-7 -0.7071067 0.7071665 -9.71928e-7 -0.7070472 0.7071014 -2.70807e-7 -0.7071122 0.7071178 -1.80232e-7 -0.7070957 0.7070581 7.91338e-7 -0.7071553 0.7071068 -2.11927e-7 -0.7071067 0.7071158 -4.31538e-7 -0.7070977 0.707111 -8.07538e-7 -0.7071025 0.7071014 -2.65892e-6 -0.7071121 0.7071069 7.92218e-7 -0.7071067 0.7071188 5.46595e-6 -0.7070949 0.707096 -1.00267e-6 -0.7071177 0.7071024 0 -0.7071112 0.7071068 0 -0.7071068 0.7071122 -3.34272e-7 -0.7071014 0.7070983 -4.31559e-7 -0.7071152 0.7071438 -8.10898e-7 -0.7070698 0.7071068 -2.15865e-7 -0.7071068 0 1 0 0.7071068 -2.15044e-7 -0.7071068 0.7070439 1.37618e-6 -0.7071696 0.7071112 -4.31543e-7 -0.7071022 0.7071107 2.71573e-7 -0.7071029 0 -1 0 0.4999848 -0.7071139 -0.4999542 0.4999848 -0.7070834 -0.4999848 0.7071068 -1.62217e-6 -0.7071068 0.7071035 1.50371e-6 -0.7071101 0.7071068 6.90958e-7 -0.7071068 0.7071068 0 -0.7071068 0.7071067 -4.31589e-7 -0.7071067 0.7071176 -6.58394e-7 -0.707096 0.7071068 0 -0.7071068 0.7071068 -4.31549e-7 -0.7071068 0.7071067 -4.31589e-7 -0.7071067 0.707164 -8.10875e-7 -0.7070496 0 1 0 0.7070487 0.01412606 -0.7070238 0.7070858 -4.31566e-7 -0.7071278 0.707103 -8.06014e-7 -0.7071107 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071095 1.68014e-7 -0.7071041 0.7071068 0 -0.7071068 0.7071189 -1.64771e-6 -0.7070947 0.7071068 1.38064e-6 -0.7071068 0.7070277 6.90704e-7 -0.7071859 0.7069767 -0.004502236 -0.7072225 0.7070989 1.50251e-7 -0.7071146 0.7071068 -2.15734e-7 -0.7071068 0.7071121 0 -0.7071014 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071219 -2.8143e-7 -0.7070918 0.7069948 4.68927e-6 -0.7072186 0 1 0 0.7071068 -4.31541e-7 -0.7071068 0.7071068 -4.31623e-7 -0.7071068 0.7072328 -8.10796e-7 -0.7069808 0.7071068 -3.66221e-4 -0.7071068 0.7074361 -4.30722e-7 -0.7067774 0.7070772 7.68606e-7 -0.7071365 0.7071068 0 -0.7071068 0 1 0 0.7071509 -3.72917e-6 -0.7070626 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071067 4.29566e-4 -0.7071067 0.7071067 -5.43841e-4 -0.7071067 0.7071068 6.90781e-7 -0.7071068 0.707111 -1.8963e-7 -0.7071026 0.7071133 1.45643e-7 -0.7071003 0.7071945 4.3178e-7 -0.707019 0.7071043 0.002638578 -0.7071043 0.707073 -7.55649e-7 -0.7071406 0.7071127 0 -0.7071008 0.7071068 0 -0.7071068 0.7070271 -3.30774e-6 -0.7071864 0.7070924 -4.13042e-7 -0.7071211 0.7069537 -7.53899e-7 -0.7072598 0.7070809 0.001457154 -0.7071312 0.7070561 -2.62959e-6 -0.7071574 0.7071095 -8.10937e-7 -0.7071041 0.7071068 0 -0.7071068 0.7071158 -0.002937912 -0.7070917 0.7071128 -2.07934e-6 -0.7071008 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 6.88797e-7 -0.7071068 0.7071037 -1.43846e-7 -0.70711 0.7071072 -1.29601e-7 -0.7071065 0.7071057 -5.68159e-7 -0.7071078 0.7071034 -1.43846e-7 -0.7071102 0.7070777 -1.25301e-6 -0.7071359 0.7071203 0 -0.7070932 0.7071059 3.67879e-7 -0.7071077 0.7071151 -4.13124e-7 -0.7070985 0.7071052 -7.53737e-7 -0.7071083 0.7071061 0 -0.7071076 0.7071068 -2.57572e-7 -0.7071068 0.7071061 -2.36109e-7 -0.7071076 0.7071083 -5.85249e-7 -0.7071052 0.7074634 9.85005e-6 -0.70675 0.7070496 9.7351e-6 -0.7071639 0.7074641 9.82608e-6 -0.7067493 0.7075054 1.07938e-5 -0.7067078 0.7074638 9.73637e-6 -0.7067496 0.7074785 9.69296e-6 -0.7067348 0.707448 9.45125e-6 -0.7067654 0.7074667 1.08154e-5 -0.7067466 0.7071058 3.16489e-7 -0.7071079 0.7071068 0 -0.7071068 0.7075192 1.04346e-5 -0.7066941 0.7149502 2.32843e-4 -0.6991755 0.7149301 2.32777e-4 -0.6991959 0.7149434 2.33232e-4 -0.6991823 0.714923 2.32724e-4 -0.6992031 0.7149178 2.3298e-4 -0.6992086 0.7149242 2.34312e-4 -0.699202 0.71492 2.33157e-4 -0.6992062 0.7149306 2.34232e-4 -0.6991953 0.7149225 2.33576e-4 -0.6992037 0.7071068 9.52255e-6 -0.7071068 0.707109 9.95153e-6 -0.7071045 0.7070993 9.47278e-6 -0.7071143 0.7070966 1.07105e-5 -0.707117 0.7071068 9.5178e-6 -0.7071068 0.7071022 1.10959e-5 -0.7071114 0.7071068 1.04342e-5 -0.7071067 0.7071058 9.69259e-6 -0.7071077 0.7070966 1.07105e-5 -0.707117 0.7191417 5.77491e-4 -0.6948633 0.7191492 5.77661e-4 -0.6948555 0.7191143 5.77623e-4 -0.6948917 0.7191376 5.7784e-4 -0.6948674 0.7191265 5.77404e-4 -0.6948789 0.7191385 5.77722e-4 -0.6948665 0.7191355 5.77389e-4 -0.6948696 0.7191236 5.77886e-4 -0.6948819 0.707096 2.32887e-4 -0.7071174 0.7071067 2.32956e-4 -0.7071067 0.7070613 2.33235e-4 -0.7071523 0.7071136 2.33043e-4 -0.7070999 0.7073093 2.38985e-4 -0.7069042 0.7071068 2.34366e-4 -0.7071068 0.7071022 2.34366e-4 -0.7071114 0 -1 0 0.7140134 7.74829e-4 -0.7001317 0.714028 7.74841e-4 -0.7001168 0.7137033 7.8006e-4 -0.7004477 0.7140831 7.74562e-4 -0.7000606 0.7140276 7.75047e-4 -0.700117 0.7140167 7.74767e-4 -0.7001283 0.7140244 7.74077e-4 -0.7001203 0.7140215 7.74689e-4 -0.7001234 0.7140096 7.75012e-4 -0.7001355 0.7071067 5.77466e-4 -0.7071067 0.7071039 5.7745e-4 -0.7071093 0.7071067 5.77953e-4 -0.7071067 0.7071067 5.77575e-4 -0.7071067 0.7071216 5.77502e-4 -0.7070917 0.7071067 5.77953e-4 -0.7071067 0.7071074 5.78206e-4 -0.7071059 0.66695 0.3321978 -0.66695 0.707109 5.76993e-4 -0.7071043 0.70712 5.72014e-4 -0.7070935 0.6967681 2.50059e-4 -0.7172964 0.6967754 4.82896e-4 -0.7172892 0.6967298 4.82959e-4 -0.7173334 0.6967638 4.83055e-4 -0.7173004 0.6967766 4.82889e-4 -0.7172881 0.6967263 4.82984e-4 -0.7173369 0 1 0 0.5001984 -0.7068087 -0.5001679 0 -1 0 0.4977264 -0.7052217 -0.5048677 0.7071307 7.75473e-4 -0.7070825 0.707876 7.96095e-4 -0.7063363 0.6967509 -0.001049458 -0.7173124 0.6967684 4.83105e-4 -0.7172959 0.6967424 -0.006724894 -0.7172898 0.6967687 4.8319e-4 -0.7172957 0.7071066 7.093e-4 -0.7071066 0.7071066 7.74809e-4 -0.7071066 0.7071073 7.75316e-4 -0.7071058 0.7071121 7.75178e-4 -0.707101 0.7071065 7.74809e-4 -0.7071065 0.7071285 7.74947e-4 -0.7070847 0.7064898 -0.03741908 -0.7067334 0.7070217 7.75041e-4 -0.7071914 0.7076779 7.746e-4 -0.7065348 0.7071065 7.75274e-4 -0.7071065 0 -1 0 0.7071031 7.76979e-4 -0.7071101 0.7071201 7.74081e-4 -0.7070931 0.6927441 7.90517e-5 -0.7211835 0.6927723 7.98121e-5 -0.7211563 0.6927268 7.74929e-5 -0.7212001 0.6927608 7.93303e-5 -0.7211675 0.6927557 7.92977e-5 -0.7211723 0.6927552 -5.41035e-5 -0.7211728 0.6927619 7.8083e-5 -0.7211664 0.6927452 2.86554e-4 -0.7211824 0.6927628 7.80031e-5 -0.7211655 0.6927558 7.86279e-5 -0.7211722 0.7070873 0.002156376 -0.707123 0.7071412 -0.001582682 -0.7070705 0.7070885 0.001009821 -0.7071244 0.7071064 4.83133e-4 -0.7071069 0.7071067 4.83125e-4 -0.7071067 0.7071067 4.83066e-4 -0.7071067 0.7070868 4.82469e-4 -0.7071267 0.7076991 4.98843e-4 -0.7065137 0.7071089 4.82335e-4 -0.7071044 0.7071093 4.83008e-4 -0.707104 0 1 0 0.6063417 -0.6558428 -0.4496597 0.5001373 -0.7068697 -0.5001373 0.7071161 4.7883e-4 -0.7070972 0.7070873 7.93206e-5 -0.7071263 0.7071089 7.91341e-5 -0.7071046 0.7070472 7.69139e-5 -0.7071663 0.7042349 4.19629e-5 -0.709967 0.7042963 -1.41773e-6 -0.7099062 0.7042874 0 -0.7099149 0.70431 -4.73965e-7 -0.7098926 0.7042895 -3.35199e-7 -0.709913 0.7071373 7.97849e-5 -0.7070764 0.7042921 5.57818e-7 -0.7099103 0.7042877 2.20381e-6 -0.7099148 0.7043014 -1.48291e-6 -0.709901 0.7068628 5.35087e-5 -0.7073507 0.7042867 0 -0.7099157 0.7071196 7.91916e-5 -0.707094 0.7071599 7.80326e-5 -0.7070537 0.707111 7.88721e-5 -0.7071027 0.7070994 7.62499e-5 -0.7071142 0.7043037 -2.82856e-7 -0.7098989 0.7071166 7.81371e-5 -0.7070969 0.7071079 -2.18221e-7 -0.7071057 0.7071067 -2.18065e-7 -0.707107 -0.7071093 1.72169e-7 0.7071042 -0.7071076 1.96342e-7 0.707106 -0.7071068 2.14644e-7 0.7071068 -0.7070992 2.14654e-7 0.7071143 -0.7071139 -1.28209e-6 0.7070996 -0.7070965 0 0.7071171 -0.7070907 -1.62493e-7 0.7071229 -0.7072592 3.89822e-6 0.7069544 -0.7071145 2.8514e-7 0.7070991 -0.7071067 3.05873e-7 0.7071068 -0.7071208 3.20586e-7 0.7070928 -0.7070989 -1.81065e-7 0.7071147 -0.7071116 1.05893e-6 0.707102 -0.707109 4.80345e-7 0.7071046 -0.7071056 3.87059e-7 0.707108 -0.7071076 6.82634e-7 0.707106 -0.7071048 8.15311e-7 0.7071089 -0.7071045 0 0.707109 -0.7071068 2.16253e-7 0.7071068 -0.7071149 2.73955e-7 0.7070987 -0.7070804 1.46307e-7 0.7071331 -0.7071068 2.15448e-7 0.7071068 -0.7071068 2.17201e-7 0.7071068 -0.7071188 5.6068e-7 0.7070948 -0.7071065 1.02425e-6 0.707107 -0.7071068 3.23466e-7 0.7071068 -0.7071151 2.79445e-7 0.7070984 -0.7071066 6.82429e-7 0.707107 -0.70698 -4.24052e-6 0.7072336 -0.7071068 0 0.7071068 -0.7071147 5.11426e-7 0.7070989 -0.7071322 -7.2675e-6 0.7070814 -0.7071167 1.04372e-6 0.7070968 -0.707109 1.14036e-6 0.7071046 -0.7071067 3.22612e-7 0.7071069 -0.7071066 6.82634e-7 0.707107 -0.7071095 9.67383e-7 0.707104 -0.7071068 1.18384e-6 0.7071068 -0.7071213 0 0.7070922 -0.7071091 0 0.7071045 -0.7071068 3.24798e-7 0.7071068 -0.7071001 -2.00409e-7 0.7071135 -0.7063623 -1.13793e-5 0.7078504 -0.7071068 2.18881e-7 0.7071068 -0.7070987 -2.44831e-7 0.7071148 -0.7070274 -1.36416e-6 0.7071862 -0.7070987 2.91363e-7 0.7071148 -0.7071108 0 0.7071027 -0.7070804 9.38889e-7 0.7071332 -0.7071266 3.47259e-7 0.707087 -0.7071068 2.1622e-7 0.7071068 -0.7070983 1.57758e-6 0.7071152 -0.7071322 -3.93148e-7 0.7070814 -0.7071186 -3.73522e-6 0.7070949 -0.7071068 0 0.7071068 -0.7071045 1.9904e-6 0.707109 -0.7071068 0 0.7071068 -0.7071067 0 0.7071068 -0.7071068 1.04374e-6 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071303 -1.52356e-7 0.7070833 -0.7070987 3.42459e-7 0.707115 -0.7071176 -1.29003e-7 0.707096 -0.7071068 0 0.7071068 -0.7071366 0 0.707077 -0.7071067 3.24215e-7 0.7071067 -0.7071068 0 0.7071068 -0.7071164 0 0.7070971 -0.7070976 7.08903e-7 0.707116 -0.7071107 1.6386e-6 0.7071029 -0.7070924 0 0.7071213 -0.7071068 0 0.7071068 -0.7071041 5.55235e-7 0.7071095 -0.7071665 -3.08835e-5 0.7070471 -0.7071136 0 0.7071 -0.7071076 0 0.7071061 -0.7071174 0 0.707096 -0.7070987 7.01043e-7 0.707115 -0.7071068 0 0.7071068 -0.7071068 2.16383e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071002 3.12146e-7 0.7071134 -0.7071599 -1.22879e-6 0.7070538 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071149 -2.5569e-6 0.7070986 -0.7071034 0 0.7071101 -0.7071068 0 0.7071068 -0.7070872 6.04399e-7 0.7071264 -0.7071182 -2.03014e-7 0.7070954 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071031 0 0.7071105 -0.7071308 -3.0597e-7 0.7070829 -0.7071191 2.99748e-7 0.7070946 -0.707127 0 0.7070865 -0.7071095 -1.11667e-6 0.7071041 -0.7071127 -5.99799e-7 0.7071009 -0.7071049 1.95675e-7 0.7071087 -0.7071061 0 0.7071076 -0.7071295 1.19185e-5 0.7070841 -0.7071126 1.58701e-6 0.7071011 -0.7071062 6.95615e-7 0.7071074 -0.7071068 0 0.7071068 -0.7071075 2.14665e-7 0.7071061 -0.7071076 2.09216e-7 0.707106 -0.7071068 0 0.7071068 -0.707109 1.44493e-7 0.7071045 -0.7071316 -8.65666e-7 0.707082 -0.7071082 3.70094e-7 0.7071053 -0.7070689 2.99841e-7 0.7071447 -0.7071248 -1.43093e-7 0.7070887 -0.707109 -3.05923e-7 0.7071046 -0.7071083 6.95613e-7 0.7071053 -0.7071068 2.14643e-7 0.7071068 -0.7071068 2.14446e-7 0.7071068 -0.7071053 1.44961e-7 0.7071082 -0.707107 0 0.7071065 -0.7071061 3.76312e-7 0.7071074 -0.7071021 1.43848e-7 0.7071115 -0.7070732 1.38846e-6 0.7071404 -0.7071203 0 0.7070932 -0.7071054 -5.59176e-7 0.7071081 -0.7070991 4.13035e-7 0.7071145 -0.7071045 -2.22814e-7 0.707109 -0.707115 0 0.7070986 -0.7071068 0 0.7071068 -0.707263 -5.59378e-7 0.7069506 -0.7071133 -1.45643e-7 0.7071003 -0.7071188 0 0.7070949 -0.7071128 1.46157e-7 0.7071008 -0.7071654 -2.08808e-6 0.7070482 -0.707073 7.55649e-7 0.7071406 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7069537 7.53899e-7 0.7072598 -0.7071064 4.13026e-7 0.7071071 -0.7070902 4.30859e-7 0.7071234 -0.7070814 1.63979e-6 0.7071321 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7070907 -5.48618e-6 0.7071229 -0.7071161 3.5762e-6 0.7070974 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 -6.89677e-7 0.7071068 -0.7071398 -9.8417e-7 0.7070739 -0.7071068 4.31285e-7 0.7071068 -0.7071123 3.51713e-7 0.7071014 -0.7070906 4.82968e-7 0.707123 -0.7071068 0 0.7071068 -0.7069949 4.31499e-7 0.7072186 -0.7070646 -8.46532e-7 0.707149 -0.7071123 3.52141e-7 0.7071014 -0.7067777 8.11318e-7 0.7074357 -0.7071068 6.47161e-7 0.7071068 -0.7071068 4.31544e-7 0.7071068 -0.7071444 -9.08476e-7 0.707069 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071148 -2.54557e-4 0.7070988 -0.7071068 0 0.7071068 -0.7071066 6.27236e-4 0.7071066 -0.7071067 -4.92164e-4 0.7071067 -0.7071052 -6.89676e-7 0.7071083 -0.7071068 -6.90932e-7 0.7071068 -0.7071068 2.15919e-7 0.7071068 -0.7070841 2.88503e-7 0.7071295 -0.7071176 -5.06061e-7 0.7070959 -0.7071067 4.31589e-7 0.7071067 -0.7070459 2.04096e-6 0.7071676 -0.7071149 -1.67838e-7 0.7070987 -0.7071068 2.16869e-7 0.7071068 -0.7051827 9.16536e-5 0.7090257 -0.7070858 4.32376e-7 0.7071278 -0.7072246 8.10805e-7 0.7069889 -0.7070692 4.31595e-7 0.7071445 -0.7070056 5.0425e-6 0.7072079 -0.7071122 1.7429e-6 0.7071014 -0.7070608 -2.24634e-5 0.7071528 -0.7071444 8.10897e-7 0.7070691 -0.7071068 0 0.7071068 -0.707123 5.9076e-6 0.7070905 -0.7070963 -6.90922e-7 0.7071173 -0.7071068 -6.90958e-7 0.7071068 -0.7071149 8.69759e-7 0.7070988 -0.7070983 5.78597e-7 0.7071152 -0.7071122 0 0.7071014 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 4.31895e-7 0.7071068 -0.7070754 8.10976e-7 0.7071382 -0.7071068 4.31549e-7 0.7071068 -0.7071169 4.91013e-6 0.7070967 -0.7071068 8.1094e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071126 -3.33317e-6 0.707101 -0.7071068 -6.90958e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071122 5.92372e-7 0.7071014 -0.7071068 0 0.7071068 -0.7071014 2.33148e-7 0.7071122 -0.7071178 1.80232e-7 0.7070957 -0.7071663 1.76403e-6 0.7070472 -0.7071112 2.11921e-7 0.7071024 -0.7070581 0 0.7071554 -0.7071185 5.60338e-7 0.707095 -0.7070872 8.10963e-7 0.7071264 -0.7071014 2.65892e-6 0.7071121 -0.7071083 0 0.7071053 -0.7071122 -3.60954e-6 0.7071014 -0.707096 9.97254e-7 0.7071177 -0.7071024 0 0.7071112 -0.7071068 0 0.7071068 -0.7071076 1.73453e-7 0.707106 -0.7071086 4.86903e-7 0.7071049 -0.7071163 5.35002e-7 0.7070973 -0.7071017 -1.75048e-7 0.7071118 -0.7071077 9.22085e-7 0.7071059 -0.7070763 -1.10726e-6 0.7071373 -0.7071058 1.35758e-7 0.7071079 -0.7071087 -4.82254e-7 0.7071049 -0.707107 2.12312e-7 0.7071066 -0.7071069 2.11927e-7 0.7071068 -0.707104 -2.98667e-6 0.7071096 -0.7071105 1.44491e-7 0.7071031 -0.707109 0 0.7071046 -0.707109 0 0.7071046 -0.7071042 1.85725e-7 0.7071095 0.6912872 0.2103444 0.6912868 0.4786206 0.7361008 0.4786206 0.1013849 0.989668 0.1013826 0 1 0 0 1 0 -2.52097e-6 1 -6.03749e-6 0 1 0 0 1 0 -1.26048e-6 1 -3.01874e-6 -1.26048e-6 1 -3.01874e-6 0 1 0 0 1 0 0 1 0 0 1 0 -1.26049e-6 1 -3.01874e-6 8.79129e-7 1 -8.79129e-7 0 1 0 -4.27923e-6 1 -4.27923e-6 -0.1925761 0.9621992 -0.1925801 -0.4193789 0.8051357 -0.4193778 -0.636866 -0.4345127 -0.6368677 -0.5090643 -0.694051 -0.5090643 -0.1883447 -0.9638737 -0.188345 0 -1 0 0.002473294 -0.9999939 -0.002473294 0.01486515 -0.9997791 -0.01486521 0.009030461 -0.9992245 -0.03832632 -0.008000314 -0.9990234 -0.04345345 -0.009585082 -0.9996659 -0.02400648 -4.46116e-4 -0.9999994 -0.001068353 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.1821467 -0.9662532 0.1821467 0.5224961 -0.673792 0.5224961 -0.7071068 -1.15597e-6 -0.7071068 0.7071068 1.00689e-6 0.7071068 0.6799204 -0.2746207 0.6799204 -0.6952246 0.1825525 -0.6952246 -0.696496 -0.1725886 -0.696496 -0.5293504 -0.6630055 -0.5293503 -0.1238378 -0.9845463 -0.1238256 -0.1242188 -0.9844487 -0.1242188 -0.1238318 -0.9845463 -0.1238318 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321241 -0.9445829 0.2321241 0.4743677 -0.7415865 0.4743677 0.4743713 -0.7415819 0.4743713 0.4743677 -0.7415865 0.4743677 0.6581426 0.3656456 0.6581426 0.5561544 0.6175634 0.5561544 0.5561544 0.6175634 0.5561544 0.5561628 0.6175482 0.5561628 0.2272389 0.9469556 0.2272389 -0.00763607 0.9999414 -0.007660925 -1.84613e-4 1 1.84621e-4 -0.03738522 0.9986163 -0.03698533 -0.001151621 0.9999986 0.001151621 -0.001151621 0.9999986 0.001151621 -0.001151621 0.9999988 0.001151621 -0.02797371 0.9992789 -0.02567487 -0.001832067 0.9999967 0.001832067 0.01622486 0.9996706 0.01988774 -0.001371443 0.999998 0.001371383 0.03020995 0.9990007 0.03293818 -5.53851e-4 0.9999997 5.53851e-4 -3.51668e-5 1 3.51634e-5 0.02033698 0.9995632 0.0214442 -3.51646e-5 1 3.51657e-5 0.001054763 0.9999988 0.001110613 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2199749 0.9503813 -0.2199687 -0.2201432 0.9503021 -0.2201432 -0.2199693 0.9503825 -0.2199693 -0.5677024 0.5961778 -0.5677024 -0.7071068 -1.00733e-6 -0.7071068 0.7071068 1.00689e-6 0.7071068 0.6799224 -0.2746108 0.6799224 -0.6952264 0.1825393 -0.6952264 -0.6964964 -0.1725852 -0.6964964 -0.5293479 -0.6630104 -0.5293468 -0.1239899 -0.9845067 -0.1239882 -0.1237412 -0.9845693 -0.1237394 -0.1239899 -0.9845067 -0.1239882 -0.1238087 -0.9845523 -0.1238069 -0.1241183 -0.9844744 -0.1241166 -0.123691 -0.9845817 -0.1236906 -0.1238033 -0.9845523 -0.1238129 -0.1238492 -0.9845419 -0.1238492 0 -1 0 0 -1 0 0 -1 0 0.5000458 0.7070223 -0.5000153 0 1 0 0.4999848 -0.7070834 -0.5000153 0 -1 0 0 -1 0 0 -1 0 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.75827e-6 -1 1.75824e-6 -1.7581e-6 -1 1.7584e-6 -1.75328e-6 -1 1.76284e-6 -1.7581e-6 -1 1.7584e-6 -1.75859e-6 -1 1.75797e-6 -1.75857e-6 -1 1.75799e-6 -1.7582e-6 -1 1.75832e-6 2.71795e-5 -1 2.71795e-5 0 -1 0 0 -1 0 -0.7070834 0 0.7070834 -0.4999848 -0.7070834 0.4999848 -0.4999848 -0.7070834 0.4999848 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2327551 -0.9442722 0.2327551 0.2327551 -0.9442722 0.2327551 0.2321399 -0.9445751 0.2321399 0.474303 -0.7416692 0.4743031 0.4742264 -0.7417659 0.4742286 0.4744852 -0.7414362 0.4744852 0.4742681 -0.7417139 0.4742681 0.4743485 -0.7416111 0.4743485 0.6581344 0.3656752 0.6581344 0.5561827 0.6175124 0.5561827 0.5561827 0.6175124 0.5561827 0.5561607 0.617552 0.5561607 0.5561607 0.6175521 0.5561607 0.2271229 0.9470113 0.2271229 0.2271229 0.9470113 0.2271229 0.2273098 0.9469216 0.2273098 -0.007473409 0.9999442 -0.007475852 -1.8462e-4 0.9999999 1.84614e-4 -1.8461e-4 1 1.84624e-4 -1.84617e-4 1 1.84617e-4 -0.03756219 0.998602 -0.03719323 -0.001141607 0.9999988 0.001140534 -0.001141607 0.9999988 0.001140534 -0.001141071 0.9999987 0.00114113 -0.02780884 0.999288 -0.02550143 -0.001832127 0.9999966 0.001832008 -0.001832067 0.9999967 0.001832067 0.01610881 0.9996748 0.01976567 0.01617252 0.9996727 0.01982718 -0.001371145 0.9999982 0.001371622 -0.001371383 0.9999982 0.001371443 -0.6908063 -0.2608937 0.6743302 -0.00257045 0.9999933 0.002570569 -5.53822e-4 0.9999997 5.53879e-4 0.02019685 0.9995691 0.02130413 -7.71902e-4 0.9999994 7.7185e-4 -2.28584e-5 1 2.28563e-5 -2.28577e-5 1 2.28569e-5 8.55943e-4 0.9999992 9.01284e-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 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.2206404 0.9501013 -0.2205116 -0.2205761 0.9501013 -0.2205761 -0.2199668 0.9503843 -0.2199641 -0.2199655 0.9503843 -0.2199655 -0.5677023 0.5961779 -0.5677023 -0.7071062 -9.36185e-7 -0.7071074 -0.7071068 -1.58245e-6 -0.7071068 0.7071068 1.06503e-6 0.7071068 0.7071064 1.32898e-6 0.7071071 0.6799224 -0.2746108 0.6799224 -0.6952266 0.1825378 -0.6952266 -0.6964957 -0.1725857 -0.6964969 -0.6964962 -0.1725893 -0.6964955 -0.5293555 -0.6629973 -0.5293555 -0.529455 -0.6628377 -0.529456 -0.5293521 -0.6630017 -0.5293536 -0.1238355 -0.9845454 -0.1238358 0 -1 0 0 -1 0 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.75713e-6 -1 1.75713e-6 -1.75713e-6 -1 1.75713e-6 -1.75678e-6 -1 1.75672e-6 -1.75715e-6 -1 1.75711e-6 2.54712e-5 -1 2.54713e-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.2321479 -0.944571 0.2321485 0.2321173 -0.944586 0.2321183 0.2321469 -0.9445716 0.2321473 0.4743428 -0.7416169 0.4743453 0.6562607 0.3656657 0.6600078 0.6581361 0.3656676 0.6581368 0.5561627 0.6175472 0.5561642 0.2273208 0.9469162 0.2273215 0.2273223 0.9469156 0.2273228 0.2271822 0.9469827 0.2271828 -0.007360875 0.9999459 -0.007347226 -1.96149e-4 1 1.9616e-4 -1.96294e-4 1 1.96296e-4 -0.03759217 0.9986003 -0.03720879 -0.001148879 0.9999988 0.001148879 -0.02791887 0.9992815 -0.02563178 -0.001824915 0.9999967 0.001824855 0.01683384 0.9996485 0.02048248 0.01615035 0.9996736 0.01979589 -0.001363813 0.9999982 0.001363813 -9.38271e-4 0.9999991 9.38271e-4 0.03032392 0.9989936 0.03304904 -5.60867e-4 0.9999998 5.60867e-4 0.02010381 0.9995729 0.0212152 -2.27139e-5 1 2.27145e-5 8.89312e-4 0.9999992 9.36424e-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.2198286 0.9504476 -0.2198287 -0.2199856 0.9503749 -0.2199859 -0.5676974 0.596192 -0.5676926 -0.5677651 0.5960585 -0.5677651 -0.5676921 0.5961965 -0.5676931 -0.7071055 -7.22462e-7 -0.707108 0.7071062 1.07881e-6 0.7071074 0.7071065 8.12558e-7 0.7071071 0.6799179 -0.2746316 0.6799185 0.6799204 -0.2746189 0.679921 -0.695226 0.1825378 -0.6952272 -0.6964955 -0.17259 -0.6964961 -0.5293345 -0.6630312 -0.529334 -0.529348 -0.6630079 -0.5293499 -0.5294281 -0.662881 -0.5294286 -0.1238234 -0.9845506 -0.1238067 -0.1238787 -0.9845344 -0.1238791 -0.1239117 -0.9845262 -0.1239122 0 -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 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.4999848 -0.7070834 0.4999848 -0.4495682 -0.6560564 0.6061586 -0.4999542 -0.7071444 0.4999542 0 -1 0 0.2323103 -0.9444916 0.2323096 0.2320737 -0.9446077 0.2320739 0.2321737 -0.9445556 0.2321856 0.485037 -0.7415025 0.4635874 0.4743716 -0.7415812 0.474372 0.6581373 0.3656627 0.6581384 0.5561607 0.6175521 0.5561607 0.2276601 0.9467543 0.2276557 -0.7213566 -0.06675666 0.689339 0.2273353 0.9469077 0.227342 0.2272539 0.9469488 0.227252 0.2271139 0.9470155 0.2271139 0.22724 0.946955 0.2272404 -0.007532656 0.9999431 -0.007553756 -1.83607e-4 1 1.83607e-4 -0.03758198 0.9986007 -0.0372045 -0.001144468 0.9999987 0.001144409 -0.02764415 0.9992967 -0.02533668 -0.001827359 0.9999967 0.001827478 -0.001789569 0.9999968 0.001863121 -0.001835644 0.9999967 0.001839637 -0.001810789 0.9999967 0.001864075 -0.001789629 0.9999967 0.001863121 -0.001827895 0.9999966 0.001827836 -0.5182663 0.6617156 0.5417865 0.01604562 0.9996771 0.01970565 -0.002466201 0.9999939 0.002466142 -0.001348495 0.9999981 0.001388311 0.030173 0.9990028 0.03290712 -5.57237e-4 0.9999997 5.57236e-4 0.020159 0.9995704 0.02127653 -2.4263e-5 1 2.42636e-5 -0.1751603 0.9688223 0.1752207 -0.002299726 0.9999888 0.004142165 -0.09259575 0.9914029 0.09244614 0.00386548 0.9999904 -0.002042293 8.87169e-4 0.9999991 9.35698e-4 0 1 0 0 1 0 0 1 0 0 1 0 -0.7070834 0 0.7070834 -0.4999848 0.7070834 0.4999848 -0.4999848 0.7070834 0.4999848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4999848 -0.7070834 0.4999848 -0.5000153 0.7070834 0.4999542 -0.4999542 0.7070834 0.5000153 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2199857 0.950375 -0.2199859 -0.56766 0.5962542 -0.5676645 -0.5676892 0.5962019 -0.5676902 -0.5676724 0.5962507 -0.5676558 -0.5676892 0.596202 -0.5676903 -0.5677044 0.5961697 -0.5677089 -0.5677099 0.5961636 -0.5677099 -0.7071061 1.23903e-7 0.7071074 0.707108 4.5139e-7 0.7071056 0.7071049 0 -0.7071086 -0.7071064 -4.77155e-7 -0.7071071 0.6672629 0.3309314 -0.6672664 -0.6894171 -0.2222757 0.6894183 0.7071084 4.73831e-7 0.7071051 0.7071087 4.73681e-7 0.707105 0.7071102 5.20101e-7 0.7071034 0.7071121 8.49001e-7 0.7071015 0.7072614 0 0.7069522 0.7071237 -9.23695e-6 0.7070899 0 1 0 0.707076 6.38079e-7 0.7071376 0.7071068 5.3589e-7 0.7071069 0.4999848 0.7070834 0.4999848 0 1 0 0.4999848 0.7070834 0.4999848 0 1 0 0.7071083 7.03591e-7 0.7071053 0 -1 0 0.7070995 6.70827e-7 0.7071142 0.7071068 6.47607e-7 0.7071068 0.7071123 3.79964e-7 0.7071014 0.7071108 5.20675e-7 0.7071027 0.5000153 -0.7070223 0.5000153 0.4525589 -0.789819 -0.4139226 0.4999848 -0.7070834 0.4999848 0.5000153 0.7070834 0.4999542 0 -1 0 0.7071068 1.21641e-6 0.7071068 0 1 0 0.5000458 0.7070834 0.4999542 0 0.9999695 0 0.4999848 0.7070834 0.4999848 0.7071067 5.39432e-7 0.7071067 0.7071098 6.50294e-7 0.7071037 0.4999848 -0.7071139 0.4999542 0 1 0 0.4999848 -0.7071139 0.4999542 0.7071821 4.06083e-7 0.7070315 0.707102 6.62685e-7 0.7071115 0.7071068 6.47541e-7 0.7071068 0.707104 5.95769e-7 0.7071095 0.4999848 -0.7070834 0.4999848 0 -1 0 0.5000458 -0.7070834 0.4999542 0 1 0 0.4999848 0.7070834 0.4999848 0 -1 0 0.5000153 0.7071139 0.4999237 0.7070987 0 0.7071149 0.7072349 6.90824e-7 0.7069787 0.7071153 4.82344e-7 0.7070984 0.7071116 -0.001910924 0.7070994 0.7071068 5.38744e-7 0.7071068 0.7071072 5.24988e-7 0.7071064 0.7071622 3.86573e-6 0.7070513 0.7071239 6.49531e-7 0.7070896 0.7070987 3.18042e-7 0.7071149 0.4999848 -0.7070834 0.4999848 0 -1 0 0.5000153 -0.7070223 0.5000153 0.7071068 1.21641e-6 0.7071067 0.7071068 8.10194e-7 0.7071068 0.7071051 1.23667e-4 0.7071084 0.7070988 0.001505553 0.7071132 0.7071091 1.03828e-6 0.7071046 0.7071893 -3.94659e-6 0.7070242 0.7071068 6.46911e-7 0.7071068 0.7071149 2.97673e-7 0.7070987 0.7070728 7.97762e-7 0.7071408 0.707115 3.23196e-7 0.7070985 0 -1 0 0.707107 7.65773e-7 0.7071066 0.7070987 -1.74124e-6 0.7071149 0.7071067 -3.96844e-4 0.7071067 0.7071083 5.15335e-7 0.7071054 0.7071062 5.95885e-7 0.7071073 0.7071077 1.42375e-6 0.7071059 0.7071036 -1.02398e-6 0.7071099 0.7071068 5.15144e-7 0.7071068 0.7071098 5.15421e-7 0.7071037 0.7068571 8.97286e-6 0.7073564 0.7070109 4.93688e-7 0.7072027 0.7067437 1.0828e-5 0.7074697 0.7067939 1.10165e-5 0.7074196 0.6992313 2.34007e-4 0.7148955 0.6991539 2.34502e-4 0.7149711 0.6991983 2.33681e-4 0.7149278 0 -1 0 0.6992098 2.33964e-4 0.7149167 0.7071464 8.41799e-6 0.7070673 0.5570238 -0.6834926 0.4716941 0 -1 0 0.4964141 -0.7082736 0.5018769 0.7071065 1.07705e-5 0.707107 0.6948533 5.77849e-4 0.7191513 0 -1 0 0.6948691 5.77082e-4 0.719136 0.694889 5.77714e-4 0.7191169 0.7071068 2.33713e-4 0.7071068 0.7071067 2.33497e-4 0.7071067 0.7071271 2.33241e-4 0.7070863 0.6948785 5.78918e-4 0.7191269 0.4981231 -0.705771 0.503708 0 1 0 0.5000458 -0.7070223 0.5000458 0.7071102 2.3562e-4 0.7071034 0.7001227 7.7512e-4 0.7140221 0.7001413 7.75108e-4 0.7140039 0.6999062 7.76283e-4 0.7142344 0 -1 0 0.7001275 7.74991e-4 0.7140174 0.7071067 5.77575e-4 0.7071067 0.7071127 5.77777e-4 0.7071006 0.4965361 0.7084262 0.5015107 0 1 0 0.4997711 0.7072359 0.4999848 0 1 0 0.7001499 7.76433e-4 0.7139955 0.707104 5.78503e-4 0.7071094 0 1 0 0.7173077 4.83026e-4 0.6967564 0 1 0 0.7172661 4.82882e-4 0.6967992 0.7172976 4.82836e-4 0.6967667 0.7070304 7.76839e-4 0.7071828 0.7172771 4.87185e-4 0.6967878 0.7173019 9.01022e-4 0.6967618 0.7173118 4.83029e-4 0.6967522 0.717277 4.82235e-4 0.696788 0.7071031 7.74872e-4 0.70711 0.7069575 7.76099e-4 0.7072557 0.7071272 7.75e-4 0.7070859 0.7071058 7.75316e-4 0.7071073 0.7069929 7.7522e-4 0.7072203 0.7172721 4.8451e-4 0.696793 0.7071119 7.78524e-4 0.7071011 0.7211935 7.96534e-5 0.6927337 0.7211585 8.03389e-5 0.6927702 0.7211664 8.03599e-5 0.6927618 0.7211755 8.1199e-5 0.6927524 0.7211772 -4.93509e-4 0.6927504 0.7211484 7.1511e-5 0.6927806 0.7071855 0.008130073 0.7069813 0.7070958 4.84085e-4 0.7071176 0.7071067 4.83795e-4 0.7071067 0.7211499 8.00179e-5 0.6927791 0.5025788 -0.7085177 0.4953459 0 -1 0 0.5001068 -0.7069308 0.5001068 0.7071067 4.84599e-4 0.7071067 0.7071204 8.05209e-5 0.7070931 0.7071126 5.85971e-5 0.7071009 0.7068342 8.79549e-5 0.7073792 0.7090213 0 -0.705187 0.7071161 8.01612e-5 0.7070975 0.7071083 8.12129e-5 0.7071053 0.7071068 4.29287e-7 0.7071067 0.7071085 4.51746e-7 0.7071051 -0.7071076 -3.61689e-7 -0.7071061 -0.7071095 -3.61364e-7 -0.7071041 -0.7071057 -4.3534e-7 -0.7071079 -0.7071137 -4.31526e-7 -0.7070999 -0.7071082 -5.88412e-7 -0.7071053 -0.7071084 -6.72279e-7 -0.7071051 -0.7071236 -5.57161e-6 -0.7070899 -0.7071205 3.17502e-6 -0.707093 -0.7071068 -6.49028e-7 -0.7071067 -0.7071312 -1.12906e-6 -0.7070824 -0.7070913 -5.47154e-7 -0.7071223 -0.7071068 -6.49129e-7 -0.7071068 -0.7070943 -4.32407e-7 -0.7071194 -0.7071239 3.37009e-6 -0.7070899 -0.7071227 3.10899e-6 -0.7070909 -0.7070897 -2.59061e-6 -0.7071239 -0.7071571 1.8559e-5 -0.7070564 -0.7071358 -4.27487e-7 -0.7070778 -0.7071122 1.23179e-6 -0.7071014 -0.7071068 -7.83883e-7 -0.7071068 -0.7070864 2.49279e-7 -0.7071273 -0.7071068 -4.32338e-7 -0.7071068 -0.7072205 -3.44972e-6 -0.706993 -0.7071068 -2.16333e-7 -0.7071068 -0.7070976 0 -0.707116 -0.7070736 0 -0.7071401 -0.7070821 -2.16394e-7 -0.7071315 -0.7071068 -6.97493e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7070896 -5.39758e-6 -0.707124 -0.7070145 -3.8472e-5 -0.7071992 -0.7070196 1.30663e-7 -0.7071939 -0.7070978 -6.37153e-6 -0.7071157 -0.7071231 2.33297e-6 -0.7070905 -0.7071176 -1.4598e-7 -0.7070959 -0.707059 -2.86803e-6 -0.7071546 -0.7071068 -4.32803e-7 -0.7071068 -0.7071068 -4.32417e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071204 -1.28309e-7 -0.7070932 -0.7071068 0 -0.7071068 -0.7071176 -2.17859e-6 -0.7070959 -0.7071123 3.235e-7 -0.7071014 -0.7071176 2.21475e-6 -0.707096 -0.7071158 -3.74388e-7 -0.7070978 -0.7071067 -2.16401e-7 -0.7071067 -0.7071176 -2.55466e-7 -0.7070959 -0.7071068 -2.16465e-7 -0.7071068 -0.7070418 -2.35623e-6 -0.7071716 -0.7071068 -8.65874e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071067 -7.84042e-7 -0.7071067 -0.7071014 -1.43711e-6 -0.7071122 -0.7071068 -6.48831e-7 -0.7071068 -0.7071112 -2.29211e-7 -0.7071024 -0.7071127 0 -0.7071008 -0.7071014 -1.74343e-7 -0.7071122 -0.7071068 -6.49387e-7 -0.7071068 -0.7071339 1.25774e-5 -0.7070797 -0.7071014 1.86635e-6 -0.7071122 -0.7071053 -4.33489e-7 -0.7071083 -0.7070993 -7.35368e-7 -0.7071142 -0.7071512 1.70372e-5 -0.7070624 -0.7071064 -5.02744e-7 -0.7071072 -0.7071083 -4.29287e-7 -0.7071052 -0.707109 -4.9368e-7 -0.7071045 -0.7071105 -4.93679e-7 -0.707103 -0.7071073 -7.91263e-7 -0.7071062 -0.7071104 0 -0.7071032 -0.7071046 1.33415e-7 -0.707109 -0.707107 -6.30242e-7 -0.7071066 -0.7071068 -5.40365e-7 -0.7071068 -0.7071041 -6.55954e-7 -0.7071095 -0.7071144 -5.92735e-7 -0.7070991 -0.7071068 -8.61828e-7 -0.7071067 -0.7071151 -8.1095e-7 -0.7070985 -0.7071067 4.45443e-7 -0.7071069 -0.7071317 -5.33725e-6 -0.7070819 -0.7071238 -5.44081e-6 -0.7070899 -0.7071068 -6.4561e-7 -0.7071068 -0.7070451 -3.29863e-6 -0.7071685 -0.7071068 -8.62588e-7 -0.7071068 -0.7071068 -8.62514e-7 -0.7071067 -0.70704 -5.69687e-7 -0.7071735 -0.7071027 -5.51828e-7 -0.7071108 -0.7071419 -1.1099e-6 -0.7070715 -0.707102 -8.10935e-7 -0.7071116 -0.7071041 6.23371e-7 -0.7071096 -0.7071051 -1.67238e-4 -0.7071085 -0.7071049 -1.01518e-4 -0.7071086 -0.7071045 -3.35431e-4 -0.707109 -0.7071587 -2.37227e-5 -0.7070548 -0.7071068 -6.46744e-7 -0.7071068 -0.7071108 -5.2643e-7 -0.7071027 -0.7071068 -5.39921e-7 -0.7071068 -0.7072992 8.64053e-6 -0.7069143 -0.7071372 2.08834e-7 -0.7070764 -0.7070989 -4.85695e-7 -0.7071147 -0.7071068 -5.39498e-7 -0.7071068 -0.7071149 -1.39067e-6 -0.7070987 -0.7071068 -4.07098e-7 -0.7071067 -0.7071068 0 -0.7071068 -0.707082 1.63655e-6 -0.7071317 -0.7071068 -3.52442e-7 -0.7071068 -0.7071273 4.41932e-7 -0.7070862 -0.707102 -8.51787e-7 -0.7071115 -0.7071068 -4.31236e-7 -0.7071068 -0.7071068 -7.55138e-7 -0.7071068 -0.707084 -1.63215e-6 -0.7071297 -0.7071014 2.62073e-6 -0.7071121 -0.7071149 -8.77815e-7 -0.7070987 -0.7071068 -6.93739e-7 -0.7071068 -0.7071068 -6.93723e-7 -0.7071068 -0.7071068 -5.4012e-7 -0.7071068 -0.7071133 -7.80463e-7 -0.7071002 -0.7070606 1.0438e-6 -0.707153 -0.707117 -8.10706e-7 -0.7070966 -0.7070872 -6.47323e-7 -0.7071264 -0.707115 7.41054e-7 -0.7070987 -0.7071098 1.41112e-6 -0.7071039 -0.7071143 1.33802e-6 -0.7070992 -0.7071097 -4.34741e-7 -0.707104 -0.7071252 -1.5854e-6 -0.7070884 -0.7072008 -7.1138e-5 -0.7070127 -0.7071644 -2.00057e-6 -0.7070491 -0.7071079 -5.20708e-7 -0.7071057 -0.691286 0.2103415 0.6912887 -0.478619 0.7361022 0.4786202 -0.1013855 0.9896675 0.101386 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.1925811 0.9621978 -0.1925818 0.4193761 0.8051369 -0.4193783 0.6368719 -0.4345104 -0.6368634 0.5090542 -0.6940648 -0.509056 0.1883637 -0.9638661 -0.1883651 0.002485632 -0.9999939 0.002485573 0.01487565 -0.9997788 0.01487565 0.02369385 -0.9994384 0.02369385 0.01773834 -0.9996854 0.01773828 0.007224977 -0.9999478 0.007224977 3.23452e-4 -1 3.23452e-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.1821449 -0.9662536 0.1821459 -0.5224954 -0.6737913 0.5224977 0.7071052 0 -0.7071083 -0.7071061 2.15763e-7 0.7071074 -0.6799222 -0.2746087 0.6799234 0.6952258 0.1825323 -0.6952288 0.6964949 -0.1725846 -0.6964979 0.5293531 -0.6630001 -0.5293545 0.1234556 -0.9846407 -0.1234561 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.232125 -0.9445823 0.2321256 -0.4743853 -0.7415751 0.474368 -0.658136 0.365663 0.6581394 -0.5562227 0.6174549 0.5562067 -0.2271811 0.9469832 0.2271817 0.007366895 0.9999458 -0.007366955 -1.84616e-4 1 -1.84619e-4 0.03728175 0.9985952 -0.03765064 -0.001141071 0.9999988 -0.001141071 0.02535039 0.9992967 -0.02763098 -0.001832067 0.9999967 -0.001832067 -0.01985973 0.9996716 0.01619678 -0.001371383 0.9999982 -0.001371383 -0.0329715 0.9989989 0.03023135 -5.52107e-4 0.9999997 -5.52079e-4 -0.02114772 0.9995755 0.02003955 -0.02111649 0.9995767 0.02000945 -2.28568e-5 1 -2.28579e-5 -9.39013e-4 0.9999991 8.93301e-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.2199785 0.9503782 -0.2199791 0.5677011 0.5961779 -0.5677036 0.7071058 0 -0.7071077 -0.7071049 1.43843e-7 0.7071087 -0.6799204 -0.2746108 0.6799244 0.6952268 0.182529 -0.6952286 0.6964941 -0.1725893 -0.6964976 0.5293487 -0.6630069 -0.5293504 0.1243786 -0.9844086 -0.1243774 0.1237721 -0.9845616 -0.1237692 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.4999848 -0.7070834 0.4999848 0.5000153 -0.7071139 0.4999237 -0.4999848 -0.7070834 -0.4999848 -0.4999848 0.7070834 -0.4999848 -0.4999848 -0.7070834 -0.4999848 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2324814 -0.9443745 0.2326139 -0.4743866 -0.741558 0.4743934 -0.4743943 -0.7415435 0.4744085 -0.474596 -0.7412899 0.4746028 -0.47434 -0.7416198 0.4743434 -0.6581356 0.3656675 0.6581373 -0.5561246 0.6176204 0.5561209 -0.5561391 0.6176204 0.5561063 -0.2272023 0.9469767 0.2271879 0.007507264 0.9999436 -0.007507264 0.007374942 0.9999458 -0.007364451 -1.84617e-4 1 -1.84617e-4 0.03719246 0.998602 -0.03756117 -0.00114113 0.9999986 -0.001141071 0.02551293 0.999288 -0.02779358 -0.001832067 0.9999967 -0.001832067 -0.01898163 0.9997028 0.01529788 -0.02002108 0.9996654 0.01637303 -0.001371383 0.9999982 -0.001371383 -0.03337311 0.9989734 0.03063321 -0.03055101 0.9989991 0.03267097 -0.02133429 0.9995678 0.02022713 -0.02066528 0.9995732 0.02064716 -2.28718e-5 1 -2.28416e-5 -2.28573e-5 1 -2.28573e-5 -9.01438e-4 0.9999992 8.55728e-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.2200471 0.9503464 -0.2200477 0.2200497 0.9503451 -0.2200508 0.567699 0.5961833 -0.5677 0.7071042 -1.49852e-7 -0.7071095 -0.7071049 -1.43841e-7 0.7071086 -0.6799208 -0.2746127 0.6799232 0.6952251 0.1825324 -0.6952295 0.6964936 -0.1725873 -0.6964986 0.5293567 -0.6629905 -0.529363 0.1238411 -0.9845439 -0.1238417 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2321663 -0.9445633 0.2321618 -0.2321385 -0.9445754 0.2321402 -0.4743466 -0.741613 0.4743474 -0.6581373 0.3656613 0.6581392 -0.5561837 0.6175088 0.5561857 -0.2271947 0.9469754 0.2272004 0.007400691 0.9999452 -0.007400751 -1.87528e-4 1 -1.80146e-4 0.03688973 0.9986245 -0.03725707 -0.001159429 0.9999986 -0.00115931 0.0256173 0.9992815 -0.02793455 -0.001835405 0.9999967 -0.001835465 -0.0205003 0.9996482 0.01683074 -0.01979732 0.9996736 0.01614874 -0.001395821 0.9999982 -0.001355946 -0.0302394 0.99902 0.03232109 -0.03277206 0.9990112 0.03004157 -0.02121961 0.9995728 0.02009844 -3.31982e-5 1 -3.31971e-5 -9.46059e-4 0.9999992 8.79666e-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.2199261 0.9504027 -0.2199255 0.5676962 0.596189 -0.5676968 0.7071059 -2.16433e-7 -0.7071077 -0.7071061 0 0.7071074 -0.6799231 -0.2746014 0.6799255 0.695227 0.1825276 -0.6952288 0.6964969 -0.1725735 -0.6964988 0.5293418 -0.6630159 -0.529346 0.5295023 -0.6627629 -0.5295023 0.5292611 -0.6631448 -0.5292653 0.1238889 -0.9845337 -0.1238743 0 -1 0 0 -1 0 0 -1 0 0.4944609 -0.708884 0.5029145 0.5000458 -0.7070223 0.5000458 0.5000458 -0.7070223 0.5000458 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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.04496e-5 -1 1.0452e-5 1.0451e-5 -1 1.04506e-5 1.04508e-5 -1 1.04508e-5 1.06127e-5 -1 1.03092e-5 1.06362e-5 -1 1.03322e-5 1.04715e-5 -1 1.0471e-5 1.06395e-5 -1 1.03359e-5 0 -1 0 1.04877e-5 -1 1.04877e-5 1.07085e-5 -1 1.02868e-5 1.05017e-5 -1 1.05017e-5 -0.2322267 -0.9445289 0.232241 -0.2320931 -0.9446025 0.2320748 -0.2320499 -0.9446203 0.2320462 -0.4844887 -0.7415422 0.4640967 -0.4743285 -0.7416356 0.4743302 -0.6581363 0.3656661 0.6581375 -0.5561853 0.617506 0.5561873 -0.2271912 0.9469785 0.2271913 -0.2271952 0.9469766 0.2271956 -0.2272346 0.9469599 0.2272254 -0.2268618 0.9471547 0.2267856 -0.2271366 0.9470086 0.2271205 0.007255196 0.9999473 -0.007255196 -1.98311e-4 1 -1.90494e-4 0.03720247 0.9986006 -0.03759026 -0.001169264 0.9999987 -0.001123189 0.02568811 0.9992785 -0.02797555 -0.001825571 0.9999967 -0.001825749 -0.001826643 0.9999966 -0.001824617 -0.001851856 0.9999967 -0.001798629 -0.001825213 0.9999966 -0.001827061 -0.01984864 0.9996717 0.01619935 -0.002525806 0.9999938 -0.002423763 -0.01853281 0.9996718 0.01768648 -0.03290766 0.9990028 0.03017348 -5.65946e-4 0.9999997 -5.49779e-4 -0.02110797 0.9995774 0.01999396 -2.28836e-5 1 -2.22273e-5 -0.09971237 0.9900076 -0.09971237 -0.2665423 0.9262346 -0.2665423 -9.84193e-4 0.9999991 9.34684e-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.2199271 0.9504019 -0.2199277 0.567663 0.5962399 -0.5676767 0.9032333 0.4126334 0.1179114 0.5678248 0.5959579 -0.567811 -0.7071068 -6.93853e-7 -0.7071068 -0.707105 8.81611e-7 0.7071085 0.7071077 6.90708e-7 0.7071058 0.7071077 -8.92096e-7 -0.7071059 0.6672663 0.330931 0.6672634 -0.6894184 -0.2222714 -0.6894184 -0.7071077 9.09171e-7 0.7071059 -0.7071047 9.0411e-7 0.7071089 -0.7071065 1.01147e-6 0.7071071 -0.7071415 -1.53595e-6 0.707072 -0.7070125 7.03777e-5 0.707201 -0.7071056 6.85698e-7 0.707108 -0.7071002 1.32066e-6 0.7071133 -0.7071067 8.62121e-7 0.7071067 -0.7070998 1.18744e-6 0.7071137 -0.7071068 8.63443e-7 0.7071068 -0.7070872 8.10963e-7 0.7071264 -0.7071071 2.53731e-6 0.7071065 -0.7071068 6.93742e-7 0.7071068 -0.7070922 1.61507e-6 0.7071214 -0.7071068 8.63119e-7 0.7071068 -0.7071068 1.07887e-6 0.7071068 -0.7069543 3.74965e-7 0.7072592 -0.7072367 -3.76372e-6 0.7069768 -0.7071068 1.07659e-6 0.7071068 -0.7071068 8.14208e-7 0.7071068 -0.7071122 2.31539e-6 0.7071014 -0.7071068 6.73752e-7 0.7071068 -0.7070959 2.67737e-6 0.7071176 -0.7070943 1.53421e-6 0.7071192 -0.7071068 8.63202e-7 0.7071068 -0.7070227 3.43439e-6 0.7071909 -0.7070214 3.73846e-7 0.7071922 -0.7071068 6.47113e-7 0.7071068 -0.7070823 1.32965e-6 0.7071313 -0.7071068 8.62965e-7 0.7071068 -0.7070944 0 0.7071192 -0.7071121 1.97189e-6 0.7071014 -0.707096 4.85619e-6 0.7071177 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 8.62358e-7 0.7071067 -0.7071068 8.62654e-7 0.7071068 -0.7071068 8.62187e-7 0.7071068 -0.7071068 4.31468e-7 0.7071068 -0.7071676 -3.92032e-7 0.7070459 -0.7071068 6.47314e-7 0.7071068 -0.7070947 9.16674e-7 0.7071188 -0.7071121 2.44256e-6 0.7071014 -0.7071121 2.44612e-6 0.7071014 -0.7071288 1.24061e-5 0.7070846 -0.7071014 5.67098e-4 0.7071118 -0.7071028 -3.70522e-4 0.7071107 -0.7071053 0 0.7071083 -0.7071079 1.26669e-6 0.7071056 -0.7070832 8.01542e-7 0.7071305 -0.7071069 8.70968e-7 0.7071065 -0.7071076 8.26051e-7 0.7071061 -0.7071068 6.46685e-7 0.7071068 -0.7070959 4.02651e-6 0.7071176 -0.707102 2.24893e-6 0.7071116 -0.7070947 4.81314e-6 0.7071188 -0.7071167 -2.73138e-6 0.7070968 -0.7071052 8.58575e-7 0.7071086 -0.7071149 8.26042e-7 0.7070988 -0.7071083 5.57034e-7 0.7071052 -0.7071073 6.38814e-7 0.7071062 -0.7071038 8.58577e-7 0.7071098 -0.7071083 8.58572e-7 0.7071052 -0.7072298 -4.70848e-5 0.7069838 -0.707457 1.0766e-5 0.7067565 -0.7074725 1.15099e-5 0.7067409 -0.7074608 9.92737e-6 0.7067526 -0.7149224 2.33694e-4 0.6992039 -0.7149024 2.34619e-4 0.6992242 -0.714934 2.34364e-4 0.6991919 -0.7149166 2.31785e-4 0.6992098 -0.7148979 -0.003876328 0.6992181 -0.7070689 1.0705e-5 0.7071447 -0.7071067 1.11848e-5 0.7071067 -0.7071034 1.13913e-5 0.7071102 -0.7191323 5.78183e-4 0.6948729 -0.7191337 5.78315e-4 0.6948714 -0.7191471 5.72993e-4 0.6948577 -0.7191359 5.78217e-4 0.6948692 -0.7071022 2.33901e-4 0.7071113 -0.7071121 2.33965e-4 0.7071013 -0.7071136 2.33872e-4 0.7070999 -0.7190732 -0.005755245 0.6949105 -0.7071041 2.35467e-4 0.7071095 -0.7071095 2.34064e-4 0.707104 -0.7140149 7.75973e-4 0.7001301 -0.7140039 7.75858e-4 0.7001413 -0.7140135 7.75593e-4 0.7001315 -0.7140242 7.745e-4 0.7001206 -0.7140195 7.75361e-4 0.7001253 -0.7071067 5.78657e-4 0.7071067 -0.7071006 5.78618e-4 0.7071127 -0.7071072 5.77953e-4 0.7071061 -0.7071596 5.78616e-4 0.7070537 -0.7139936 -0.00285387 0.7001464 -0.7071148 5.7638e-4 0.7070986 -0.7070986 5.79192e-4 0.7071148 -0.696757 4.84322e-4 0.7173072 -0.6966567 4.85613e-4 0.7174045 -0.6967797 4.84374e-4 0.717285 -0.6967694 4.84092e-4 0.717295 -0.7071066 7.76294e-4 0.7071066 -0.6967629 4.83221e-4 0.7173013 -0.6967537 4.80596e-4 0.7173102 -0.6967821 4.85452e-4 0.7172827 -0.6967725 4.85615e-4 0.7172921 -0.7071128 7.75701e-4 0.7071003 -0.7068831 7.79187e-4 0.70733 -0.7071065 7.75783e-4 0.7071065 -0.7070456 7.74823e-4 0.7071676 -0.7071065 7.75907e-4 0.7071065 -0.6967815 0.005852103 0.7172595 -0.7071066 7.75672e-4 0.7071066 -0.6926952 7.77371e-5 0.7212304 -0.6927587 8.10536e-5 0.7211694 -0.6927658 8.01605e-5 0.7211626 -0.6927545 8.11784e-5 0.7211735 -0.6927505 8.12748e-5 0.7211773 -0.6927464 8.39326e-5 0.7211812 -0.7071216 -4.6467e-4 0.7070918 -0.7071051 4.84075e-4 0.7071083 -0.7071666 4.85712e-4 0.7070468 -0.6906772 0.008416175 0.7231143 -0.7071013 4.85405e-4 0.7071121 -0.707104 4.84999e-4 0.7071094 -0.7070941 8.03164e-5 0.7071195 -0.7071229 8.10945e-5 0.7070907 -0.7066782 -9.97956e-4 0.7075344 -0.7042832 6.67885e-7 0.7099191 -0.7070978 8.00592e-5 0.7071157 -0.7071051 8.07539e-5 0.7071085 -0.7071053 8.37242e-7 0.7071083 -0.7071071 8.05944e-7 0.7071064 0.707108 -8.38717e-7 -0.7071056 0.7071049 -8.36303e-7 -0.7071087 0.7071084 -8.58572e-7 -0.7071052 0.7070983 -7.9122e-7 -0.7071153 0.7070998 -1.08093e-6 -0.7071138 0.7071337 8.37462e-7 -0.70708 0.7070931 0 -0.7071204 0.7071177 0 -0.7070959 0.7071014 -7.22988e-7 -0.7071122 0 1 0 0.7070832 -7.1263e-7 -0.7071304 0.7071068 -7.57255e-7 -0.7071068 0.7071068 -8.64488e-7 -0.7071068 0.7071068 -1.04495e-6 -0.7071068 0.7071068 -1.05004e-6 -0.7071068 0.7071068 0 -0.7071068 0.7071045 -2.0794e-7 -0.707109 0.7071284 -3.80341e-7 -0.7070851 0.4495682 -0.6559954 -0.6062197 -0.005676388 -0.999939 0.005676388 0.5000153 -0.7070528 -0.5000153 0.7071068 -1.16952e-6 -0.7071068 0.7070966 -9.32011e-7 -0.707117 0.7071135 -9.66816e-7 -0.7071001 0.7071068 0 -0.7071068 0.7071067 -8.65252e-7 -0.7071067 0.707116 -8.05161e-7 -0.7070977 0.7071183 -0.001176893 -0.7070943 0.7071191 -1.00041e-6 -0.7070945 0.7071041 7.3858e-7 -0.7071095 0.7067635 -0.03169268 -0.7067396 0.7071015 1.46647e-6 -0.7071121 0.7071076 -1.00081e-6 -0.7071061 0 0 0 0.4999848 -0.7070834 -0.4999848 0 -1 0 0.4999848 -0.7070834 -0.4999848 0.4999848 -0.7070834 -0.4999848 0 -1 0 0.7071117 -7.66488e-7 -0.707102 0.7071068 -5.3978e-7 -0.7071068 0.7071515 -1.15538e-6 -0.7070621 0.7070963 -7.97599e-7 -0.7071173 0 1 0 0.7070923 -7.7185e-7 -0.7071213 0 -1 0 0.7071051 0 -0.7071085 0 0 0 0.7071068 -1.17937e-6 -0.7071067 0.7071068 -8.65614e-7 -0.7071068 0.7071021 -8.35522e-7 -0.7071114 0.7071117 -1.06399e-6 -0.7071019 0.7071068 -1.08197e-6 -0.7071068 0.7071045 -1.08201e-6 -0.707109 0 0.9999695 0 0.4999848 0.7070834 -0.4999848 0.7071055 0 -0.7071082 0 -1 0 0 -1 0 0.7070702 5.11405e-7 -0.7071433 0.7071014 -9.38681e-7 -0.7071122 0.7070585 2.3743e-6 -0.7071551 0.7071204 -1.22865e-6 -0.7070932 0.7071045 -7.57405e-7 -0.707109 0 0 0 0 1 0 0.7071097 -9.015e-7 -0.7071039 0.7071061 -7.26879e-7 -0.7071075 0.7071068 -1.48015e-6 -0.7071068 0.7071076 -1.73476e-6 -0.7071061 0.7071083 -9.01424e-7 -0.7071052 0.707103 -9.01506e-7 -0.7071105 0.7070991 -1.29458e-6 -0.7071145 0.7071146 -6.13195e-7 -0.7070989 0.7071064 -5.69507e-7 -0.7071071 0.7071066 2.31223e-7 -0.707107 0.707108 -1.34542e-6 -0.7071056 0.7071067 -8.6302e-7 -0.7071068 0.7071068 -8.63024e-7 -0.7071068 0.7071079 -1.26674e-6 -0.7071056 0.7071123 -6.46938e-7 -0.7071012 0 -1 0 0.7071068 -8.10194e-7 -0.7071068 0.7071014 -2.53782e-6 -0.7071122 0.7071068 -6.99088e-7 -0.7071068 0.7071068 -8.62289e-7 -0.7071068 0.7071068 -8.62579e-7 -0.7071068 0.7067777 -6.47244e-7 -0.7074358 0.7071067 -8.62093e-7 -0.7071068 0 -1 0 0.7071068 -8.63081e-7 -0.7071068 0.707118 -7.50057e-7 -0.7070956 0.4999848 -0.7070834 -0.4999848 0 -1 0 0.4999237 -0.7070528 -0.5001068 0.7071054 -0.001925587 -0.7071054 0.7071056 0.00186187 -0.7071056 0.7071067 7.13147e-4 -0.7071067 0.7071053 0 -0.7071083 0.7071068 -1.07882e-6 -0.7071068 0 1 0 0.7071068 -6.47172e-7 -0.7071068 0.7071068 -6.41606e-7 -0.7071068 0.7072213 -5.46141e-6 -0.7069923 0.7071068 -6.47316e-7 -0.7071068 0 1 0 0.4850363 0.7276436 -0.4850512 0 -1 0 0 -1 0 0.7071068 0 -0.7071068 0.7071053 -6.78591e-7 -0.7071083 0.7071171 -1.09119e-6 -0.7070965 0.7071068 -8.63075e-7 -0.7071068 0.7070817 -7.82974e-7 -0.7071318 0.7071132 -8.63091e-7 -0.7071005 0.4999848 0.7070834 -0.4999848 0 1 0 0.4999848 0.7070834 -0.4999848 0 -1 0 0.7071068 -8.10939e-7 -0.7071067 0.4999848 0.7070834 -0.4999848 0 -1 0 0.707104 5.82124e-7 -0.7071096 0.7071756 1.44183e-6 -0.707038 0.7071068 -1.07887e-6 -0.7071068 0.7071068 -8.62781e-7 -0.7071068 0.7070999 -8.47717e-7 -0.7071137 0.5000153 0.7071139 -0.4999542 0 1 0 0 -1 0 0.4999848 -0.7070834 -0.4999848 0.7071071 -2.37507e-6 -0.7071065 0.4999848 0.7070834 -0.4999848 0 1 0 0.707101 -1.01147e-6 -0.7071126 0.7070664 -2.61609e-6 -0.7071472 0.7071047 -1.56562e-6 -0.7071088 0.7071065 -1.30877e-6 -0.7071071 0.7071059 -9.06393e-7 -0.7071076 -0.6912872 0.210343 -0.6912872 -0.4786194 0.736102 -0.4786202 -0.1013875 0.9896672 -0.1013877 8.79129e-7 1 -8.79129e-7 8.79129e-7 1 -8.79129e-7 -2.13961e-6 1 -2.13961e-6 0 1 0 8.79129e-7 1 -8.79129e-7 8.79129e-7 1 -8.79129e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.75826e-6 1 -1.75826e-6 1.75825e-6 1 -1.75826e-6 0.1925784 0.9621999 0.1925742 0.4193779 0.8051369 0.4193767 0.6368677 -0.4345118 0.6368666 0.5090558 -0.6940636 0.5090558 0.1883645 -0.9638659 0.1883645 -0.002473294 -0.9999939 0.002473294 -0.01487559 -0.9997788 0.01487571 -0.02368354 -0.999439 0.02368348 -0.003024578 -0.9994689 0.03244429 0.0187059 -0.9992762 0.0331217 0.01656222 -0.9997151 0.01718431 7.57422e-4 -0.9999994 7.57421e-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.1821266 -0.9662608 -0.1821266 -0.5224968 -0.6737909 -0.5224968 0.7071068 4.32904e-7 0.7071068 -0.7071068 -7.19209e-7 -0.7071068 -0.6799238 -0.2746038 -0.6799238 0.6952255 0.1825459 0.6952255 0.6964962 -0.1725858 0.6964962 0.5293539 -0.663 0.5293539 0.1242117 -0.9844505 0.1242117 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2321254 -0.9445823 -0.2321254 -0.4743672 -0.7415751 -0.4743861 -0.6581443 0.3656396 -0.6581443 -0.5561592 0.6175552 -0.5561587 -0.2272389 0.9469556 -0.2272389 0.007367193 0.9999458 0.007367193 1.95162e-4 1 -1.95171e-4 0.03766018 0.9985953 0.03727042 0 1 0 0.02792638 0.9992815 0.02562469 0.001832067 0.9999967 -0.001832067 -0.01619678 0.9996716 -0.01985979 0.001371383 0.9999981 -0.001371383 -0.03023093 0.9989989 -0.03297108 5.64399e-4 0.9999997 -5.64399e-4 -0.02041137 0.9995756 -0.02078044 -0.02001035 0.9995768 -0.02111756 2.28574e-5 1 -2.28574e-5 -8.65537e-4 0.9999992 -9.11252e-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.2199681 0.950383 0.2199681 0.5677023 0.5961779 0.5677023 0.7071068 4.33488e-7 0.7071068 -0.7071068 -2.87683e-7 -0.7071068 -0.6799219 -0.2746142 -0.6799215 0.6952264 0.1825394 0.6952264 0.6964965 -0.1725825 0.6964969 0.5293489 -0.6630069 0.5293501 0.1242566 -0.9844393 0.1242566 0.1238975 -0.9845297 0.1238975 -1.75824e-6 -1 1.75827e-6 -1.75826e-6 -1 1.75826e-6 -1.75841e-6 -1 1.75811e-6 -1.75817e-6 -1 1.75835e-6 -1.75819e-6 -1 1.75832e-6 -1.75826e-6 -1 1.75826e-6 -1.75827e-6 -1 1.75824e-6 -1.75835e-6 -1 1.75817e-6 -1.75826e-6 -1 1.75826e-6 -1.75823e-6 -1 1.75828e-6 -1.75823e-6 -1 1.75828e-6 1.53202e-5 -1 1.53202e-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 -8.79215e-7 -1 8.79049e-7 -8.78404e-7 -1 8.80041e-7 -8.79115e-7 -1 8.79142e-7 -0.2322822 -0.9445145 -0.2322442 -0.4743748 -0.7415785 -0.4743735 -0.474491 -0.7414401 -0.4744732 -0.4743416 -0.7416207 -0.4743403 -0.4743476 -0.741613 -0.4743463 -0.6581377 0.3656631 -0.6581377 -0.5561172 0.6176264 -0.5561215 -0.5561091 0.6176264 -0.5561297 -0.2273132 0.9469243 -0.2272953 0.007277011 0.999947 0.007277011 0.00778675 0.9999452 0.007007658 1.9516e-4 1 -1.95174e-4 0.03756999 0.9986021 0.03718018 0 -1 0 0.02808499 0.999273 0.02578336 0.001832067 0.9999966 -0.001832067 -0.01675158 0.9996519 -0.02038705 -0.01637303 0.9996655 -0.02002108 -0.5072177 0.7125462 0.484695 -0.7070834 0 0.7070834 -0.5076144 0.7049776 0.4952543 -0.03063046 0.9989736 -0.03337055 -0.03023582 0.9989984 -0.03298699 -0.01994049 0.9995791 -0.02106881 -0.02010196 0.9995729 -0.02121347 2.28575e-5 1 -2.28575e-5 2.28574e-5 1 -2.28574e-5 -8.83212e-4 0.9999991 -9.28927e-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.2199541 0.9503897 0.2199541 0.2199541 0.9503897 0.2199541 0.5676981 0.5961861 0.5676981 0.707108 7.99207e-7 0.7071058 -0.707108 -7.91128e-7 -0.7071056 -0.679924 -0.2746083 -0.6799218 0.6952258 0.1825411 0.6952264 0.696497 -0.172586 0.6964955 0.5293567 -0.6629973 0.5293544 0.1238426 -0.9845436 0.1238422 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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.66015e-6 -1 7.66013e-6 -8.78658e-7 -1 8.78658e-7 -8.65933e-7 -1 8.91382e-7 -8.78658e-7 -1 8.78658e-7 -8.78652e-7 -1 8.78665e-7 -8.78655e-7 -1 8.78662e-7 -0.2321807 -0.944553 -0.2321889 -0.2321284 -0.944582 -0.2321234 -0.4743353 -0.7416279 -0.4743353 -0.6581332 0.3656746 -0.6581358 -0.5561847 0.6175088 -0.5561847 -0.227194 0.946974 -0.2272073 0.007354497 0.9999459 0.007354497 1.93404e-4 1 -1.98904e-4 0.03759866 0.9986001 0.0372067 0.001147091 0.9999988 -0.00114715 0.02792328 0.9992814 0.02563059 0.001835405 0.9999966 -0.001835405 -0.01683676 0.9996479 -0.02050638 -0.01613801 0.9996736 -0.01980769 0.001375377 0.9999981 -0.001375317 -0.03076905 0.9989644 -0.0335195 -0.03004127 0.9990112 -0.03277176 -0.02010923 0.9995729 -0.02120947 2.27142e-5 1 -2.27142e-5 -8.90155e-4 0.9999991 -9.35583e-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.2199841 0.9503742 0.2199907 0.5676923 0.5961981 0.5676913 0.7071068 5.82702e-7 0.7071068 -0.7071074 -6.45097e-7 -0.7071062 -0.6799229 -0.2746064 -0.6799236 0.695226 0.1825428 0.695226 0.6964955 -0.1725913 0.6964956 0.5293433 -0.6630181 0.5293419 0.5293077 -0.6630726 0.5293092 0.5294212 -0.6628936 0.5294198 0.1238861 -0.9845337 0.1238771 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.2322441 -0.9445274 -0.23223 -0.2320209 -0.9446272 -0.2320466 -0.2320529 -0.9446169 -0.2320564 -0.4707621 -0.7416329 -0.4778742 -0.474332 -0.7416319 -0.4743324 -0.6581374 0.3656676 -0.6581356 -0.556187 0.617506 -0.5561856 -0.2271681 0.9469892 -0.2271695 -0.2272268 0.9469619 -0.2272247 -0.2272815 0.9469338 -0.2272871 -0.2278885 0.9466698 -0.2277791 -0.2271179 0.9470096 -0.227135 0.007553577 0.9999431 0.007532596 1.943e-4 1 -1.94304e-4 0.03759115 0.9986004 0.03720343 0.00114566 0.9999987 -0.00114566 0.02797549 0.9992784 0.02568805 0.00182569 0.9999967 -0.00182569 0.001793026 0.9999967 -0.001856565 0.00182569 0.9999966 -0.00182569 0.001825749 0.9999967 -0.001826226 -0.01620048 0.9996718 -0.01984977 -0.02955085 0.9990419 -0.03228068 -0.01613241 0.999674 -0.01978641 -0.03017282 0.9990029 -0.03290694 5.57653e-4 0.9999997 -5.57659e-4 -0.01999354 0.9995772 -0.02110755 3.46882e-5 1 -3.46871e-5 -0.5098859 -0.6910156 0.5123611 -0.02231204 0.9995449 0.02030164 -8.87907e-4 0.9999991 -9.34941e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 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.2199877 0.9503741 0.2199871 0.5676783 0.5962194 0.5676828 0.8788871 0.4761847 0.02838301 0.5676478 0.5962837 0.5676459 0.7071068 -5.20389e-7 -0.7071068 -0.7071067 0 -0.7071069 -0.7071068 5.92037e-7 0.7071068 0.7071048 0 0.7071089 -0.6672652 0.3309323 0.667264 0.6894178 -0.2222751 -0.6894178 -0.7071047 0 -0.707109 -0.7071088 0 -0.7071048 -0.7071043 0 -0.7071093 -0.707108 0 -0.7071056 -0.7071068 0 -0.7071068 -0.7071052 3.04101e-7 -0.7071084 -0.7071068 0 -0.7071068 -0.707153 1.36728e-6 -0.7070606 -0.7070967 -1.63388e-7 -0.7071168 -0.7071068 0 -0.7071068 -0.7071166 -1.21639e-6 -0.707097 -0.707104 1.35684e-7 -0.7071096 -0.7071095 2.81826e-7 -0.7071041 -0.7071068 -2.156e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071014 -1.90727e-7 -0.7071122 -0.7069543 4.88332e-7 -0.7072592 -0.7070092 -4.646e-6 -0.7072043 -0.7071068 -2.18299e-7 -0.7071068 -0.7070987 3.48581e-6 -0.7071149 -0.7071068 1.21811e-6 -0.7071068 -0.707111 5.38979e-7 -0.7071025 -0.7071068 -1.38206e-6 -0.7071068 -0.7071254 7.89901e-7 -0.7070881 -0.7070978 -2.62838e-7 -0.7071159 -0.7070647 -5.00079e-7 -0.7071488 -0.7070214 2.73314e-7 -0.7071922 -0.7071068 -3.23748e-7 -0.7071068 -0.7071251 7.81125e-7 -0.7070884 -0.7070874 0 -0.7071262 -0.7071006 -8.10947e-7 -0.707113 -0.7071121 -1.97189e-6 -0.7071014 -0.7071148 2.25463e-6 -0.7070987 -0.7071068 -1.03603e-6 -0.7071068 -0.706936 -7.80059e-5 -0.7072775 -0.7070971 0 -0.7071165 -0.7071068 2.1543e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7072328 6.1261e-6 -0.7069806 -0.7071372 1.96549e-7 -0.7070764 -0.7070897 2.19722e-7 -0.7071239 -0.7071068 0 -0.7071068 -0.7071042 4.07099e-7 -0.7071095 -0.7071067 0 -0.7071067 -0.7071068 8.04528e-7 -0.7071068 -0.7071087 -4.8125e-4 -0.7071046 -0.7071149 -0.001071095 -0.7070978 -0.7071046 1.03319e-6 -0.7071091 -0.7071067 0 -0.7071067 -0.7071422 -6.31962e-7 -0.7070713 -0.7071124 -2.44284e-7 -0.7071011 -0.7071178 0 -0.7070958 -0.7071068 0 -0.7071068 -0.7071096 4.00738e-7 -0.7071041 -0.7071067 -4.45443e-7 -0.7071069 -0.7071008 -6.75523e-7 -0.7071128 -0.707127 8.25428e-6 -0.7070866 -0.7071088 0 -0.7071048 -0.7071067 0 -0.7071068 -0.7071053 5.57033e-7 -0.7071083 -0.7071059 9.58211e-7 -0.7071077 -0.7071046 -1.28788e-7 -0.7071091 -0.7071083 -1.28785e-7 -0.7071053 -0.7069742 -5.17596e-5 -0.7072394 -0.7067477 1.01105e-5 -0.7074657 -0.7067305 1.10094e-5 -0.7074828 -0.7067369 1.46846e-5 -0.7074765 -0.6991904 2.3326e-4 -0.7149354 -0.6992177 2.33761e-4 -0.7149087 -0.6991994 2.32911e-4 -0.7149266 -0.6992152 2.29246e-4 -0.7149111 -0.699289 -0.003840744 -0.7148287 -0.7071299 9.83875e-6 -0.7070837 -0.7069837 -4.92129e-5 -0.7072298 -0.7070904 9.99235e-6 -0.7071231 -0.6948664 5.77197e-4 -0.7191386 -0.6948714 5.78625e-4 -0.7191339 -0.6948789 5.8155e-4 -0.7191265 -0.6948692 5.77795e-4 -0.7191359 -0.7071068 2.33281e-4 -0.7071068 -0.7071014 2.33316e-4 -0.7071122 -0.7071204 2.32747e-4 -0.7070931 -0.6948112 -0.005805552 -0.7191689 -0.7070905 2.31365e-4 -0.7071231 -0.7071122 2.36951e-4 -0.7071014 -0.700108 7.74601e-4 -0.7140365 -0.7000864 7.75781e-4 -0.7140578 -0.700117 7.75152e-4 -0.7140276 -0.7001344 7.76587e-4 -0.7140108 -0.7001082 7.68489e-4 -0.7140364 -0.7070956 5.7808e-4 -0.7071178 -0.7071127 5.77969e-4 -0.7071006 -0.707107 5.79014e-4 -0.7071064 -0.7070537 5.7775e-4 -0.7071596 -0.7001467 -0.002853691 -0.7139933 -0.7071174 5.80849e-4 -0.7070958 -0.7071121 5.79913e-4 -0.7071013 -0.7172771 4.82885e-4 -0.6967878 -0.7173427 4.84463e-4 -0.6967203 -0.7172855 4.83402e-4 -0.6967793 -0.717252 4.82405e-4 -0.6968138 -0.7071065 7.75428e-4 -0.7071065 -0.7172865 4.84657e-4 -0.6967782 -0.7173052 4.80731e-4 -0.6967588 -0.7172827 4.85104e-4 -0.6967821 -0.7173071 4.79935e-4 -0.696757 -0.7071297 7.75434e-4 -0.7070835 -0.7074046 7.79814e-4 -0.7068084 -0.7071066 7.74701e-4 -0.7071066 -0.707105 7.75328e-4 -0.7071082 -0.7071065 7.75582e-4 -0.7071065 -0.7172607 0.005853474 -0.6967803 -0.7071066 7.75672e-4 -0.7071066 -0.7211672 7.9216e-5 -0.692761 -0.7211955 7.87877e-5 -0.6927314 -0.7211514 7.90512e-5 -0.6927775 -0.7211849 8.45505e-5 -0.6927427 -0.7211651 7.95856e-5 -0.6927633 -0.7211468 7.09479e-5 -0.6927823 -0.7071014 0 -0.7071122 -0.707107 4.83355e-4 -0.7071064 -0.7071067 4.83363e-4 -0.7071067 -0.7231585 0.008437991 -0.6906306 -0.7070959 4.83768e-4 -0.7071175 -0.7071121 4.86203e-4 -0.7071014 -0.7071039 8.00005e-5 -0.7071098 -0.7071115 7.98249e-5 -0.707102 -0.7073632 -0.001069128 -0.7068495 -0.7098836 4.45248e-7 -0.7043191 -0.7071156 7.9744e-5 -0.707098 -0.7070984 8.36524e-5 -0.7071153 -0.7071091 0 -0.7071045 -0.7071082 -1.30238e-7 -0.7071054 0.7071065 0 0.707107 0.7071053 0 0.7071083 0.7071079 0 0.7071056 0.7071014 0 0.7071123 0.7070963 2.28931e-7 0.7071171 0.7072246 -7.74361e-6 0.706989 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071015 0 0.7071123 0 1 0 0.4999848 -0.7070834 0.4999848 0.7070912 0 0.7071223 0.7071235 0 0.7070901 0.7070942 0 0.7071194 0.707096 -3.28228e-6 0.7071176 0.7071068 -7.00055e-7 0.7071068 0.7071167 2.71361e-4 0.7070968 0.7071082 -1.34549e-7 0.7071052 0.7071214 -3.2231e-7 0.7070923 0.6062197 -0.6560259 0.4495682 0 -1 0 0.7071067 7.79663e-7 0.7071068 0.7071068 4.32656e-7 0.7071068 0.7071068 4.32534e-7 0.7071068 0.7071033 -0.003156661 0.7071033 0.7071067 2.16826e-7 0.7071067 0.7071067 2.16661e-7 0.7071067 0.7070986 -7.7765e-4 0.7071146 0.7070821 -2.69962e-7 0.7071315 0.7071014 -2.87224e-6 0.7071122 0.7069964 -0.01766854 0.7069964 0.7071068 -1.40082e-6 0.7071068 0.7071068 -1.4036e-6 0.7071068 0.5000153 -0.7070528 0.5000153 0 -1 0 0.4999542 -0.7071139 0.4999542 0.4999848 -0.7070834 0.4999848 0 -0.9999695 0 0.4999848 -0.7070834 0.4999848 -0.4053096 -0.8194257 -0.405297 0.7071117 0 0.707102 0.7071176 2.86869e-7 0.7070959 0.707077 0 0.7071366 0.7070998 1.71068e-7 0.7071138 0.7071262 -3.07678e-7 0.7070875 0 0.9999695 0 0.4999848 0.7070834 0.4999848 0.7071033 -6.97847e-7 0.7071102 0.4999848 -0.7070834 0.4999848 0 -0.9999695 0 0.4999542 -0.7071444 0.4999542 0.7071022 -2.40087e-6 0.7071114 0.7070997 3.86628e-7 0.7071139 0.7070882 3.12381e-7 0.7071254 0.7070969 0 0.7071167 0.7071148 0 0.7070987 0.707116 2.16393e-7 0.7070975 0 1 0 0.7071041 -6.97848e-7 0.7071095 0 -1 0 0 -1 0 0.7071068 0 0.7071068 0.7071014 -2.51223e-7 0.7071123 0.7071065 -2.27805e-7 0.707107 0.7070897 -4.2848e-7 0.7071238 0.707116 2.16393e-7 0.7070976 0 -1 0 0 -1 0 0.7071064 0 0.7071071 0.707107 -1.8172e-7 0.7071066 0.7071045 -5.316e-7 0.707109 0.7071038 -7.12582e-7 0.7071098 0.707109 0 0.7071045 0.7071068 0 0.7071068 0.7071048 1.43843e-7 0.7071088 0.7071176 -2.72015e-7 0.7070961 0.7071074 -8.54263e-7 0.7071062 0.707104 1.48641e-6 0.7071096 0.707107 2.245e-7 0.7071065 0.7071068 -2.15746e-7 0.7071068 0.7071122 0 0.7071014 0.707107 2.10982e-7 0.7071066 0.7070985 -3.23459e-7 0.707115 0.6062197 -0.6559954 0.4495682 0 -0.9999695 0 0.5000153 -0.7070834 0.4999542 0.7071068 8.10194e-7 0.7071068 0.7071123 -1.16042e-6 0.7071014 0.7071068 6.99061e-7 0.7071068 0.7071068 2.1558e-7 0.7071068 0.7072299 3.93754e-7 0.7069837 0.7071068 -3.2347e-7 0.7071068 0.7071182 -2.8756e-7 0.7070953 0 1 0 0.5000153 -0.7070528 0.4999848 0.7071067 -3.23602e-7 0.7071067 0.7071068 -3.23714e-7 0.7071068 0 1 0 0 0 0 0.7070991 -0.006672203 0.7070831 0.7071108 2.20631e-4 0.7071028 0.7071005 0.009846746 0.7070446 0.707109 3.90556e-7 0.7071045 0.7071259 5.68704e-7 0.7070877 0 -1 0 0.7071068 -3.23699e-7 0.7071068 0.7071068 -3.20803e-7 0.7071068 0.7071068 1.21401e-6 0.7071069 0.707099 -2.15762e-7 0.7071147 0 -1 0 0 1 0 0 -1 0 0 1 0 0.70643 -0.04323285 0.7064614 0.7071045 1.3636e-6 0.707109 0.7071068 2.15344e-7 0.7071068 0.7071211 0 0.7070925 0.7070881 1.55659e-7 0.7071256 0.7071131 -2.15782e-7 0.7071005 0.5000153 0.7070528 0.5000153 0 1 0 0.5000153 0.7070528 0.5000153 0.5000153 -0.7070528 0.5000153 0 -1 0 0.4999848 -0.7070834 0.4999848 0.7071068 0 0.7071068 0.5000153 0.7070528 0.5000153 0 -1 0 0.4999848 0.7070834 0.4999848 0.7071068 -3.4703e-7 0.7071068 0.7071068 0 0.7071068 0.7071067 0 0.7071067 0.7070987 0 0.7071149 0.7071102 -2.1193e-7 0.7071034 0.4999848 0.7070834 0.4999848 0 1 0 0.5000153 -0.7070528 0.5000153 0 -0.9999695 0 0.4999848 -0.7070834 0.4999848 0.7071068 3.96106e-7 0.7071068 0.4999848 0.7070834 0.4999848 0 1 0 0.7071093 0 0.7071042 0.7071068 0 0.7071067 0.7071065 1.5784e-6 0.7071072 0.7070903 -1.1174e-5 0.7071233 0.7071068 0 0.7071068 0.6912864 0.2103423 -0.6912882 0.4786196 0.7361022 -0.4786196 0.1013864 0.9896674 -0.1013864 0 1 0 2.13961e-6 1 -2.13961e-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 4.27923e-6 1 -4.27923e-6 0 1 0 0 1 0 -0.1925802 0.9621982 0.1925809 -0.4193771 0.8051364 0.4193786 -0.6368699 -0.4345036 0.6368699 -0.5090556 -0.694064 0.5090556 -0.1883444 -0.9638738 0.1883447 0.003528475 -0.999958 -0.008450388 0.01535785 -0.9988664 -0.04505765 -0.001994311 -0.9989693 -0.04534697 -0.03245794 -0.9994686 -0.002986669 -0.0330919 -0.9992778 0.01867616 -0.01719641 -0.9997152 0.0165497 -7.87377e-4 -0.9999994 7.8738e-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.1821457 -0.9662536 -0.1821452 0.5224966 -0.6737913 -0.5224966 -0.7071052 4.33489e-7 0.7071083 0.7071062 -5.71829e-7 -0.7071074 0.6799226 -0.274605 -0.6799244 -0.6952258 0.1825323 0.6952288 -0.696495 -0.1725942 0.6964956 -0.5293841 -0.6629506 0.5293855 -0.1233857 -0.9846441 0.1234986 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321254 -0.9445822 -0.2321254 0.4743654 -0.7415888 -0.4743663 0.6581363 0.365666 -0.6581375 0.5561666 0.6175406 -0.5561676 0.22718 0.9469838 -0.2271806 -0.007285237 0.999947 0.007285237 1.84619e-4 1 1.84615e-4 -0.03724759 0.9985979 0.03761637 0 -1 0 -0.02565002 0.9992801 0.02795177 0.001833856 0.9999967 0.001833796 0.01984149 0.9996723 -0.01617503 0.001371443 0.9999981 0.001371383 0.0327838 0.9990108 -0.03004366 5.52098e-4 0.9999997 5.52086e-4 0.02078044 0.9995756 -0.02041137 0.02108508 0.9995781 -0.01997905 2.28569e-5 1 2.28579e-5 9.59877e-4 0.9999991 -9.14164e-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.2194139 0.950604 0.2195667 -0.5677019 0.5961778 0.5677029 -0.7071058 5.77984e-7 0.7071077 0.7071068 -6.47288e-7 -0.7071068 0.6799219 -0.2746127 -0.679922 -0.6952255 0.1825394 0.6952273 -0.6964951 -0.1725879 0.6964969 -0.5293467 -0.6630103 0.5293481 -0.1242649 -0.9844371 0.1242658 -0.1238557 -0.9845402 0.1238566 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 8.79119e-7 -1 8.79139e-7 8.79129e-7 -1 8.79129e-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.2321494 -0.9445704 -0.2321494 0.7790211 -0.1294317 0.6134929 0.4743954 -0.7415461 -0.4744031 0.4743972 -0.7415482 -0.474398 0.4743579 -0.741599 -0.4743579 0.6581352 0.3656721 -0.6581352 0.5561155 0.6176326 -0.5561165 0.5561186 0.6176266 -0.55612 0.227198 0.9469753 -0.227198 -0.007532954 0.9999432 0.007532954 -0.006991624 0.9999455 0.007748305 1.8461e-4 1 1.84623e-4 -0.0371949 0.9986017 0.03756368 -0.5120701 0.7032075 -0.4931791 -0.7070834 0 -0.7070834 -0.5086825 0.7130345 -0.4824671 -0.02572739 0.9992766 0.0280081 0.001832067 0.9999967 0.001832127 0.7020739 0.1468958 0.6967881 0.02003085 0.9996654 -0.01636785 0 -1 0 0.03285044 0.9990066 -0.03011029 0.03297603 0.9989984 -0.0302459 0.02133488 0.9995678 -0.020226 0.02087634 0.9995868 -0.0197578 3.52108e-5 1 3.51181e-5 3.51666e-5 1 3.51637e-5 9.08868e-4 0.9999992 -8.3854e-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.2200426 0.9503459 0.220054 -0.2200409 0.9503468 0.220052 -0.5676974 0.596186 0.5676988 -0.7071068 8.66978e-7 0.7071068 0.7071066 -5.79853e-7 -0.707107 0.679924 -0.2746058 -0.6799228 -0.6952282 0.1825258 0.6952282 -0.696494 -0.1725907 0.6964974 -0.529406 -0.6629176 0.529405 -0.1238416 -0.9845439 0.1238411 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.001368641 -0.9999982 -0.0013296 0 -1 0 0 -1 0 0 -1 0 0.23214 -0.9445751 -0.23214 0.2321485 -0.944571 -0.2321485 0.4743364 -0.7416255 -0.4743381 0.6581369 0.365666 -0.6581369 0.5561863 0.617506 -0.5561863 0.2271848 0.9469816 -0.2271844 -0.007295906 0.9999467 0.007295906 1.86468e-4 1 1.81321e-4 -0.03731995 0.9985924 0.03768718 0.00114715 0.9999987 0.001147091 -0.0255559 0.9992854 0.02784872 0.001824915 0.9999967 0.001824915 0.02047038 0.9996489 -0.0168218 0.01975256 0.9996752 -0.01610386 0.001364827 0.9999982 0.001364886 0.03264158 0.9990194 -0.02991437 0.03292578 0.9990017 -0.030191 0.02108657 0.9995784 -0.01996535 2.27141e-5 1 2.27141e-5 9.581e-4 0.9999991 -9.12673e-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.2199295 0.9504013 0.2199285 -0.5678154 0.5960168 0.5677585 -0.7071074 7.22481e-7 0.7071062 0.7071074 -5.20062e-7 -0.7071061 0.6799244 -0.2746112 -0.6799202 -0.6952275 0.1825356 0.6952262 -0.6964971 -0.172579 0.6964971 -0.5293453 -0.6630159 0.5293425 -0.5295037 -0.6627629 0.5295009 -0.5292797 -0.6631184 0.5292797 -0.1237063 -0.9845744 0.1237338 0 -1 0 0 -1 0 1.04025e-5 -1 1.06367e-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.2320576 -0.9446155 -0.2320576 0.2331398 -0.9440824 -0.2331398 0.2322897 -0.9445014 -0.2322897 0.6493967 0.08321833 0.7558827 0.4743389 -0.7416234 -0.4743389 0.6581392 0.36566 -0.6581379 0.5561615 0.6175507 -0.5561615 0.227158 0.9469928 -0.227165 0.2270454 0.9470508 -0.2270355 0.2271208 0.9470112 -0.2271254 0.2268403 0.9471551 -0.2268056 0.2272548 0.9469459 -0.2272636 -0.007373809 0.9999457 0.007373809 1.94302e-4 1 1.94302e-4 -0.03711801 0.9986068 0.03750562 0.00114566 0.9999988 0.00114566 -0.02550035 0.999288 0.0278086 0.001825571 0.9999967 0.001825749 0.001856505 0.9999966 0.001793146 0.00182569 0.9999967 0.00182569 0.001825094 0.9999966 0.001827001 0.01959234 0.9996809 -0.01594293 0.002240717 0.9999951 0.002206206 0.01996171 0.999668 -0.01629894 0.03290563 0.9990029 -0.03017145 5.57661e-4 0.9999997 5.57649e-4 0.02098888 0.9995821 -0.01987487 2.25469e-5 1 2.25469e-5 0 0 0 0.008726775 0.9999387 0.006817698 9.47322e-4 0.9999991 -8.99667e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.4967498 0.7054353 -0.5055391 -0.4997711 0.7072359 -0.4999848 -0.4998322 0.707297 -0.4998322 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2199276 0.9504019 0.2199273 -0.5677257 0.5961437 0.5677149 -0.5677704 0.5960484 0.5677704 -0.5677282 0.5961394 0.5677169 0.7071068 9.41657e-7 0.7071068 0.7071065 -2.26188e-7 -0.7071071 -0.7071068 -9.6206e-7 -0.7071068 -0.7071111 1.74897e-7 0.7071026 -0.6672652 0.3309295 -0.6672652 0.689418 -0.2222734 0.689418 0.7071127 -1.72144e-7 -0.7071008 0.7071037 -1.86339e-7 -0.7071098 0.7071095 -1.72923e-7 -0.707104 0.7071408 -2.2872e-6 -0.7070729 0.7072099 7.91848e-7 -0.7070037 0.7071071 -1.30891e-6 -0.7071065 0.4999848 0.7070834 -0.4999848 0 1 0 0.4999848 0.7070834 -0.4999848 0.7071068 -2.15831e-7 -0.7071068 0.7071112 0 -0.7071024 0.4999848 0.7070834 -0.4999848 0 -1 0 0.4999848 -0.7070834 -0.4999848 0.7071098 2.20317e-7 -0.7071038 0 1 0 0.7070922 -6.94267e-7 -0.7071214 0.7071068 -6.47607e-7 -0.7071068 0.7071068 -2.15801e-7 -0.7071068 0.7071068 -2.15675e-7 -0.7071068 0.5468307 -0.6586199 0.5168615 0.4999542 -0.7071139 -0.4999848 0 1 0 0 1 0 0.7071068 -8.1094e-7 -0.7071068 0.4999848 0.7070834 -0.4999848 0 -1 0 0.4999542 0.7071139 -0.4999542 0.4999542 0.7070834 -0.5000153 0 0.9999695 0 0.7071067 -4.31534e-7 -0.7071067 0.7071129 -6.53216e-7 -0.7071008 0.5000153 -0.7070834 -0.4999848 0 -1 0 0.4999848 -0.7070834 -0.4999848 0.7070692 -3.36505e-7 -0.7071445 0.7071164 -1.84945e-7 -0.7070972 0.707087 5.92596e-7 -0.7071266 0.7071122 0 -0.7071014 0 1 0 -0.5631834 -0.6046798 0.5631933 0 -1 0 0.7071068 0 -0.7071068 0.7070214 6.90874e-7 -0.7071922 0.7071068 0 -0.7071068 0.7070648 -0.003914535 -0.7071379 0.7071122 0 -0.7071014 0.7072747 -7.58518e-6 -0.7069388 0.7069957 3.66992e-6 -0.7072178 0.7070896 0 -0.707124 0.7071014 -2.12022e-7 -0.7071123 0.5000153 -0.7070834 -0.4999848 0 -0.9999695 0 0.4999848 -0.7070834 -0.4999848 0.7071015 -8.10947e-7 -0.7071121 0.7071068 0 -0.7071068 0.7071034 -2.46195e-4 -0.7071102 0.7070976 -0.001335859 -0.7071146 0.7071068 6.88163e-7 -0.7071068 0.7072686 8.79681e-6 -0.706945 0.7071206 1.6146e-7 -0.707093 0.7071014 -6.6463e-7 -0.7071122 0.7071067 -2.11208e-7 -0.707107 0.7071123 -4.30636e-7 -0.7071012 0 1 0 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071219 -4.04104e-4 -0.7070915 0.7071048 -1.92774e-7 -0.7071087 0.7070994 0 -0.7071141 0.7071121 2.70514e-6 -0.7071014 0.7071126 -2.74167e-6 -0.7071011 0.707109 -1.93176e-7 -0.7071045 0.7071068 -2.58088e-7 -0.7071068 0.7074895 1.02308e-5 -0.706724 0.7072033 -2.35958e-7 -0.7070103 0.7074678 1.0055e-5 -0.7067455 0.7074704 1.07109e-5 -0.7067431 0.7149356 2.32983e-4 -0.6991903 0.7149398 2.3301e-4 -0.699186 0.7148834 2.32756e-4 -0.6992436 0 -1 0 0.7149865 2.34365e-4 -0.6991383 0.7071148 1.03069e-5 -0.7070988 0 1 0 0.7071148 1.0025e-5 -0.7070987 0.7191289 5.7772e-4 -0.6948764 0 -1 0 0.7191367 5.78215e-4 -0.6948685 0.7191409 5.77508e-4 -0.6948641 0.7070977 2.32848e-4 -0.7071158 0.7071067 2.32956e-4 -0.7071067 0.7071067 2.32956e-4 -0.7071067 0.7190712 5.76929e-4 -0.6949363 0 -1 0 0.7071118 2.31883e-4 -0.7071018 0.7140079 7.7471e-4 -0.7001372 0.7140171 7.75015e-4 -0.7001279 0.7142344 7.76189e-4 -0.6999062 0 1 0 0.7140175 7.76074e-4 -0.7001276 0.7071067 5.77467e-4 -0.7071067 0.7071037 5.7746e-4 -0.7071097 0 0 0 0.5057833 -0.7049471 -0.497177 0 -1 0 0.5001068 -0.7069308 -0.5001068 0.7139686 7.74052e-4 -0.7001773 0.7071094 5.76925e-4 -0.707104 0.5057528 -0.7049471 -0.4972075 0 1 0 0.5001679 -0.7068392 -0.5001679 0.6967718 4.82834e-4 -0.7172928 0.6959036 0.05017179 -0.7163804 0.6967591 4.83155e-4 -0.7173052 0.6967667 4.82927e-4 -0.7172976 0.7071447 7.75809e-4 -0.7070685 0.6967688 4.83174e-4 -0.7172957 0.696756 -2.45434e-4 -0.7173084 0.6967605 4.82215e-4 -0.7173038 0.6967824 4.81989e-4 -0.7172825 0.7071073 7.74799e-4 -0.7071058 0.7066594 7.71588e-4 -0.7075536 0.7071375 7.74685e-4 -0.7070757 0.7070258 7.74191e-4 -0.7071874 0.7071066 7.74933e-4 -0.7071066 0.6967504 4.82945e-4 -0.7173136 0.707108 7.75149e-4 -0.7071053 0.6927537 7.92201e-5 -0.7211742 0.6927792 7.98925e-5 -0.7211498 0.6927549 7.91606e-5 -0.7211732 0.6927524 8.01426e-5 -0.7211754 0.6927626 -9.57989e-5 -0.7211657 0.6927505 8.07518e-5 -0.7211773 0.7071143 4.08279e-4 -0.7070991 0.7070958 4.82637e-4 -0.7071176 0.7071068 4.82929e-4 -0.7071068 0.6927387 7.80979e-5 -0.7211886 0 1 0 0.7071054 4.83603e-4 -0.707108 0.7070938 7.93652e-5 -0.7071197 0.7070487 5.70257e-5 -0.707165 0.7071258 7.87182e-5 -0.7070879 -0.7094014 -1.32465e-6 -0.7048047 0.7071045 7.94913e-5 -0.7071092 0.7071068 7.91613e-5 -0.7071068 0.7071062 -2.79037e-7 -0.7071073 0.7071069 -2.26211e-7 -0.7071067 -0.7071091 1.79933e-7 0.7071045 -0.7071081 1.79903e-7 0.7071055 -0.7071062 1.95887e-7 0.7071073 -0.7071162 3.5959e-7 0.7070974 -0.7070956 3.09857e-7 0.707118 -0.707188 2.99951e-6 0.7070256 -0.7070986 -3.36888e-6 0.7071149 -0.7070968 3.92891e-6 0.7071166 -0.7071151 2.71857e-7 0.7070984 -0.7071109 4.04779e-7 0.7071028 -0.7070755 -3.14507e-7 0.7071381 -0.7071028 -1.34618e-7 0.7071108 -0.7071068 0 0.7071068 -0.7070813 7.13403e-6 0.7071322 -0.7071068 1.04439e-6 0.7071068 -0.7070983 2.33935e-6 0.7071154 -0.7071062 2.30743e-6 0.7071073 -0.7071069 3.20614e-7 0.7071067 -0.7070987 3.44652e-6 0.707115 -0.7071122 -1.62995e-6 0.7071014 -0.7071068 3.22794e-7 0.7071068 -0.7071233 8.77672e-7 0.7070903 -0.7071921 3.63059e-6 0.7070215 -0.7071068 2.16331e-7 0.7071068 -0.7071068 2.17376e-7 0.7071068 -0.7071068 3.24482e-7 0.7071068 -0.707113 0 0.7071006 -0.7071068 0 0.7071068 -0.7070989 1.49567e-6 0.7071148 -0.7071068 0 0.7071068 -0.7071068 1.04693e-6 0.7071068 -0.7070631 -1.7331e-7 0.7071503 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.707115 0 0.7070987 -0.707059 2.54229e-6 0.7071546 -0.7069677 1.22564e-6 0.7072458 -0.7071102 1.61881e-7 0.7071033 -0.7071068 0 0.7071068 -0.7070865 7.81044e-7 0.7071272 -0.7071068 3.50333e-7 0.7071068 -0.7071121 1.4369e-6 0.7071014 -0.7071068 0 0.7071068 -0.7070986 2.8493e-6 0.7071149 -0.7070932 7.36767e-7 0.7071203 -0.7071208 -3.22761e-7 0.7070929 -0.7071123 0 0.7071014 -0.7071068 0 0.7071068 -0.7070419 3.05233e-6 0.7071717 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7070996 3.72427e-6 0.707114 -0.7071068 -3.91938e-7 0.7071068 -0.707119 -2.48087e-7 0.7070946 -0.7070934 9.47597e-7 0.7071202 -0.7071048 0 0.7071087 -0.7071068 0 0.7071068 -0.7071068 3.24148e-7 0.7071068 -0.7070999 2.73418e-6 0.7071135 -0.7070987 -3.18524e-6 0.707115 -0.7071074 2.16743e-7 0.7071062 -0.707107 2.75764e-7 0.7071065 -0.7070999 3.39318e-6 0.7071137 -0.7071068 0 0.7071068 -0.7071068 2.14643e-7 0.7071068 -0.707109 1.50247e-7 0.7071045 -0.707105 1.50253e-7 0.7071086 -0.7071149 0 0.7070987 -0.7071144 7.53728e-7 0.7070991 -0.7071068 5.99065e-7 0.7071068 -0.707111 0 0.7071026 -0.7070333 2.61712e-6 0.7071802 -0.7071014 6.6463e-7 0.7071122 -0.7070923 2.81277e-7 0.7071212 -0.707156 -1.28061e-6 0.7070576 -0.7071123 8.10934e-7 0.7071013 -0.7071067 0 0.7071067 -0.70714 7.10862e-6 0.7070736 -0.7071068 0 0.7071068 -0.7071256 -3.81795e-7 0.7070878 -0.7069835 5.73201e-6 0.70723 -0.7074361 -1.27018e-6 0.7067774 -0.7071233 -2.68507e-7 0.7070903 -0.7071068 0 0.7071068 -0.7070906 6.99282e-7 0.707123 -0.7071303 8.8353e-7 0.7070833 -0.7071164 8.10929e-7 0.7070972 -0.7071068 0 0.7071068 -0.7071006 0.001106858 0.7071123 -0.7070975 -4.24648e-4 0.7071157 -0.7071024 6.43746e-4 0.707111 -0.7071414 1.51306e-5 0.7070721 -0.7070482 2.73785e-6 0.7071654 -0.7071067 2.15735e-7 0.7071068 -0.7071067 4.31589e-7 0.7071067 -0.7071068 2.1554e-7 0.7071068 -0.7072285 -4.08263e-6 0.706985 -0.7071384 -6.48421e-7 0.7070752 -0.7071122 1.8491e-7 0.7071014 -0.7071014 0 0.7071123 -0.7071121 1.73018e-6 0.7071014 -0.707096 -2.78576e-6 0.7071176 -0.7071068 0 0.7071068 -0.7070214 -3.96971e-5 0.7071922 -0.7070965 7.07101e-7 0.707117 -0.7071163 -1.95423e-7 0.7070972 -0.7070943 5.38781e-7 0.7071194 -0.7071195 0 0.7070941 -0.7070954 7.61525e-7 0.7071183 -0.7071068 8.1422e-7 0.7071068 -0.7071068 8.11027e-7 0.7071068 -0.7071013 4.44425e-7 0.7071121 -0.7071014 4.44432e-7 0.7071122 -0.7071068 0 0.7071068 -0.7071002 -2.41334e-7 0.7071134 -0.7071068 4.31662e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071068 4.31549e-7 0.7071068 -0.7071176 -4.4845e-7 0.707096 -0.7071067 8.54812e-7 0.7071068 -0.7071372 -1.38674e-5 0.7070764 -0.7071101 0 0.7071035 -0.707151 3.02231e-6 0.7070625 -0.707201 7.03775e-5 0.7070126 -0.7071068 0 0.7071068 -0.7071038 1.74478e-7 0.7071099 0.691287 0.2103441 0.691287 0.4786206 0.7361008 0.4786206 0.1013858 0.9896676 0.1013858 -1.26048e-6 1 -3.01873e-6 0 1 0 0 1 0 -2.52097e-6 1 -6.03748e-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 -2.13961e-6 1 -2.13961e-6 0 1 0 1.75825e-6 1 -1.75826e-6 -0.1925821 0.9621977 -0.1925816 -0.4193766 0.8051372 -0.4193773 -0.6368673 -0.4345113 -0.6368673 -0.5090644 -0.6940503 -0.5090653 -0.1883446 -0.9638738 -0.1883446 0.008492588 -0.9999576 0.003546059 0.04503369 -0.9988678 0.01533043 0.04534876 -0.9989693 -0.00199604 0.01773828 -0.9996853 -0.01773828 0.007212698 -0.999948 -0.007212698 3.11147e-4 -1 -3.11147e-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.1821458 -0.9662534 0.1821464 0.5224961 -0.673792 0.5224961 -0.7071068 -1.15597e-6 -0.7071068 0.7071068 1.01106e-6 0.7071068 0.6799204 -0.2746207 0.6799204 -0.6952246 0.1825525 -0.6952246 -0.696496 -0.1725887 -0.696496 -0.5293503 -0.6630055 -0.5293503 -0.1241627 -0.9844487 -0.1242749 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321241 -0.9445829 0.2321241 0.4743713 -0.7415818 0.4743713 0.6581426 0.3656456 0.6581426 0.5561628 0.6175482 0.5561628 0.2272389 0.9469556 0.2272389 -0.007451951 0.9999446 -0.007451951 -1.8462e-4 1 1.84613e-4 -0.03761738 0.9985978 -0.03724867 -0.00115168 0.9999987 0.001151621 -0.02795231 0.99928 -0.02565068 -0.001832067 0.9999967 0.001832067 0.01622331 0.9996706 0.01988631 -0.001371383 0.9999982 0.001371383 0.03004443 0.9990108 0.03278458 -5.53851e-4 0.9999997 5.53851e-4 0.0200228 0.9995757 0.02115541 0.01999884 0.9995767 0.02113056 -3.51651e-5 1 3.51651e-5 8.54972e-4 0.9999993 9.25303e-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.2201343 0.9502921 -0.2201949 -0.5677024 0.5961778 -0.5677024 -0.7071068 -1.01147e-6 -0.7071068 0.7071068 1.00689e-6 0.7071068 0.6799224 -0.2746108 0.6799224 -0.6952264 0.1825394 -0.6952264 -0.6964964 -0.1725859 -0.6964961 -0.529348 -0.6630104 -0.5293468 -0.1242217 -0.9844481 -0.1242212 -0.1238582 -0.98454 -0.123855 0 -1 0 0 -1 0 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.35619e-5 -1 1.70784e-5 -1.75827e-6 -1 1.75824e-6 -1.75826e-6 -1 1.75826e-6 -1.75857e-6 -1 1.75796e-6 -1.7566e-6 -1 1.75973e-6 -1.75814e-6 -1 1.75837e-6 -1.75837e-6 -1 1.75815e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321399 -0.9445751 0.2321399 0.7071068 0 -0.7071068 0.4743165 -0.7416527 0.4743154 0.4744862 -0.741435 0.4744862 0.4743485 -0.7416111 0.4743485 0.6581344 0.3656752 0.6581344 0.5561474 0.617576 0.5561474 0.5561474 0.617576 0.5561474 0.2273098 0.9469217 0.2273098 -0.007533252 0.9999433 -0.007533252 -0.007364451 0.9999458 -0.007374942 -1.84604e-4 1 1.8463e-4 -0.03756392 0.9986017 -0.0371952 -0.001141011 0.9999986 0.00114113 -0.02800798 0.9992766 -0.02572745 -0.001831948 0.9999967 0.001832187 -0.6997755 -0.17107 0.6935773 0.01636642 0.9996654 0.02002942 -0.001371443 0.9999982 0.001371383 0.03011065 0.9990066 0.0328508 0.03267043 0.9989992 0.03055071 0.02022582 0.9995678 0.0213347 0.02064818 0.9995732 0.02066624 -2.28573e-5 1 2.28573e-5 -2.28553e-5 1 2.28591e-5 8.50866e-4 0.9999993 8.96581e-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.2199472 0.9503905 -0.2199571 -0.2199513 0.9503906 -0.219953 -0.5677024 0.5961778 -0.5677024 -0.7071061 -9.39224e-7 -0.7071074 0.7071068 1.07687e-6 0.7071067 0.6799222 -0.2746061 0.6799245 -0.6952255 0.1825411 -0.6952267 -0.6964957 -0.1725848 -0.6964972 -0.5294222 -0.6628908 -0.5294222 -0.1238355 -0.9845454 -0.1238358 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.53203e-5 -1 1.53203e-5 -1.75713e-6 -1 1.75714e-6 -1.77388e-6 -1 1.73962e-6 -1.75716e-6 -1 1.7571e-6 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2321103 -0.9445895 0.2321109 0.2321234 -0.9445831 0.2321238 0.4743396 -0.7416219 0.4743405 0.6581369 0.365666 0.6581369 0.5561658 0.6175428 0.5561658 0.2271822 0.9469826 0.2271828 -0.007462322 0.9999443 -0.007462322 -1.92159e-4 1 2.00028e-4 -0.03753072 0.9986051 -0.03713911 -0.001148819 0.9999987 0.001148879 -0.02785116 0.9992854 -0.02555507 -0.001824855 0.9999967 0.001824975 0.0168308 0.9996486 0.02047944 0.01610338 0.9996752 0.01975208 -0.001345515 0.9999982 0.001385152 0.03217214 0.9990288 0.03010493 0.03022664 0.9989995 0.03295874 0.01996678 0.9995782 0.021088 -2.27142e-5 1 2.27142e-5 9.1265e-4 0.9999991 9.58081e-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.220005 0.950364 -0.2200136 -0.5677667 0.5959891 -0.5678363 -0.7071068 -1.01147e-6 -0.7071068 0.7071057 1.16117e-6 0.7071077 0.6799198 -0.2746207 0.6799211 -0.695227 0.1825345 -0.695227 -0.696494 -0.1725941 -0.6964965 -0.5293402 -0.6630203 -0.5293421 -0.5293483 -0.6630074 -0.5293502 -0.5294373 -0.6628673 -0.5294368 -0.123857 -0.9845405 -0.1238532 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.2320804 -0.9446045 0.2320798 0.2320634 -0.9446127 0.2320634 0.2320522 -0.9446181 0.2320528 0.55369 0.1994175 -0.8084924 0.4743728 -0.74158 0.4743728 0.6581373 0.3656627 0.6581384 0.5561586 0.617555 0.5561596 0.227208 0.9469678 0.2272191 0.2270197 0.9470527 0.2270535 0.2271147 0.9470112 0.2271315 0.2278304 0.9466843 0.2277768 0.2272365 0.9469538 0.2272487 -0.00737375 0.9999457 -0.007373809 -1.802e-4 0.9999999 1.87588e-4 -0.03766423 0.9985941 -0.0372976 -0.001123189 0.9999988 0.001169264 -0.02779906 0.9992879 -0.0255118 -0.001827418 0.9999966 0.001827418 -0.001828968 0.9999967 0.001825928 -0.00355786 0.9999937 1.48728e-4 -0.001827836 0.9999967 0.001827836 0.01592862 0.999681 0.01960247 0.02926355 0.9990482 0.03234976 0.01750737 0.9996779 0.01837158 0.03017145 0.9990029 0.03290569 -5.49752e-4 0.9999998 5.65976e-4 0.02020961 0.9995684 0.02132362 -2.39375e-5 1 2.46434e-5 0.1180577 0.9864138 -0.114237 -0.3496156 0.8695223 0.3488551 8.99659e-4 0.9999992 9.47317e-4 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.5054781 0.7053743 -0.4968718 0.7070834 5.49333e-4 -0.7070834 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.2199863 0.9503747 -0.2199863 -0.5677097 0.5961548 -0.5677193 -0.5677542 0.5960782 -0.5677552 -0.567722 0.5961288 -0.5677343</float_array> + <technique_common> + <accessor source="#Kinton-mesh-normals-array" count="31662" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Kinton-mesh-vertices"> + <input semantic="POSITION" source="#Kinton-mesh-positions"/> + </vertices> + <polylist material="mat_kinton_struct-material" count="13848"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>0 0 1 0 2 0 3 1 2 1 1 1 4 2 2 2 5 2 3 3 5 3 2 3 6 4 0 4 2 4 4 5 6 5 2 5 7 6 8 6 1 6 9 7 1 7 8 7 0 8 10 8 1 8 7 9 1 9 10 9 11 10 3 10 1 10 11 11 1 11 9 11 7 12 5 12 8 12 9 13 8 13 5 13 12 14 5 14 7 14 12 15 4 15 5 15 13 16 5 16 3 16 9 17 5 17 13 17 14 18 15 18 16 18 17 19 16 19 15 19 16 20 0 20 6 20 17 21 0 21 16 21 6 22 14 22 16 22 7 23 10 23 15 23 18 24 15 24 10 24 14 25 19 25 15 25 7 26 15 26 19 26 20 27 17 27 15 27 20 28 15 28 18 28 10 29 0 29 18 29 21 30 0 30 17 30 18 31 0 31 21 31 22 32 23 32 24 32 25 33 24 33 23 33 6 34 24 34 14 34 25 35 14 35 24 35 6 36 22 36 24 36 7 37 19 37 23 37 26 38 23 38 19 38 22 39 27 39 23 39 7 40 23 40 27 40 28 41 25 41 23 41 28 42 23 42 26 42 26 43 19 43 14 43 29 44 14 44 25 44 26 45 14 45 29 45 30 46 31 46 32 46 33 47 32 47 31 47 6 48 32 48 22 48 33 49 22 49 32 49 6 50 30 50 32 50 7 51 27 51 31 51 34 52 31 52 27 52 30 53 35 53 31 53 7 54 31 54 35 54 36 55 33 55 31 55 36 56 31 56 34 56 34 57 27 57 22 57 37 58 22 58 33 58 34 59 22 59 37 59 38 60 39 60 40 60 41 61 40 61 39 61 6 62 40 62 30 62 41 63 30 63 40 63 6 64 38 64 40 64 7 65 35 65 39 65 42 66 39 66 35 66 38 67 43 67 39 67 7 68 39 68 43 68 44 69 41 69 39 69 44 70 39 70 42 70 42 71 35 71 30 71 45 72 30 72 41 72 42 73 30 73 45 73 46 74 47 74 48 74 49 75 48 75 47 75 6 76 48 76 38 76 49 77 38 77 48 77 6 78 46 78 48 78 7 79 43 79 47 79 50 80 47 80 43 80 46 81 51 81 47 81 7 82 47 82 51 82 52 83 49 83 47 83 52 84 47 84 50 84 50 85 43 85 38 85 53 86 38 86 49 86 50 87 38 87 53 87 54 88 55 88 56 88 57 89 56 89 55 89 6 90 56 90 46 90 57 91 46 91 56 91 6 92 54 92 56 92 7 93 51 93 55 93 58 94 55 94 51 94 54 95 59 95 55 95 7 96 55 96 59 96 60 97 57 97 55 97 60 98 55 98 58 98 58 99 51 99 46 99 61 100 46 100 57 100 58 101 46 101 61 101 62 102 63 102 64 102 65 103 64 103 63 103 6 104 64 104 54 104 65 105 54 105 64 105 6 106 62 106 64 106 7 107 59 107 63 107 66 108 63 108 59 108 62 109 67 109 63 109 7 110 63 110 67 110 68 111 65 111 63 111 68 112 63 112 66 112 66 113 59 113 54 113 69 114 54 114 65 114 66 115 54 115 69 115 70 116 71 116 72 116 73 117 72 117 71 117 6 118 72 118 62 118 73 119 62 119 72 119 6 120 70 120 72 120 7 121 67 121 71 121 74 122 71 122 67 122 70 123 75 123 71 123 7 124 71 124 75 124 76 125 73 125 71 125 76 126 71 126 74 126 74 127 67 127 62 127 77 128 62 128 73 128 74 129 62 129 77 129 78 130 79 130 80 130 81 131 80 131 79 131 6 132 80 132 70 132 81 133 70 133 80 133 6 134 78 134 80 134 7 135 75 135 79 135 82 136 79 136 75 136 78 137 83 137 79 137 7 138 79 138 83 138 84 139 81 139 79 139 84 140 79 140 82 140 82 141 75 141 70 141 85 142 70 142 81 142 82 143 70 143 85 143 6 144 86 144 87 144 88 145 87 145 86 145 6 146 87 146 78 146 88 147 78 147 87 147 7 148 83 148 86 148 89 149 86 149 83 149 90 150 91 150 86 150 7 151 86 151 91 151 6 152 90 152 86 152 92 153 88 153 86 153 92 154 86 154 89 154 89 155 83 155 78 155 93 156 78 156 88 156 89 157 78 157 93 157 6 158 94 158 95 158 96 159 95 159 94 159 6 160 95 160 90 160 96 161 90 161 95 161 7 162 91 162 94 162 97 163 94 163 91 163 98 164 7 164 94 164 6 165 98 165 94 165 99 166 96 166 94 166 99 167 94 167 97 167 97 168 91 168 90 168 100 169 90 169 96 169 97 170 90 170 100 170 101 171 102 171 103 171 104 172 103 172 102 172 101 173 103 173 105 173 104 174 105 174 103 174 106 175 107 175 102 175 108 176 102 176 107 176 101 177 109 177 102 177 110 178 102 178 109 178 111 179 106 179 102 179 110 180 111 180 102 180 112 181 104 181 102 181 112 182 102 182 108 182 113 183 105 183 107 183 108 184 107 184 105 184 106 185 113 185 107 185 113 186 114 186 105 186 101 187 105 187 114 187 115 188 105 188 104 188 108 189 105 189 115 189 116 190 114 190 113 190 101 191 114 191 117 191 116 192 117 192 114 192 106 193 118 193 113 193 119 194 113 194 118 194 120 195 116 195 113 195 120 196 113 196 119 196 121 197 117 197 118 197 119 198 118 198 117 198 106 199 121 199 118 199 121 200 122 200 117 200 101 201 117 201 122 201 123 202 117 202 116 202 119 203 117 203 123 203 124 204 122 204 121 204 101 205 122 205 125 205 124 206 125 206 122 206 106 207 126 207 121 207 127 208 121 208 126 208 128 209 124 209 121 209 128 210 121 210 127 210 129 211 125 211 126 211 127 212 126 212 125 212 106 213 129 213 126 213 129 214 130 214 125 214 101 215 125 215 130 215 131 216 125 216 124 216 127 217 125 217 131 217 132 218 130 218 129 218 101 219 130 219 133 219 132 220 133 220 130 220 106 221 134 221 129 221 135 222 129 222 134 222 136 223 132 223 129 223 136 224 129 224 135 224 137 225 133 225 134 225 135 226 134 226 133 226 106 227 137 227 134 227 137 228 138 228 133 228 101 229 133 229 138 229 139 230 133 230 132 230 135 231 133 231 139 231 140 232 138 232 137 232 101 233 138 233 141 233 140 234 141 234 138 234 106 235 142 235 137 235 143 236 137 236 142 236 144 237 140 237 137 237 144 238 137 238 143 238 145 239 141 239 142 239 143 240 142 240 141 240 106 241 145 241 142 241 145 242 146 242 141 242 101 243 141 243 146 243 147 244 141 244 140 244 143 245 141 245 147 245 148 246 146 246 145 246 101 247 146 247 149 247 148 248 149 248 146 248 106 249 150 249 145 249 151 250 145 250 150 250 152 251 148 251 145 251 152 252 145 252 151 252 153 253 149 253 150 253 151 254 150 254 149 254 106 255 153 255 150 255 153 256 154 256 149 256 101 257 149 257 154 257 155 258 149 258 148 258 151 259 149 259 155 259 156 260 154 260 153 260 101 261 154 261 157 261 156 262 157 262 154 262 106 263 158 263 153 263 159 264 153 264 158 264 160 265 156 265 153 265 160 266 153 266 159 266 161 267 157 267 158 267 159 268 158 268 157 268 106 269 161 269 158 269 161 270 162 270 157 270 101 271 157 271 162 271 163 272 157 272 156 272 159 273 157 273 163 273 164 274 162 274 161 274 101 275 162 275 165 275 164 276 165 276 162 276 106 277 166 277 161 277 167 278 161 278 166 278 168 279 164 279 161 279 168 280 161 280 167 280 169 281 165 281 166 281 167 282 166 282 165 282 106 283 169 283 166 283 169 284 170 284 165 284 101 285 165 285 170 285 171 286 165 286 164 286 167 287 165 287 171 287 172 288 170 288 169 288 101 289 170 289 173 289 172 290 173 290 170 290 106 291 174 291 169 291 175 292 169 292 174 292 176 293 172 293 169 293 176 294 169 294 175 294 106 295 173 295 174 295 175 296 174 296 173 296 177 297 101 297 173 297 106 298 177 298 173 298 178 299 173 299 172 299 175 300 173 300 178 300 179 301 180 301 109 301 181 302 109 302 180 302 101 303 179 303 109 303 182 304 110 304 109 304 183 305 182 305 109 305 183 306 109 306 181 306 179 307 184 307 180 307 181 308 180 308 184 308 179 309 185 309 184 309 186 310 184 310 185 310 181 311 184 311 186 311 179 312 187 312 185 312 188 313 185 313 187 313 186 314 185 314 188 314 179 315 189 315 187 315 190 316 187 316 189 316 188 317 187 317 190 317 179 318 191 318 189 318 192 319 189 319 191 319 190 320 189 320 192 320 179 321 193 321 191 321 194 322 191 322 193 322 192 323 191 323 194 323 195 324 196 324 193 324 197 325 193 325 196 325 179 326 195 326 193 326 194 327 193 327 197 327 198 328 196 328 195 328 197 329 196 329 198 329 199 330 195 330 179 330 200 331 195 331 199 331 198 332 195 332 200 332 101 333 201 333 179 333 199 334 179 334 201 334 202 335 201 335 101 335 203 336 201 336 202 336 199 337 201 337 203 337 202 338 101 338 177 338 204 339 205 339 177 339 206 340 177 340 205 340 106 341 204 341 177 341 202 342 177 342 206 342 204 343 207 343 205 343 208 344 205 344 207 344 206 345 205 345 208 345 209 346 207 346 204 346 208 347 207 347 209 347 210 348 204 348 106 348 209 349 204 349 210 349 211 350 106 350 111 350 210 351 106 351 211 351 12 352 7 352 111 352 212 353 111 353 7 353 110 354 12 354 111 354 211 355 111 355 212 355 213 356 7 356 98 356 212 357 7 357 213 357 214 358 215 358 98 358 216 359 98 359 215 359 6 360 214 360 98 360 213 361 98 361 216 361 217 362 215 362 214 362 216 363 215 363 217 363 218 364 214 364 6 364 217 365 214 365 218 365 219 366 6 366 4 366 218 367 6 367 219 367 220 368 4 368 12 368 221 369 4 369 220 369 219 370 4 370 221 370 220 371 12 371 110 371 220 372 110 372 182 372 221 373 13 373 3 373 18 374 3 374 11 374 221 375 3 375 18 375 220 376 9 376 13 376 221 377 220 377 13 377 216 378 11 378 9 378 220 379 182 379 9 379 212 380 9 380 182 380 213 381 216 381 9 381 212 382 213 382 9 382 216 383 18 383 11 383 221 384 21 384 17 384 26 385 17 385 20 385 26 386 29 386 17 386 221 387 17 387 29 387 221 388 18 388 21 388 216 389 20 389 18 389 216 390 26 390 20 390 221 391 29 391 25 391 34 392 25 392 28 392 34 393 37 393 25 393 221 394 25 394 37 394 216 395 28 395 26 395 216 396 34 396 28 396 221 397 37 397 33 397 42 398 33 398 36 398 42 399 45 399 33 399 221 400 33 400 45 400 216 401 36 401 34 401 216 402 42 402 36 402 221 403 45 403 41 403 50 404 41 404 44 404 50 405 53 405 41 405 221 406 41 406 53 406 216 407 44 407 42 407 216 408 50 408 44 408 221 409 53 409 49 409 58 410 49 410 52 410 58 411 61 411 49 411 221 412 49 412 61 412 216 413 52 413 50 413 216 414 58 414 52 414 221 415 61 415 57 415 66 416 57 416 60 416 66 417 69 417 57 417 221 418 57 418 69 418 216 419 60 419 58 419 216 420 66 420 60 420 221 421 69 421 65 421 74 422 65 422 68 422 74 423 77 423 65 423 221 424 65 424 77 424 216 425 68 425 66 425 216 426 74 426 68 426 221 427 77 427 73 427 82 428 73 428 76 428 82 429 85 429 73 429 221 430 73 430 85 430 216 431 76 431 74 431 216 432 82 432 76 432 221 433 85 433 81 433 89 434 81 434 84 434 89 435 93 435 81 435 221 436 81 436 93 436 216 437 84 437 82 437 216 438 89 438 84 438 221 439 93 439 88 439 216 440 88 440 92 440 97 441 100 441 88 441 221 442 88 442 100 442 216 443 97 443 88 443 216 444 92 444 89 444 221 445 100 445 96 445 216 446 96 446 99 446 219 447 221 447 96 447 216 448 219 448 96 448 216 449 99 449 97 449 206 450 115 450 104 450 212 451 104 451 112 451 212 452 182 452 104 452 183 453 104 453 182 453 183 454 206 454 104 454 116 455 108 455 115 455 206 456 116 456 115 456 212 457 112 457 108 457 120 458 108 458 116 458 212 459 108 459 120 459 206 460 123 460 116 460 124 461 119 461 123 461 206 462 124 462 123 462 212 463 120 463 119 463 128 464 119 464 124 464 212 465 119 465 128 465 206 466 131 466 124 466 132 467 127 467 131 467 206 468 132 468 131 468 212 469 128 469 127 469 136 470 127 470 132 470 212 471 127 471 136 471 206 472 139 472 132 472 140 473 135 473 139 473 206 474 140 474 139 474 212 475 136 475 135 475 144 476 135 476 140 476 212 477 135 477 144 477 206 478 147 478 140 478 148 479 143 479 147 479 206 480 148 480 147 480 212 481 144 481 143 481 152 482 143 482 148 482 212 483 143 483 152 483 206 484 155 484 148 484 156 485 151 485 155 485 206 486 156 486 155 486 212 487 152 487 151 487 160 488 151 488 156 488 212 489 151 489 160 489 206 490 163 490 156 490 164 491 159 491 163 491 206 492 164 492 163 492 212 493 160 493 159 493 168 494 159 494 164 494 212 495 159 495 168 495 206 496 171 496 164 496 172 497 167 497 171 497 206 498 172 498 171 498 212 499 168 499 167 499 176 500 167 500 172 500 212 501 167 501 176 501 206 502 178 502 172 502 206 503 175 503 178 503 212 504 176 504 175 504 211 505 212 505 175 505 206 506 211 506 175 506 217 507 218 507 219 507 216 508 217 508 219 508 209 509 210 509 211 509 206 510 209 510 211 510 206 511 208 511 209 511 183 512 202 512 206 512 181 513 203 513 202 513 183 514 181 514 202 514 194 515 199 515 203 515 192 516 194 516 203 516 190 517 192 517 203 517 188 518 190 518 203 518 186 519 188 519 203 519 181 520 186 520 203 520 198 521 200 521 199 521 197 522 198 522 199 522 194 523 197 523 199 523 222 524 223 524 224 524 225 525 224 525 223 525 226 526 224 526 227 526 225 527 227 527 224 527 228 528 222 528 224 528 226 529 228 529 224 529 229 530 230 530 223 530 231 531 223 531 230 531 222 532 232 532 223 532 229 533 223 533 232 533 233 534 225 534 223 534 233 535 223 535 231 535 229 536 227 536 230 536 231 537 230 537 227 537 234 538 227 538 229 538 234 539 226 539 227 539 235 540 227 540 225 540 231 541 227 541 235 541 236 542 237 542 238 542 239 543 238 543 237 543 228 544 238 544 222 544 239 545 222 545 238 545 228 546 236 546 238 546 229 547 232 547 237 547 240 548 237 548 232 548 236 549 241 549 237 549 229 550 237 550 241 550 242 551 239 551 237 551 242 552 237 552 240 552 240 553 232 553 222 553 243 554 222 554 239 554 240 555 222 555 243 555 244 556 245 556 246 556 247 557 246 557 245 557 228 558 246 558 236 558 247 559 236 559 246 559 228 560 244 560 246 560 229 561 241 561 245 561 248 562 245 562 241 562 244 563 249 563 245 563 229 564 245 564 249 564 250 565 247 565 245 565 250 566 245 566 248 566 248 567 241 567 236 567 251 568 236 568 247 568 248 569 236 569 251 569 252 570 253 570 254 570 255 571 254 571 253 571 228 572 254 572 244 572 255 573 244 573 254 573 228 574 252 574 254 574 229 575 249 575 253 575 256 576 253 576 249 576 252 577 257 577 253 577 229 578 253 578 257 578 258 579 255 579 253 579 258 580 253 580 256 580 256 581 249 581 244 581 259 582 244 582 255 582 256 583 244 583 259 583 260 584 261 584 262 584 263 585 262 585 261 585 228 586 262 586 252 586 263 587 252 587 262 587 228 588 260 588 262 588 229 589 257 589 261 589 264 590 261 590 257 590 260 591 265 591 261 591 229 592 261 592 265 592 266 593 263 593 261 593 266 594 261 594 264 594 264 595 257 595 252 595 267 596 252 596 263 596 264 597 252 597 267 597 268 598 269 598 270 598 271 599 270 599 269 599 228 600 270 600 260 600 271 601 260 601 270 601 228 602 268 602 270 602 229 603 265 603 269 603 272 604 269 604 265 604 268 605 273 605 269 605 229 606 269 606 273 606 274 607 271 607 269 607 274 608 269 608 272 608 272 609 265 609 260 609 275 610 260 610 271 610 272 611 260 611 275 611 276 612 277 612 278 612 279 613 278 613 277 613 228 614 278 614 268 614 279 615 268 615 278 615 228 616 276 616 278 616 229 617 273 617 277 617 280 618 277 618 273 618 276 619 281 619 277 619 229 620 277 620 281 620 282 621 279 621 277 621 282 622 277 622 280 622 280 623 273 623 268 623 283 624 268 624 279 624 280 625 268 625 283 625 284 626 285 626 286 626 287 627 286 627 285 627 228 628 286 628 276 628 287 629 276 629 286 629 228 630 284 630 286 630 229 631 281 631 285 631 288 632 285 632 281 632 284 633 289 633 285 633 229 634 285 634 289 634 290 635 287 635 285 635 290 636 285 636 288 636 288 637 281 637 276 637 291 638 276 638 287 638 288 639 276 639 291 639 292 640 293 640 294 640 295 641 294 641 293 641 228 642 294 642 284 642 295 643 284 643 294 643 228 644 292 644 294 644 229 645 289 645 293 645 296 646 293 646 289 646 292 647 297 647 293 647 229 648 293 648 297 648 298 649 295 649 293 649 298 650 293 650 296 650 296 651 289 651 284 651 299 652 284 652 295 652 296 653 284 653 299 653 300 654 301 654 302 654 303 655 302 655 301 655 228 656 302 656 292 656 303 657 292 657 302 657 228 658 300 658 302 658 229 659 297 659 301 659 304 660 301 660 297 660 300 661 305 661 301 661 229 662 301 662 305 662 306 663 303 663 301 663 306 664 301 664 304 664 304 665 297 665 292 665 307 666 292 666 303 666 304 667 292 667 307 667 228 668 308 668 309 668 310 669 309 669 308 669 228 670 309 670 300 670 310 671 300 671 309 671 229 672 305 672 308 672 311 673 308 673 305 673 312 674 313 674 308 674 229 675 308 675 313 675 228 676 312 676 308 676 314 677 310 677 308 677 314 678 308 678 311 678 311 679 305 679 300 679 315 680 300 680 310 680 311 681 300 681 315 681 228 682 316 682 317 682 318 683 317 683 316 683 228 684 317 684 312 684 318 685 312 685 317 685 229 686 313 686 316 686 319 687 316 687 313 687 320 688 229 688 316 688 228 689 320 689 316 689 321 690 318 690 316 690 321 691 316 691 319 691 319 692 313 692 312 692 322 693 312 693 318 693 319 694 312 694 322 694 323 695 324 695 325 695 326 696 325 696 324 696 323 697 325 697 327 697 326 698 327 698 325 698 328 699 329 699 324 699 330 700 324 700 329 700 323 701 331 701 324 701 332 702 324 702 331 702 333 703 328 703 324 703 332 704 333 704 324 704 334 705 326 705 324 705 334 706 324 706 330 706 335 707 327 707 329 707 330 708 329 708 327 708 328 709 335 709 329 709 335 710 336 710 327 710 323 711 327 711 336 711 337 712 327 712 326 712 330 713 327 713 337 713 338 714 336 714 335 714 323 715 336 715 339 715 338 716 339 716 336 716 328 717 340 717 335 717 341 718 335 718 340 718 342 719 338 719 335 719 342 720 335 720 341 720 343 721 339 721 340 721 341 722 340 722 339 722 328 723 343 723 340 723 343 724 344 724 339 724 323 725 339 725 344 725 345 726 339 726 338 726 341 727 339 727 345 727 346 728 344 728 343 728 323 729 344 729 347 729 346 730 347 730 344 730 328 731 348 731 343 731 349 732 343 732 348 732 350 733 346 733 343 733 350 734 343 734 349 734 351 735 347 735 348 735 349 736 348 736 347 736 328 737 351 737 348 737 351 738 352 738 347 738 323 739 347 739 352 739 353 740 347 740 346 740 349 741 347 741 353 741 354 742 352 742 351 742 323 743 352 743 355 743 354 744 355 744 352 744 328 745 356 745 351 745 357 746 351 746 356 746 358 747 354 747 351 747 358 748 351 748 357 748 359 749 355 749 356 749 357 750 356 750 355 750 328 751 359 751 356 751 359 752 360 752 355 752 323 753 355 753 360 753 361 754 355 754 354 754 357 755 355 755 361 755 362 756 360 756 359 756 323 757 360 757 363 757 362 758 363 758 360 758 328 759 364 759 359 759 365 760 359 760 364 760 366 761 362 761 359 761 366 762 359 762 365 762 367 763 363 763 364 763 365 764 364 764 363 764 328 765 367 765 364 765 367 766 368 766 363 766 323 767 363 767 368 767 369 768 363 768 362 768 365 769 363 769 369 769 370 770 368 770 367 770 323 771 368 771 371 771 370 772 371 772 368 772 328 773 372 773 367 773 373 774 367 774 372 774 374 775 370 775 367 775 374 776 367 776 373 776 375 777 371 777 372 777 373 778 372 778 371 778 328 779 375 779 372 779 375 780 376 780 371 780 323 781 371 781 376 781 377 782 371 782 370 782 373 783 371 783 377 783 378 784 376 784 375 784 323 785 376 785 379 785 378 786 379 786 376 786 328 787 380 787 375 787 381 788 375 788 380 788 382 789 378 789 375 789 382 790 375 790 381 790 383 791 379 791 380 791 381 792 380 792 379 792 328 793 383 793 380 793 383 794 384 794 379 794 323 795 379 795 384 795 385 796 379 796 378 796 381 797 379 797 385 797 386 798 384 798 383 798 323 799 384 799 387 799 386 800 387 800 384 800 328 801 388 801 383 801 389 802 383 802 388 802 390 803 386 803 383 803 390 804 383 804 389 804 391 805 387 805 388 805 389 806 388 806 387 806 328 807 391 807 388 807 391 808 392 808 387 808 323 809 387 809 392 809 393 810 387 810 386 810 389 811 387 811 393 811 394 812 392 812 391 812 323 813 392 813 395 813 394 814 395 814 392 814 328 815 396 815 391 815 397 816 391 816 396 816 398 817 394 817 391 817 398 818 391 818 397 818 328 819 395 819 396 819 397 820 396 820 395 820 399 821 323 821 395 821 328 822 399 822 395 822 400 823 395 823 394 823 397 824 395 824 400 824 401 825 402 825 331 825 403 826 331 826 402 826 323 827 401 827 331 827 404 828 332 828 331 828 405 829 404 829 331 829 405 830 331 830 403 830 401 831 406 831 402 831 403 832 402 832 406 832 401 833 407 833 406 833 408 834 406 834 407 834 403 835 406 835 408 835 401 836 409 836 407 836 410 837 407 837 409 837 408 838 407 838 410 838 401 839 411 839 409 839 412 840 409 840 411 840 410 841 409 841 412 841 401 842 413 842 411 842 414 843 411 843 413 843 412 844 411 844 414 844 401 845 415 845 413 845 416 846 413 846 415 846 414 847 413 847 416 847 417 848 418 848 415 848 419 849 415 849 418 849 401 850 417 850 415 850 416 851 415 851 419 851 420 852 418 852 417 852 419 853 418 853 420 853 421 854 417 854 401 854 422 855 417 855 421 855 420 856 417 856 422 856 323 857 423 857 401 857 421 858 401 858 423 858 424 859 423 859 323 859 425 860 423 860 424 860 421 861 423 861 425 861 424 862 323 862 399 862 426 863 427 863 399 863 428 864 399 864 427 864 328 865 426 865 399 865 424 866 399 866 428 866 426 867 429 867 427 867 430 868 427 868 429 868 428 869 427 869 430 869 431 870 429 870 426 870 430 871 429 871 431 871 432 872 426 872 328 872 431 873 426 873 432 873 433 874 328 874 333 874 432 875 328 875 433 875 234 876 229 876 333 876 434 877 333 877 229 877 332 878 234 878 333 878 433 879 333 879 434 879 435 880 229 880 320 880 434 881 229 881 435 881 436 882 437 882 320 882 438 883 320 883 437 883 228 884 436 884 320 884 435 885 320 885 438 885 439 886 437 886 436 886 438 887 437 887 439 887 440 888 436 888 228 888 439 889 436 889 440 889 441 890 228 890 226 890 440 891 228 891 441 891 442 892 226 892 234 892 443 893 226 893 442 893 441 894 226 894 443 894 442 895 234 895 332 895 442 896 332 896 404 896 443 897 235 897 225 897 240 898 225 898 233 898 443 899 225 899 240 899 442 900 231 900 235 900 443 901 442 901 235 901 438 902 233 902 231 902 442 903 404 903 231 903 434 904 231 904 404 904 435 905 438 905 231 905 434 906 435 906 231 906 438 907 240 907 233 907 443 908 243 908 239 908 248 909 239 909 242 909 248 910 251 910 239 910 443 911 239 911 251 911 443 912 240 912 243 912 438 913 242 913 240 913 438 914 248 914 242 914 443 915 251 915 247 915 256 916 247 916 250 916 256 917 259 917 247 917 443 918 247 918 259 918 438 919 250 919 248 919 438 920 256 920 250 920 443 921 259 921 255 921 264 922 255 922 258 922 264 923 267 923 255 923 443 924 255 924 267 924 438 925 258 925 256 925 438 926 264 926 258 926 443 927 267 927 263 927 272 928 263 928 266 928 272 929 275 929 263 929 443 930 263 930 275 930 438 931 266 931 264 931 438 932 272 932 266 932 443 933 275 933 271 933 280 934 271 934 274 934 280 935 283 935 271 935 443 936 271 936 283 936 438 937 274 937 272 937 438 938 280 938 274 938 443 939 283 939 279 939 288 940 279 940 282 940 288 941 291 941 279 941 443 942 279 942 291 942 438 943 282 943 280 943 438 944 288 944 282 944 443 945 291 945 287 945 296 946 287 946 290 946 296 947 299 947 287 947 443 948 287 948 299 948 438 949 290 949 288 949 438 950 296 950 290 950 443 951 299 951 295 951 304 952 295 952 298 952 304 953 307 953 295 953 443 954 295 954 307 954 438 955 298 955 296 955 438 956 304 956 298 956 443 957 307 957 303 957 311 958 303 958 306 958 311 959 315 959 303 959 443 960 303 960 315 960 438 961 306 961 304 961 438 962 311 962 306 962 443 963 315 963 310 963 438 964 310 964 314 964 319 965 322 965 310 965 443 966 310 966 322 966 438 967 319 967 310 967 438 968 314 968 311 968 443 969 322 969 318 969 438 970 318 970 321 970 441 971 443 971 318 971 438 972 441 972 318 972 438 973 321 973 319 973 428 974 337 974 326 974 434 975 326 975 334 975 434 976 404 976 326 976 405 977 326 977 404 977 405 978 428 978 326 978 338 979 330 979 337 979 428 980 338 980 337 980 434 981 334 981 330 981 342 982 330 982 338 982 434 983 330 983 342 983 428 984 345 984 338 984 346 985 341 985 345 985 428 986 346 986 345 986 434 987 342 987 341 987 350 988 341 988 346 988 434 989 341 989 350 989 428 990 353 990 346 990 354 991 349 991 353 991 428 992 354 992 353 992 434 993 350 993 349 993 358 994 349 994 354 994 434 995 349 995 358 995 428 996 361 996 354 996 362 997 357 997 361 997 428 998 362 998 361 998 434 999 358 999 357 999 366 1000 357 1000 362 1000 434 1001 357 1001 366 1001 428 1002 369 1002 362 1002 370 1003 365 1003 369 1003 428 1004 370 1004 369 1004 434 1005 366 1005 365 1005 374 1006 365 1006 370 1006 434 1007 365 1007 374 1007 428 1008 377 1008 370 1008 378 1009 373 1009 377 1009 428 1010 378 1010 377 1010 434 1011 374 1011 373 1011 382 1012 373 1012 378 1012 434 1013 373 1013 382 1013 428 1014 385 1014 378 1014 386 1015 381 1015 385 1015 428 1016 386 1016 385 1016 434 1017 382 1017 381 1017 390 1018 381 1018 386 1018 434 1019 381 1019 390 1019 428 1020 393 1020 386 1020 394 1021 389 1021 393 1021 428 1022 394 1022 393 1022 434 1023 390 1023 389 1023 398 1024 389 1024 394 1024 434 1025 389 1025 398 1025 428 1026 400 1026 394 1026 428 1027 397 1027 400 1027 434 1028 398 1028 397 1028 433 1029 434 1029 397 1029 428 1030 433 1030 397 1030 439 1031 440 1031 441 1031 438 1032 439 1032 441 1032 431 1033 432 1033 433 1033 428 1034 431 1034 433 1034 428 1035 430 1035 431 1035 405 1036 424 1036 428 1036 403 1037 425 1037 424 1037 405 1038 403 1038 424 1038 416 1039 421 1039 425 1039 414 1040 416 1040 425 1040 412 1041 414 1041 425 1041 410 1042 412 1042 425 1042 408 1043 410 1043 425 1043 403 1044 408 1044 425 1044 420 1045 422 1045 421 1045 419 1046 420 1046 421 1046 416 1047 419 1047 421 1047 444 1048 445 1048 446 1048 447 1049 446 1049 445 1049 448 1050 446 1050 449 1050 447 1051 449 1051 446 1051 450 1052 444 1052 446 1052 448 1053 450 1053 446 1053 451 1054 452 1054 445 1054 453 1055 445 1055 452 1055 444 1056 454 1056 445 1056 451 1057 445 1057 454 1057 455 1058 447 1058 445 1058 455 1059 445 1059 453 1059 451 1060 449 1060 452 1060 453 1061 452 1061 449 1061 456 1062 449 1062 451 1062 456 1063 448 1063 449 1063 457 1064 449 1064 447 1064 453 1065 449 1065 457 1065 458 1066 459 1066 460 1066 461 1067 460 1067 459 1067 450 1068 460 1068 444 1068 461 1069 444 1069 460 1069 450 1070 458 1070 460 1070 451 1071 454 1071 459 1071 462 1072 459 1072 454 1072 458 1073 463 1073 459 1073 451 1074 459 1074 463 1074 464 1075 461 1075 459 1075 464 1076 459 1076 462 1076 462 1077 454 1077 444 1077 465 1078 444 1078 461 1078 462 1079 444 1079 465 1079 466 1080 467 1080 468 1080 469 1081 468 1081 467 1081 450 1082 468 1082 458 1082 469 1083 458 1083 468 1083 450 1084 466 1084 468 1084 451 1085 463 1085 467 1085 470 1086 467 1086 463 1086 466 1087 471 1087 467 1087 451 1088 467 1088 471 1088 472 1089 469 1089 467 1089 472 1090 467 1090 470 1090 470 1091 463 1091 458 1091 473 1092 458 1092 469 1092 470 1093 458 1093 473 1093 474 1094 475 1094 476 1094 477 1095 476 1095 475 1095 450 1096 476 1096 466 1096 477 1097 466 1097 476 1097 450 1098 474 1098 476 1098 451 1099 471 1099 475 1099 478 1100 475 1100 471 1100 474 1101 479 1101 475 1101 451 1102 475 1102 479 1102 480 1103 477 1103 475 1103 480 1104 475 1104 478 1104 478 1105 471 1105 466 1105 481 1106 466 1106 477 1106 478 1107 466 1107 481 1107 482 1108 483 1108 484 1108 485 1109 484 1109 483 1109 450 1110 484 1110 474 1110 485 1111 474 1111 484 1111 450 1112 482 1112 484 1112 451 1113 479 1113 483 1113 486 1114 483 1114 479 1114 482 1115 487 1115 483 1115 451 1116 483 1116 487 1116 488 1117 485 1117 483 1117 488 1118 483 1118 486 1118 486 1119 479 1119 474 1119 489 1120 474 1120 485 1120 486 1121 474 1121 489 1121 490 1122 491 1122 492 1122 493 1123 492 1123 491 1123 450 1124 492 1124 482 1124 493 1125 482 1125 492 1125 450 1126 490 1126 492 1126 451 1127 487 1127 491 1127 494 1128 491 1128 487 1128 490 1129 495 1129 491 1129 451 1130 491 1130 495 1130 496 1131 493 1131 491 1131 496 1132 491 1132 494 1132 494 1133 487 1133 482 1133 497 1134 482 1134 493 1134 494 1135 482 1135 497 1135 498 1136 499 1136 500 1136 501 1137 500 1137 499 1137 450 1138 500 1138 490 1138 501 1139 490 1139 500 1139 450 1140 498 1140 500 1140 451 1141 495 1141 499 1141 502 1142 499 1142 495 1142 498 1143 503 1143 499 1143 451 1144 499 1144 503 1144 504 1145 501 1145 499 1145 504 1146 499 1146 502 1146 502 1147 495 1147 490 1147 505 1148 490 1148 501 1148 502 1149 490 1149 505 1149 506 1150 507 1150 508 1150 509 1151 508 1151 507 1151 450 1152 508 1152 498 1152 509 1153 498 1153 508 1153 450 1154 506 1154 508 1154 451 1155 503 1155 507 1155 510 1156 507 1156 503 1156 506 1157 511 1157 507 1157 451 1158 507 1158 511 1158 512 1159 509 1159 507 1159 512 1160 507 1160 510 1160 510 1161 503 1161 498 1161 513 1162 498 1162 509 1162 510 1163 498 1163 513 1163 514 1164 515 1164 516 1164 517 1165 516 1165 515 1165 450 1166 516 1166 506 1166 517 1167 506 1167 516 1167 450 1168 514 1168 516 1168 451 1169 511 1169 515 1169 518 1170 515 1170 511 1170 514 1171 519 1171 515 1171 451 1172 515 1172 519 1172 520 1173 517 1173 515 1173 520 1174 515 1174 518 1174 518 1175 511 1175 506 1175 521 1176 506 1176 517 1176 518 1177 506 1177 521 1177 522 1178 523 1178 524 1178 525 1179 524 1179 523 1179 450 1180 524 1180 514 1180 525 1181 514 1181 524 1181 450 1182 522 1182 524 1182 451 1183 519 1183 523 1183 526 1184 523 1184 519 1184 522 1185 527 1185 523 1185 451 1186 523 1186 527 1186 528 1187 525 1187 523 1187 528 1188 523 1188 526 1188 526 1189 519 1189 514 1189 529 1190 514 1190 525 1190 526 1191 514 1191 529 1191 450 1192 530 1192 531 1192 532 1193 531 1193 530 1193 450 1194 531 1194 522 1194 532 1195 522 1195 531 1195 451 1196 527 1196 530 1196 533 1197 530 1197 527 1197 534 1198 535 1198 530 1198 451 1199 530 1199 535 1199 450 1200 534 1200 530 1200 536 1201 532 1201 530 1201 536 1202 530 1202 533 1202 533 1203 527 1203 522 1203 537 1204 522 1204 532 1204 533 1205 522 1205 537 1205 450 1206 538 1206 539 1206 540 1207 539 1207 538 1207 450 1208 539 1208 534 1208 540 1209 534 1209 539 1209 451 1210 535 1210 538 1210 541 1211 538 1211 535 1211 542 1212 451 1212 538 1212 450 1213 542 1213 538 1213 543 1214 540 1214 538 1214 543 1215 538 1215 541 1215 541 1216 535 1216 534 1216 544 1217 534 1217 540 1217 541 1218 534 1218 544 1218 545 1219 546 1219 547 1219 548 1220 547 1220 546 1220 545 1221 547 1221 549 1221 548 1222 549 1222 547 1222 550 1223 551 1223 546 1223 552 1224 546 1224 551 1224 545 1225 553 1225 546 1225 554 1226 546 1226 553 1226 555 1227 550 1227 546 1227 554 1228 555 1228 546 1228 556 1229 548 1229 546 1229 556 1230 546 1230 552 1230 557 1231 549 1231 551 1231 552 1232 551 1232 549 1232 550 1233 557 1233 551 1233 557 1234 558 1234 549 1234 545 1235 549 1235 558 1235 559 1236 549 1236 548 1236 552 1237 549 1237 559 1237 560 1238 558 1238 557 1238 545 1239 558 1239 561 1239 560 1240 561 1240 558 1240 550 1241 562 1241 557 1241 563 1242 557 1242 562 1242 564 1243 560 1243 557 1243 564 1244 557 1244 563 1244 565 1245 561 1245 562 1245 563 1246 562 1246 561 1246 550 1247 565 1247 562 1247 565 1248 566 1248 561 1248 545 1249 561 1249 566 1249 567 1250 561 1250 560 1250 563 1251 561 1251 567 1251 568 1252 566 1252 565 1252 545 1253 566 1253 569 1253 568 1254 569 1254 566 1254 550 1255 570 1255 565 1255 571 1256 565 1256 570 1256 572 1257 568 1257 565 1257 572 1258 565 1258 571 1258 573 1259 569 1259 570 1259 571 1260 570 1260 569 1260 550 1261 573 1261 570 1261 573 1262 574 1262 569 1262 545 1263 569 1263 574 1263 575 1264 569 1264 568 1264 571 1265 569 1265 575 1265 576 1266 574 1266 573 1266 545 1267 574 1267 577 1267 576 1268 577 1268 574 1268 550 1269 578 1269 573 1269 579 1270 573 1270 578 1270 580 1271 576 1271 573 1271 580 1272 573 1272 579 1272 581 1273 577 1273 578 1273 579 1274 578 1274 577 1274 550 1275 581 1275 578 1275 581 1276 582 1276 577 1276 545 1277 577 1277 582 1277 583 1278 577 1278 576 1278 579 1279 577 1279 583 1279 584 1280 582 1280 581 1280 545 1281 582 1281 585 1281 584 1282 585 1282 582 1282 550 1283 586 1283 581 1283 587 1284 581 1284 586 1284 588 1285 584 1285 581 1285 588 1286 581 1286 587 1286 589 1287 585 1287 586 1287 587 1288 586 1288 585 1288 550 1289 589 1289 586 1289 589 1290 590 1290 585 1290 545 1291 585 1291 590 1291 591 1292 585 1292 584 1292 587 1293 585 1293 591 1293 592 1294 590 1294 589 1294 545 1295 590 1295 593 1295 592 1296 593 1296 590 1296 550 1297 594 1297 589 1297 595 1298 589 1298 594 1298 596 1299 592 1299 589 1299 596 1300 589 1300 595 1300 597 1301 593 1301 594 1301 595 1302 594 1302 593 1302 550 1303 597 1303 594 1303 597 1304 598 1304 593 1304 545 1305 593 1305 598 1305 599 1306 593 1306 592 1306 595 1307 593 1307 599 1307 600 1308 598 1308 597 1308 545 1309 598 1309 601 1309 600 1310 601 1310 598 1310 550 1311 602 1311 597 1311 603 1312 597 1312 602 1312 604 1313 600 1313 597 1313 604 1314 597 1314 603 1314 605 1315 601 1315 602 1315 603 1316 602 1316 601 1316 550 1317 605 1317 602 1317 605 1318 606 1318 601 1318 545 1319 601 1319 606 1319 607 1320 601 1320 600 1320 603 1321 601 1321 607 1321 608 1322 606 1322 605 1322 545 1323 606 1323 609 1323 608 1324 609 1324 606 1324 550 1325 610 1325 605 1325 611 1326 605 1326 610 1326 612 1327 608 1327 605 1327 612 1328 605 1328 611 1328 613 1329 609 1329 610 1329 611 1330 610 1330 609 1330 550 1331 613 1331 610 1331 613 1332 614 1332 609 1332 545 1333 609 1333 614 1333 615 1334 609 1334 608 1334 611 1335 609 1335 615 1335 616 1336 614 1336 613 1336 545 1337 614 1337 617 1337 616 1338 617 1338 614 1338 550 1339 618 1339 613 1339 619 1340 613 1340 618 1340 620 1341 616 1341 613 1341 620 1342 613 1342 619 1342 550 1343 617 1343 618 1343 619 1344 618 1344 617 1344 621 1345 545 1345 617 1345 550 1346 621 1346 617 1346 622 1347 617 1347 616 1347 619 1348 617 1348 622 1348 623 1349 624 1349 553 1349 625 1350 553 1350 624 1350 545 1351 623 1351 553 1351 626 1352 554 1352 553 1352 627 1353 626 1353 553 1353 627 1354 553 1354 625 1354 623 1355 628 1355 624 1355 625 1356 624 1356 628 1356 623 1357 629 1357 628 1357 630 1358 628 1358 629 1358 625 1359 628 1359 630 1359 623 1360 631 1360 629 1360 632 1361 629 1361 631 1361 630 1362 629 1362 632 1362 623 1363 633 1363 631 1363 634 1364 631 1364 633 1364 632 1365 631 1365 634 1365 623 1366 635 1366 633 1366 636 1367 633 1367 635 1367 634 1368 633 1368 636 1368 623 1369 637 1369 635 1369 638 1370 635 1370 637 1370 636 1371 635 1371 638 1371 639 1372 640 1372 637 1372 641 1373 637 1373 640 1373 623 1374 639 1374 637 1374 638 1375 637 1375 641 1375 642 1376 640 1376 639 1376 641 1377 640 1377 642 1377 643 1378 639 1378 623 1378 644 1379 639 1379 643 1379 642 1380 639 1380 644 1380 545 1381 645 1381 623 1381 643 1382 623 1382 645 1382 646 1383 645 1383 545 1383 647 1384 645 1384 646 1384 643 1385 645 1385 647 1385 646 1386 545 1386 621 1386 648 1387 649 1387 621 1387 650 1388 621 1388 649 1388 550 1389 648 1389 621 1389 646 1390 621 1390 650 1390 648 1391 651 1391 649 1391 652 1392 649 1392 651 1392 650 1393 649 1393 652 1393 653 1394 651 1394 648 1394 652 1395 651 1395 653 1395 654 1396 648 1396 550 1396 653 1397 648 1397 654 1397 655 1398 550 1398 555 1398 654 1399 550 1399 655 1399 456 1400 451 1400 555 1400 656 1401 555 1401 451 1401 554 1402 456 1402 555 1402 655 1403 555 1403 656 1403 657 1404 451 1404 542 1404 656 1405 451 1405 657 1405 658 1406 659 1406 542 1406 660 1407 542 1407 659 1407 450 1408 658 1408 542 1408 657 1409 542 1409 660 1409 661 1410 659 1410 658 1410 660 1411 659 1411 661 1411 662 1412 658 1412 450 1412 661 1413 658 1413 662 1413 663 1414 450 1414 448 1414 662 1415 450 1415 663 1415 664 1416 448 1416 456 1416 665 1417 448 1417 664 1417 663 1418 448 1418 665 1418 664 1419 456 1419 554 1419 664 1420 554 1420 626 1420 665 1421 457 1421 447 1421 462 1422 447 1422 455 1422 665 1423 447 1423 462 1423 664 1424 453 1424 457 1424 665 1425 664 1425 457 1425 660 1426 455 1426 453 1426 664 1427 626 1427 453 1427 656 1428 453 1428 626 1428 657 1429 660 1429 453 1429 656 1430 657 1430 453 1430 660 1431 462 1431 455 1431 665 1432 465 1432 461 1432 470 1433 461 1433 464 1433 470 1434 473 1434 461 1434 665 1435 461 1435 473 1435 665 1436 462 1436 465 1436 660 1437 464 1437 462 1437 660 1438 470 1438 464 1438 665 1439 473 1439 469 1439 478 1440 469 1440 472 1440 478 1441 481 1441 469 1441 665 1442 469 1442 481 1442 660 1443 472 1443 470 1443 660 1444 478 1444 472 1444 665 1445 481 1445 477 1445 486 1446 477 1446 480 1446 486 1447 489 1447 477 1447 665 1448 477 1448 489 1448 660 1449 480 1449 478 1449 660 1450 486 1450 480 1450 665 1451 489 1451 485 1451 494 1452 485 1452 488 1452 494 1453 497 1453 485 1453 665 1454 485 1454 497 1454 660 1455 488 1455 486 1455 660 1456 494 1456 488 1456 665 1457 497 1457 493 1457 502 1458 493 1458 496 1458 502 1459 505 1459 493 1459 665 1460 493 1460 505 1460 660 1461 496 1461 494 1461 660 1462 502 1462 496 1462 665 1463 505 1463 501 1463 510 1464 501 1464 504 1464 510 1465 513 1465 501 1465 665 1466 501 1466 513 1466 660 1467 504 1467 502 1467 660 1468 510 1468 504 1468 665 1469 513 1469 509 1469 518 1470 509 1470 512 1470 518 1471 521 1471 509 1471 665 1472 509 1472 521 1472 660 1473 512 1473 510 1473 660 1474 518 1474 512 1474 665 1475 521 1475 517 1475 526 1476 517 1476 520 1476 526 1477 529 1477 517 1477 665 1478 517 1478 529 1478 660 1479 520 1479 518 1479 660 1480 526 1480 520 1480 665 1481 529 1481 525 1481 533 1482 525 1482 528 1482 533 1483 537 1483 525 1483 665 1484 525 1484 537 1484 660 1485 528 1485 526 1485 660 1486 533 1486 528 1486 665 1487 537 1487 532 1487 660 1488 532 1488 536 1488 541 1489 544 1489 532 1489 665 1490 532 1490 544 1490 660 1491 541 1491 532 1491 660 1492 536 1492 533 1492 665 1493 544 1493 540 1493 660 1494 540 1494 543 1494 663 1495 665 1495 540 1495 660 1496 663 1496 540 1496 660 1497 543 1497 541 1497 650 1498 559 1498 548 1498 656 1499 548 1499 556 1499 656 1500 626 1500 548 1500 627 1501 548 1501 626 1501 627 1502 650 1502 548 1502 560 1503 552 1503 559 1503 650 1504 560 1504 559 1504 656 1505 556 1505 552 1505 564 1506 552 1506 560 1506 656 1507 552 1507 564 1507 650 1508 567 1508 560 1508 568 1509 563 1509 567 1509 650 1510 568 1510 567 1510 656 1511 564 1511 563 1511 572 1512 563 1512 568 1512 656 1513 563 1513 572 1513 650 1514 575 1514 568 1514 576 1515 571 1515 575 1515 650 1516 576 1516 575 1516 656 1517 572 1517 571 1517 580 1518 571 1518 576 1518 656 1519 571 1519 580 1519 650 1520 583 1520 576 1520 584 1521 579 1521 583 1521 650 1522 584 1522 583 1522 656 1523 580 1523 579 1523 588 1524 579 1524 584 1524 656 1525 579 1525 588 1525 650 1526 591 1526 584 1526 592 1527 587 1527 591 1527 650 1528 592 1528 591 1528 656 1529 588 1529 587 1529 596 1530 587 1530 592 1530 656 1531 587 1531 596 1531 650 1532 599 1532 592 1532 600 1533 595 1533 599 1533 650 1534 600 1534 599 1534 656 1535 596 1535 595 1535 604 1536 595 1536 600 1536 656 1537 595 1537 604 1537 650 1538 607 1538 600 1538 608 1539 603 1539 607 1539 650 1540 608 1540 607 1540 656 1541 604 1541 603 1541 612 1542 603 1542 608 1542 656 1543 603 1543 612 1543 650 1544 615 1544 608 1544 616 1545 611 1545 615 1545 650 1546 616 1546 615 1546 656 1547 612 1547 611 1547 620 1548 611 1548 616 1548 656 1549 611 1549 620 1549 650 1550 622 1550 616 1550 650 1551 619 1551 622 1551 656 1552 620 1552 619 1552 655 1553 656 1553 619 1553 650 1554 655 1554 619 1554 661 1555 662 1555 663 1555 660 1556 661 1556 663 1556 653 1557 654 1557 655 1557 650 1558 653 1558 655 1558 650 1559 652 1559 653 1559 627 1560 646 1560 650 1560 625 1561 647 1561 646 1561 627 1562 625 1562 646 1562 638 1563 643 1563 647 1563 636 1564 638 1564 647 1564 634 1565 636 1565 647 1565 632 1566 634 1566 647 1566 630 1567 632 1567 647 1567 625 1568 630 1568 647 1568 642 1569 644 1569 643 1569 641 1570 642 1570 643 1570 638 1571 641 1571 643 1571 666 1572 667 1572 668 1572 669 1573 668 1573 667 1573 670 1574 668 1574 671 1574 669 1575 671 1575 668 1575 672 1576 666 1576 668 1576 670 1577 672 1577 668 1577 673 1578 674 1578 667 1578 675 1579 667 1579 674 1579 666 1580 676 1580 667 1580 673 1581 667 1581 676 1581 677 1582 669 1582 667 1582 677 1583 667 1583 675 1583 673 1584 671 1584 674 1584 675 1585 674 1585 671 1585 678 1586 671 1586 673 1586 678 1587 670 1587 671 1587 679 1588 671 1588 669 1588 675 1589 671 1589 679 1589 680 1590 681 1590 682 1590 683 1591 682 1591 681 1591 672 1592 682 1592 666 1592 683 1593 666 1593 682 1593 672 1594 680 1594 682 1594 673 1595 676 1595 681 1595 684 1596 681 1596 676 1596 680 1597 685 1597 681 1597 673 1598 681 1598 685 1598 686 1599 683 1599 681 1599 686 1600 681 1600 684 1600 684 1601 676 1601 666 1601 687 1602 666 1602 683 1602 684 1603 666 1603 687 1603 688 1604 689 1604 690 1604 691 1605 690 1605 689 1605 672 1606 690 1606 680 1606 691 1607 680 1607 690 1607 672 1608 688 1608 690 1608 673 1609 685 1609 689 1609 692 1610 689 1610 685 1610 688 1611 693 1611 689 1611 673 1612 689 1612 693 1612 694 1613 691 1613 689 1613 694 1614 689 1614 692 1614 692 1615 685 1615 680 1615 695 1616 680 1616 691 1616 692 1617 680 1617 695 1617 696 1618 697 1618 698 1618 699 1619 698 1619 697 1619 672 1620 698 1620 688 1620 699 1621 688 1621 698 1621 672 1622 696 1622 698 1622 673 1623 693 1623 697 1623 700 1624 697 1624 693 1624 696 1625 701 1625 697 1625 673 1626 697 1626 701 1626 702 1627 699 1627 697 1627 702 1628 697 1628 700 1628 700 1629 693 1629 688 1629 703 1630 688 1630 699 1630 700 1631 688 1631 703 1631 704 1632 705 1632 706 1632 707 1633 706 1633 705 1633 672 1634 706 1634 696 1634 707 1635 696 1635 706 1635 672 1636 704 1636 706 1636 673 1637 701 1637 705 1637 708 1638 705 1638 701 1638 704 1639 709 1639 705 1639 673 1640 705 1640 709 1640 710 1641 707 1641 705 1641 710 1642 705 1642 708 1642 708 1643 701 1643 696 1643 711 1644 696 1644 707 1644 708 1645 696 1645 711 1645 712 1646 713 1646 714 1646 715 1647 714 1647 713 1647 672 1648 714 1648 704 1648 715 1649 704 1649 714 1649 672 1650 712 1650 714 1650 673 1651 709 1651 713 1651 716 1652 713 1652 709 1652 712 1653 717 1653 713 1653 673 1654 713 1654 717 1654 718 1655 715 1655 713 1655 718 1656 713 1656 716 1656 716 1657 709 1657 704 1657 719 1658 704 1658 715 1658 716 1659 704 1659 719 1659 720 1660 721 1660 722 1660 723 1661 722 1661 721 1661 672 1662 722 1662 712 1662 723 1663 712 1663 722 1663 672 1664 720 1664 722 1664 673 1665 717 1665 721 1665 724 1666 721 1666 717 1666 720 1667 725 1667 721 1667 673 1668 721 1668 725 1668 726 1669 723 1669 721 1669 726 1670 721 1670 724 1670 724 1671 717 1671 712 1671 727 1672 712 1672 723 1672 724 1673 712 1673 727 1673 728 1674 729 1674 730 1674 731 1675 730 1675 729 1675 672 1676 730 1676 720 1676 731 1677 720 1677 730 1677 672 1678 728 1678 730 1678 673 1679 725 1679 729 1679 732 1680 729 1680 725 1680 728 1681 733 1681 729 1681 673 1682 729 1682 733 1682 734 1683 731 1683 729 1683 734 1684 729 1684 732 1684 732 1685 725 1685 720 1685 735 1686 720 1686 731 1686 732 1687 720 1687 735 1687 736 1688 737 1688 738 1688 739 1689 738 1689 737 1689 672 1690 738 1690 728 1690 739 1691 728 1691 738 1691 672 1692 736 1692 738 1692 673 1693 733 1693 737 1693 740 1694 737 1694 733 1694 736 1695 741 1695 737 1695 673 1696 737 1696 741 1696 742 1697 739 1697 737 1697 742 1698 737 1698 740 1698 740 1699 733 1699 728 1699 743 1700 728 1700 739 1700 740 1701 728 1701 743 1701 744 1702 745 1702 746 1702 747 1703 746 1703 745 1703 672 1704 746 1704 736 1704 747 1705 736 1705 746 1705 672 1706 744 1706 746 1706 673 1707 741 1707 745 1707 748 1708 745 1708 741 1708 744 1709 749 1709 745 1709 673 1710 745 1710 749 1710 750 1711 747 1711 745 1711 750 1712 745 1712 748 1712 748 1713 741 1713 736 1713 751 1714 736 1714 747 1714 748 1715 736 1715 751 1715 672 1716 752 1716 753 1716 754 1717 753 1717 752 1717 672 1718 753 1718 744 1718 754 1719 744 1719 753 1719 673 1720 749 1720 752 1720 755 1721 752 1721 749 1721 756 1722 757 1722 752 1722 673 1723 752 1723 757 1723 672 1724 756 1724 752 1724 758 1725 754 1725 752 1725 758 1726 752 1726 755 1726 755 1727 749 1727 744 1727 759 1728 744 1728 754 1728 755 1729 744 1729 759 1729 672 1730 760 1730 761 1730 762 1731 761 1731 760 1731 672 1732 761 1732 756 1732 762 1733 756 1733 761 1733 673 1734 757 1734 760 1734 763 1735 760 1735 757 1735 764 1736 673 1736 760 1736 672 1737 764 1737 760 1737 765 1738 762 1738 760 1738 765 1739 760 1739 763 1739 763 1740 757 1740 756 1740 766 1741 756 1741 762 1741 763 1742 756 1742 766 1742 767 1743 768 1743 769 1743 770 1744 769 1744 768 1744 767 1745 769 1745 771 1745 770 1746 771 1746 769 1746 772 1747 773 1747 768 1747 774 1748 768 1748 773 1748 767 1749 775 1749 768 1749 776 1750 768 1750 775 1750 777 1751 772 1751 768 1751 776 1752 777 1752 768 1752 778 1753 770 1753 768 1753 778 1754 768 1754 774 1754 779 1755 771 1755 773 1755 774 1756 773 1756 771 1756 772 1757 779 1757 773 1757 779 1758 780 1758 771 1758 767 1759 771 1759 780 1759 781 1760 771 1760 770 1760 774 1761 771 1761 781 1761 782 1762 780 1762 779 1762 767 1763 780 1763 783 1763 782 1764 783 1764 780 1764 772 1765 784 1765 779 1765 785 1766 779 1766 784 1766 786 1767 782 1767 779 1767 786 1768 779 1768 785 1768 787 1769 783 1769 784 1769 785 1770 784 1770 783 1770 772 1771 787 1771 784 1771 787 1772 788 1772 783 1772 767 1773 783 1773 788 1773 789 1774 783 1774 782 1774 785 1775 783 1775 789 1775 790 1776 788 1776 787 1776 767 1777 788 1777 791 1777 790 1778 791 1778 788 1778 772 1779 792 1779 787 1779 793 1780 787 1780 792 1780 794 1781 790 1781 787 1781 794 1782 787 1782 793 1782 795 1783 791 1783 792 1783 793 1784 792 1784 791 1784 772 1785 795 1785 792 1785 795 1786 796 1786 791 1786 767 1787 791 1787 796 1787 797 1788 791 1788 790 1788 793 1789 791 1789 797 1789 798 1790 796 1790 795 1790 767 1791 796 1791 799 1791 798 1792 799 1792 796 1792 772 1793 800 1793 795 1793 801 1794 795 1794 800 1794 802 1795 798 1795 795 1795 802 1796 795 1796 801 1796 803 1797 799 1797 800 1797 801 1798 800 1798 799 1798 772 1799 803 1799 800 1799 803 1800 804 1800 799 1800 767 1801 799 1801 804 1801 805 1802 799 1802 798 1802 801 1803 799 1803 805 1803 806 1804 804 1804 803 1804 767 1805 804 1805 807 1805 806 1806 807 1806 804 1806 772 1807 808 1807 803 1807 809 1808 803 1808 808 1808 810 1809 806 1809 803 1809 810 1810 803 1810 809 1810 811 1811 807 1811 808 1811 809 1812 808 1812 807 1812 772 1813 811 1813 808 1813 811 1814 812 1814 807 1814 767 1815 807 1815 812 1815 813 1816 807 1816 806 1816 809 1817 807 1817 813 1817 814 1818 812 1818 811 1818 767 1819 812 1819 815 1819 814 1820 815 1820 812 1820 772 1821 816 1821 811 1821 817 1822 811 1822 816 1822 818 1823 814 1823 811 1823 818 1824 811 1824 817 1824 819 1825 815 1825 816 1825 817 1826 816 1826 815 1826 772 1827 819 1827 816 1827 819 1828 820 1828 815 1828 767 1829 815 1829 820 1829 821 1830 815 1830 814 1830 817 1831 815 1831 821 1831 822 1832 820 1832 819 1832 767 1833 820 1833 823 1833 822 1834 823 1834 820 1834 772 1835 824 1835 819 1835 825 1836 819 1836 824 1836 826 1837 822 1837 819 1837 826 1838 819 1838 825 1838 827 1839 823 1839 824 1839 825 1840 824 1840 823 1840 772 1841 827 1841 824 1841 827 1842 828 1842 823 1842 767 1843 823 1843 828 1843 829 1844 823 1844 822 1844 825 1845 823 1845 829 1845 830 1846 828 1846 827 1846 767 1847 828 1847 831 1847 830 1848 831 1848 828 1848 772 1849 832 1849 827 1849 833 1850 827 1850 832 1850 834 1851 830 1851 827 1851 834 1852 827 1852 833 1852 835 1853 831 1853 832 1853 833 1854 832 1854 831 1854 772 1855 835 1855 832 1855 835 1856 836 1856 831 1856 767 1857 831 1857 836 1857 837 1858 831 1858 830 1858 833 1859 831 1859 837 1859 838 1860 836 1860 835 1860 767 1861 836 1861 839 1861 838 1862 839 1862 836 1862 772 1863 840 1863 835 1863 841 1864 835 1864 840 1864 842 1865 838 1865 835 1865 842 1866 835 1866 841 1866 772 1867 839 1867 840 1867 841 1868 840 1868 839 1868 843 1869 767 1869 839 1869 772 1870 843 1870 839 1870 844 1871 839 1871 838 1871 841 1872 839 1872 844 1872 845 1873 846 1873 775 1873 847 1874 775 1874 846 1874 767 1875 845 1875 775 1875 848 1876 776 1876 775 1876 849 1877 848 1877 775 1877 849 1878 775 1878 847 1878 845 1879 850 1879 846 1879 847 1880 846 1880 850 1880 845 1881 851 1881 850 1881 852 1882 850 1882 851 1882 847 1883 850 1883 852 1883 845 1884 853 1884 851 1884 854 1885 851 1885 853 1885 852 1886 851 1886 854 1886 845 1887 855 1887 853 1887 856 1888 853 1888 855 1888 854 1889 853 1889 856 1889 845 1890 857 1890 855 1890 858 1891 855 1891 857 1891 856 1892 855 1892 858 1892 845 1893 859 1893 857 1893 860 1894 857 1894 859 1894 858 1895 857 1895 860 1895 861 1896 862 1896 859 1896 863 1897 859 1897 862 1897 845 1898 861 1898 859 1898 860 1899 859 1899 863 1899 864 1900 862 1900 861 1900 863 1901 862 1901 864 1901 865 1902 861 1902 845 1902 866 1903 861 1903 865 1903 864 1904 861 1904 866 1904 767 1905 867 1905 845 1905 865 1906 845 1906 867 1906 868 1907 867 1907 767 1907 869 1908 867 1908 868 1908 865 1909 867 1909 869 1909 868 1910 767 1910 843 1910 870 1911 871 1911 843 1911 872 1912 843 1912 871 1912 772 1913 870 1913 843 1913 868 1914 843 1914 872 1914 870 1915 873 1915 871 1915 874 1916 871 1916 873 1916 872 1917 871 1917 874 1917 875 1918 873 1918 870 1918 874 1919 873 1919 875 1919 876 1920 870 1920 772 1920 875 1921 870 1921 876 1921 877 1922 772 1922 777 1922 876 1923 772 1923 877 1923 678 1924 673 1924 777 1924 878 1925 777 1925 673 1925 776 1926 678 1926 777 1926 877 1927 777 1927 878 1927 879 1928 673 1928 764 1928 878 1929 673 1929 879 1929 880 1930 881 1930 764 1930 882 1931 764 1931 881 1931 672 1932 880 1932 764 1932 879 1933 764 1933 882 1933 883 1934 881 1934 880 1934 882 1935 881 1935 883 1935 884 1936 880 1936 672 1936 883 1937 880 1937 884 1937 885 1938 672 1938 670 1938 884 1939 672 1939 885 1939 886 1940 670 1940 678 1940 887 1941 670 1941 886 1941 885 1942 670 1942 887 1942 886 1943 678 1943 776 1943 886 1944 776 1944 848 1944 887 1945 679 1945 669 1945 684 1946 669 1946 677 1946 887 1947 669 1947 684 1947 886 1948 675 1948 679 1948 887 1949 886 1949 679 1949 882 1950 677 1950 675 1950 886 1951 848 1951 675 1951 878 1952 675 1952 848 1952 879 1953 882 1953 675 1953 878 1954 879 1954 675 1954 882 1955 684 1955 677 1955 887 1956 687 1956 683 1956 692 1957 683 1957 686 1957 692 1958 695 1958 683 1958 887 1959 683 1959 695 1959 887 1960 684 1960 687 1960 882 1961 686 1961 684 1961 882 1962 692 1962 686 1962 887 1963 695 1963 691 1963 700 1964 691 1964 694 1964 700 1965 703 1965 691 1965 887 1966 691 1966 703 1966 882 1967 694 1967 692 1967 882 1968 700 1968 694 1968 887 1969 703 1969 699 1969 708 1970 699 1970 702 1970 708 1971 711 1971 699 1971 887 1972 699 1972 711 1972 882 1973 702 1973 700 1973 882 1974 708 1974 702 1974 887 1975 711 1975 707 1975 716 1976 707 1976 710 1976 716 1977 719 1977 707 1977 887 1978 707 1978 719 1978 882 1979 710 1979 708 1979 882 1980 716 1980 710 1980 887 1981 719 1981 715 1981 724 1982 715 1982 718 1982 724 1983 727 1983 715 1983 887 1984 715 1984 727 1984 882 1985 718 1985 716 1985 882 1986 724 1986 718 1986 887 1987 727 1987 723 1987 732 1988 723 1988 726 1988 732 1989 735 1989 723 1989 887 1990 723 1990 735 1990 882 1991 726 1991 724 1991 882 1992 732 1992 726 1992 887 1993 735 1993 731 1993 740 1994 731 1994 734 1994 740 1995 743 1995 731 1995 887 1996 731 1996 743 1996 882 1997 734 1997 732 1997 882 1998 740 1998 734 1998 887 1999 743 1999 739 1999 748 2000 739 2000 742 2000 748 2001 751 2001 739 2001 887 2002 739 2002 751 2002 882 2003 742 2003 740 2003 882 2004 748 2004 742 2004 887 2005 751 2005 747 2005 755 2006 747 2006 750 2006 755 2007 759 2007 747 2007 887 2008 747 2008 759 2008 882 2009 750 2009 748 2009 882 2010 755 2010 750 2010 887 2011 759 2011 754 2011 882 2012 754 2012 758 2012 763 2013 766 2013 754 2013 887 2014 754 2014 766 2014 882 2015 763 2015 754 2015 882 2016 758 2016 755 2016 887 2017 766 2017 762 2017 882 2018 762 2018 765 2018 885 2019 887 2019 762 2019 882 2020 885 2020 762 2020 882 2021 765 2021 763 2021 872 2022 781 2022 770 2022 878 2023 770 2023 778 2023 878 2024 848 2024 770 2024 849 2025 770 2025 848 2025 849 2026 872 2026 770 2026 782 2027 774 2027 781 2027 872 2028 782 2028 781 2028 878 2029 778 2029 774 2029 786 2030 774 2030 782 2030 878 2031 774 2031 786 2031 872 2032 789 2032 782 2032 790 2033 785 2033 789 2033 872 2034 790 2034 789 2034 878 2035 786 2035 785 2035 794 2036 785 2036 790 2036 878 2037 785 2037 794 2037 872 2038 797 2038 790 2038 798 2039 793 2039 797 2039 872 2040 798 2040 797 2040 878 2041 794 2041 793 2041 802 2042 793 2042 798 2042 878 2043 793 2043 802 2043 872 2044 805 2044 798 2044 806 2045 801 2045 805 2045 872 2046 806 2046 805 2046 878 2047 802 2047 801 2047 810 2048 801 2048 806 2048 878 2049 801 2049 810 2049 872 2050 813 2050 806 2050 814 2051 809 2051 813 2051 872 2052 814 2052 813 2052 878 2053 810 2053 809 2053 818 2054 809 2054 814 2054 878 2055 809 2055 818 2055 872 2056 821 2056 814 2056 822 2057 817 2057 821 2057 872 2058 822 2058 821 2058 878 2059 818 2059 817 2059 826 2060 817 2060 822 2060 878 2061 817 2061 826 2061 872 2062 829 2062 822 2062 830 2063 825 2063 829 2063 872 2064 830 2064 829 2064 878 2065 826 2065 825 2065 834 2066 825 2066 830 2066 878 2067 825 2067 834 2067 872 2068 837 2068 830 2068 838 2069 833 2069 837 2069 872 2070 838 2070 837 2070 878 2071 834 2071 833 2071 842 2072 833 2072 838 2072 878 2073 833 2073 842 2073 872 2074 844 2074 838 2074 872 2075 841 2075 844 2075 878 2076 842 2076 841 2076 877 2077 878 2077 841 2077 872 2078 877 2078 841 2078 883 2079 884 2079 885 2079 882 2080 883 2080 885 2080 875 2081 876 2081 877 2081 872 2082 875 2082 877 2082 872 2083 874 2083 875 2083 849 2084 868 2084 872 2084 847 2085 869 2085 868 2085 849 2086 847 2086 868 2086 860 2087 865 2087 869 2087 858 2088 860 2088 869 2088 856 2089 858 2089 869 2089 854 2090 856 2090 869 2090 852 2091 854 2091 869 2091 847 2092 852 2092 869 2092 864 2093 866 2093 865 2093 863 2094 864 2094 865 2094 860 2095 863 2095 865 2095 888 2096 889 2096 890 2096 891 2097 890 2097 889 2097 892 2098 890 2098 893 2098 894 2099 893 2099 890 2099 895 2100 888 2100 890 2100 892 2101 895 2101 890 2101 894 2102 890 2102 891 2102 888 2103 896 2103 889 2103 897 2104 889 2104 896 2104 897 2105 891 2105 889 2105 888 2106 898 2106 896 2106 899 2107 896 2107 898 2107 897 2108 896 2108 899 2108 900 2109 901 2109 898 2109 902 2110 898 2110 901 2110 903 2111 900 2111 898 2111 904 2112 903 2112 898 2112 905 2113 898 2113 888 2113 906 2114 904 2114 898 2114 905 2115 906 2115 898 2115 899 2116 898 2116 902 2116 907 2117 908 2117 901 2117 909 2118 901 2118 908 2118 900 2119 907 2119 901 2119 902 2120 901 2120 909 2120 910 2121 911 2121 908 2121 912 2122 908 2122 911 2122 910 2123 908 2123 907 2123 909 2124 908 2124 912 2124 913 2125 914 2125 911 2125 915 2126 911 2126 914 2126 910 2127 913 2127 911 2127 912 2128 911 2128 915 2128 916 2129 917 2129 914 2129 918 2130 914 2130 917 2130 916 2131 914 2131 913 2131 915 2132 914 2132 918 2132 919 2133 893 2133 917 2133 920 2134 917 2134 893 2134 916 2135 921 2135 917 2135 919 2136 917 2136 921 2136 918 2137 917 2137 920 2137 922 2138 892 2138 893 2138 923 2139 922 2139 893 2139 924 2140 923 2140 893 2140 919 2141 924 2141 893 2141 920 2142 893 2142 894 2142 888 2143 925 2143 926 2143 927 2144 926 2144 925 2144 928 2145 926 2145 929 2145 930 2146 929 2146 926 2146 928 2147 888 2147 926 2147 930 2148 926 2148 927 2148 888 2149 931 2149 925 2149 932 2150 925 2150 931 2150 932 2151 927 2151 925 2151 888 2152 933 2152 931 2152 934 2153 931 2153 933 2153 932 2154 931 2154 934 2154 935 2155 936 2155 933 2155 937 2156 933 2156 936 2156 938 2157 935 2157 933 2157 939 2158 938 2158 933 2158 940 2159 933 2159 888 2159 940 2160 939 2160 933 2160 934 2161 933 2161 937 2161 941 2162 942 2162 936 2162 943 2163 936 2163 942 2163 935 2164 941 2164 936 2164 937 2165 936 2165 943 2165 944 2166 945 2166 942 2166 946 2167 942 2167 945 2167 944 2168 942 2168 941 2168 943 2169 942 2169 946 2169 947 2170 948 2170 945 2170 949 2171 945 2171 948 2171 944 2172 947 2172 945 2172 946 2173 945 2173 949 2173 950 2174 951 2174 948 2174 952 2175 948 2175 951 2175 950 2176 948 2176 947 2176 949 2177 948 2177 952 2177 953 2178 929 2178 951 2178 954 2179 951 2179 929 2179 950 2180 955 2180 951 2180 953 2181 951 2181 955 2181 952 2182 951 2182 954 2182 956 2183 928 2183 929 2183 957 2184 956 2184 929 2184 958 2185 957 2185 929 2185 953 2186 958 2186 929 2186 954 2187 929 2187 930 2187 959 2188 941 2188 935 2188 960 2189 944 2189 941 2189 960 2190 941 2190 959 2190 961 2191 935 2191 938 2191 961 2192 959 2192 935 2192 939 2193 962 2193 938 2193 963 2194 938 2194 962 2194 961 2195 938 2195 963 2195 964 2196 965 2196 962 2196 966 2197 962 2197 965 2197 967 2198 968 2198 962 2198 964 2199 962 2199 968 2199 939 2200 967 2200 962 2200 963 2201 962 2201 966 2201 969 2202 970 2202 965 2202 971 2203 965 2203 970 2203 972 2204 969 2204 965 2204 973 2205 972 2205 965 2205 964 2206 973 2206 965 2206 966 2207 965 2207 971 2207 974 2208 975 2208 970 2208 976 2209 970 2209 975 2209 977 2210 974 2210 970 2210 969 2211 977 2211 970 2211 971 2212 970 2212 976 2212 974 2213 978 2213 975 2213 979 2214 975 2214 978 2214 976 2215 975 2215 979 2215 974 2216 947 2216 978 2216 980 2217 978 2217 947 2217 979 2218 978 2218 980 2218 981 2219 947 2219 944 2219 982 2220 947 2220 974 2220 983 2221 950 2221 947 2221 982 2222 983 2222 947 2222 980 2223 947 2223 981 2223 981 2224 944 2224 960 2224 984 2225 907 2225 900 2225 985 2226 910 2226 907 2226 985 2227 907 2227 984 2227 986 2228 900 2228 903 2228 986 2229 984 2229 900 2229 904 2230 987 2230 903 2230 988 2231 903 2231 987 2231 986 2232 903 2232 988 2232 989 2233 990 2233 987 2233 991 2234 987 2234 990 2234 992 2235 993 2235 987 2235 989 2236 987 2236 993 2236 904 2237 992 2237 987 2237 988 2238 987 2238 991 2238 994 2239 995 2239 990 2239 996 2240 990 2240 995 2240 997 2241 994 2241 990 2241 998 2242 997 2242 990 2242 989 2243 998 2243 990 2243 991 2244 990 2244 996 2244 974 2245 999 2245 995 2245 1000 2246 995 2246 999 2246 994 2247 974 2247 995 2247 996 2248 995 2248 1000 2248 974 2249 1001 2249 999 2249 1002 2250 999 2250 1001 2250 1000 2251 999 2251 1002 2251 974 2252 913 2252 1001 2252 1003 2253 1001 2253 913 2253 1002 2254 1001 2254 1003 2254 1004 2255 913 2255 910 2255 1005 2256 913 2256 974 2256 1005 2257 916 2257 913 2257 1003 2258 913 2258 1004 2258 1004 2259 910 2259 985 2259 1006 2260 1007 2260 1008 2260 1009 2261 1008 2261 1007 2261 1006 2262 1008 2262 1010 2262 1011 2263 1010 2263 1008 2263 1011 2264 1008 2264 1009 2264 1012 2265 1013 2265 1007 2265 1014 2266 1007 2266 1013 2266 1006 2267 1012 2267 1007 2267 1014 2268 1009 2268 1007 2268 1012 2269 1015 2269 1013 2269 1016 2270 1013 2270 1015 2270 1014 2271 1013 2271 1016 2271 1012 2272 1017 2272 1015 2272 1018 2273 1015 2273 1017 2273 1016 2274 1015 2274 1018 2274 1012 2275 1019 2275 1017 2275 1020 2276 1017 2276 1019 2276 1018 2277 1017 2277 1020 2277 1021 2278 1022 2278 1019 2278 1023 2279 1019 2279 1022 2279 1012 2280 1021 2280 1019 2280 1020 2281 1019 2281 1023 2281 1021 2282 1024 2282 1022 2282 1025 2283 1022 2283 1024 2283 1023 2284 1022 2284 1025 2284 1021 2285 1026 2285 1024 2285 1027 2286 1024 2286 1026 2286 1025 2287 1024 2287 1027 2287 1028 2288 1029 2288 1026 2288 1030 2289 1026 2289 1029 2289 1031 2290 1032 2290 1026 2290 1028 2291 1026 2291 1032 2291 1021 2292 1031 2292 1026 2292 1027 2293 1026 2293 1030 2293 1028 2294 1033 2294 1029 2294 1034 2295 1029 2295 1033 2295 1030 2296 1029 2296 1034 2296 1028 2297 1035 2297 1033 2297 1036 2298 1033 2298 1035 2298 1034 2299 1033 2299 1036 2299 1028 2300 1037 2300 1035 2300 1038 2301 1035 2301 1037 2301 1036 2302 1035 2302 1038 2302 1039 2303 1040 2303 1037 2303 1041 2304 1037 2304 1040 2304 1028 2305 1039 2305 1037 2305 1038 2306 1037 2306 1041 2306 1039 2307 1042 2307 1040 2307 1043 2308 1040 2308 1042 2308 1041 2309 1040 2309 1043 2309 1039 2310 1044 2310 1042 2310 1045 2311 1042 2311 1044 2311 1043 2312 1042 2312 1045 2312 1039 2313 1046 2313 1044 2313 1047 2314 1044 2314 1046 2314 1045 2315 1044 2315 1047 2315 1048 2316 1049 2316 1046 2316 1050 2317 1046 2317 1049 2317 1039 2318 1048 2318 1046 2318 1047 2319 1046 2319 1050 2319 1048 2320 1051 2320 1049 2320 1052 2321 1049 2321 1051 2321 1050 2322 1049 2322 1052 2322 1048 2323 1053 2323 1051 2323 1054 2324 1051 2324 1053 2324 1052 2325 1051 2325 1054 2325 1048 2326 1055 2326 1053 2326 1056 2327 1053 2327 1055 2327 1054 2328 1053 2328 1056 2328 1057 2329 1058 2329 1055 2329 1059 2330 1055 2330 1058 2330 1048 2331 1057 2331 1055 2331 1056 2332 1055 2332 1059 2332 1060 2333 1061 2333 1058 2333 1062 2334 1058 2334 1061 2334 1057 2335 1060 2335 1058 2335 1059 2336 1058 2336 1062 2336 1060 2337 1063 2337 1061 2337 1064 2338 1061 2338 1063 2338 1062 2339 1061 2339 1064 2339 1060 2340 1065 2340 1063 2340 1066 2341 1063 2341 1065 2341 1064 2342 1063 2342 1066 2342 1067 2343 1068 2343 1065 2343 1069 2344 1065 2344 1068 2344 1070 2345 1067 2345 1065 2345 1060 2346 1070 2346 1065 2346 1066 2347 1065 2347 1069 2347 1071 2348 1072 2348 1068 2348 1073 2349 1068 2349 1072 2349 1071 2350 1068 2350 1067 2350 1069 2351 1068 2351 1073 2351 1071 2352 1074 2352 1072 2352 1075 2353 1072 2353 1074 2353 1073 2354 1072 2354 1075 2354 1071 2355 1076 2355 1074 2355 1077 2356 1074 2356 1076 2356 1075 2357 1074 2357 1077 2357 1071 2358 1078 2358 1076 2358 1079 2359 1076 2359 1078 2359 1077 2360 1076 2360 1079 2360 1006 2361 1080 2361 1078 2361 1081 2362 1078 2362 1080 2362 1071 2363 1006 2363 1078 2363 1079 2364 1078 2364 1081 2364 1006 2365 1010 2365 1080 2365 1082 2366 1080 2366 1010 2366 1081 2367 1080 2367 1082 2367 1082 2368 1010 2368 1011 2368 1083 2369 1084 2369 1085 2369 1086 2370 1085 2370 1084 2370 1083 2371 1085 2371 1087 2371 1088 2372 1087 2372 1085 2372 1088 2373 1085 2373 1086 2373 1071 2374 1089 2374 1084 2374 1090 2375 1084 2375 1089 2375 1083 2376 1071 2376 1084 2376 1090 2377 1086 2377 1084 2377 1071 2378 1067 2378 1089 2378 1091 2379 1089 2379 1067 2379 1090 2380 1089 2380 1091 2380 1092 2381 1093 2381 1067 2381 1094 2382 1067 2382 1093 2382 1070 2383 1092 2383 1067 2383 1091 2384 1067 2384 1094 2384 1095 2385 1096 2385 1093 2385 1097 2386 1093 2386 1096 2386 1092 2387 1095 2387 1093 2387 1094 2388 1093 2388 1097 2388 1098 2389 1099 2389 1096 2389 1100 2390 1096 2390 1099 2390 1098 2391 1096 2391 1095 2391 1097 2392 1096 2392 1100 2392 1101 2393 1102 2393 1099 2393 1103 2394 1099 2394 1102 2394 1098 2395 1101 2395 1099 2395 1100 2396 1099 2396 1103 2396 1104 2397 1105 2397 1102 2397 1106 2398 1102 2398 1105 2398 1104 2399 1102 2399 1101 2399 1103 2400 1102 2400 1106 2400 1083 2401 1087 2401 1105 2401 1107 2402 1105 2402 1087 2402 1108 2403 1105 2403 1104 2403 1108 2404 1083 2404 1105 2404 1106 2405 1105 2405 1107 2405 1107 2406 1087 2406 1088 2406 1109 2407 1095 2407 1092 2407 1110 2408 1098 2408 1095 2408 1110 2409 1095 2409 1109 2409 1111 2410 1092 2410 1070 2410 1111 2411 1109 2411 1092 2411 1112 2412 1070 2412 1060 2412 1111 2413 1070 2413 1112 2413 1057 2414 1113 2414 1060 2414 1114 2415 1060 2415 1113 2415 1112 2416 1060 2416 1114 2416 1057 2417 1115 2417 1113 2417 1116 2418 1113 2418 1115 2418 1114 2419 1113 2419 1116 2419 1104 2420 1117 2420 1115 2420 1118 2421 1115 2421 1117 2421 1057 2422 1104 2422 1115 2422 1116 2423 1115 2423 1118 2423 1104 2424 1119 2424 1117 2424 1120 2425 1117 2425 1119 2425 1118 2426 1117 2426 1120 2426 1104 2427 1101 2427 1119 2427 1121 2428 1119 2428 1101 2428 1120 2429 1119 2429 1121 2429 1122 2430 1101 2430 1098 2430 1121 2431 1101 2431 1122 2431 1122 2432 1098 2432 1110 2432 1123 2433 1124 2433 1125 2433 1126 2434 1125 2434 1124 2434 1127 2435 1125 2435 1128 2435 1129 2436 1128 2436 1125 2436 1127 2437 1123 2437 1125 2437 1129 2438 1125 2438 1126 2438 1130 2439 1131 2439 1124 2439 1132 2440 1124 2440 1131 2440 1123 2441 1130 2441 1124 2441 1132 2442 1126 2442 1124 2442 1133 2443 1134 2443 1131 2443 1135 2444 1131 2444 1134 2444 1133 2445 1131 2445 1130 2445 1132 2446 1131 2446 1135 2446 1136 2447 1137 2447 1134 2447 1138 2448 1134 2448 1137 2448 1133 2449 1136 2449 1134 2449 1135 2450 1134 2450 1138 2450 1136 2451 1139 2451 1137 2451 1140 2452 1137 2452 1139 2452 1138 2453 1137 2453 1140 2453 1028 2454 1141 2454 1139 2454 1142 2455 1139 2455 1141 2455 1136 2456 1028 2456 1139 2456 1140 2457 1139 2457 1142 2457 1028 2458 1143 2458 1141 2458 1144 2459 1141 2459 1143 2459 1142 2460 1141 2460 1144 2460 1028 2461 1032 2461 1143 2461 1145 2462 1143 2462 1032 2462 1144 2463 1143 2463 1145 2463 1146 2464 1128 2464 1032 2464 1147 2465 1032 2465 1128 2465 1031 2466 1146 2466 1032 2466 1145 2467 1032 2467 1147 2467 1146 2468 1127 2468 1128 2468 1147 2469 1128 2469 1129 2469 1148 2470 1149 2470 1150 2470 1151 2471 1150 2471 1149 2471 1148 2472 1150 2472 1152 2472 1153 2473 1152 2473 1150 2473 1153 2474 1150 2474 1151 2474 1133 2475 1154 2475 1149 2475 1155 2476 1149 2476 1154 2476 1148 2477 1133 2477 1149 2477 1155 2478 1151 2478 1149 2478 1133 2479 1130 2479 1154 2479 1156 2480 1154 2480 1130 2480 1155 2481 1154 2481 1156 2481 1157 2482 1130 2482 1123 2482 1156 2483 1130 2483 1157 2483 1158 2484 1123 2484 1127 2484 1157 2485 1123 2485 1158 2485 1159 2486 1127 2486 1146 2486 1158 2487 1127 2487 1159 2487 1160 2488 1146 2488 1031 2488 1159 2489 1146 2489 1160 2489 1161 2490 1031 2490 1021 2490 1160 2491 1031 2491 1161 2491 1148 2492 1152 2492 1021 2492 1162 2493 1021 2493 1152 2493 1012 2494 1148 2494 1021 2494 1161 2495 1021 2495 1162 2495 1162 2496 1152 2496 1153 2496 1163 2497 1164 2497 1165 2497 1166 2498 1165 2498 1164 2498 1163 2499 1165 2499 1167 2499 1168 2500 1167 2500 1165 2500 1168 2501 1165 2501 1166 2501 1108 2502 1169 2502 1164 2502 1170 2503 1164 2503 1169 2503 1163 2504 1108 2504 1164 2504 1170 2505 1166 2505 1164 2505 1108 2506 1171 2506 1169 2506 1172 2507 1169 2507 1171 2507 1170 2508 1169 2508 1172 2508 1108 2509 1173 2509 1171 2509 1174 2510 1171 2510 1173 2510 1172 2511 1171 2511 1174 2511 1104 2512 1175 2512 1173 2512 1176 2513 1173 2513 1175 2513 1108 2514 1104 2514 1173 2514 1174 2515 1173 2515 1176 2515 1177 2516 1178 2516 1175 2516 1179 2517 1175 2517 1178 2517 1104 2518 1177 2518 1175 2518 1176 2519 1175 2519 1179 2519 1177 2520 1180 2520 1178 2520 1181 2521 1178 2521 1180 2521 1179 2522 1178 2522 1181 2522 1177 2523 1182 2523 1180 2523 1183 2524 1180 2524 1182 2524 1181 2525 1180 2525 1183 2525 1184 2526 1185 2526 1182 2526 1186 2527 1182 2527 1185 2527 1177 2528 1184 2528 1182 2528 1183 2529 1182 2529 1186 2529 1184 2530 1187 2530 1185 2530 1188 2531 1185 2531 1187 2531 1186 2532 1185 2532 1188 2532 1184 2533 1189 2533 1187 2533 1190 2534 1187 2534 1189 2534 1188 2535 1187 2535 1190 2535 1184 2536 1191 2536 1189 2536 1192 2537 1189 2537 1191 2537 1190 2538 1189 2538 1192 2538 1193 2539 1194 2539 1191 2539 1195 2540 1191 2540 1194 2540 1184 2541 1196 2541 1191 2541 1193 2542 1191 2542 1196 2542 1192 2543 1191 2543 1195 2543 1163 2544 1197 2544 1194 2544 1198 2545 1194 2545 1197 2545 1193 2546 1163 2546 1194 2546 1195 2547 1194 2547 1198 2547 1163 2548 1167 2548 1197 2548 1199 2549 1197 2549 1167 2549 1198 2550 1197 2550 1199 2550 1199 2551 1167 2551 1168 2551 1200 2552 1201 2552 1202 2552 1203 2553 1202 2553 1201 2553 1200 2554 1202 2554 1204 2554 1205 2555 1204 2555 1202 2555 1205 2556 1202 2556 1203 2556 1206 2557 1207 2557 1201 2557 1208 2558 1201 2558 1207 2558 1200 2559 1206 2559 1201 2559 1208 2560 1203 2560 1201 2560 1206 2561 1209 2561 1207 2561 1210 2562 1207 2562 1209 2562 1208 2563 1207 2563 1210 2563 1211 2564 1212 2564 1209 2564 1213 2565 1209 2565 1212 2565 1211 2566 1209 2566 1206 2566 1210 2567 1209 2567 1213 2567 1214 2568 1215 2568 1212 2568 1216 2569 1212 2569 1215 2569 1211 2570 1214 2570 1212 2570 1213 2571 1212 2571 1216 2571 1214 2572 1217 2572 1215 2572 1218 2573 1215 2573 1217 2573 1216 2574 1215 2574 1218 2574 1214 2575 1219 2575 1217 2575 1220 2576 1217 2576 1219 2576 1218 2577 1217 2577 1220 2577 1214 2578 1221 2578 1219 2578 1222 2579 1219 2579 1221 2579 1220 2580 1219 2580 1222 2580 1223 2581 1204 2581 1221 2581 1224 2582 1221 2582 1204 2582 1225 2583 1223 2583 1221 2583 1214 2584 1225 2584 1221 2584 1222 2585 1221 2585 1224 2585 1223 2586 1200 2586 1204 2586 1224 2587 1204 2587 1205 2587 1226 2588 1227 2588 1228 2588 1229 2589 1228 2589 1227 2589 1226 2590 1228 2590 1230 2590 1231 2591 1230 2591 1228 2591 1231 2592 1228 2592 1229 2592 1226 2593 1232 2593 1227 2593 1233 2594 1227 2594 1232 2594 1233 2595 1229 2595 1227 2595 1226 2596 1234 2596 1232 2596 1235 2597 1232 2597 1234 2597 1233 2598 1232 2598 1235 2598 1236 2599 1237 2599 1234 2599 1238 2600 1234 2600 1237 2600 1226 2601 1236 2601 1234 2601 1235 2602 1234 2602 1238 2602 1236 2603 1239 2603 1237 2603 1240 2604 1237 2604 1239 2604 1238 2605 1237 2605 1240 2605 1241 2606 1242 2606 1239 2606 1243 2607 1239 2607 1242 2607 1236 2608 1241 2608 1239 2608 1240 2609 1239 2609 1243 2609 1241 2610 1244 2610 1242 2610 1245 2611 1242 2611 1244 2611 1243 2612 1242 2612 1245 2612 1246 2613 1247 2613 1244 2613 1248 2614 1244 2614 1247 2614 1241 2615 1246 2615 1244 2615 1245 2616 1244 2616 1248 2616 1249 2617 1230 2617 1247 2617 1250 2618 1247 2618 1230 2618 1251 2619 1249 2619 1247 2619 1252 2620 1251 2620 1247 2620 1246 2621 1252 2621 1247 2621 1248 2622 1247 2622 1250 2622 1249 2623 1253 2623 1230 2623 1226 2624 1230 2624 1253 2624 1250 2625 1230 2625 1231 2625 1206 2626 1254 2626 1255 2626 1256 2627 1255 2627 1254 2627 1206 2628 1255 2628 1257 2628 1258 2629 1257 2629 1255 2629 1258 2630 1255 2630 1256 2630 1259 2631 1260 2631 1254 2631 1261 2632 1254 2632 1260 2632 1206 2633 1259 2633 1254 2633 1261 2634 1256 2634 1254 2634 1259 2635 1262 2635 1260 2635 1263 2636 1260 2636 1262 2636 1261 2637 1260 2637 1263 2637 1264 2638 1265 2638 1262 2638 1266 2639 1262 2639 1265 2639 1264 2640 1262 2640 1259 2640 1263 2641 1262 2641 1266 2641 1264 2642 1267 2642 1265 2642 1268 2643 1265 2643 1267 2643 1266 2644 1265 2644 1268 2644 1269 2645 1270 2645 1267 2645 1271 2646 1267 2646 1270 2646 1269 2647 1267 2647 1272 2647 1264 2648 1272 2648 1267 2648 1268 2649 1267 2649 1271 2649 1273 2650 1274 2650 1270 2650 1275 2651 1270 2651 1274 2651 1269 2652 1273 2652 1270 2652 1271 2653 1270 2653 1275 2653 1226 2654 1276 2654 1274 2654 1277 2655 1274 2655 1276 2655 1226 2656 1274 2656 1273 2656 1275 2657 1274 2657 1277 2657 1206 2658 1257 2658 1276 2658 1278 2659 1276 2659 1257 2659 1211 2660 1206 2660 1276 2660 1226 2661 1211 2661 1276 2661 1277 2662 1276 2662 1278 2662 1278 2663 1257 2663 1258 2663 1279 2664 1280 2664 1272 2664 1281 2665 1272 2665 1280 2665 1282 2666 1269 2666 1272 2666 1264 2667 1279 2667 1272 2667 1282 2668 1272 2668 1281 2668 1283 2669 1284 2669 1280 2669 1285 2670 1280 2670 1284 2670 1279 2671 1283 2671 1280 2671 1285 2672 1281 2672 1280 2672 1283 2673 1286 2673 1284 2673 1287 2674 1284 2674 1286 2674 1285 2675 1284 2675 1287 2675 1288 2676 1289 2676 1286 2676 1290 2677 1286 2677 1289 2677 1291 2678 1288 2678 1286 2678 1283 2679 1291 2679 1286 2679 1287 2680 1286 2680 1290 2680 1288 2681 1292 2681 1289 2681 1293 2682 1289 2682 1292 2682 1290 2683 1289 2683 1293 2683 1236 2684 1294 2684 1292 2684 1295 2685 1292 2685 1294 2685 1288 2686 1236 2686 1292 2686 1293 2687 1292 2687 1295 2687 1236 2688 1296 2688 1294 2688 1297 2689 1294 2689 1296 2689 1295 2690 1294 2690 1297 2690 1236 2691 1273 2691 1296 2691 1298 2692 1296 2692 1273 2692 1297 2693 1296 2693 1298 2693 1299 2694 1273 2694 1269 2694 1226 2695 1273 2695 1236 2695 1298 2696 1273 2696 1299 2696 1299 2697 1269 2697 1282 2697 895 2698 1300 2698 1301 2698 1302 2699 1301 2699 1300 2699 895 2700 1301 2700 1303 2700 1304 2701 1303 2701 1301 2701 1304 2702 1301 2702 1302 2702 895 2703 1305 2703 1300 2703 1306 2704 1300 2704 1305 2704 1306 2705 1302 2705 1300 2705 895 2706 1307 2706 1305 2706 1308 2707 1305 2707 1307 2707 1306 2708 1305 2708 1308 2708 895 2709 1309 2709 1307 2709 1310 2710 1307 2710 1309 2710 1308 2711 1307 2711 1310 2711 895 2712 1311 2712 1309 2712 1312 2713 1309 2713 1311 2713 1310 2714 1309 2714 1312 2714 974 2715 1313 2715 1311 2715 1314 2716 1311 2716 1313 2716 895 2717 974 2717 1311 2717 1312 2718 1311 2718 1314 2718 1315 2719 1316 2719 1313 2719 1317 2720 1313 2720 1316 2720 974 2721 1315 2721 1313 2721 1314 2722 1313 2722 1317 2722 1315 2723 1318 2723 1316 2723 1319 2724 1316 2724 1318 2724 1317 2725 1316 2725 1319 2725 1315 2726 1320 2726 1318 2726 1321 2727 1318 2727 1320 2727 1319 2728 1318 2728 1321 2728 1315 2729 1322 2729 1320 2729 1323 2730 1320 2730 1322 2730 1321 2731 1320 2731 1323 2731 1315 2732 1324 2732 1322 2732 1325 2733 1322 2733 1324 2733 1323 2734 1322 2734 1325 2734 1315 2735 1326 2735 1324 2735 1327 2736 1324 2736 1326 2736 1325 2737 1324 2737 1327 2737 1328 2738 1329 2738 1326 2738 1330 2739 1326 2739 1329 2739 1315 2740 1328 2740 1326 2740 1327 2741 1326 2741 1330 2741 1328 2742 1331 2742 1329 2742 1332 2743 1329 2743 1331 2743 1330 2744 1329 2744 1332 2744 1328 2745 1333 2745 1331 2745 1334 2746 1331 2746 1333 2746 1332 2747 1331 2747 1334 2747 1335 2748 1336 2748 1333 2748 1337 2749 1333 2749 1336 2749 1335 2750 1333 2750 1328 2750 1334 2751 1333 2751 1337 2751 1335 2752 1338 2752 1336 2752 1339 2753 1336 2753 1338 2753 1337 2754 1336 2754 1339 2754 1335 2755 1340 2755 1338 2755 1341 2756 1338 2756 1340 2756 1339 2757 1338 2757 1341 2757 1335 2758 1303 2758 1340 2758 1342 2759 1340 2759 1303 2759 1341 2760 1340 2760 1342 2760 1335 2761 895 2761 1303 2761 1342 2762 1303 2762 1304 2762 1226 2763 1343 2763 1344 2763 1345 2764 1344 2764 1343 2764 1346 2765 1226 2765 1344 2765 1345 2766 1346 2766 1344 2766 1226 2767 1347 2767 1343 2767 1348 2768 1343 2768 1347 2768 1348 2769 1345 2769 1343 2769 1226 2770 1253 2770 1347 2770 1349 2771 1347 2771 1253 2771 1348 2772 1347 2772 1349 2772 1350 2773 1253 2773 1249 2773 1349 2774 1253 2774 1350 2774 1351 2775 1249 2775 1251 2775 1352 2776 1249 2776 1351 2776 1350 2777 1249 2777 1352 2777 1351 2778 1251 2778 1252 2778 1353 2779 1252 2779 1246 2779 1351 2780 1252 2780 1353 2780 1354 2781 1246 2781 1241 2781 1353 2782 1246 2782 1354 2782 1355 2783 1241 2783 1236 2783 1354 2784 1241 2784 1355 2784 1356 2785 1236 2785 1288 2785 1355 2786 1236 2786 1356 2786 1357 2787 1288 2787 1291 2787 1356 2788 1288 2788 1357 2788 1283 2789 1358 2789 1291 2789 1359 2790 1291 2790 1358 2790 1357 2791 1291 2791 1359 2791 1283 2792 1360 2792 1358 2792 1361 2793 1358 2793 1360 2793 1359 2794 1358 2794 1361 2794 1362 2795 1328 2795 1360 2795 1363 2796 1360 2796 1328 2796 1283 2797 1362 2797 1360 2797 1361 2798 1360 2798 1363 2798 1364 2799 1328 2799 1315 2799 1362 2800 1335 2800 1328 2800 1363 2801 1328 2801 1364 2801 1365 2802 1315 2802 974 2802 1364 2803 1315 2803 1365 2803 1366 2804 974 2804 977 2804 1367 2805 974 2805 895 2805 1368 2806 982 2806 974 2806 1369 2807 1368 2807 974 2807 1370 2808 1369 2808 974 2808 994 2809 1370 2809 974 2809 1371 2810 1005 2810 974 2810 1372 2811 1371 2811 974 2811 1373 2812 1372 2812 974 2812 1374 2813 1373 2813 974 2813 1375 2814 1374 2814 974 2814 1367 2815 1375 2815 974 2815 1365 2816 974 2816 1366 2816 1376 2817 1196 2817 977 2817 1377 2818 977 2818 1196 2818 888 2819 1376 2819 977 2819 1378 2820 888 2820 977 2820 1379 2821 1378 2821 977 2821 1380 2822 1379 2822 977 2822 969 2823 1380 2823 977 2823 1366 2824 977 2824 1377 2824 1381 2825 1196 2825 1184 2825 1376 2826 1193 2826 1196 2826 1377 2827 1196 2827 1381 2827 1382 2828 1184 2828 1177 2828 1381 2829 1184 2829 1382 2829 1383 2830 1177 2830 1104 2830 1382 2831 1177 2831 1383 2831 1384 2832 1104 2832 1057 2832 1383 2833 1104 2833 1384 2833 1385 2834 1057 2834 1048 2834 1384 2835 1057 2835 1385 2835 1386 2836 1048 2836 1039 2836 1385 2837 1048 2837 1386 2837 1387 2838 1039 2838 1028 2838 1386 2839 1039 2839 1387 2839 1388 2840 1028 2840 1136 2840 1387 2841 1028 2841 1388 2841 1133 2842 1389 2842 1136 2842 1390 2843 1136 2843 1389 2843 1388 2844 1136 2844 1390 2844 1391 2845 1392 2845 1389 2845 1393 2846 1389 2846 1392 2846 1133 2847 1391 2847 1389 2847 1390 2848 1389 2848 1393 2848 1394 2849 1395 2849 1392 2849 1396 2850 1392 2850 1395 2850 1391 2851 1394 2851 1392 2851 1393 2852 1392 2852 1396 2852 1397 2853 1398 2853 1395 2853 1399 2854 1395 2854 1398 2854 1394 2855 1397 2855 1395 2855 1396 2856 1395 2856 1399 2856 1400 2857 1401 2857 1398 2857 1402 2858 1398 2858 1401 2858 1397 2859 1400 2859 1398 2859 1399 2860 1398 2860 1402 2860 1403 2861 1401 2861 1400 2861 1402 2862 1401 2862 1403 2862 1404 2863 1400 2863 1397 2863 1403 2864 1400 2864 1404 2864 1405 2865 1397 2865 1394 2865 1404 2866 1397 2866 1405 2866 1406 2867 1394 2867 1391 2867 1405 2868 1394 2868 1406 2868 1407 2869 1391 2869 1133 2869 1406 2870 1391 2870 1407 2870 1408 2871 1133 2871 1148 2871 1407 2872 1133 2872 1408 2872 1409 2873 1148 2873 1012 2873 1408 2874 1148 2874 1409 2874 1410 2875 1012 2875 1006 2875 1409 2876 1012 2876 1410 2876 1411 2877 1006 2877 1071 2877 1410 2878 1006 2878 1411 2878 1412 2879 1071 2879 1083 2879 1411 2880 1071 2880 1412 2880 1413 2881 1083 2881 1108 2881 1412 2882 1083 2882 1413 2882 1414 2883 1108 2883 1163 2883 1413 2884 1108 2884 1414 2884 1415 2885 1163 2885 1193 2885 1414 2886 1163 2886 1415 2886 1416 2887 1193 2887 1376 2887 1415 2888 1193 2888 1416 2888 1417 2889 1376 2889 888 2889 1416 2890 1376 2890 1417 2890 1418 2891 888 2891 895 2891 1419 2892 940 2892 888 2892 1420 2893 1419 2893 888 2893 1421 2894 1420 2894 888 2894 1422 2895 1421 2895 888 2895 1423 2896 1422 2896 888 2896 1378 2897 1423 2897 888 2897 1424 2898 888 2898 928 2898 1425 2899 905 2899 888 2899 1426 2900 1425 2900 888 2900 1424 2901 1426 2901 888 2901 1417 2902 888 2902 1418 2902 1427 2903 895 2903 1335 2903 1428 2904 1367 2904 895 2904 1429 2905 1428 2905 895 2905 892 2906 1429 2906 895 2906 1418 2907 895 2907 1427 2907 1430 2908 1335 2908 1362 2908 1427 2909 1335 2909 1430 2909 1431 2910 1432 2910 1362 2910 1433 2911 1362 2911 1432 2911 1431 2912 1362 2912 1283 2912 1430 2913 1362 2913 1433 2913 1264 2914 1434 2914 1432 2914 1435 2915 1432 2915 1434 2915 1431 2916 1264 2916 1432 2916 1433 2917 1432 2917 1435 2917 1264 2918 1259 2918 1434 2918 1436 2919 1434 2919 1259 2919 1435 2920 1434 2920 1436 2920 1437 2921 1259 2921 1206 2921 1436 2922 1259 2922 1437 2922 1438 2923 1206 2923 1200 2923 1437 2924 1206 2924 1438 2924 1439 2925 1200 2925 1223 2925 1438 2926 1200 2926 1439 2926 1440 2927 1223 2927 1225 2927 1439 2928 1223 2928 1440 2928 1214 2929 1441 2929 1225 2929 1442 2930 1225 2930 1441 2930 1440 2931 1225 2931 1442 2931 1214 2932 1443 2932 1441 2932 1444 2933 1441 2933 1443 2933 1442 2934 1441 2934 1444 2934 1214 2935 1445 2935 1443 2935 1446 2936 1443 2936 1445 2936 1447 2937 1443 2937 1446 2937 1444 2938 1443 2938 1447 2938 1214 2939 1448 2939 1445 2939 1446 2940 1445 2940 1448 2940 1214 2941 1449 2941 1448 2941 1450 2942 1448 2942 1449 2942 1446 2943 1448 2943 1450 2943 1214 2944 1451 2944 1449 2944 1452 2945 1449 2945 1451 2945 1450 2946 1449 2946 1452 2946 1214 2947 1453 2947 1451 2947 1454 2948 1451 2948 1453 2948 1452 2949 1451 2949 1454 2949 1455 2950 1453 2950 1214 2950 1456 2951 1453 2951 1455 2951 1454 2952 1453 2952 1456 2952 1455 2953 1214 2953 1211 2953 1457 2954 1211 2954 1226 2954 1455 2955 1211 2955 1457 2955 1458 2956 1226 2956 1346 2956 1457 2957 1226 2957 1458 2957 1459 2958 1346 2958 1345 2958 1458 2959 1346 2959 1459 2959 1460 2960 968 2960 967 2960 1461 2961 964 2961 968 2961 1461 2962 968 2962 1462 2962 1460 2963 1462 2963 968 2963 1460 2964 967 2964 939 2964 1463 2965 939 2965 940 2965 1460 2966 939 2966 1463 2966 1464 2967 940 2967 1419 2967 1463 2968 940 2968 1464 2968 1465 2969 1419 2969 1420 2969 1464 2970 1419 2970 1465 2970 1466 2971 1420 2971 1421 2971 1465 2972 1420 2972 1466 2972 1467 2973 1421 2973 1422 2973 1466 2974 1421 2974 1467 2974 1468 2975 1422 2975 1423 2975 1467 2976 1422 2976 1468 2976 1469 2977 1423 2977 1378 2977 1470 2978 1423 2978 1469 2978 1468 2979 1423 2979 1470 2979 1469 2980 1378 2980 1379 2980 1471 2981 1379 2981 1380 2981 1469 2982 1379 2982 1471 2982 1472 2983 1380 2983 969 2983 1471 2984 1380 2984 1472 2984 1473 2985 969 2985 972 2985 1472 2986 969 2986 1473 2986 1474 2987 972 2987 973 2987 1473 2988 972 2988 1474 2988 1475 2989 973 2989 964 2989 1474 2990 973 2990 1475 2990 1475 2991 964 2991 1461 2991 1476 2992 955 2992 950 2992 1476 2993 953 2993 955 2993 1477 2994 950 2994 983 2994 1477 2995 1476 2995 950 2995 1478 2996 983 2996 982 2996 1477 2997 983 2997 1478 2997 1479 2998 982 2998 1368 2998 1478 2999 982 2999 1479 2999 1480 3000 1368 3000 1369 3000 1479 3001 1368 3001 1480 3001 1481 3002 1369 3002 1370 3002 1480 3003 1369 3003 1481 3003 994 3004 1482 3004 1370 3004 1483 3005 1370 3005 1482 3005 1481 3006 1370 3006 1483 3006 1484 3007 1485 3007 1482 3007 1486 3008 1482 3008 1485 3008 994 3009 1484 3009 1482 3009 1487 3010 1482 3010 1486 3010 1483 3011 1482 3011 1487 3011 1488 3012 1489 3012 1485 3012 1486 3013 1485 3013 1489 3013 1490 3014 1488 3014 1485 3014 1484 3015 1490 3015 1485 3015 1488 3016 1491 3016 1489 3016 1492 3017 1489 3017 1491 3017 1486 3018 1489 3018 1492 3018 1493 3019 928 3019 1491 3019 1494 3020 1491 3020 928 3020 1488 3021 1493 3021 1491 3021 1492 3022 1491 3022 1494 3022 1495 3023 928 3023 956 3023 1493 3024 1424 3024 928 3024 1494 3025 928 3025 1495 3025 1496 3026 956 3026 957 3026 1495 3027 956 3027 1496 3027 1497 3028 957 3028 958 3028 1496 3029 957 3029 1497 3029 1498 3030 958 3030 953 3030 1497 3031 958 3031 1498 3031 1499 3032 953 3032 1476 3032 1498 3033 953 3033 1499 3033 1500 3034 993 3034 992 3034 1501 3035 989 3035 993 3035 1501 3036 993 3036 1502 3036 1500 3037 1502 3037 993 3037 1500 3038 992 3038 904 3038 1503 3039 904 3039 906 3039 1500 3040 904 3040 1503 3040 1504 3041 906 3041 905 3041 1503 3042 906 3042 1504 3042 1505 3043 905 3043 1425 3043 1504 3044 905 3044 1505 3044 1506 3045 1425 3045 1426 3045 1505 3046 1425 3046 1506 3046 1507 3047 1426 3047 1424 3047 1506 3048 1426 3048 1507 3048 1508 3049 1424 3049 1493 3049 1507 3050 1424 3050 1508 3050 1509 3051 1493 3051 1488 3051 1510 3052 1493 3052 1509 3052 1508 3053 1493 3053 1510 3053 1509 3054 1488 3054 1490 3054 1511 3055 1490 3055 1484 3055 1509 3056 1490 3056 1511 3056 1512 3057 1484 3057 994 3057 1511 3058 1484 3058 1512 3058 1513 3059 994 3059 997 3059 1512 3060 994 3060 1513 3060 1514 3061 997 3061 998 3061 1513 3062 997 3062 1514 3062 1515 3063 998 3063 989 3063 1514 3064 998 3064 1515 3064 1515 3065 989 3065 1501 3065 1516 3066 921 3066 916 3066 1516 3067 919 3067 921 3067 1517 3068 916 3068 1005 3068 1517 3069 1516 3069 916 3069 1518 3070 1005 3070 1371 3070 1517 3071 1005 3071 1518 3071 1519 3072 1371 3072 1372 3072 1520 3073 1371 3073 1519 3073 1518 3074 1371 3074 1520 3074 1519 3075 1372 3075 1373 3075 1521 3076 1373 3076 1374 3076 1519 3077 1373 3077 1521 3077 1522 3078 1374 3078 1375 3078 1521 3079 1374 3079 1522 3079 1523 3080 1375 3080 1367 3080 1524 3081 1375 3081 1523 3081 1522 3082 1375 3082 1524 3082 1523 3083 1367 3083 1428 3083 1525 3084 1428 3084 1429 3084 1523 3085 1428 3085 1525 3085 1526 3086 1429 3086 892 3086 1525 3087 1429 3087 1526 3087 1527 3088 892 3088 922 3088 1528 3089 892 3089 1527 3089 1526 3090 892 3090 1528 3090 1527 3091 922 3091 923 3091 1529 3092 923 3092 924 3092 1527 3093 923 3093 1529 3093 1530 3094 924 3094 919 3094 1529 3095 924 3095 1530 3095 1531 3096 919 3096 1516 3096 1530 3097 919 3097 1531 3097 1532 3098 1283 3098 1279 3098 1533 3099 1431 3099 1283 3099 1533 3100 1283 3100 1532 3100 1534 3101 1279 3101 1264 3101 1534 3102 1532 3102 1279 3102 1535 3103 1264 3103 1431 3103 1534 3104 1264 3104 1535 3104 1535 3105 1431 3105 1533 3105 1427 3106 894 3106 891 3106 1506 3107 891 3107 897 3107 1506 3108 1427 3108 891 3108 1427 3109 920 3109 894 3109 1427 3110 918 3110 920 3110 985 3111 915 3111 918 3111 1004 3112 985 3112 918 3112 1530 3113 1004 3113 918 3113 1529 3114 918 3114 1427 3114 1529 3115 1530 3115 918 3115 984 3116 912 3116 915 3116 985 3117 984 3117 915 3117 986 3118 909 3118 912 3118 986 3119 912 3119 984 3119 988 3120 902 3120 909 3120 986 3121 988 3121 909 3121 1501 3122 899 3122 902 3122 1501 3123 902 3123 988 3123 1503 3124 897 3124 899 3124 1501 3125 1502 3125 899 3125 1500 3126 899 3126 1502 3126 1500 3127 1503 3127 899 3127 1505 3128 1506 3128 897 3128 1504 3129 1505 3129 897 3129 1503 3130 1504 3130 897 3130 1427 3131 930 3131 927 3131 1466 3132 927 3132 932 3132 1418 3133 1427 3133 927 3133 1466 3134 1418 3134 927 3134 1427 3135 954 3135 930 3135 1427 3136 952 3136 954 3136 960 3137 949 3137 952 3137 981 3138 960 3138 952 3138 1498 3139 981 3139 952 3139 1496 3140 952 3140 1427 3140 1497 3141 1498 3141 952 3141 1496 3142 1497 3142 952 3142 959 3143 946 3143 949 3143 960 3144 959 3144 949 3144 961 3145 943 3145 946 3145 961 3146 946 3146 959 3146 963 3147 937 3147 943 3147 961 3148 963 3148 943 3148 1461 3149 934 3149 937 3149 1461 3150 937 3150 963 3150 1463 3151 932 3151 934 3151 1461 3152 1462 3152 934 3152 1460 3153 934 3153 1462 3153 1460 3154 1463 3154 934 3154 1465 3155 1466 3155 932 3155 1464 3156 1465 3156 932 3156 1463 3157 1464 3157 932 3157 1498 3158 980 3158 981 3158 1476 3159 979 3159 980 3159 1499 3160 1476 3160 980 3160 1498 3161 1499 3161 980 3161 1480 3162 976 3162 979 3162 1477 3163 979 3163 1476 3163 1479 3164 1480 3164 979 3164 1478 3165 1479 3165 979 3165 1477 3166 1478 3166 979 3166 1377 3167 971 3167 976 3167 1480 3168 1377 3168 976 3168 1377 3169 966 3169 971 3169 1377 3170 963 3170 966 3170 1475 3171 963 3171 1377 3171 1475 3172 1461 3172 963 3172 1530 3173 1003 3173 1004 3173 1516 3174 1002 3174 1003 3174 1531 3175 1516 3175 1003 3175 1530 3176 1531 3176 1003 3176 1519 3177 1000 3177 1002 3177 1517 3178 1002 3178 1516 3178 1520 3179 1519 3179 1002 3179 1518 3180 1520 3180 1002 3180 1517 3181 1518 3181 1002 3181 1377 3182 996 3182 1000 3182 1366 3183 1377 3183 1000 3183 1519 3184 1366 3184 1000 3184 1377 3185 991 3185 996 3185 1377 3186 988 3186 991 3186 1514 3187 988 3187 1377 3187 1515 3188 1501 3188 988 3188 1514 3189 1515 3189 988 3189 1412 3190 1011 3190 1009 3190 1411 3191 1009 3191 1014 3191 1411 3192 1412 3192 1009 3192 1412 3193 1082 3193 1011 3193 1412 3194 1081 3194 1082 3194 1412 3195 1079 3195 1081 3195 1413 3196 1077 3196 1079 3196 1412 3197 1413 3197 1079 3197 1091 3198 1075 3198 1077 3198 1413 3199 1091 3199 1077 3199 1091 3200 1073 3200 1075 3200 1091 3201 1069 3201 1073 3201 1112 3202 1066 3202 1069 3202 1091 3203 1094 3203 1069 3203 1112 3204 1069 3204 1094 3204 1386 3205 1064 3205 1066 3205 1386 3206 1066 3206 1112 3206 1386 3207 1062 3207 1064 3207 1386 3208 1059 3208 1062 3208 1386 3209 1056 3209 1059 3209 1387 3210 1054 3210 1056 3210 1386 3211 1387 3211 1056 3211 1387 3212 1052 3212 1054 3212 1387 3213 1050 3213 1052 3213 1387 3214 1047 3214 1050 3214 1388 3215 1045 3215 1047 3215 1387 3216 1388 3216 1047 3216 1388 3217 1043 3217 1045 3217 1388 3218 1041 3218 1043 3218 1388 3219 1038 3219 1041 3219 1145 3220 1036 3220 1038 3220 1388 3221 1145 3221 1038 3221 1145 3222 1034 3222 1036 3222 1145 3223 1030 3223 1034 3223 1410 3224 1027 3224 1030 3224 1145 3225 1147 3225 1030 3225 1161 3226 1030 3226 1147 3226 1410 3227 1030 3227 1161 3227 1410 3228 1025 3228 1027 3228 1410 3229 1023 3229 1025 3229 1410 3230 1020 3230 1023 3230 1411 3231 1018 3231 1020 3231 1410 3232 1411 3232 1020 3232 1411 3233 1016 3233 1018 3233 1411 3234 1014 3234 1016 3234 1414 3235 1088 3235 1086 3235 1413 3236 1086 3236 1090 3236 1413 3237 1414 3237 1086 3237 1414 3238 1107 3238 1088 3238 1414 3239 1106 3239 1107 3239 1110 3240 1103 3240 1106 3240 1122 3241 1110 3241 1106 3241 1414 3242 1122 3242 1106 3242 1109 3243 1100 3243 1103 3243 1110 3244 1109 3244 1103 3244 1111 3245 1097 3245 1100 3245 1111 3246 1100 3246 1109 3246 1112 3247 1094 3247 1097 3247 1111 3248 1112 3248 1097 3248 1413 3249 1090 3249 1091 3249 1414 3250 1121 3250 1122 3250 1385 3251 1120 3251 1121 3251 1384 3252 1121 3252 1414 3252 1384 3253 1385 3253 1121 3253 1385 3254 1118 3254 1120 3254 1385 3255 1116 3255 1118 3255 1386 3256 1114 3256 1116 3256 1385 3257 1386 3257 1116 3257 1386 3258 1112 3258 1114 3258 1160 3259 1129 3259 1126 3259 1159 3260 1126 3260 1132 3260 1159 3261 1160 3261 1126 3261 1161 3262 1147 3262 1129 3262 1160 3263 1161 3263 1129 3263 1390 3264 1144 3264 1145 3264 1388 3265 1390 3265 1145 3265 1390 3266 1142 3266 1144 3266 1390 3267 1140 3267 1142 3267 1393 3268 1138 3268 1140 3268 1390 3269 1393 3269 1140 3269 1393 3270 1135 3270 1138 3270 1158 3271 1132 3271 1135 3271 1157 3272 1158 3272 1135 3272 1393 3273 1157 3273 1135 3273 1158 3274 1159 3274 1132 3274 1410 3275 1153 3275 1151 3275 1409 3276 1151 3276 1155 3276 1409 3277 1410 3277 1151 3277 1410 3278 1162 3278 1153 3278 1410 3279 1161 3279 1162 3279 1393 3280 1156 3280 1157 3280 1409 3281 1155 3281 1156 3281 1393 3282 1409 3282 1156 3282 1416 3283 1168 3283 1166 3283 1415 3284 1166 3284 1170 3284 1415 3285 1416 3285 1166 3285 1416 3286 1199 3286 1168 3286 1416 3287 1198 3287 1199 3287 1416 3288 1195 3288 1198 3288 1382 3289 1192 3289 1195 3289 1416 3290 1417 3290 1195 3290 1382 3291 1195 3291 1417 3291 1383 3292 1190 3292 1192 3292 1382 3293 1383 3293 1192 3293 1383 3294 1188 3294 1190 3294 1383 3295 1186 3295 1188 3295 1383 3296 1183 3296 1186 3296 1384 3297 1181 3297 1183 3297 1383 3298 1384 3298 1183 3298 1384 3299 1179 3299 1181 3299 1384 3300 1176 3300 1179 3300 1414 3301 1174 3301 1176 3301 1384 3302 1414 3302 1176 3302 1415 3303 1172 3303 1174 3303 1414 3304 1415 3304 1174 3304 1415 3305 1170 3305 1172 3305 1440 3306 1205 3306 1203 3306 1439 3307 1203 3307 1208 3307 1439 3308 1440 3308 1203 3308 1440 3309 1224 3309 1205 3309 1442 3310 1222 3310 1224 3310 1440 3311 1442 3311 1224 3311 1446 3312 1220 3312 1222 3312 1447 3313 1446 3313 1222 3313 1444 3314 1447 3314 1222 3314 1442 3315 1444 3315 1222 3315 1457 3316 1218 3316 1220 3316 1450 3317 1457 3317 1220 3317 1446 3318 1450 3318 1220 3318 1457 3319 1216 3319 1218 3319 1457 3320 1213 3320 1216 3320 1457 3321 1210 3321 1213 3321 1439 3322 1208 3322 1210 3322 1439 3323 1210 3323 1457 3323 1459 3324 1231 3324 1229 3324 1459 3325 1229 3325 1233 3325 1459 3326 1250 3326 1231 3326 1459 3327 1248 3327 1250 3327 1355 3328 1245 3328 1248 3328 1354 3329 1248 3329 1459 3329 1354 3330 1355 3330 1248 3330 1356 3331 1243 3331 1245 3331 1355 3332 1356 3332 1245 3332 1356 3333 1240 3333 1243 3333 1357 3334 1238 3334 1240 3334 1356 3335 1357 3335 1240 3335 1357 3336 1235 3336 1238 3336 1458 3337 1233 3337 1235 3337 1357 3338 1458 3338 1235 3338 1458 3339 1459 3339 1233 3339 1439 3340 1258 3340 1256 3340 1438 3341 1256 3341 1261 3341 1438 3342 1439 3342 1256 3342 1439 3343 1278 3343 1258 3343 1439 3344 1277 3344 1278 3344 1282 3345 1275 3345 1277 3345 1299 3346 1282 3346 1277 3346 1457 3347 1299 3347 1277 3347 1439 3348 1457 3348 1277 3348 1281 3349 1271 3349 1275 3349 1282 3350 1281 3350 1275 3350 1535 3351 1268 3351 1271 3351 1534 3352 1271 3352 1281 3352 1534 3353 1535 3353 1271 3353 1533 3354 1266 3354 1268 3354 1535 3355 1533 3355 1268 3355 1533 3356 1263 3356 1266 3356 1438 3357 1261 3357 1263 3357 1437 3358 1438 3358 1263 3358 1533 3359 1437 3359 1263 3359 1534 3360 1281 3360 1285 3360 1457 3361 1298 3361 1299 3361 1357 3362 1297 3362 1298 3362 1457 3363 1458 3363 1298 3363 1357 3364 1298 3364 1458 3364 1357 3365 1295 3365 1297 3365 1357 3366 1293 3366 1295 3366 1359 3367 1290 3367 1293 3367 1357 3368 1359 3368 1293 3368 1359 3369 1287 3369 1290 3369 1534 3370 1285 3370 1287 3370 1534 3371 1287 3371 1359 3371 1430 3372 1304 3372 1302 3372 1430 3373 1302 3373 1306 3373 1430 3374 1342 3374 1304 3374 1433 3375 1341 3375 1342 3375 1430 3376 1433 3376 1342 3376 1433 3377 1339 3377 1341 3377 1433 3378 1337 3378 1339 3378 1365 3379 1334 3379 1337 3379 1365 3380 1337 3380 1433 3380 1365 3381 1332 3381 1334 3381 1365 3382 1330 3382 1332 3382 1365 3383 1327 3383 1330 3383 1366 3384 1325 3384 1327 3384 1365 3385 1366 3385 1327 3385 1366 3386 1323 3386 1325 3386 1366 3387 1321 3387 1323 3387 1366 3388 1319 3388 1321 3388 1366 3389 1317 3389 1319 3389 1366 3390 1314 3390 1317 3390 1427 3391 1312 3391 1314 3391 1366 3392 1427 3392 1314 3392 1430 3393 1310 3393 1312 3393 1427 3394 1430 3394 1312 3394 1430 3395 1308 3395 1310 3395 1430 3396 1306 3396 1308 3396 1348 3397 1459 3397 1345 3397 1353 3398 1354 3398 1459 3398 1351 3399 1353 3399 1459 3399 1352 3400 1351 3400 1459 3400 1350 3401 1352 3401 1459 3401 1349 3402 1350 3402 1459 3402 1348 3403 1349 3403 1459 3403 1456 3404 1455 3404 1457 3404 1454 3405 1456 3405 1457 3405 1452 3406 1454 3406 1457 3406 1450 3407 1452 3407 1457 3407 1533 3408 1436 3408 1437 3408 1533 3409 1435 3409 1436 3409 1364 3410 1433 3410 1435 3410 1533 3411 1364 3411 1435 3411 1364 3412 1365 3412 1433 3412 1524 3413 1427 3413 1366 3413 1495 3414 1496 3414 1427 3414 1494 3415 1495 3415 1427 3415 1492 3416 1494 3416 1427 3416 1506 3417 1492 3417 1427 3417 1527 3418 1529 3418 1427 3418 1528 3419 1527 3419 1427 3419 1526 3420 1528 3420 1427 3420 1525 3421 1526 3421 1427 3421 1523 3422 1525 3422 1427 3422 1524 3423 1523 3423 1427 3423 1381 3424 1417 3424 1418 3424 1377 3425 1381 3425 1418 3425 1470 3426 1377 3426 1418 3426 1468 3427 1470 3427 1418 3427 1467 3428 1468 3428 1418 3428 1466 3429 1467 3429 1418 3429 1381 3430 1382 3430 1417 3430 1393 3431 1408 3431 1409 3431 1396 3432 1407 3432 1408 3432 1393 3433 1396 3433 1408 3433 1399 3434 1406 3434 1407 3434 1396 3435 1399 3435 1407 3435 1402 3436 1405 3436 1406 3436 1399 3437 1402 3437 1406 3437 1403 3438 1404 3438 1405 3438 1402 3439 1403 3439 1405 3439 1474 3440 1475 3440 1377 3440 1473 3441 1474 3441 1377 3441 1472 3442 1473 3442 1377 3442 1471 3443 1472 3443 1377 3443 1469 3444 1471 3444 1377 3444 1470 3445 1469 3445 1377 3445 1511 3446 1377 3446 1480 3446 1513 3447 1514 3447 1377 3447 1512 3448 1513 3448 1377 3448 1511 3449 1512 3449 1377 3449 1522 3450 1524 3450 1366 3450 1521 3451 1522 3451 1366 3451 1519 3452 1521 3452 1366 3452 1532 3453 1363 3453 1364 3453 1533 3454 1532 3454 1364 3454 1534 3455 1361 3455 1363 3455 1534 3456 1363 3456 1532 3456 1534 3457 1359 3457 1361 3457 1506 3458 1486 3458 1492 3458 1507 3459 1487 3459 1486 3459 1506 3460 1507 3460 1486 3460 1510 3461 1483 3461 1487 3461 1508 3462 1510 3462 1487 3462 1507 3463 1508 3463 1487 3463 1510 3464 1481 3464 1483 3464 1509 3465 1480 3465 1481 3465 1510 3466 1509 3466 1481 3466 1509 3467 1511 3467 1480 3467 1536 3468 1537 3468 1538 3468 1539 3469 1538 3469 1537 3469 1540 3470 1538 3470 1541 3470 1542 3471 1541 3471 1538 3471 1543 3472 1536 3472 1538 3472 1540 3473 1543 3473 1538 3473 1542 3474 1538 3474 1539 3474 1536 3475 1544 3475 1537 3475 1545 3476 1537 3476 1544 3476 1545 3477 1539 3477 1537 3477 1536 3478 1546 3478 1544 3478 1547 3479 1544 3479 1546 3479 1545 3480 1544 3480 1547 3480 1548 3481 1549 3481 1546 3481 1550 3482 1546 3482 1549 3482 1551 3483 1548 3483 1546 3483 1552 3484 1551 3484 1546 3484 1553 3485 1546 3485 1536 3485 1554 3486 1552 3486 1546 3486 1553 3487 1554 3487 1546 3487 1547 3488 1546 3488 1550 3488 1555 3489 1556 3489 1549 3489 1557 3490 1549 3490 1556 3490 1548 3491 1555 3491 1549 3491 1550 3492 1549 3492 1557 3492 1558 3493 1559 3493 1556 3493 1560 3494 1556 3494 1559 3494 1558 3495 1556 3495 1555 3495 1557 3496 1556 3496 1560 3496 1561 3497 1562 3497 1559 3497 1563 3498 1559 3498 1562 3498 1558 3499 1561 3499 1559 3499 1560 3500 1559 3500 1563 3500 1564 3501 1565 3501 1562 3501 1566 3502 1562 3502 1565 3502 1564 3503 1562 3503 1561 3503 1563 3504 1562 3504 1566 3504 1567 3505 1541 3505 1565 3505 1568 3506 1565 3506 1541 3506 1564 3507 1569 3507 1565 3507 1567 3508 1565 3508 1569 3508 1566 3509 1565 3509 1568 3509 1570 3510 1540 3510 1541 3510 1571 3511 1570 3511 1541 3511 1572 3512 1571 3512 1541 3512 1567 3513 1572 3513 1541 3513 1568 3514 1541 3514 1542 3514 1536 3515 1573 3515 1574 3515 1575 3516 1574 3516 1573 3516 1576 3517 1574 3517 1577 3517 1578 3518 1577 3518 1574 3518 1576 3519 1536 3519 1574 3519 1578 3520 1574 3520 1575 3520 1536 3521 1579 3521 1573 3521 1580 3522 1573 3522 1579 3522 1580 3523 1575 3523 1573 3523 1536 3524 1581 3524 1579 3524 1582 3525 1579 3525 1581 3525 1580 3526 1579 3526 1582 3526 1583 3527 1584 3527 1581 3527 1585 3528 1581 3528 1584 3528 1586 3529 1583 3529 1581 3529 1587 3530 1586 3530 1581 3530 1588 3531 1581 3531 1536 3531 1588 3532 1587 3532 1581 3532 1582 3533 1581 3533 1585 3533 1589 3534 1590 3534 1584 3534 1591 3535 1584 3535 1590 3535 1583 3536 1589 3536 1584 3536 1585 3537 1584 3537 1591 3537 1592 3538 1593 3538 1590 3538 1594 3539 1590 3539 1593 3539 1592 3540 1590 3540 1589 3540 1591 3541 1590 3541 1594 3541 1595 3542 1596 3542 1593 3542 1597 3543 1593 3543 1596 3543 1592 3544 1595 3544 1593 3544 1594 3545 1593 3545 1597 3545 1598 3546 1599 3546 1596 3546 1600 3547 1596 3547 1599 3547 1598 3548 1596 3548 1595 3548 1597 3549 1596 3549 1600 3549 1601 3550 1577 3550 1599 3550 1602 3551 1599 3551 1577 3551 1598 3552 1603 3552 1599 3552 1601 3553 1599 3553 1603 3553 1600 3554 1599 3554 1602 3554 1604 3555 1576 3555 1577 3555 1605 3556 1604 3556 1577 3556 1606 3557 1605 3557 1577 3557 1601 3558 1606 3558 1577 3558 1602 3559 1577 3559 1578 3559 1607 3560 1589 3560 1583 3560 1608 3561 1592 3561 1589 3561 1608 3562 1589 3562 1607 3562 1609 3563 1583 3563 1586 3563 1609 3564 1607 3564 1583 3564 1587 3565 1610 3565 1586 3565 1611 3566 1586 3566 1610 3566 1609 3567 1586 3567 1611 3567 1612 3568 1613 3568 1610 3568 1614 3569 1610 3569 1613 3569 1615 3570 1616 3570 1610 3570 1612 3571 1610 3571 1616 3571 1587 3572 1615 3572 1610 3572 1611 3573 1610 3573 1614 3573 1617 3574 1618 3574 1613 3574 1619 3575 1613 3575 1618 3575 1620 3576 1617 3576 1613 3576 1621 3577 1620 3577 1613 3577 1612 3578 1621 3578 1613 3578 1614 3579 1613 3579 1619 3579 1622 3580 1623 3580 1618 3580 1624 3581 1618 3581 1623 3581 1625 3582 1622 3582 1618 3582 1617 3583 1625 3583 1618 3583 1619 3584 1618 3584 1624 3584 1622 3585 1626 3585 1623 3585 1627 3586 1623 3586 1626 3586 1624 3587 1623 3587 1627 3587 1622 3588 1595 3588 1626 3588 1628 3589 1626 3589 1595 3589 1627 3590 1626 3590 1628 3590 1629 3591 1595 3591 1592 3591 1630 3592 1595 3592 1622 3592 1631 3593 1598 3593 1595 3593 1630 3594 1631 3594 1595 3594 1628 3595 1595 3595 1629 3595 1629 3596 1592 3596 1608 3596 1632 3597 1555 3597 1548 3597 1633 3598 1558 3598 1555 3598 1633 3599 1555 3599 1632 3599 1634 3600 1548 3600 1551 3600 1634 3601 1632 3601 1548 3601 1552 3602 1635 3602 1551 3602 1636 3603 1551 3603 1635 3603 1634 3604 1551 3604 1636 3604 1637 3605 1638 3605 1635 3605 1639 3606 1635 3606 1638 3606 1640 3607 1641 3607 1635 3607 1637 3608 1635 3608 1641 3608 1552 3609 1640 3609 1635 3609 1636 3610 1635 3610 1639 3610 1642 3611 1643 3611 1638 3611 1644 3612 1638 3612 1643 3612 1645 3613 1642 3613 1638 3613 1646 3614 1645 3614 1638 3614 1637 3615 1646 3615 1638 3615 1639 3616 1638 3616 1644 3616 1622 3617 1647 3617 1643 3617 1648 3618 1643 3618 1647 3618 1642 3619 1622 3619 1643 3619 1644 3620 1643 3620 1648 3620 1622 3621 1649 3621 1647 3621 1650 3622 1647 3622 1649 3622 1648 3623 1647 3623 1650 3623 1622 3624 1561 3624 1649 3624 1651 3625 1649 3625 1561 3625 1650 3626 1649 3626 1651 3626 1652 3627 1561 3627 1558 3627 1653 3628 1561 3628 1622 3628 1653 3629 1564 3629 1561 3629 1651 3630 1561 3630 1652 3630 1652 3631 1558 3631 1633 3631 1654 3632 1655 3632 1656 3632 1657 3633 1656 3633 1655 3633 1654 3634 1656 3634 1658 3634 1659 3635 1658 3635 1656 3635 1659 3636 1656 3636 1657 3636 1660 3637 1661 3637 1655 3637 1662 3638 1655 3638 1661 3638 1654 3639 1660 3639 1655 3639 1662 3640 1657 3640 1655 3640 1660 3641 1663 3641 1661 3641 1664 3642 1661 3642 1663 3642 1662 3643 1661 3643 1664 3643 1660 3644 1665 3644 1663 3644 1666 3645 1663 3645 1665 3645 1664 3646 1663 3646 1666 3646 1660 3647 1667 3647 1665 3647 1668 3648 1665 3648 1667 3648 1666 3649 1665 3649 1668 3649 1669 3650 1670 3650 1667 3650 1671 3651 1667 3651 1670 3651 1660 3652 1669 3652 1667 3652 1668 3653 1667 3653 1671 3653 1669 3654 1672 3654 1670 3654 1673 3655 1670 3655 1672 3655 1671 3656 1670 3656 1673 3656 1669 3657 1674 3657 1672 3657 1675 3658 1672 3658 1674 3658 1673 3659 1672 3659 1675 3659 1676 3660 1677 3660 1674 3660 1678 3661 1674 3661 1677 3661 1679 3662 1680 3662 1674 3662 1676 3663 1674 3663 1680 3663 1669 3664 1679 3664 1674 3664 1675 3665 1674 3665 1678 3665 1676 3666 1681 3666 1677 3666 1682 3667 1677 3667 1681 3667 1678 3668 1677 3668 1682 3668 1676 3669 1683 3669 1681 3669 1684 3670 1681 3670 1683 3670 1682 3671 1681 3671 1684 3671 1676 3672 1685 3672 1683 3672 1686 3673 1683 3673 1685 3673 1684 3674 1683 3674 1686 3674 1687 3675 1688 3675 1685 3675 1689 3676 1685 3676 1688 3676 1676 3677 1687 3677 1685 3677 1686 3678 1685 3678 1689 3678 1687 3679 1690 3679 1688 3679 1691 3680 1688 3680 1690 3680 1689 3681 1688 3681 1691 3681 1687 3682 1692 3682 1690 3682 1693 3683 1690 3683 1692 3683 1691 3684 1690 3684 1693 3684 1687 3685 1694 3685 1692 3685 1695 3686 1692 3686 1694 3686 1693 3687 1692 3687 1695 3687 1696 3688 1697 3688 1694 3688 1698 3689 1694 3689 1697 3689 1687 3690 1696 3690 1694 3690 1695 3691 1694 3691 1698 3691 1696 3692 1699 3692 1697 3692 1700 3693 1697 3693 1699 3693 1698 3694 1697 3694 1700 3694 1696 3695 1701 3695 1699 3695 1702 3696 1699 3696 1701 3696 1700 3697 1699 3697 1702 3697 1696 3698 1703 3698 1701 3698 1704 3699 1701 3699 1703 3699 1702 3700 1701 3700 1704 3700 1705 3701 1706 3701 1703 3701 1707 3702 1703 3702 1706 3702 1696 3703 1705 3703 1703 3703 1704 3704 1703 3704 1707 3704 1708 3705 1709 3705 1706 3705 1710 3706 1706 3706 1709 3706 1705 3707 1708 3707 1706 3707 1707 3708 1706 3708 1710 3708 1708 3709 1711 3709 1709 3709 1712 3710 1709 3710 1711 3710 1710 3711 1709 3711 1712 3711 1708 3712 1713 3712 1711 3712 1714 3713 1711 3713 1713 3713 1712 3714 1711 3714 1714 3714 1715 3715 1716 3715 1713 3715 1717 3716 1713 3716 1716 3716 1718 3717 1715 3717 1713 3717 1708 3718 1718 3718 1713 3718 1714 3719 1713 3719 1717 3719 1719 3720 1720 3720 1716 3720 1721 3721 1716 3721 1720 3721 1719 3722 1716 3722 1715 3722 1717 3723 1716 3723 1721 3723 1719 3724 1722 3724 1720 3724 1723 3725 1720 3725 1722 3725 1721 3726 1720 3726 1723 3726 1719 3727 1724 3727 1722 3727 1725 3728 1722 3728 1724 3728 1723 3729 1722 3729 1725 3729 1719 3730 1726 3730 1724 3730 1727 3731 1724 3731 1726 3731 1725 3732 1724 3732 1727 3732 1654 3733 1728 3733 1726 3733 1729 3734 1726 3734 1728 3734 1719 3735 1654 3735 1726 3735 1727 3736 1726 3736 1729 3736 1654 3737 1658 3737 1728 3737 1730 3738 1728 3738 1658 3738 1729 3739 1728 3739 1730 3739 1730 3740 1658 3740 1659 3740 1731 3741 1732 3741 1733 3741 1734 3742 1733 3742 1732 3742 1731 3743 1733 3743 1735 3743 1736 3744 1735 3744 1733 3744 1736 3745 1733 3745 1734 3745 1719 3746 1737 3746 1732 3746 1738 3747 1732 3747 1737 3747 1731 3748 1719 3748 1732 3748 1738 3749 1734 3749 1732 3749 1719 3750 1715 3750 1737 3750 1739 3751 1737 3751 1715 3751 1738 3752 1737 3752 1739 3752 1740 3753 1741 3753 1715 3753 1742 3754 1715 3754 1741 3754 1718 3755 1740 3755 1715 3755 1739 3756 1715 3756 1742 3756 1743 3757 1744 3757 1741 3757 1745 3758 1741 3758 1744 3758 1740 3759 1743 3759 1741 3759 1742 3760 1741 3760 1745 3760 1746 3761 1747 3761 1744 3761 1748 3762 1744 3762 1747 3762 1746 3763 1744 3763 1743 3763 1745 3764 1744 3764 1748 3764 1749 3765 1750 3765 1747 3765 1751 3766 1747 3766 1750 3766 1746 3767 1749 3767 1747 3767 1748 3768 1747 3768 1751 3768 1752 3769 1753 3769 1750 3769 1754 3770 1750 3770 1753 3770 1752 3771 1750 3771 1749 3771 1751 3772 1750 3772 1754 3772 1731 3773 1735 3773 1753 3773 1755 3774 1753 3774 1735 3774 1756 3775 1753 3775 1752 3775 1756 3776 1731 3776 1753 3776 1754 3777 1753 3777 1755 3777 1755 3778 1735 3778 1736 3778 1757 3779 1743 3779 1740 3779 1758 3780 1746 3780 1743 3780 1758 3781 1743 3781 1757 3781 1759 3782 1740 3782 1718 3782 1759 3783 1757 3783 1740 3783 1760 3784 1718 3784 1708 3784 1759 3785 1718 3785 1760 3785 1705 3786 1761 3786 1708 3786 1762 3787 1708 3787 1761 3787 1760 3788 1708 3788 1762 3788 1705 3789 1763 3789 1761 3789 1764 3790 1761 3790 1763 3790 1762 3791 1761 3791 1764 3791 1752 3792 1765 3792 1763 3792 1766 3793 1763 3793 1765 3793 1705 3794 1752 3794 1763 3794 1764 3795 1763 3795 1766 3795 1752 3796 1767 3796 1765 3796 1768 3797 1765 3797 1767 3797 1766 3798 1765 3798 1768 3798 1752 3799 1749 3799 1767 3799 1769 3800 1767 3800 1749 3800 1768 3801 1767 3801 1769 3801 1770 3802 1749 3802 1746 3802 1769 3803 1749 3803 1770 3803 1770 3804 1746 3804 1758 3804 1771 3805 1772 3805 1773 3805 1774 3806 1773 3806 1772 3806 1775 3807 1773 3807 1776 3807 1777 3808 1776 3808 1773 3808 1775 3809 1771 3809 1773 3809 1777 3810 1773 3810 1774 3810 1778 3811 1779 3811 1772 3811 1780 3812 1772 3812 1779 3812 1771 3813 1778 3813 1772 3813 1780 3814 1774 3814 1772 3814 1781 3815 1782 3815 1779 3815 1783 3816 1779 3816 1782 3816 1781 3817 1779 3817 1778 3817 1780 3818 1779 3818 1783 3818 1784 3819 1785 3819 1782 3819 1786 3820 1782 3820 1785 3820 1781 3821 1784 3821 1782 3821 1783 3822 1782 3822 1786 3822 1784 3823 1787 3823 1785 3823 1788 3824 1785 3824 1787 3824 1786 3825 1785 3825 1788 3825 1676 3826 1789 3826 1787 3826 1790 3827 1787 3827 1789 3827 1784 3828 1676 3828 1787 3828 1788 3829 1787 3829 1790 3829 1676 3830 1791 3830 1789 3830 1792 3831 1789 3831 1791 3831 1790 3832 1789 3832 1792 3832 1676 3833 1680 3833 1791 3833 1793 3834 1791 3834 1680 3834 1792 3835 1791 3835 1793 3835 1794 3836 1776 3836 1680 3836 1795 3837 1680 3837 1776 3837 1679 3838 1794 3838 1680 3838 1793 3839 1680 3839 1795 3839 1794 3840 1775 3840 1776 3840 1795 3841 1776 3841 1777 3841 1796 3842 1797 3842 1798 3842 1799 3843 1798 3843 1797 3843 1796 3844 1798 3844 1800 3844 1801 3845 1800 3845 1798 3845 1801 3846 1798 3846 1799 3846 1781 3847 1802 3847 1797 3847 1803 3848 1797 3848 1802 3848 1796 3849 1781 3849 1797 3849 1803 3850 1799 3850 1797 3850 1781 3851 1778 3851 1802 3851 1804 3852 1802 3852 1778 3852 1803 3853 1802 3853 1804 3853 1805 3854 1778 3854 1771 3854 1804 3855 1778 3855 1805 3855 1806 3856 1771 3856 1775 3856 1805 3857 1771 3857 1806 3857 1807 3858 1775 3858 1794 3858 1806 3859 1775 3859 1807 3859 1808 3860 1794 3860 1679 3860 1807 3861 1794 3861 1808 3861 1809 3862 1679 3862 1669 3862 1808 3863 1679 3863 1809 3863 1796 3864 1800 3864 1669 3864 1810 3865 1669 3865 1800 3865 1660 3866 1796 3866 1669 3866 1809 3867 1669 3867 1810 3867 1810 3868 1800 3868 1801 3868 1811 3869 1812 3869 1813 3869 1814 3870 1813 3870 1812 3870 1811 3871 1813 3871 1815 3871 1816 3872 1815 3872 1813 3872 1816 3873 1813 3873 1814 3873 1756 3874 1817 3874 1812 3874 1818 3875 1812 3875 1817 3875 1811 3876 1756 3876 1812 3876 1818 3877 1814 3877 1812 3877 1756 3878 1819 3878 1817 3878 1820 3879 1817 3879 1819 3879 1818 3880 1817 3880 1820 3880 1756 3881 1821 3881 1819 3881 1822 3882 1819 3882 1821 3882 1820 3883 1819 3883 1822 3883 1752 3884 1823 3884 1821 3884 1824 3885 1821 3885 1823 3885 1756 3886 1752 3886 1821 3886 1822 3887 1821 3887 1824 3887 1825 3888 1826 3888 1823 3888 1827 3889 1823 3889 1826 3889 1752 3890 1825 3890 1823 3890 1824 3891 1823 3891 1827 3891 1825 3892 1828 3892 1826 3892 1829 3893 1826 3893 1828 3893 1827 3894 1826 3894 1829 3894 1825 3895 1830 3895 1828 3895 1831 3896 1828 3896 1830 3896 1829 3897 1828 3897 1831 3897 1832 3898 1833 3898 1830 3898 1834 3899 1830 3899 1833 3899 1825 3900 1832 3900 1830 3900 1831 3901 1830 3901 1834 3901 1832 3902 1835 3902 1833 3902 1836 3903 1833 3903 1835 3903 1834 3904 1833 3904 1836 3904 1832 3905 1837 3905 1835 3905 1838 3906 1835 3906 1837 3906 1836 3907 1835 3907 1838 3907 1832 3908 1839 3908 1837 3908 1840 3909 1837 3909 1839 3909 1838 3910 1837 3910 1840 3910 1841 3911 1842 3911 1839 3911 1843 3912 1839 3912 1842 3912 1832 3913 1844 3913 1839 3913 1841 3914 1839 3914 1844 3914 1840 3915 1839 3915 1843 3915 1811 3916 1845 3916 1842 3916 1846 3917 1842 3917 1845 3917 1841 3918 1811 3918 1842 3918 1843 3919 1842 3919 1846 3919 1811 3920 1815 3920 1845 3920 1847 3921 1845 3921 1815 3921 1846 3922 1845 3922 1847 3922 1847 3923 1815 3923 1816 3923 1848 3924 1849 3924 1850 3924 1851 3925 1850 3925 1849 3925 1848 3926 1850 3926 1852 3926 1853 3927 1852 3927 1850 3927 1853 3928 1850 3928 1851 3928 1854 3929 1855 3929 1849 3929 1856 3930 1849 3930 1855 3930 1848 3931 1854 3931 1849 3931 1856 3932 1851 3932 1849 3932 1854 3933 1857 3933 1855 3933 1858 3934 1855 3934 1857 3934 1856 3935 1855 3935 1858 3935 1859 3936 1860 3936 1857 3936 1861 3937 1857 3937 1860 3937 1859 3938 1857 3938 1854 3938 1858 3939 1857 3939 1861 3939 1862 3940 1863 3940 1860 3940 1864 3941 1860 3941 1863 3941 1859 3942 1862 3942 1860 3942 1861 3943 1860 3943 1864 3943 1862 3944 1865 3944 1863 3944 1866 3945 1863 3945 1865 3945 1864 3946 1863 3946 1866 3946 1862 3947 1867 3947 1865 3947 1868 3948 1865 3948 1867 3948 1866 3949 1865 3949 1868 3949 1862 3950 1869 3950 1867 3950 1870 3951 1867 3951 1869 3951 1868 3952 1867 3952 1870 3952 1871 3953 1852 3953 1869 3953 1872 3954 1869 3954 1852 3954 1873 3955 1871 3955 1869 3955 1862 3956 1873 3956 1869 3956 1870 3957 1869 3957 1872 3957 1871 3958 1848 3958 1852 3958 1872 3959 1852 3959 1853 3959 1874 3960 1875 3960 1876 3960 1877 3961 1876 3961 1875 3961 1874 3962 1876 3962 1878 3962 1879 3963 1878 3963 1876 3963 1879 3964 1876 3964 1877 3964 1874 3965 1880 3965 1875 3965 1881 3966 1875 3966 1880 3966 1881 3967 1877 3967 1875 3967 1874 3968 1882 3968 1880 3968 1883 3969 1880 3969 1882 3969 1881 3970 1880 3970 1883 3970 1884 3971 1885 3971 1882 3971 1886 3972 1882 3972 1885 3972 1874 3973 1884 3973 1882 3973 1883 3974 1882 3974 1886 3974 1884 3975 1887 3975 1885 3975 1888 3976 1885 3976 1887 3976 1886 3977 1885 3977 1888 3977 1889 3978 1890 3978 1887 3978 1891 3979 1887 3979 1890 3979 1884 3980 1889 3980 1887 3980 1888 3981 1887 3981 1891 3981 1889 3982 1892 3982 1890 3982 1893 3983 1890 3983 1892 3983 1891 3984 1890 3984 1893 3984 1894 3985 1895 3985 1892 3985 1896 3986 1892 3986 1895 3986 1889 3987 1894 3987 1892 3987 1893 3988 1892 3988 1896 3988 1897 3989 1878 3989 1895 3989 1898 3990 1895 3990 1878 3990 1899 3991 1897 3991 1895 3991 1900 3992 1899 3992 1895 3992 1894 3993 1900 3993 1895 3993 1896 3994 1895 3994 1898 3994 1897 3995 1901 3995 1878 3995 1874 3996 1878 3996 1901 3996 1898 3997 1878 3997 1879 3997 1854 3998 1902 3998 1903 3998 1904 3999 1903 3999 1902 3999 1854 4000 1903 4000 1905 4000 1906 4001 1905 4001 1903 4001 1906 4002 1903 4002 1904 4002 1907 4003 1908 4003 1902 4003 1909 4004 1902 4004 1908 4004 1854 4005 1907 4005 1902 4005 1909 4006 1904 4006 1902 4006 1907 4007 1910 4007 1908 4007 1911 4008 1908 4008 1910 4008 1909 4009 1908 4009 1911 4009 1912 4010 1913 4010 1910 4010 1914 4011 1910 4011 1913 4011 1912 4012 1910 4012 1907 4012 1911 4013 1910 4013 1914 4013 1912 4014 1915 4014 1913 4014 1916 4015 1913 4015 1915 4015 1914 4016 1913 4016 1916 4016 1917 4017 1918 4017 1915 4017 1919 4018 1915 4018 1918 4018 1917 4019 1915 4019 1920 4019 1912 4020 1920 4020 1915 4020 1916 4021 1915 4021 1919 4021 1921 4022 1922 4022 1918 4022 1923 4023 1918 4023 1922 4023 1917 4024 1921 4024 1918 4024 1919 4025 1918 4025 1923 4025 1874 4026 1924 4026 1922 4026 1925 4027 1922 4027 1924 4027 1874 4028 1922 4028 1921 4028 1923 4029 1922 4029 1925 4029 1854 4030 1905 4030 1924 4030 1926 4031 1924 4031 1905 4031 1859 4032 1854 4032 1924 4032 1874 4033 1859 4033 1924 4033 1925 4034 1924 4034 1926 4034 1926 4035 1905 4035 1906 4035 1927 4036 1928 4036 1920 4036 1929 4037 1920 4037 1928 4037 1930 4038 1917 4038 1920 4038 1912 4039 1927 4039 1920 4039 1930 4040 1920 4040 1929 4040 1931 4041 1932 4041 1928 4041 1933 4042 1928 4042 1932 4042 1927 4043 1931 4043 1928 4043 1933 4044 1929 4044 1928 4044 1931 4045 1934 4045 1932 4045 1935 4046 1932 4046 1934 4046 1933 4047 1932 4047 1935 4047 1936 4048 1937 4048 1934 4048 1938 4049 1934 4049 1937 4049 1939 4050 1936 4050 1934 4050 1931 4051 1939 4051 1934 4051 1935 4052 1934 4052 1938 4052 1936 4053 1940 4053 1937 4053 1941 4054 1937 4054 1940 4054 1938 4055 1937 4055 1941 4055 1884 4056 1942 4056 1940 4056 1943 4057 1940 4057 1942 4057 1936 4058 1884 4058 1940 4058 1941 4059 1940 4059 1943 4059 1884 4060 1944 4060 1942 4060 1945 4061 1942 4061 1944 4061 1943 4062 1942 4062 1945 4062 1884 4063 1921 4063 1944 4063 1946 4064 1944 4064 1921 4064 1945 4065 1944 4065 1946 4065 1947 4066 1921 4066 1917 4066 1874 4067 1921 4067 1884 4067 1946 4068 1921 4068 1947 4068 1947 4069 1917 4069 1930 4069 1543 4070 1948 4070 1949 4070 1950 4071 1949 4071 1948 4071 1543 4072 1949 4072 1951 4072 1952 4073 1951 4073 1949 4073 1952 4074 1949 4074 1950 4074 1543 4075 1953 4075 1948 4075 1954 4076 1948 4076 1953 4076 1954 4077 1950 4077 1948 4077 1543 4078 1955 4078 1953 4078 1956 4079 1953 4079 1955 4079 1954 4080 1953 4080 1956 4080 1543 4081 1957 4081 1955 4081 1958 4082 1955 4082 1957 4082 1956 4083 1955 4083 1958 4083 1543 4084 1959 4084 1957 4084 1960 4085 1957 4085 1959 4085 1958 4086 1957 4086 1960 4086 1622 4087 1961 4087 1959 4087 1962 4088 1959 4088 1961 4088 1543 4089 1622 4089 1959 4089 1960 4090 1959 4090 1962 4090 1963 4091 1964 4091 1961 4091 1965 4092 1961 4092 1964 4092 1622 4093 1963 4093 1961 4093 1962 4094 1961 4094 1965 4094 1963 4095 1966 4095 1964 4095 1967 4096 1964 4096 1966 4096 1965 4097 1964 4097 1967 4097 1963 4098 1968 4098 1966 4098 1969 4099 1966 4099 1968 4099 1967 4100 1966 4100 1969 4100 1963 4101 1970 4101 1968 4101 1971 4102 1968 4102 1970 4102 1969 4103 1968 4103 1971 4103 1963 4104 1972 4104 1970 4104 1973 4105 1970 4105 1972 4105 1971 4106 1970 4106 1973 4106 1963 4107 1974 4107 1972 4107 1975 4108 1972 4108 1974 4108 1973 4109 1972 4109 1975 4109 1976 4110 1977 4110 1974 4110 1978 4111 1974 4111 1977 4111 1963 4112 1976 4112 1974 4112 1975 4113 1974 4113 1978 4113 1976 4114 1979 4114 1977 4114 1980 4115 1977 4115 1979 4115 1978 4116 1977 4116 1980 4116 1976 4117 1981 4117 1979 4117 1982 4118 1979 4118 1981 4118 1980 4119 1979 4119 1982 4119 1983 4120 1984 4120 1981 4120 1985 4121 1981 4121 1984 4121 1983 4122 1981 4122 1976 4122 1982 4123 1981 4123 1985 4123 1983 4124 1986 4124 1984 4124 1987 4125 1984 4125 1986 4125 1985 4126 1984 4126 1987 4126 1983 4127 1988 4127 1986 4127 1989 4128 1986 4128 1988 4128 1987 4129 1986 4129 1989 4129 1983 4130 1951 4130 1988 4130 1990 4131 1988 4131 1951 4131 1989 4132 1988 4132 1990 4132 1983 4133 1543 4133 1951 4133 1990 4134 1951 4134 1952 4134 1874 4135 1991 4135 1992 4135 1993 4136 1992 4136 1991 4136 1994 4137 1874 4137 1992 4137 1993 4138 1994 4138 1992 4138 1874 4139 1995 4139 1991 4139 1996 4140 1991 4140 1995 4140 1996 4141 1993 4141 1991 4141 1874 4142 1901 4142 1995 4142 1997 4143 1995 4143 1901 4143 1996 4144 1995 4144 1997 4144 1998 4145 1901 4145 1897 4145 1997 4146 1901 4146 1998 4146 1999 4147 1897 4147 1899 4147 2000 4148 1897 4148 1999 4148 1998 4149 1897 4149 2000 4149 1999 4150 1899 4150 1900 4150 2001 4151 1900 4151 1894 4151 1999 4152 1900 4152 2001 4152 2002 4153 1894 4153 1889 4153 2001 4154 1894 4154 2002 4154 2003 4155 1889 4155 1884 4155 2002 4156 1889 4156 2003 4156 2004 4157 1884 4157 1936 4157 2003 4158 1884 4158 2004 4158 2005 4159 1936 4159 1939 4159 2004 4160 1936 4160 2005 4160 1931 4161 2006 4161 1939 4161 2007 4162 1939 4162 2006 4162 2005 4163 1939 4163 2007 4163 1931 4164 2008 4164 2006 4164 2009 4165 2006 4165 2008 4165 2007 4166 2006 4166 2009 4166 2010 4167 1976 4167 2008 4167 2011 4168 2008 4168 1976 4168 1931 4169 2010 4169 2008 4169 2009 4170 2008 4170 2011 4170 2012 4171 1976 4171 1963 4171 2010 4172 1983 4172 1976 4172 2011 4173 1976 4173 2012 4173 2013 4174 1963 4174 1622 4174 2012 4175 1963 4175 2013 4175 2014 4176 1622 4176 1625 4176 2015 4177 1622 4177 1543 4177 2016 4178 1630 4178 1622 4178 2017 4179 2016 4179 1622 4179 2018 4180 2017 4180 1622 4180 1642 4181 2018 4181 1622 4181 2019 4182 1653 4182 1622 4182 2020 4183 2019 4183 1622 4183 2021 4184 2020 4184 1622 4184 2022 4185 2021 4185 1622 4185 2023 4186 2022 4186 1622 4186 2015 4187 2023 4187 1622 4187 2013 4188 1622 4188 2014 4188 2024 4189 1844 4189 1625 4189 2025 4190 1625 4190 1844 4190 1536 4191 2024 4191 1625 4191 2026 4192 1536 4192 1625 4192 2027 4193 2026 4193 1625 4193 2028 4194 2027 4194 1625 4194 1617 4195 2028 4195 1625 4195 2014 4196 1625 4196 2025 4196 2029 4197 1844 4197 1832 4197 2024 4198 1841 4198 1844 4198 2025 4199 1844 4199 2029 4199 2030 4200 1832 4200 1825 4200 2029 4201 1832 4201 2030 4201 2031 4202 1825 4202 1752 4202 2030 4203 1825 4203 2031 4203 2032 4204 1752 4204 1705 4204 2031 4205 1752 4205 2032 4205 2033 4206 1705 4206 1696 4206 2032 4207 1705 4207 2033 4207 2034 4208 1696 4208 1687 4208 2033 4209 1696 4209 2034 4209 2035 4210 1687 4210 1676 4210 2034 4211 1687 4211 2035 4211 2036 4212 1676 4212 1784 4212 2035 4213 1676 4213 2036 4213 1781 4214 2037 4214 1784 4214 2038 4215 1784 4215 2037 4215 2036 4216 1784 4216 2038 4216 2039 4217 2040 4217 2037 4217 2041 4218 2037 4218 2040 4218 1781 4219 2039 4219 2037 4219 2038 4220 2037 4220 2041 4220 2042 4221 2043 4221 2040 4221 2044 4222 2040 4222 2043 4222 2039 4223 2042 4223 2040 4223 2041 4224 2040 4224 2044 4224 2045 4225 2046 4225 2043 4225 2047 4226 2043 4226 2046 4226 2042 4227 2045 4227 2043 4227 2044 4228 2043 4228 2047 4228 2048 4229 2049 4229 2046 4229 2050 4230 2046 4230 2049 4230 2045 4231 2048 4231 2046 4231 2047 4232 2046 4232 2050 4232 2051 4233 2049 4233 2048 4233 2050 4234 2049 4234 2051 4234 2052 4235 2048 4235 2045 4235 2051 4236 2048 4236 2052 4236 2053 4237 2045 4237 2042 4237 2052 4238 2045 4238 2053 4238 2054 4239 2042 4239 2039 4239 2053 4240 2042 4240 2054 4240 2055 4241 2039 4241 1781 4241 2054 4242 2039 4242 2055 4242 2056 4243 1781 4243 1796 4243 2055 4244 1781 4244 2056 4244 2057 4245 1796 4245 1660 4245 2056 4246 1796 4246 2057 4246 2058 4247 1660 4247 1654 4247 2057 4248 1660 4248 2058 4248 2059 4249 1654 4249 1719 4249 2058 4250 1654 4250 2059 4250 2060 4251 1719 4251 1731 4251 2059 4252 1719 4252 2060 4252 2061 4253 1731 4253 1756 4253 2060 4254 1731 4254 2061 4254 2062 4255 1756 4255 1811 4255 2061 4256 1756 4256 2062 4256 2063 4257 1811 4257 1841 4257 2062 4258 1811 4258 2063 4258 2064 4259 1841 4259 2024 4259 2063 4260 1841 4260 2064 4260 2065 4261 2024 4261 1536 4261 2064 4262 2024 4262 2065 4262 2066 4263 1536 4263 1543 4263 2067 4264 1588 4264 1536 4264 2068 4265 2067 4265 1536 4265 2069 4266 2068 4266 1536 4266 2070 4267 2069 4267 1536 4267 2071 4268 2070 4268 1536 4268 2026 4269 2071 4269 1536 4269 2072 4270 1536 4270 1576 4270 2073 4271 1553 4271 1536 4271 2074 4272 2073 4272 1536 4272 2072 4273 2074 4273 1536 4273 2065 4274 1536 4274 2066 4274 2075 4275 1543 4275 1983 4275 2076 4276 2015 4276 1543 4276 2077 4277 2076 4277 1543 4277 1540 4278 2077 4278 1543 4278 2066 4279 1543 4279 2075 4279 2078 4280 1983 4280 2010 4280 2075 4281 1983 4281 2078 4281 2079 4282 2080 4282 2010 4282 2081 4283 2010 4283 2080 4283 2079 4284 2010 4284 1931 4284 2078 4285 2010 4285 2081 4285 1912 4286 2082 4286 2080 4286 2083 4287 2080 4287 2082 4287 2079 4288 1912 4288 2080 4288 2081 4289 2080 4289 2083 4289 1912 4290 1907 4290 2082 4290 2084 4291 2082 4291 1907 4291 2083 4292 2082 4292 2084 4292 2085 4293 1907 4293 1854 4293 2084 4294 1907 4294 2085 4294 2086 4295 1854 4295 1848 4295 2085 4296 1854 4296 2086 4296 2087 4297 1848 4297 1871 4297 2086 4298 1848 4298 2087 4298 2088 4299 1871 4299 1873 4299 2087 4300 1871 4300 2088 4300 1862 4301 2089 4301 1873 4301 2090 4302 1873 4302 2089 4302 2088 4303 1873 4303 2090 4303 1862 4304 2091 4304 2089 4304 2092 4305 2089 4305 2091 4305 2090 4306 2089 4306 2092 4306 1862 4307 2093 4307 2091 4307 2094 4308 2091 4308 2093 4308 2095 4309 2091 4309 2094 4309 2092 4310 2091 4310 2095 4310 1862 4311 2096 4311 2093 4311 2094 4312 2093 4312 2096 4312 1862 4313 2097 4313 2096 4313 2098 4314 2096 4314 2097 4314 2094 4315 2096 4315 2098 4315 1862 4316 2099 4316 2097 4316 2100 4317 2097 4317 2099 4317 2098 4318 2097 4318 2100 4318 1862 4319 2101 4319 2099 4319 2102 4320 2099 4320 2101 4320 2100 4321 2099 4321 2102 4321 2103 4322 2101 4322 1862 4322 2104 4323 2101 4323 2103 4323 2102 4324 2101 4324 2104 4324 2103 4325 1862 4325 1859 4325 2105 4326 1859 4326 1874 4326 2103 4327 1859 4327 2105 4327 2106 4328 1874 4328 1994 4328 2105 4329 1874 4329 2106 4329 2107 4330 1994 4330 1993 4330 2106 4331 1994 4331 2107 4331 2108 4332 1616 4332 1615 4332 2109 4333 1612 4333 1616 4333 2109 4334 1616 4334 2110 4334 2108 4335 2110 4335 1616 4335 2108 4336 1615 4336 1587 4336 2111 4337 1587 4337 1588 4337 2108 4338 1587 4338 2111 4338 2112 4339 1588 4339 2067 4339 2111 4340 1588 4340 2112 4340 2113 4341 2067 4341 2068 4341 2112 4342 2067 4342 2113 4342 2114 4343 2068 4343 2069 4343 2113 4344 2068 4344 2114 4344 2115 4345 2069 4345 2070 4345 2114 4346 2069 4346 2115 4346 2116 4347 2070 4347 2071 4347 2115 4348 2070 4348 2116 4348 2117 4349 2071 4349 2026 4349 2118 4350 2071 4350 2117 4350 2116 4351 2071 4351 2118 4351 2117 4352 2026 4352 2027 4352 2119 4353 2027 4353 2028 4353 2117 4354 2027 4354 2119 4354 2120 4355 2028 4355 1617 4355 2119 4356 2028 4356 2120 4356 2121 4357 1617 4357 1620 4357 2120 4358 1617 4358 2121 4358 2122 4359 1620 4359 1621 4359 2121 4360 1620 4360 2122 4360 2123 4361 1621 4361 1612 4361 2122 4362 1621 4362 2123 4362 2123 4363 1612 4363 2109 4363 2124 4364 1603 4364 1598 4364 2124 4365 1601 4365 1603 4365 2125 4366 1598 4366 1631 4366 2125 4367 2124 4367 1598 4367 2126 4368 1631 4368 1630 4368 2125 4369 1631 4369 2126 4369 2127 4370 1630 4370 2016 4370 2126 4371 1630 4371 2127 4371 2128 4372 2016 4372 2017 4372 2127 4373 2016 4373 2128 4373 2129 4374 2017 4374 2018 4374 2128 4375 2017 4375 2129 4375 1642 4376 2130 4376 2018 4376 2131 4377 2018 4377 2130 4377 2129 4378 2018 4378 2131 4378 2132 4379 2133 4379 2130 4379 2134 4380 2130 4380 2133 4380 1642 4381 2132 4381 2130 4381 2135 4382 2130 4382 2134 4382 2131 4383 2130 4383 2135 4383 2136 4384 2137 4384 2133 4384 2134 4385 2133 4385 2137 4385 2138 4386 2136 4386 2133 4386 2132 4387 2138 4387 2133 4387 2136 4388 2139 4388 2137 4388 2140 4389 2137 4389 2139 4389 2134 4390 2137 4390 2140 4390 2141 4391 1576 4391 2139 4391 2142 4392 2139 4392 1576 4392 2136 4393 2141 4393 2139 4393 2140 4394 2139 4394 2142 4394 2143 4395 1576 4395 1604 4395 2141 4396 2072 4396 1576 4396 2142 4397 1576 4397 2143 4397 2144 4398 1604 4398 1605 4398 2143 4399 1604 4399 2144 4399 2145 4400 1605 4400 1606 4400 2144 4401 1605 4401 2145 4401 2146 4402 1606 4402 1601 4402 2145 4403 1606 4403 2146 4403 2147 4404 1601 4404 2124 4404 2146 4405 1601 4405 2147 4405 2148 4406 1641 4406 1640 4406 2149 4407 1637 4407 1641 4407 2149 4408 1641 4408 2150 4408 2148 4409 2150 4409 1641 4409 2148 4410 1640 4410 1552 4410 2151 4411 1552 4411 1554 4411 2148 4412 1552 4412 2151 4412 2152 4413 1554 4413 1553 4413 2151 4414 1554 4414 2152 4414 2153 4415 1553 4415 2073 4415 2152 4416 1553 4416 2153 4416 2154 4417 2073 4417 2074 4417 2153 4418 2073 4418 2154 4418 2155 4419 2074 4419 2072 4419 2154 4420 2074 4420 2155 4420 2156 4421 2072 4421 2141 4421 2155 4422 2072 4422 2156 4422 2157 4423 2141 4423 2136 4423 2158 4424 2141 4424 2157 4424 2156 4425 2141 4425 2158 4425 2157 4426 2136 4426 2138 4426 2159 4427 2138 4427 2132 4427 2157 4428 2138 4428 2159 4428 2160 4429 2132 4429 1642 4429 2159 4430 2132 4430 2160 4430 2161 4431 1642 4431 1645 4431 2160 4432 1642 4432 2161 4432 2162 4433 1645 4433 1646 4433 2161 4434 1645 4434 2162 4434 2163 4435 1646 4435 1637 4435 2162 4436 1646 4436 2163 4436 2163 4437 1637 4437 2149 4437 2164 4438 1569 4438 1564 4438 2164 4439 1567 4439 1569 4439 2165 4440 1564 4440 1653 4440 2165 4441 2164 4441 1564 4441 2166 4442 1653 4442 2019 4442 2165 4443 1653 4443 2166 4443 2167 4444 2019 4444 2020 4444 2168 4445 2019 4445 2167 4445 2166 4446 2019 4446 2168 4446 2167 4447 2020 4447 2021 4447 2169 4448 2021 4448 2022 4448 2167 4449 2021 4449 2169 4449 2170 4450 2022 4450 2023 4450 2169 4451 2022 4451 2170 4451 2171 4452 2023 4452 2015 4452 2172 4453 2023 4453 2171 4453 2170 4454 2023 4454 2172 4454 2171 4455 2015 4455 2076 4455 2173 4456 2076 4456 2077 4456 2171 4457 2076 4457 2173 4457 2174 4458 2077 4458 1540 4458 2173 4459 2077 4459 2174 4459 2175 4460 1540 4460 1570 4460 2176 4461 1540 4461 2175 4461 2174 4462 1540 4462 2176 4462 2175 4463 1570 4463 1571 4463 2177 4464 1571 4464 1572 4464 2175 4465 1571 4465 2177 4465 2178 4466 1572 4466 1567 4466 2177 4467 1572 4467 2178 4467 2179 4468 1567 4468 2164 4468 2178 4469 1567 4469 2179 4469 2180 4470 1931 4470 1927 4470 2181 4471 2079 4471 1931 4471 2181 4472 1931 4472 2180 4472 2182 4473 1927 4473 1912 4473 2182 4474 2180 4474 1927 4474 2183 4475 1912 4475 2079 4475 2182 4476 1912 4476 2183 4476 2183 4477 2079 4477 2181 4477 2075 4478 1542 4478 1539 4478 2154 4479 1539 4479 1545 4479 2154 4480 2075 4480 1539 4480 2075 4481 1568 4481 1542 4481 2075 4482 1566 4482 1568 4482 1633 4483 1563 4483 1566 4483 1652 4484 1633 4484 1566 4484 2178 4485 1652 4485 1566 4485 2177 4486 1566 4486 2075 4486 2177 4487 2178 4487 1566 4487 1632 4488 1560 4488 1563 4488 1633 4489 1632 4489 1563 4489 1634 4490 1557 4490 1560 4490 1634 4491 1560 4491 1632 4491 1636 4492 1550 4492 1557 4492 1634 4493 1636 4493 1557 4493 2149 4494 1547 4494 1550 4494 2149 4495 1550 4495 1636 4495 2151 4496 1545 4496 1547 4496 2149 4497 2150 4497 1547 4497 2148 4498 1547 4498 2150 4498 2148 4499 2151 4499 1547 4499 2153 4500 2154 4500 1545 4500 2152 4501 2153 4501 1545 4501 2151 4502 2152 4502 1545 4502 2075 4503 1578 4503 1575 4503 2114 4504 1575 4504 1580 4504 2066 4505 2075 4505 1575 4505 2114 4506 2066 4506 1575 4506 2075 4507 1602 4507 1578 4507 2075 4508 1600 4508 1602 4508 1608 4509 1597 4509 1600 4509 1629 4510 1608 4510 1600 4510 2146 4511 1629 4511 1600 4511 2144 4512 1600 4512 2075 4512 2145 4513 2146 4513 1600 4513 2144 4514 2145 4514 1600 4514 1607 4515 1594 4515 1597 4515 1608 4516 1607 4516 1597 4516 1609 4517 1591 4517 1594 4517 1609 4518 1594 4518 1607 4518 1611 4519 1585 4519 1591 4519 1609 4520 1611 4520 1591 4520 2109 4521 1582 4521 1585 4521 2109 4522 1585 4522 1611 4522 2111 4523 1580 4523 1582 4523 2109 4524 2110 4524 1582 4524 2108 4525 1582 4525 2110 4525 2108 4526 2111 4526 1582 4526 2113 4527 2114 4527 1580 4527 2112 4528 2113 4528 1580 4528 2111 4529 2112 4529 1580 4529 2146 4530 1628 4530 1629 4530 2124 4531 1627 4531 1628 4531 2147 4532 2124 4532 1628 4532 2146 4533 2147 4533 1628 4533 2128 4534 1624 4534 1627 4534 2125 4535 1627 4535 2124 4535 2127 4536 2128 4536 1627 4536 2126 4537 2127 4537 1627 4537 2125 4538 2126 4538 1627 4538 2025 4539 1619 4539 1624 4539 2128 4540 2025 4540 1624 4540 2025 4541 1614 4541 1619 4541 2025 4542 1611 4542 1614 4542 2123 4543 1611 4543 2025 4543 2123 4544 2109 4544 1611 4544 2178 4545 1651 4545 1652 4545 2164 4546 1650 4546 1651 4546 2179 4547 2164 4547 1651 4547 2178 4548 2179 4548 1651 4548 2167 4549 1648 4549 1650 4549 2165 4550 1650 4550 2164 4550 2168 4551 2167 4551 1650 4551 2166 4552 2168 4552 1650 4552 2165 4553 2166 4553 1650 4553 2025 4554 1644 4554 1648 4554 2014 4555 2025 4555 1648 4555 2167 4556 2014 4556 1648 4556 2025 4557 1639 4557 1644 4557 2025 4558 1636 4558 1639 4558 2162 4559 1636 4559 2025 4559 2163 4560 2149 4560 1636 4560 2162 4561 2163 4561 1636 4561 2060 4562 1659 4562 1657 4562 2059 4563 1657 4563 1662 4563 2059 4564 2060 4564 1657 4564 2060 4565 1730 4565 1659 4565 2060 4566 1729 4566 1730 4566 2060 4567 1727 4567 1729 4567 2061 4568 1725 4568 1727 4568 2060 4569 2061 4569 1727 4569 1739 4570 1723 4570 1725 4570 2061 4571 1739 4571 1725 4571 1739 4572 1721 4572 1723 4572 1739 4573 1717 4573 1721 4573 1760 4574 1714 4574 1717 4574 1739 4575 1742 4575 1717 4575 1760 4576 1717 4576 1742 4576 2034 4577 1712 4577 1714 4577 2034 4578 1714 4578 1760 4578 2034 4579 1710 4579 1712 4579 2034 4580 1707 4580 1710 4580 2034 4581 1704 4581 1707 4581 2035 4582 1702 4582 1704 4582 2034 4583 2035 4583 1704 4583 2035 4584 1700 4584 1702 4584 2035 4585 1698 4585 1700 4585 2035 4586 1695 4586 1698 4586 2036 4587 1693 4587 1695 4587 2035 4588 2036 4588 1695 4588 2036 4589 1691 4589 1693 4589 2036 4590 1689 4590 1691 4590 2036 4591 1686 4591 1689 4591 1793 4592 1684 4592 1686 4592 2036 4593 1793 4593 1686 4593 1793 4594 1682 4594 1684 4594 1793 4595 1678 4595 1682 4595 2058 4596 1675 4596 1678 4596 1793 4597 1795 4597 1678 4597 1809 4598 1678 4598 1795 4598 2058 4599 1678 4599 1809 4599 2058 4600 1673 4600 1675 4600 2058 4601 1671 4601 1673 4601 2058 4602 1668 4602 1671 4602 2059 4603 1666 4603 1668 4603 2058 4604 2059 4604 1668 4604 2059 4605 1664 4605 1666 4605 2059 4606 1662 4606 1664 4606 2062 4607 1736 4607 1734 4607 2061 4608 1734 4608 1738 4608 2061 4609 2062 4609 1734 4609 2062 4610 1755 4610 1736 4610 2062 4611 1754 4611 1755 4611 1758 4612 1751 4612 1754 4612 1770 4613 1758 4613 1754 4613 2062 4614 1770 4614 1754 4614 1757 4615 1748 4615 1751 4615 1758 4616 1757 4616 1751 4616 1759 4617 1745 4617 1748 4617 1759 4618 1748 4618 1757 4618 1760 4619 1742 4619 1745 4619 1759 4620 1760 4620 1745 4620 2061 4621 1738 4621 1739 4621 2062 4622 1769 4622 1770 4622 2033 4623 1768 4623 1769 4623 2032 4624 1769 4624 2062 4624 2032 4625 2033 4625 1769 4625 2033 4626 1766 4626 1768 4626 2033 4627 1764 4627 1766 4627 2034 4628 1762 4628 1764 4628 2033 4629 2034 4629 1764 4629 2034 4630 1760 4630 1762 4630 1808 4631 1777 4631 1774 4631 1807 4632 1774 4632 1780 4632 1807 4633 1808 4633 1774 4633 1809 4634 1795 4634 1777 4634 1808 4635 1809 4635 1777 4635 2038 4636 1792 4636 1793 4636 2036 4637 2038 4637 1793 4637 2038 4638 1790 4638 1792 4638 2038 4639 1788 4639 1790 4639 2041 4640 1786 4640 1788 4640 2038 4641 2041 4641 1788 4641 2041 4642 1783 4642 1786 4642 1806 4643 1780 4643 1783 4643 1805 4644 1806 4644 1783 4644 2041 4645 1805 4645 1783 4645 1806 4646 1807 4646 1780 4646 2058 4647 1801 4647 1799 4647 2057 4648 1799 4648 1803 4648 2057 4649 2058 4649 1799 4649 2058 4650 1810 4650 1801 4650 2058 4651 1809 4651 1810 4651 2041 4652 1804 4652 1805 4652 2057 4653 1803 4653 1804 4653 2041 4654 2057 4654 1804 4654 2064 4655 1816 4655 1814 4655 2063 4656 1814 4656 1818 4656 2063 4657 2064 4657 1814 4657 2064 4658 1847 4658 1816 4658 2064 4659 1846 4659 1847 4659 2064 4660 1843 4660 1846 4660 2030 4661 1840 4661 1843 4661 2064 4662 2065 4662 1843 4662 2030 4663 1843 4663 2065 4663 2031 4664 1838 4664 1840 4664 2030 4665 2031 4665 1840 4665 2031 4666 1836 4666 1838 4666 2031 4667 1834 4667 1836 4667 2031 4668 1831 4668 1834 4668 2032 4669 1829 4669 1831 4669 2031 4670 2032 4670 1831 4670 2032 4671 1827 4671 1829 4671 2032 4672 1824 4672 1827 4672 2062 4673 1822 4673 1824 4673 2032 4674 2062 4674 1824 4674 2063 4675 1820 4675 1822 4675 2062 4676 2063 4676 1822 4676 2063 4677 1818 4677 1820 4677 2088 4678 1853 4678 1851 4678 2087 4679 1851 4679 1856 4679 2087 4680 2088 4680 1851 4680 2088 4681 1872 4681 1853 4681 2090 4682 1870 4682 1872 4682 2088 4683 2090 4683 1872 4683 2094 4684 1868 4684 1870 4684 2095 4685 2094 4685 1870 4685 2092 4686 2095 4686 1870 4686 2090 4687 2092 4687 1870 4687 2105 4688 1866 4688 1868 4688 2098 4689 2105 4689 1868 4689 2094 4690 2098 4690 1868 4690 2105 4691 1864 4691 1866 4691 2105 4692 1861 4692 1864 4692 2105 4693 1858 4693 1861 4693 2087 4694 1856 4694 1858 4694 2087 4695 1858 4695 2105 4695 2107 4696 1879 4696 1877 4696 2107 4697 1877 4697 1881 4697 2107 4698 1898 4698 1879 4698 2107 4699 1896 4699 1898 4699 2003 4700 1893 4700 1896 4700 2002 4701 1896 4701 2107 4701 2002 4702 2003 4702 1896 4702 2004 4703 1891 4703 1893 4703 2003 4704 2004 4704 1893 4704 2004 4705 1888 4705 1891 4705 2005 4706 1886 4706 1888 4706 2004 4707 2005 4707 1888 4707 2005 4708 1883 4708 1886 4708 2106 4709 1881 4709 1883 4709 2005 4710 2106 4710 1883 4710 2106 4711 2107 4711 1881 4711 2087 4712 1906 4712 1904 4712 2086 4713 1904 4713 1909 4713 2086 4714 2087 4714 1904 4714 2087 4715 1926 4715 1906 4715 2087 4716 1925 4716 1926 4716 1930 4717 1923 4717 1925 4717 1947 4718 1930 4718 1925 4718 2105 4719 1947 4719 1925 4719 2087 4720 2105 4720 1925 4720 1929 4721 1919 4721 1923 4721 1930 4722 1929 4722 1923 4722 2183 4723 1916 4723 1919 4723 2182 4724 1919 4724 1929 4724 2182 4725 2183 4725 1919 4725 2181 4726 1914 4726 1916 4726 2183 4727 2181 4727 1916 4727 2181 4728 1911 4728 1914 4728 2086 4729 1909 4729 1911 4729 2085 4730 2086 4730 1911 4730 2181 4731 2085 4731 1911 4731 2182 4732 1929 4732 1933 4732 2105 4733 1946 4733 1947 4733 2005 4734 1945 4734 1946 4734 2105 4735 2106 4735 1946 4735 2005 4736 1946 4736 2106 4736 2005 4737 1943 4737 1945 4737 2005 4738 1941 4738 1943 4738 2007 4739 1938 4739 1941 4739 2005 4740 2007 4740 1941 4740 2007 4741 1935 4741 1938 4741 2182 4742 1933 4742 1935 4742 2182 4743 1935 4743 2007 4743 2078 4744 1952 4744 1950 4744 2078 4745 1950 4745 1954 4745 2078 4746 1990 4746 1952 4746 2081 4747 1989 4747 1990 4747 2078 4748 2081 4748 1990 4748 2081 4749 1987 4749 1989 4749 2081 4750 1985 4750 1987 4750 2013 4751 1982 4751 1985 4751 2013 4752 1985 4752 2081 4752 2013 4753 1980 4753 1982 4753 2013 4754 1978 4754 1980 4754 2013 4755 1975 4755 1978 4755 2014 4756 1973 4756 1975 4756 2013 4757 2014 4757 1975 4757 2014 4758 1971 4758 1973 4758 2014 4759 1969 4759 1971 4759 2014 4760 1967 4760 1969 4760 2014 4761 1965 4761 1967 4761 2014 4762 1962 4762 1965 4762 2075 4763 1960 4763 1962 4763 2014 4764 2075 4764 1962 4764 2078 4765 1958 4765 1960 4765 2075 4766 2078 4766 1960 4766 2078 4767 1956 4767 1958 4767 2078 4768 1954 4768 1956 4768 1996 4769 2107 4769 1993 4769 2001 4770 2002 4770 2107 4770 1999 4771 2001 4771 2107 4771 2000 4772 1999 4772 2107 4772 1998 4773 2000 4773 2107 4773 1997 4774 1998 4774 2107 4774 1996 4775 1997 4775 2107 4775 2104 4776 2103 4776 2105 4776 2102 4777 2104 4777 2105 4777 2100 4778 2102 4778 2105 4778 2098 4779 2100 4779 2105 4779 2181 4780 2084 4780 2085 4780 2181 4781 2083 4781 2084 4781 2012 4782 2081 4782 2083 4782 2181 4783 2012 4783 2083 4783 2012 4784 2013 4784 2081 4784 2172 4785 2075 4785 2014 4785 2143 4786 2144 4786 2075 4786 2142 4787 2143 4787 2075 4787 2140 4788 2142 4788 2075 4788 2154 4789 2140 4789 2075 4789 2175 4790 2177 4790 2075 4790 2176 4791 2175 4791 2075 4791 2174 4792 2176 4792 2075 4792 2173 4793 2174 4793 2075 4793 2171 4794 2173 4794 2075 4794 2172 4795 2171 4795 2075 4795 2029 4796 2065 4796 2066 4796 2025 4797 2029 4797 2066 4797 2118 4798 2025 4798 2066 4798 2116 4799 2118 4799 2066 4799 2115 4800 2116 4800 2066 4800 2114 4801 2115 4801 2066 4801 2029 4802 2030 4802 2065 4802 2041 4803 2056 4803 2057 4803 2044 4804 2055 4804 2056 4804 2041 4805 2044 4805 2056 4805 2047 4806 2054 4806 2055 4806 2044 4807 2047 4807 2055 4807 2050 4808 2053 4808 2054 4808 2047 4809 2050 4809 2054 4809 2051 4810 2052 4810 2053 4810 2050 4811 2051 4811 2053 4811 2122 4812 2123 4812 2025 4812 2121 4813 2122 4813 2025 4813 2120 4814 2121 4814 2025 4814 2119 4815 2120 4815 2025 4815 2117 4816 2119 4816 2025 4816 2118 4817 2117 4817 2025 4817 2159 4818 2025 4818 2128 4818 2161 4819 2162 4819 2025 4819 2160 4820 2161 4820 2025 4820 2159 4821 2160 4821 2025 4821 2170 4822 2172 4822 2014 4822 2169 4823 2170 4823 2014 4823 2167 4824 2169 4824 2014 4824 2180 4825 2011 4825 2012 4825 2181 4826 2180 4826 2012 4826 2182 4827 2009 4827 2011 4827 2182 4828 2011 4828 2180 4828 2182 4829 2007 4829 2009 4829 2154 4830 2134 4830 2140 4830 2155 4831 2135 4831 2134 4831 2154 4832 2155 4832 2134 4832 2158 4833 2131 4833 2135 4833 2156 4834 2158 4834 2135 4834 2155 4835 2156 4835 2135 4835 2158 4836 2129 4836 2131 4836 2157 4837 2128 4837 2129 4837 2158 4838 2157 4838 2129 4838 2157 4839 2159 4839 2128 4839 2184 4840 2185 4840 2186 4840 2187 4841 2186 4841 2185 4841 2188 4842 2186 4842 2189 4842 2190 4843 2189 4843 2186 4843 2191 4844 2184 4844 2186 4844 2188 4845 2191 4845 2186 4845 2190 4846 2186 4846 2187 4846 2184 4847 2192 4847 2185 4847 2193 4848 2185 4848 2192 4848 2193 4849 2187 4849 2185 4849 2184 4850 2194 4850 2192 4850 2195 4851 2192 4851 2194 4851 2193 4852 2192 4852 2195 4852 2196 4853 2197 4853 2194 4853 2198 4854 2194 4854 2197 4854 2199 4855 2196 4855 2194 4855 2200 4856 2199 4856 2194 4856 2201 4857 2194 4857 2184 4857 2202 4858 2200 4858 2194 4858 2201 4859 2202 4859 2194 4859 2195 4860 2194 4860 2198 4860 2203 4861 2204 4861 2197 4861 2205 4862 2197 4862 2204 4862 2196 4863 2203 4863 2197 4863 2198 4864 2197 4864 2205 4864 2206 4865 2207 4865 2204 4865 2208 4866 2204 4866 2207 4866 2206 4867 2204 4867 2203 4867 2205 4868 2204 4868 2208 4868 2209 4869 2210 4869 2207 4869 2211 4870 2207 4870 2210 4870 2206 4871 2209 4871 2207 4871 2208 4872 2207 4872 2211 4872 2212 4873 2213 4873 2210 4873 2214 4874 2210 4874 2213 4874 2212 4875 2210 4875 2209 4875 2211 4876 2210 4876 2214 4876 2215 4877 2189 4877 2213 4877 2216 4878 2213 4878 2189 4878 2212 4879 2217 4879 2213 4879 2215 4880 2213 4880 2217 4880 2214 4881 2213 4881 2216 4881 2218 4882 2188 4882 2189 4882 2219 4883 2218 4883 2189 4883 2220 4884 2219 4884 2189 4884 2215 4885 2220 4885 2189 4885 2216 4886 2189 4886 2190 4886 2184 4887 2221 4887 2222 4887 2223 4888 2222 4888 2221 4888 2224 4889 2222 4889 2225 4889 2226 4890 2225 4890 2222 4890 2224 4891 2184 4891 2222 4891 2226 4892 2222 4892 2223 4892 2184 4893 2227 4893 2221 4893 2228 4894 2221 4894 2227 4894 2228 4895 2223 4895 2221 4895 2184 4896 2229 4896 2227 4896 2230 4897 2227 4897 2229 4897 2228 4898 2227 4898 2230 4898 2231 4899 2232 4899 2229 4899 2233 4900 2229 4900 2232 4900 2234 4901 2231 4901 2229 4901 2235 4902 2234 4902 2229 4902 2236 4903 2229 4903 2184 4903 2236 4904 2235 4904 2229 4904 2230 4905 2229 4905 2233 4905 2237 4906 2238 4906 2232 4906 2239 4907 2232 4907 2238 4907 2231 4908 2237 4908 2232 4908 2233 4909 2232 4909 2239 4909 2240 4910 2241 4910 2238 4910 2242 4911 2238 4911 2241 4911 2240 4912 2238 4912 2237 4912 2239 4913 2238 4913 2242 4913 2243 4914 2244 4914 2241 4914 2245 4915 2241 4915 2244 4915 2240 4916 2243 4916 2241 4916 2242 4917 2241 4917 2245 4917 2246 4918 2247 4918 2244 4918 2248 4919 2244 4919 2247 4919 2246 4920 2244 4920 2243 4920 2245 4921 2244 4921 2248 4921 2249 4922 2225 4922 2247 4922 2250 4923 2247 4923 2225 4923 2246 4924 2251 4924 2247 4924 2249 4925 2247 4925 2251 4925 2248 4926 2247 4926 2250 4926 2252 4927 2224 4927 2225 4927 2253 4928 2252 4928 2225 4928 2254 4929 2253 4929 2225 4929 2249 4930 2254 4930 2225 4930 2250 4931 2225 4931 2226 4931 2255 4932 2237 4932 2231 4932 2256 4933 2240 4933 2237 4933 2256 4934 2237 4934 2255 4934 2257 4935 2231 4935 2234 4935 2257 4936 2255 4936 2231 4936 2235 4937 2258 4937 2234 4937 2259 4938 2234 4938 2258 4938 2257 4939 2234 4939 2259 4939 2260 4940 2261 4940 2258 4940 2262 4941 2258 4941 2261 4941 2263 4942 2264 4942 2258 4942 2260 4943 2258 4943 2264 4943 2235 4944 2263 4944 2258 4944 2259 4945 2258 4945 2262 4945 2265 4946 2266 4946 2261 4946 2267 4947 2261 4947 2266 4947 2268 4948 2265 4948 2261 4948 2269 4949 2268 4949 2261 4949 2260 4950 2269 4950 2261 4950 2262 4951 2261 4951 2267 4951 2270 4952 2271 4952 2266 4952 2272 4953 2266 4953 2271 4953 2273 4954 2270 4954 2266 4954 2265 4955 2273 4955 2266 4955 2267 4956 2266 4956 2272 4956 2270 4957 2274 4957 2271 4957 2275 4958 2271 4958 2274 4958 2272 4959 2271 4959 2275 4959 2270 4960 2243 4960 2274 4960 2276 4961 2274 4961 2243 4961 2275 4962 2274 4962 2276 4962 2277 4963 2243 4963 2240 4963 2278 4964 2243 4964 2270 4964 2279 4965 2246 4965 2243 4965 2278 4966 2279 4966 2243 4966 2276 4967 2243 4967 2277 4967 2277 4968 2240 4968 2256 4968 2280 4969 2203 4969 2196 4969 2281 4970 2206 4970 2203 4970 2281 4971 2203 4971 2280 4971 2282 4972 2196 4972 2199 4972 2282 4973 2280 4973 2196 4973 2200 4974 2283 4974 2199 4974 2284 4975 2199 4975 2283 4975 2282 4976 2199 4976 2284 4976 2285 4977 2286 4977 2283 4977 2287 4978 2283 4978 2286 4978 2288 4979 2289 4979 2283 4979 2285 4980 2283 4980 2289 4980 2200 4981 2288 4981 2283 4981 2284 4982 2283 4982 2287 4982 2290 4983 2291 4983 2286 4983 2292 4984 2286 4984 2291 4984 2293 4985 2290 4985 2286 4985 2294 4986 2293 4986 2286 4986 2285 4987 2294 4987 2286 4987 2287 4988 2286 4988 2292 4988 2270 4989 2295 4989 2291 4989 2296 4990 2291 4990 2295 4990 2290 4991 2270 4991 2291 4991 2292 4992 2291 4992 2296 4992 2270 4993 2297 4993 2295 4993 2298 4994 2295 4994 2297 4994 2296 4995 2295 4995 2298 4995 2270 4996 2209 4996 2297 4996 2299 4997 2297 4997 2209 4997 2298 4998 2297 4998 2299 4998 2300 4999 2209 4999 2206 4999 2301 5000 2209 5000 2270 5000 2301 5001 2212 5001 2209 5001 2299 5002 2209 5002 2300 5002 2300 5003 2206 5003 2281 5003 2302 5004 2303 5004 2304 5004 2305 5005 2304 5005 2303 5005 2302 5006 2304 5006 2306 5006 2307 5007 2306 5007 2304 5007 2307 5008 2304 5008 2305 5008 2308 5009 2309 5009 2303 5009 2310 5010 2303 5010 2309 5010 2302 5011 2308 5011 2303 5011 2310 5012 2305 5012 2303 5012 2308 5013 2311 5013 2309 5013 2312 5014 2309 5014 2311 5014 2310 5015 2309 5015 2312 5015 2308 5016 2313 5016 2311 5016 2314 5017 2311 5017 2313 5017 2312 5018 2311 5018 2314 5018 2308 5019 2315 5019 2313 5019 2316 5020 2313 5020 2315 5020 2314 5021 2313 5021 2316 5021 2317 5022 2318 5022 2315 5022 2319 5023 2315 5023 2318 5023 2308 5024 2317 5024 2315 5024 2316 5025 2315 5025 2319 5025 2317 5026 2320 5026 2318 5026 2321 5027 2318 5027 2320 5027 2319 5028 2318 5028 2321 5028 2317 5029 2322 5029 2320 5029 2323 5030 2320 5030 2322 5030 2321 5031 2320 5031 2323 5031 2324 5032 2325 5032 2322 5032 2326 5033 2322 5033 2325 5033 2327 5034 2328 5034 2322 5034 2324 5035 2322 5035 2328 5035 2317 5036 2327 5036 2322 5036 2323 5037 2322 5037 2326 5037 2324 5038 2329 5038 2325 5038 2330 5039 2325 5039 2329 5039 2326 5040 2325 5040 2330 5040 2324 5041 2331 5041 2329 5041 2332 5042 2329 5042 2331 5042 2330 5043 2329 5043 2332 5043 2324 5044 2333 5044 2331 5044 2334 5045 2331 5045 2333 5045 2332 5046 2331 5046 2334 5046 2335 5047 2336 5047 2333 5047 2337 5048 2333 5048 2336 5048 2324 5049 2335 5049 2333 5049 2334 5050 2333 5050 2337 5050 2335 5051 2338 5051 2336 5051 2339 5052 2336 5052 2338 5052 2337 5053 2336 5053 2339 5053 2335 5054 2340 5054 2338 5054 2341 5055 2338 5055 2340 5055 2339 5056 2338 5056 2341 5056 2335 5057 2342 5057 2340 5057 2343 5058 2340 5058 2342 5058 2341 5059 2340 5059 2343 5059 2344 5060 2345 5060 2342 5060 2346 5061 2342 5061 2345 5061 2335 5062 2344 5062 2342 5062 2343 5063 2342 5063 2346 5063 2344 5064 2347 5064 2345 5064 2348 5065 2345 5065 2347 5065 2346 5066 2345 5066 2348 5066 2344 5067 2349 5067 2347 5067 2350 5068 2347 5068 2349 5068 2348 5069 2347 5069 2350 5069 2344 5070 2351 5070 2349 5070 2352 5071 2349 5071 2351 5071 2350 5072 2349 5072 2352 5072 2353 5073 2354 5073 2351 5073 2355 5074 2351 5074 2354 5074 2344 5075 2353 5075 2351 5075 2352 5076 2351 5076 2355 5076 2356 5077 2357 5077 2354 5077 2358 5078 2354 5078 2357 5078 2353 5079 2356 5079 2354 5079 2355 5080 2354 5080 2358 5080 2356 5081 2359 5081 2357 5081 2360 5082 2357 5082 2359 5082 2358 5083 2357 5083 2360 5083 2356 5084 2361 5084 2359 5084 2362 5085 2359 5085 2361 5085 2360 5086 2359 5086 2362 5086 2363 5087 2364 5087 2361 5087 2365 5088 2361 5088 2364 5088 2366 5089 2363 5089 2361 5089 2356 5090 2366 5090 2361 5090 2362 5091 2361 5091 2365 5091 2367 5092 2368 5092 2364 5092 2369 5093 2364 5093 2368 5093 2367 5094 2364 5094 2363 5094 2365 5095 2364 5095 2369 5095 2367 5096 2370 5096 2368 5096 2371 5097 2368 5097 2370 5097 2369 5098 2368 5098 2371 5098 2367 5099 2372 5099 2370 5099 2373 5100 2370 5100 2372 5100 2371 5101 2370 5101 2373 5101 2367 5102 2374 5102 2372 5102 2375 5103 2372 5103 2374 5103 2373 5104 2372 5104 2375 5104 2302 5105 2376 5105 2374 5105 2377 5106 2374 5106 2376 5106 2367 5107 2302 5107 2374 5107 2375 5108 2374 5108 2377 5108 2302 5109 2306 5109 2376 5109 2378 5110 2376 5110 2306 5110 2377 5111 2376 5111 2378 5111 2378 5112 2306 5112 2307 5112 2379 5113 2380 5113 2381 5113 2382 5114 2381 5114 2380 5114 2379 5115 2381 5115 2383 5115 2384 5116 2383 5116 2381 5116 2384 5117 2381 5117 2382 5117 2367 5118 2385 5118 2380 5118 2386 5119 2380 5119 2385 5119 2379 5120 2367 5120 2380 5120 2386 5121 2382 5121 2380 5121 2367 5122 2363 5122 2385 5122 2387 5123 2385 5123 2363 5123 2386 5124 2385 5124 2387 5124 2388 5125 2389 5125 2363 5125 2390 5126 2363 5126 2389 5126 2366 5127 2388 5127 2363 5127 2387 5128 2363 5128 2390 5128 2391 5129 2392 5129 2389 5129 2393 5130 2389 5130 2392 5130 2388 5131 2391 5131 2389 5131 2390 5132 2389 5132 2393 5132 2394 5133 2395 5133 2392 5133 2396 5134 2392 5134 2395 5134 2394 5135 2392 5135 2391 5135 2393 5136 2392 5136 2396 5136 2397 5137 2398 5137 2395 5137 2399 5138 2395 5138 2398 5138 2394 5139 2397 5139 2395 5139 2396 5140 2395 5140 2399 5140 2400 5141 2401 5141 2398 5141 2402 5142 2398 5142 2401 5142 2400 5143 2398 5143 2397 5143 2399 5144 2398 5144 2402 5144 2379 5145 2383 5145 2401 5145 2403 5146 2401 5146 2383 5146 2404 5147 2401 5147 2400 5147 2404 5148 2379 5148 2401 5148 2402 5149 2401 5149 2403 5149 2403 5150 2383 5150 2384 5150 2405 5151 2391 5151 2388 5151 2406 5152 2394 5152 2391 5152 2406 5153 2391 5153 2405 5153 2407 5154 2388 5154 2366 5154 2407 5155 2405 5155 2388 5155 2408 5156 2366 5156 2356 5156 2407 5157 2366 5157 2408 5157 2353 5158 2409 5158 2356 5158 2410 5159 2356 5159 2409 5159 2408 5160 2356 5160 2410 5160 2353 5161 2411 5161 2409 5161 2412 5162 2409 5162 2411 5162 2410 5163 2409 5163 2412 5163 2400 5164 2413 5164 2411 5164 2414 5165 2411 5165 2413 5165 2353 5166 2400 5166 2411 5166 2412 5167 2411 5167 2414 5167 2400 5168 2415 5168 2413 5168 2416 5169 2413 5169 2415 5169 2414 5170 2413 5170 2416 5170 2400 5171 2397 5171 2415 5171 2417 5172 2415 5172 2397 5172 2416 5173 2415 5173 2417 5173 2418 5174 2397 5174 2394 5174 2417 5175 2397 5175 2418 5175 2418 5176 2394 5176 2406 5176 2419 5177 2420 5177 2421 5177 2422 5178 2421 5178 2420 5178 2423 5179 2421 5179 2424 5179 2425 5180 2424 5180 2421 5180 2423 5181 2419 5181 2421 5181 2425 5182 2421 5182 2422 5182 2426 5183 2427 5183 2420 5183 2428 5184 2420 5184 2427 5184 2419 5185 2426 5185 2420 5185 2428 5186 2422 5186 2420 5186 2429 5187 2430 5187 2427 5187 2431 5188 2427 5188 2430 5188 2429 5189 2427 5189 2426 5189 2428 5190 2427 5190 2431 5190 2432 5191 2433 5191 2430 5191 2434 5192 2430 5192 2433 5192 2429 5193 2432 5193 2430 5193 2431 5194 2430 5194 2434 5194 2432 5195 2435 5195 2433 5195 2436 5196 2433 5196 2435 5196 2434 5197 2433 5197 2436 5197 2324 5198 2437 5198 2435 5198 2438 5199 2435 5199 2437 5199 2432 5200 2324 5200 2435 5200 2436 5201 2435 5201 2438 5201 2324 5202 2439 5202 2437 5202 2440 5203 2437 5203 2439 5203 2438 5204 2437 5204 2440 5204 2324 5205 2328 5205 2439 5205 2441 5206 2439 5206 2328 5206 2440 5207 2439 5207 2441 5207 2442 5208 2424 5208 2328 5208 2443 5209 2328 5209 2424 5209 2327 5210 2442 5210 2328 5210 2441 5211 2328 5211 2443 5211 2442 5212 2423 5212 2424 5212 2443 5213 2424 5213 2425 5213 2444 5214 2445 5214 2446 5214 2447 5215 2446 5215 2445 5215 2444 5216 2446 5216 2448 5216 2449 5217 2448 5217 2446 5217 2449 5218 2446 5218 2447 5218 2429 5219 2450 5219 2445 5219 2451 5220 2445 5220 2450 5220 2444 5221 2429 5221 2445 5221 2451 5222 2447 5222 2445 5222 2429 5223 2426 5223 2450 5223 2452 5224 2450 5224 2426 5224 2451 5225 2450 5225 2452 5225 2453 5226 2426 5226 2419 5226 2452 5227 2426 5227 2453 5227 2454 5228 2419 5228 2423 5228 2453 5229 2419 5229 2454 5229 2455 5230 2423 5230 2442 5230 2454 5231 2423 5231 2455 5231 2456 5232 2442 5232 2327 5232 2455 5233 2442 5233 2456 5233 2457 5234 2327 5234 2317 5234 2456 5235 2327 5235 2457 5235 2444 5236 2448 5236 2317 5236 2458 5237 2317 5237 2448 5237 2308 5238 2444 5238 2317 5238 2457 5239 2317 5239 2458 5239 2458 5240 2448 5240 2449 5240 2459 5241 2460 5241 2461 5241 2462 5242 2461 5242 2460 5242 2459 5243 2461 5243 2463 5243 2464 5244 2463 5244 2461 5244 2464 5245 2461 5245 2462 5245 2404 5246 2465 5246 2460 5246 2466 5247 2460 5247 2465 5247 2459 5248 2404 5248 2460 5248 2466 5249 2462 5249 2460 5249 2404 5250 2467 5250 2465 5250 2468 5251 2465 5251 2467 5251 2466 5252 2465 5252 2468 5252 2404 5253 2469 5253 2467 5253 2470 5254 2467 5254 2469 5254 2468 5255 2467 5255 2470 5255 2400 5256 2471 5256 2469 5256 2472 5257 2469 5257 2471 5257 2404 5258 2400 5258 2469 5258 2470 5259 2469 5259 2472 5259 2473 5260 2474 5260 2471 5260 2475 5261 2471 5261 2474 5261 2400 5262 2473 5262 2471 5262 2472 5263 2471 5263 2475 5263 2473 5264 2476 5264 2474 5264 2477 5265 2474 5265 2476 5265 2475 5266 2474 5266 2477 5266 2473 5267 2478 5267 2476 5267 2479 5268 2476 5268 2478 5268 2477 5269 2476 5269 2479 5269 2480 5270 2481 5270 2478 5270 2482 5271 2478 5271 2481 5271 2473 5272 2480 5272 2478 5272 2479 5273 2478 5273 2482 5273 2480 5274 2483 5274 2481 5274 2484 5275 2481 5275 2483 5275 2482 5276 2481 5276 2484 5276 2480 5277 2485 5277 2483 5277 2486 5278 2483 5278 2485 5278 2484 5279 2483 5279 2486 5279 2480 5280 2487 5280 2485 5280 2488 5281 2485 5281 2487 5281 2486 5282 2485 5282 2488 5282 2489 5283 2490 5283 2487 5283 2491 5284 2487 5284 2490 5284 2480 5285 2492 5285 2487 5285 2489 5286 2487 5286 2492 5286 2488 5287 2487 5287 2491 5287 2459 5288 2493 5288 2490 5288 2494 5289 2490 5289 2493 5289 2489 5290 2459 5290 2490 5290 2491 5291 2490 5291 2494 5291 2459 5292 2463 5292 2493 5292 2495 5293 2493 5293 2463 5293 2494 5294 2493 5294 2495 5294 2495 5295 2463 5295 2464 5295 2496 5296 2497 5296 2498 5296 2499 5297 2498 5297 2497 5297 2496 5298 2498 5298 2500 5298 2501 5299 2500 5299 2498 5299 2501 5300 2498 5300 2499 5300 2502 5301 2503 5301 2497 5301 2504 5302 2497 5302 2503 5302 2496 5303 2502 5303 2497 5303 2504 5304 2499 5304 2497 5304 2502 5305 2505 5305 2503 5305 2506 5306 2503 5306 2505 5306 2504 5307 2503 5307 2506 5307 2507 5308 2508 5308 2505 5308 2509 5309 2505 5309 2508 5309 2507 5310 2505 5310 2502 5310 2506 5311 2505 5311 2509 5311 2510 5312 2511 5312 2508 5312 2512 5313 2508 5313 2511 5313 2507 5314 2510 5314 2508 5314 2509 5315 2508 5315 2512 5315 2510 5316 2513 5316 2511 5316 2514 5317 2511 5317 2513 5317 2512 5318 2511 5318 2514 5318 2510 5319 2515 5319 2513 5319 2516 5320 2513 5320 2515 5320 2514 5321 2513 5321 2516 5321 2510 5322 2517 5322 2515 5322 2518 5323 2515 5323 2517 5323 2516 5324 2515 5324 2518 5324 2519 5325 2500 5325 2517 5325 2520 5326 2517 5326 2500 5326 2521 5327 2519 5327 2517 5327 2510 5328 2521 5328 2517 5328 2518 5329 2517 5329 2520 5329 2519 5330 2496 5330 2500 5330 2520 5331 2500 5331 2501 5331 2522 5332 2523 5332 2524 5332 2525 5333 2524 5333 2523 5333 2522 5334 2524 5334 2526 5334 2527 5335 2526 5335 2524 5335 2527 5336 2524 5336 2525 5336 2522 5337 2528 5337 2523 5337 2529 5338 2523 5338 2528 5338 2529 5339 2525 5339 2523 5339 2522 5340 2530 5340 2528 5340 2531 5341 2528 5341 2530 5341 2529 5342 2528 5342 2531 5342 2532 5343 2533 5343 2530 5343 2534 5344 2530 5344 2533 5344 2522 5345 2532 5345 2530 5345 2531 5346 2530 5346 2534 5346 2532 5347 2535 5347 2533 5347 2536 5348 2533 5348 2535 5348 2534 5349 2533 5349 2536 5349 2537 5350 2538 5350 2535 5350 2539 5351 2535 5351 2538 5351 2532 5352 2537 5352 2535 5352 2536 5353 2535 5353 2539 5353 2537 5354 2540 5354 2538 5354 2541 5355 2538 5355 2540 5355 2539 5356 2538 5356 2541 5356 2542 5357 2543 5357 2540 5357 2544 5358 2540 5358 2543 5358 2537 5359 2542 5359 2540 5359 2541 5360 2540 5360 2544 5360 2545 5361 2526 5361 2543 5361 2546 5362 2543 5362 2526 5362 2547 5363 2545 5363 2543 5363 2548 5364 2547 5364 2543 5364 2542 5365 2548 5365 2543 5365 2544 5366 2543 5366 2546 5366 2545 5367 2549 5367 2526 5367 2522 5368 2526 5368 2549 5368 2546 5369 2526 5369 2527 5369 2502 5370 2550 5370 2551 5370 2552 5371 2551 5371 2550 5371 2502 5372 2551 5372 2553 5372 2554 5373 2553 5373 2551 5373 2554 5374 2551 5374 2552 5374 2555 5375 2556 5375 2550 5375 2557 5376 2550 5376 2556 5376 2502 5377 2555 5377 2550 5377 2557 5378 2552 5378 2550 5378 2555 5379 2558 5379 2556 5379 2559 5380 2556 5380 2558 5380 2557 5381 2556 5381 2559 5381 2560 5382 2561 5382 2558 5382 2562 5383 2558 5383 2561 5383 2560 5384 2558 5384 2555 5384 2559 5385 2558 5385 2562 5385 2560 5386 2563 5386 2561 5386 2564 5387 2561 5387 2563 5387 2562 5388 2561 5388 2564 5388 2565 5389 2566 5389 2563 5389 2567 5390 2563 5390 2566 5390 2565 5391 2563 5391 2568 5391 2560 5392 2568 5392 2563 5392 2564 5393 2563 5393 2567 5393 2569 5394 2570 5394 2566 5394 2571 5395 2566 5395 2570 5395 2565 5396 2569 5396 2566 5396 2567 5397 2566 5397 2571 5397 2522 5398 2572 5398 2570 5398 2573 5399 2570 5399 2572 5399 2522 5400 2570 5400 2569 5400 2571 5401 2570 5401 2573 5401 2502 5402 2553 5402 2572 5402 2574 5403 2572 5403 2553 5403 2507 5404 2502 5404 2572 5404 2522 5405 2507 5405 2572 5405 2573 5406 2572 5406 2574 5406 2574 5407 2553 5407 2554 5407 2575 5408 2576 5408 2568 5408 2577 5409 2568 5409 2576 5409 2578 5410 2565 5410 2568 5410 2560 5411 2575 5411 2568 5411 2578 5412 2568 5412 2577 5412 2579 5413 2580 5413 2576 5413 2581 5414 2576 5414 2580 5414 2575 5415 2579 5415 2576 5415 2581 5416 2577 5416 2576 5416 2579 5417 2582 5417 2580 5417 2583 5418 2580 5418 2582 5418 2581 5419 2580 5419 2583 5419 2584 5420 2585 5420 2582 5420 2586 5421 2582 5421 2585 5421 2587 5422 2584 5422 2582 5422 2579 5423 2587 5423 2582 5423 2583 5424 2582 5424 2586 5424 2584 5425 2588 5425 2585 5425 2589 5426 2585 5426 2588 5426 2586 5427 2585 5427 2589 5427 2532 5428 2590 5428 2588 5428 2591 5429 2588 5429 2590 5429 2584 5430 2532 5430 2588 5430 2589 5431 2588 5431 2591 5431 2532 5432 2592 5432 2590 5432 2593 5433 2590 5433 2592 5433 2591 5434 2590 5434 2593 5434 2532 5435 2569 5435 2592 5435 2594 5436 2592 5436 2569 5436 2593 5437 2592 5437 2594 5437 2595 5438 2569 5438 2565 5438 2522 5439 2569 5439 2532 5439 2594 5440 2569 5440 2595 5440 2595 5441 2565 5441 2578 5441 2191 5442 2596 5442 2597 5442 2598 5443 2597 5443 2596 5443 2191 5444 2597 5444 2599 5444 2600 5445 2599 5445 2597 5445 2600 5446 2597 5446 2598 5446 2191 5447 2601 5447 2596 5447 2602 5448 2596 5448 2601 5448 2602 5449 2598 5449 2596 5449 2191 5450 2603 5450 2601 5450 2604 5451 2601 5451 2603 5451 2602 5452 2601 5452 2604 5452 2191 5453 2605 5453 2603 5453 2606 5454 2603 5454 2605 5454 2604 5455 2603 5455 2606 5455 2191 5456 2607 5456 2605 5456 2608 5457 2605 5457 2607 5457 2606 5458 2605 5458 2608 5458 2270 5459 2609 5459 2607 5459 2610 5460 2607 5460 2609 5460 2191 5461 2270 5461 2607 5461 2608 5462 2607 5462 2610 5462 2611 5463 2612 5463 2609 5463 2613 5464 2609 5464 2612 5464 2270 5465 2611 5465 2609 5465 2610 5466 2609 5466 2613 5466 2611 5467 2614 5467 2612 5467 2615 5468 2612 5468 2614 5468 2613 5469 2612 5469 2615 5469 2611 5470 2616 5470 2614 5470 2617 5471 2614 5471 2616 5471 2615 5472 2614 5472 2617 5472 2611 5473 2618 5473 2616 5473 2619 5474 2616 5474 2618 5474 2617 5475 2616 5475 2619 5475 2611 5476 2620 5476 2618 5476 2621 5477 2618 5477 2620 5477 2619 5478 2618 5478 2621 5478 2611 5479 2622 5479 2620 5479 2623 5480 2620 5480 2622 5480 2621 5481 2620 5481 2623 5481 2624 5482 2625 5482 2622 5482 2626 5483 2622 5483 2625 5483 2611 5484 2624 5484 2622 5484 2623 5485 2622 5485 2626 5485 2624 5486 2627 5486 2625 5486 2628 5487 2625 5487 2627 5487 2626 5488 2625 5488 2628 5488 2624 5489 2629 5489 2627 5489 2630 5490 2627 5490 2629 5490 2628 5491 2627 5491 2630 5491 2631 5492 2632 5492 2629 5492 2633 5493 2629 5493 2632 5493 2631 5494 2629 5494 2624 5494 2630 5495 2629 5495 2633 5495 2631 5496 2634 5496 2632 5496 2635 5497 2632 5497 2634 5497 2633 5498 2632 5498 2635 5498 2631 5499 2636 5499 2634 5499 2637 5500 2634 5500 2636 5500 2635 5501 2634 5501 2637 5501 2631 5502 2599 5502 2636 5502 2638 5503 2636 5503 2599 5503 2637 5504 2636 5504 2638 5504 2631 5505 2191 5505 2599 5505 2638 5506 2599 5506 2600 5506 2522 5507 2639 5507 2640 5507 2641 5508 2640 5508 2639 5508 2642 5509 2522 5509 2640 5509 2641 5510 2642 5510 2640 5510 2522 5511 2643 5511 2639 5511 2644 5512 2639 5512 2643 5512 2644 5513 2641 5513 2639 5513 2522 5514 2549 5514 2643 5514 2645 5515 2643 5515 2549 5515 2644 5516 2643 5516 2645 5516 2646 5517 2549 5517 2545 5517 2645 5518 2549 5518 2646 5518 2647 5519 2545 5519 2547 5519 2648 5520 2545 5520 2647 5520 2646 5521 2545 5521 2648 5521 2647 5522 2547 5522 2548 5522 2649 5523 2548 5523 2542 5523 2647 5524 2548 5524 2649 5524 2650 5525 2542 5525 2537 5525 2649 5526 2542 5526 2650 5526 2651 5527 2537 5527 2532 5527 2650 5528 2537 5528 2651 5528 2652 5529 2532 5529 2584 5529 2651 5530 2532 5530 2652 5530 2653 5531 2584 5531 2587 5531 2652 5532 2584 5532 2653 5532 2579 5533 2654 5533 2587 5533 2655 5534 2587 5534 2654 5534 2653 5535 2587 5535 2655 5535 2579 5536 2656 5536 2654 5536 2657 5537 2654 5537 2656 5537 2655 5538 2654 5538 2657 5538 2658 5539 2624 5539 2656 5539 2659 5540 2656 5540 2624 5540 2579 5541 2658 5541 2656 5541 2657 5542 2656 5542 2659 5542 2660 5543 2624 5543 2611 5543 2658 5544 2631 5544 2624 5544 2659 5545 2624 5545 2660 5545 2661 5546 2611 5546 2270 5546 2660 5547 2611 5547 2661 5547 2662 5548 2270 5548 2273 5548 2663 5549 2270 5549 2191 5549 2664 5550 2278 5550 2270 5550 2665 5551 2664 5551 2270 5551 2666 5552 2665 5552 2270 5552 2290 5553 2666 5553 2270 5553 2667 5554 2301 5554 2270 5554 2668 5555 2667 5555 2270 5555 2669 5556 2668 5556 2270 5556 2670 5557 2669 5557 2270 5557 2671 5558 2670 5558 2270 5558 2663 5559 2671 5559 2270 5559 2661 5560 2270 5560 2662 5560 2672 5561 2492 5561 2273 5561 2673 5562 2273 5562 2492 5562 2184 5563 2672 5563 2273 5563 2674 5564 2184 5564 2273 5564 2675 5565 2674 5565 2273 5565 2676 5566 2675 5566 2273 5566 2265 5567 2676 5567 2273 5567 2662 5568 2273 5568 2673 5568 2677 5569 2492 5569 2480 5569 2672 5570 2489 5570 2492 5570 2673 5571 2492 5571 2677 5571 2678 5572 2480 5572 2473 5572 2677 5573 2480 5573 2678 5573 2679 5574 2473 5574 2400 5574 2678 5575 2473 5575 2679 5575 2680 5576 2400 5576 2353 5576 2679 5577 2400 5577 2680 5577 2681 5578 2353 5578 2344 5578 2680 5579 2353 5579 2681 5579 2682 5580 2344 5580 2335 5580 2681 5581 2344 5581 2682 5581 2683 5582 2335 5582 2324 5582 2682 5583 2335 5583 2683 5583 2684 5584 2324 5584 2432 5584 2683 5585 2324 5585 2684 5585 2429 5586 2685 5586 2432 5586 2686 5587 2432 5587 2685 5587 2684 5588 2432 5588 2686 5588 2687 5589 2688 5589 2685 5589 2689 5590 2685 5590 2688 5590 2429 5591 2687 5591 2685 5591 2686 5592 2685 5592 2689 5592 2690 5593 2691 5593 2688 5593 2692 5594 2688 5594 2691 5594 2687 5595 2690 5595 2688 5595 2689 5596 2688 5596 2692 5596 2693 5597 2694 5597 2691 5597 2695 5598 2691 5598 2694 5598 2690 5599 2693 5599 2691 5599 2692 5600 2691 5600 2695 5600 2696 5601 2697 5601 2694 5601 2698 5602 2694 5602 2697 5602 2693 5603 2696 5603 2694 5603 2695 5604 2694 5604 2698 5604 2699 5605 2697 5605 2696 5605 2698 5606 2697 5606 2699 5606 2700 5607 2696 5607 2693 5607 2699 5608 2696 5608 2700 5608 2701 5609 2693 5609 2690 5609 2700 5610 2693 5610 2701 5610 2702 5611 2690 5611 2687 5611 2701 5612 2690 5612 2702 5612 2703 5613 2687 5613 2429 5613 2702 5614 2687 5614 2703 5614 2704 5615 2429 5615 2444 5615 2703 5616 2429 5616 2704 5616 2705 5617 2444 5617 2308 5617 2704 5618 2444 5618 2705 5618 2706 5619 2308 5619 2302 5619 2705 5620 2308 5620 2706 5620 2707 5621 2302 5621 2367 5621 2706 5622 2302 5622 2707 5622 2708 5623 2367 5623 2379 5623 2707 5624 2367 5624 2708 5624 2709 5625 2379 5625 2404 5625 2708 5626 2379 5626 2709 5626 2710 5627 2404 5627 2459 5627 2709 5628 2404 5628 2710 5628 2711 5629 2459 5629 2489 5629 2710 5630 2459 5630 2711 5630 2712 5631 2489 5631 2672 5631 2711 5632 2489 5632 2712 5632 2713 5633 2672 5633 2184 5633 2712 5634 2672 5634 2713 5634 2714 5635 2184 5635 2191 5635 2715 5636 2236 5636 2184 5636 2716 5637 2715 5637 2184 5637 2717 5638 2716 5638 2184 5638 2718 5639 2717 5639 2184 5639 2719 5640 2718 5640 2184 5640 2674 5641 2719 5641 2184 5641 2720 5642 2184 5642 2224 5642 2721 5643 2201 5643 2184 5643 2722 5644 2721 5644 2184 5644 2720 5645 2722 5645 2184 5645 2713 5646 2184 5646 2714 5646 2723 5647 2191 5647 2631 5647 2724 5648 2663 5648 2191 5648 2725 5649 2724 5649 2191 5649 2188 5650 2725 5650 2191 5650 2714 5651 2191 5651 2723 5651 2726 5652 2631 5652 2658 5652 2723 5653 2631 5653 2726 5653 2727 5654 2728 5654 2658 5654 2729 5655 2658 5655 2728 5655 2727 5656 2658 5656 2579 5656 2726 5657 2658 5657 2729 5657 2560 5658 2730 5658 2728 5658 2731 5659 2728 5659 2730 5659 2727 5660 2560 5660 2728 5660 2729 5661 2728 5661 2731 5661 2560 5662 2555 5662 2730 5662 2732 5663 2730 5663 2555 5663 2731 5664 2730 5664 2732 5664 2733 5665 2555 5665 2502 5665 2732 5666 2555 5666 2733 5666 2734 5667 2502 5667 2496 5667 2733 5668 2502 5668 2734 5668 2735 5669 2496 5669 2519 5669 2734 5670 2496 5670 2735 5670 2736 5671 2519 5671 2521 5671 2735 5672 2519 5672 2736 5672 2510 5673 2737 5673 2521 5673 2738 5674 2521 5674 2737 5674 2736 5675 2521 5675 2738 5675 2510 5676 2739 5676 2737 5676 2740 5677 2737 5677 2739 5677 2738 5678 2737 5678 2740 5678 2510 5679 2741 5679 2739 5679 2742 5680 2739 5680 2741 5680 2743 5681 2739 5681 2742 5681 2740 5682 2739 5682 2743 5682 2510 5683 2744 5683 2741 5683 2742 5684 2741 5684 2744 5684 2510 5685 2745 5685 2744 5685 2746 5686 2744 5686 2745 5686 2742 5687 2744 5687 2746 5687 2510 5688 2747 5688 2745 5688 2748 5689 2745 5689 2747 5689 2746 5690 2745 5690 2748 5690 2510 5691 2749 5691 2747 5691 2750 5692 2747 5692 2749 5692 2748 5693 2747 5693 2750 5693 2751 5694 2749 5694 2510 5694 2752 5695 2749 5695 2751 5695 2750 5696 2749 5696 2752 5696 2751 5697 2510 5697 2507 5697 2753 5698 2507 5698 2522 5698 2751 5699 2507 5699 2753 5699 2754 5700 2522 5700 2642 5700 2753 5701 2522 5701 2754 5701 2755 5702 2642 5702 2641 5702 2754 5703 2642 5703 2755 5703 2756 5704 2264 5704 2263 5704 2757 5705 2260 5705 2264 5705 2757 5706 2264 5706 2758 5706 2756 5707 2758 5707 2264 5707 2756 5708 2263 5708 2235 5708 2759 5709 2235 5709 2236 5709 2756 5710 2235 5710 2759 5710 2760 5711 2236 5711 2715 5711 2759 5712 2236 5712 2760 5712 2761 5713 2715 5713 2716 5713 2760 5714 2715 5714 2761 5714 2762 5715 2716 5715 2717 5715 2761 5716 2716 5716 2762 5716 2763 5717 2717 5717 2718 5717 2762 5718 2717 5718 2763 5718 2764 5719 2718 5719 2719 5719 2763 5720 2718 5720 2764 5720 2765 5721 2719 5721 2674 5721 2766 5722 2719 5722 2765 5722 2764 5723 2719 5723 2766 5723 2765 5724 2674 5724 2675 5724 2767 5725 2675 5725 2676 5725 2765 5726 2675 5726 2767 5726 2768 5727 2676 5727 2265 5727 2767 5728 2676 5728 2768 5728 2769 5729 2265 5729 2268 5729 2768 5730 2265 5730 2769 5730 2770 5731 2268 5731 2269 5731 2769 5732 2268 5732 2770 5732 2771 5733 2269 5733 2260 5733 2770 5734 2269 5734 2771 5734 2771 5735 2260 5735 2757 5735 2772 5736 2251 5736 2246 5736 2772 5737 2249 5737 2251 5737 2773 5738 2246 5738 2279 5738 2773 5739 2772 5739 2246 5739 2774 5740 2279 5740 2278 5740 2773 5741 2279 5741 2774 5741 2775 5742 2278 5742 2664 5742 2774 5743 2278 5743 2775 5743 2776 5744 2664 5744 2665 5744 2775 5745 2664 5745 2776 5745 2777 5746 2665 5746 2666 5746 2776 5747 2665 5747 2777 5747 2290 5748 2778 5748 2666 5748 2779 5749 2666 5749 2778 5749 2777 5750 2666 5750 2779 5750 2780 5751 2781 5751 2778 5751 2782 5752 2778 5752 2781 5752 2290 5753 2780 5753 2778 5753 2783 5754 2778 5754 2782 5754 2779 5755 2778 5755 2783 5755 2784 5756 2785 5756 2781 5756 2782 5757 2781 5757 2785 5757 2786 5758 2784 5758 2781 5758 2780 5759 2786 5759 2781 5759 2784 5760 2787 5760 2785 5760 2788 5761 2785 5761 2787 5761 2782 5762 2785 5762 2788 5762 2789 5763 2224 5763 2787 5763 2790 5764 2787 5764 2224 5764 2784 5765 2789 5765 2787 5765 2788 5766 2787 5766 2790 5766 2791 5767 2224 5767 2252 5767 2789 5768 2720 5768 2224 5768 2790 5769 2224 5769 2791 5769 2792 5770 2252 5770 2253 5770 2791 5771 2252 5771 2792 5771 2793 5772 2253 5772 2254 5772 2792 5773 2253 5773 2793 5773 2794 5774 2254 5774 2249 5774 2793 5775 2254 5775 2794 5775 2795 5776 2249 5776 2772 5776 2794 5777 2249 5777 2795 5777 2796 5778 2289 5778 2288 5778 2797 5779 2285 5779 2289 5779 2797 5780 2289 5780 2798 5780 2796 5781 2798 5781 2289 5781 2796 5782 2288 5782 2200 5782 2799 5783 2200 5783 2202 5783 2796 5784 2200 5784 2799 5784 2800 5785 2202 5785 2201 5785 2799 5786 2202 5786 2800 5786 2801 5787 2201 5787 2721 5787 2800 5788 2201 5788 2801 5788 2802 5789 2721 5789 2722 5789 2801 5790 2721 5790 2802 5790 2803 5791 2722 5791 2720 5791 2802 5792 2722 5792 2803 5792 2804 5793 2720 5793 2789 5793 2803 5794 2720 5794 2804 5794 2805 5795 2789 5795 2784 5795 2806 5796 2789 5796 2805 5796 2804 5797 2789 5797 2806 5797 2805 5798 2784 5798 2786 5798 2807 5799 2786 5799 2780 5799 2805 5800 2786 5800 2807 5800 2808 5801 2780 5801 2290 5801 2807 5802 2780 5802 2808 5802 2809 5803 2290 5803 2293 5803 2808 5804 2290 5804 2809 5804 2810 5805 2293 5805 2294 5805 2809 5806 2293 5806 2810 5806 2811 5807 2294 5807 2285 5807 2810 5808 2294 5808 2811 5808 2811 5809 2285 5809 2797 5809 2812 5810 2217 5810 2212 5810 2812 5811 2215 5811 2217 5811 2813 5812 2212 5812 2301 5812 2813 5813 2812 5813 2212 5813 2814 5814 2301 5814 2667 5814 2813 5815 2301 5815 2814 5815 2815 5816 2667 5816 2668 5816 2816 5817 2667 5817 2815 5817 2814 5818 2667 5818 2816 5818 2815 5819 2668 5819 2669 5819 2817 5820 2669 5820 2670 5820 2815 5821 2669 5821 2817 5821 2818 5822 2670 5822 2671 5822 2817 5823 2670 5823 2818 5823 2819 5824 2671 5824 2663 5824 2820 5825 2671 5825 2819 5825 2818 5826 2671 5826 2820 5826 2819 5827 2663 5827 2724 5827 2821 5828 2724 5828 2725 5828 2819 5829 2724 5829 2821 5829 2822 5830 2725 5830 2188 5830 2821 5831 2725 5831 2822 5831 2823 5832 2188 5832 2218 5832 2824 5833 2188 5833 2823 5833 2822 5834 2188 5834 2824 5834 2823 5835 2218 5835 2219 5835 2825 5836 2219 5836 2220 5836 2823 5837 2219 5837 2825 5837 2826 5838 2220 5838 2215 5838 2825 5839 2220 5839 2826 5839 2827 5840 2215 5840 2812 5840 2826 5841 2215 5841 2827 5841 2828 5842 2579 5842 2575 5842 2829 5843 2727 5843 2579 5843 2829 5844 2579 5844 2828 5844 2830 5845 2575 5845 2560 5845 2830 5846 2828 5846 2575 5846 2831 5847 2560 5847 2727 5847 2830 5848 2560 5848 2831 5848 2831 5849 2727 5849 2829 5849 2723 5850 2190 5850 2187 5850 2802 5851 2187 5851 2193 5851 2802 5852 2723 5852 2187 5852 2723 5853 2216 5853 2190 5853 2723 5854 2214 5854 2216 5854 2281 5855 2211 5855 2214 5855 2300 5856 2281 5856 2214 5856 2826 5857 2300 5857 2214 5857 2825 5858 2214 5858 2723 5858 2825 5859 2826 5859 2214 5859 2280 5860 2208 5860 2211 5860 2281 5861 2280 5861 2211 5861 2282 5862 2205 5862 2208 5862 2282 5863 2208 5863 2280 5863 2284 5864 2198 5864 2205 5864 2282 5865 2284 5865 2205 5865 2797 5866 2195 5866 2198 5866 2797 5867 2198 5867 2284 5867 2799 5868 2193 5868 2195 5868 2797 5869 2798 5869 2195 5869 2796 5870 2195 5870 2798 5870 2796 5871 2799 5871 2195 5871 2801 5872 2802 5872 2193 5872 2800 5873 2801 5873 2193 5873 2799 5874 2800 5874 2193 5874 2723 5875 2226 5875 2223 5875 2762 5876 2223 5876 2228 5876 2714 5877 2723 5877 2223 5877 2762 5878 2714 5878 2223 5878 2723 5879 2250 5879 2226 5879 2723 5880 2248 5880 2250 5880 2256 5881 2245 5881 2248 5881 2277 5882 2256 5882 2248 5882 2794 5883 2277 5883 2248 5883 2792 5884 2248 5884 2723 5884 2793 5885 2794 5885 2248 5885 2792 5886 2793 5886 2248 5886 2255 5887 2242 5887 2245 5887 2256 5888 2255 5888 2245 5888 2257 5889 2239 5889 2242 5889 2257 5890 2242 5890 2255 5890 2259 5891 2233 5891 2239 5891 2257 5892 2259 5892 2239 5892 2757 5893 2230 5893 2233 5893 2757 5894 2233 5894 2259 5894 2759 5895 2228 5895 2230 5895 2757 5896 2758 5896 2230 5896 2756 5897 2230 5897 2758 5897 2756 5898 2759 5898 2230 5898 2761 5899 2762 5899 2228 5899 2760 5900 2761 5900 2228 5900 2759 5901 2760 5901 2228 5901 2794 5902 2276 5902 2277 5902 2772 5903 2275 5903 2276 5903 2795 5904 2772 5904 2276 5904 2794 5905 2795 5905 2276 5905 2776 5906 2272 5906 2275 5906 2773 5907 2275 5907 2772 5907 2775 5908 2776 5908 2275 5908 2774 5909 2775 5909 2275 5909 2773 5910 2774 5910 2275 5910 2673 5911 2267 5911 2272 5911 2776 5912 2673 5912 2272 5912 2673 5913 2262 5913 2267 5913 2673 5914 2259 5914 2262 5914 2771 5915 2259 5915 2673 5915 2771 5916 2757 5916 2259 5916 2826 5917 2299 5917 2300 5917 2812 5918 2298 5918 2299 5918 2827 5919 2812 5919 2299 5919 2826 5920 2827 5920 2299 5920 2815 5921 2296 5921 2298 5921 2813 5922 2298 5922 2812 5922 2816 5923 2815 5923 2298 5923 2814 5924 2816 5924 2298 5924 2813 5925 2814 5925 2298 5925 2673 5926 2292 5926 2296 5926 2662 5927 2673 5927 2296 5927 2815 5928 2662 5928 2296 5928 2673 5929 2287 5929 2292 5929 2673 5930 2284 5930 2287 5930 2810 5931 2284 5931 2673 5931 2811 5932 2797 5932 2284 5932 2810 5933 2811 5933 2284 5933 2708 5934 2307 5934 2305 5934 2707 5935 2305 5935 2310 5935 2707 5936 2708 5936 2305 5936 2708 5937 2378 5937 2307 5937 2708 5938 2377 5938 2378 5938 2708 5939 2375 5939 2377 5939 2709 5940 2373 5940 2375 5940 2708 5941 2709 5941 2375 5941 2387 5942 2371 5942 2373 5942 2709 5943 2387 5943 2373 5943 2387 5944 2369 5944 2371 5944 2387 5945 2365 5945 2369 5945 2408 5946 2362 5946 2365 5946 2387 5947 2390 5947 2365 5947 2408 5948 2365 5948 2390 5948 2682 5949 2360 5949 2362 5949 2682 5950 2362 5950 2408 5950 2682 5951 2358 5951 2360 5951 2682 5952 2355 5952 2358 5952 2682 5953 2352 5953 2355 5953 2683 5954 2350 5954 2352 5954 2682 5955 2683 5955 2352 5955 2683 5956 2348 5956 2350 5956 2683 5957 2346 5957 2348 5957 2683 5958 2343 5958 2346 5958 2684 5959 2341 5959 2343 5959 2683 5960 2684 5960 2343 5960 2684 5961 2339 5961 2341 5961 2684 5962 2337 5962 2339 5962 2684 5963 2334 5963 2337 5963 2441 5964 2332 5964 2334 5964 2684 5965 2441 5965 2334 5965 2441 5966 2330 5966 2332 5966 2441 5967 2326 5967 2330 5967 2706 5968 2323 5968 2326 5968 2441 5969 2443 5969 2326 5969 2457 5970 2326 5970 2443 5970 2706 5971 2326 5971 2457 5971 2706 5972 2321 5972 2323 5972 2706 5973 2319 5973 2321 5973 2706 5974 2316 5974 2319 5974 2707 5975 2314 5975 2316 5975 2706 5976 2707 5976 2316 5976 2707 5977 2312 5977 2314 5977 2707 5978 2310 5978 2312 5978 2710 5979 2384 5979 2382 5979 2709 5980 2382 5980 2386 5980 2709 5981 2710 5981 2382 5981 2710 5982 2403 5982 2384 5982 2710 5983 2402 5983 2403 5983 2406 5984 2399 5984 2402 5984 2418 5985 2406 5985 2402 5985 2710 5986 2418 5986 2402 5986 2405 5987 2396 5987 2399 5987 2406 5988 2405 5988 2399 5988 2407 5989 2393 5989 2396 5989 2407 5990 2396 5990 2405 5990 2408 5991 2390 5991 2393 5991 2407 5992 2408 5992 2393 5992 2709 5993 2386 5993 2387 5993 2710 5994 2417 5994 2418 5994 2681 5995 2416 5995 2417 5995 2680 5996 2417 5996 2710 5996 2680 5997 2681 5997 2417 5997 2681 5998 2414 5998 2416 5998 2681 5999 2412 5999 2414 5999 2682 6000 2410 6000 2412 6000 2681 6001 2682 6001 2412 6001 2682 6002 2408 6002 2410 6002 2456 6003 2425 6003 2422 6003 2455 6004 2422 6004 2428 6004 2455 6005 2456 6005 2422 6005 2457 6006 2443 6006 2425 6006 2456 6007 2457 6007 2425 6007 2686 6008 2440 6008 2441 6008 2684 6009 2686 6009 2441 6009 2686 6010 2438 6010 2440 6010 2686 6011 2436 6011 2438 6011 2689 6012 2434 6012 2436 6012 2686 6013 2689 6013 2436 6013 2689 6014 2431 6014 2434 6014 2454 6015 2428 6015 2431 6015 2453 6016 2454 6016 2431 6016 2689 6017 2453 6017 2431 6017 2454 6018 2455 6018 2428 6018 2706 6019 2449 6019 2447 6019 2705 6020 2447 6020 2451 6020 2705 6021 2706 6021 2447 6021 2706 6022 2458 6022 2449 6022 2706 6023 2457 6023 2458 6023 2689 6024 2452 6024 2453 6024 2705 6025 2451 6025 2452 6025 2689 6026 2705 6026 2452 6026 2712 6027 2464 6027 2462 6027 2711 6028 2462 6028 2466 6028 2711 6029 2712 6029 2462 6029 2712 6030 2495 6030 2464 6030 2712 6031 2494 6031 2495 6031 2712 6032 2491 6032 2494 6032 2678 6033 2488 6033 2491 6033 2712 6034 2713 6034 2491 6034 2678 6035 2491 6035 2713 6035 2679 6036 2486 6036 2488 6036 2678 6037 2679 6037 2488 6037 2679 6038 2484 6038 2486 6038 2679 6039 2482 6039 2484 6039 2679 6040 2479 6040 2482 6040 2680 6041 2477 6041 2479 6041 2679 6042 2680 6042 2479 6042 2680 6043 2475 6043 2477 6043 2680 6044 2472 6044 2475 6044 2710 6045 2470 6045 2472 6045 2680 6046 2710 6046 2472 6046 2711 6047 2468 6047 2470 6047 2710 6048 2711 6048 2470 6048 2711 6049 2466 6049 2468 6049 2736 6050 2501 6050 2499 6050 2735 6051 2499 6051 2504 6051 2735 6052 2736 6052 2499 6052 2736 6053 2520 6053 2501 6053 2738 6054 2518 6054 2520 6054 2736 6055 2738 6055 2520 6055 2742 6056 2516 6056 2518 6056 2743 6057 2742 6057 2518 6057 2740 6058 2743 6058 2518 6058 2738 6059 2740 6059 2518 6059 2753 6060 2514 6060 2516 6060 2746 6061 2753 6061 2516 6061 2742 6062 2746 6062 2516 6062 2753 6063 2512 6063 2514 6063 2753 6064 2509 6064 2512 6064 2753 6065 2506 6065 2509 6065 2735 6066 2504 6066 2506 6066 2735 6067 2506 6067 2753 6067 2755 6068 2527 6068 2525 6068 2755 6069 2525 6069 2529 6069 2755 6070 2546 6070 2527 6070 2755 6071 2544 6071 2546 6071 2651 6072 2541 6072 2544 6072 2650 6073 2544 6073 2755 6073 2650 6074 2651 6074 2544 6074 2652 6075 2539 6075 2541 6075 2651 6076 2652 6076 2541 6076 2652 6077 2536 6077 2539 6077 2653 6078 2534 6078 2536 6078 2652 6079 2653 6079 2536 6079 2653 6080 2531 6080 2534 6080 2754 6081 2529 6081 2531 6081 2653 6082 2754 6082 2531 6082 2754 6083 2755 6083 2529 6083 2735 6084 2554 6084 2552 6084 2734 6085 2552 6085 2557 6085 2734 6086 2735 6086 2552 6086 2735 6087 2574 6087 2554 6087 2735 6088 2573 6088 2574 6088 2578 6089 2571 6089 2573 6089 2595 6090 2578 6090 2573 6090 2753 6091 2595 6091 2573 6091 2735 6092 2753 6092 2573 6092 2577 6093 2567 6093 2571 6093 2578 6094 2577 6094 2571 6094 2831 6095 2564 6095 2567 6095 2830 6096 2567 6096 2577 6096 2830 6097 2831 6097 2567 6097 2829 6098 2562 6098 2564 6098 2831 6099 2829 6099 2564 6099 2829 6100 2559 6100 2562 6100 2734 6101 2557 6101 2559 6101 2733 6102 2734 6102 2559 6102 2829 6103 2733 6103 2559 6103 2830 6104 2577 6104 2581 6104 2753 6105 2594 6105 2595 6105 2653 6106 2593 6106 2594 6106 2753 6107 2754 6107 2594 6107 2653 6108 2594 6108 2754 6108 2653 6109 2591 6109 2593 6109 2653 6110 2589 6110 2591 6110 2655 6111 2586 6111 2589 6111 2653 6112 2655 6112 2589 6112 2655 6113 2583 6113 2586 6113 2830 6114 2581 6114 2583 6114 2830 6115 2583 6115 2655 6115 2726 6116 2600 6116 2598 6116 2726 6117 2598 6117 2602 6117 2726 6118 2638 6118 2600 6118 2729 6119 2637 6119 2638 6119 2726 6120 2729 6120 2638 6120 2729 6121 2635 6121 2637 6121 2729 6122 2633 6122 2635 6122 2661 6123 2630 6123 2633 6123 2661 6124 2633 6124 2729 6124 2661 6125 2628 6125 2630 6125 2661 6126 2626 6126 2628 6126 2661 6127 2623 6127 2626 6127 2662 6128 2621 6128 2623 6128 2661 6129 2662 6129 2623 6129 2662 6130 2619 6130 2621 6130 2662 6131 2617 6131 2619 6131 2662 6132 2615 6132 2617 6132 2662 6133 2613 6133 2615 6133 2662 6134 2610 6134 2613 6134 2723 6135 2608 6135 2610 6135 2662 6136 2723 6136 2610 6136 2726 6137 2606 6137 2608 6137 2723 6138 2726 6138 2608 6138 2726 6139 2604 6139 2606 6139 2726 6140 2602 6140 2604 6140 2644 6141 2755 6141 2641 6141 2649 6142 2650 6142 2755 6142 2647 6143 2649 6143 2755 6143 2648 6144 2647 6144 2755 6144 2646 6145 2648 6145 2755 6145 2645 6146 2646 6146 2755 6146 2644 6147 2645 6147 2755 6147 2752 6148 2751 6148 2753 6148 2750 6149 2752 6149 2753 6149 2748 6150 2750 6150 2753 6150 2746 6151 2748 6151 2753 6151 2829 6152 2732 6152 2733 6152 2829 6153 2731 6153 2732 6153 2660 6154 2729 6154 2731 6154 2829 6155 2660 6155 2731 6155 2660 6156 2661 6156 2729 6156 2820 6157 2723 6157 2662 6157 2791 6158 2792 6158 2723 6158 2790 6159 2791 6159 2723 6159 2788 6160 2790 6160 2723 6160 2802 6161 2788 6161 2723 6161 2823 6162 2825 6162 2723 6162 2824 6163 2823 6163 2723 6163 2822 6164 2824 6164 2723 6164 2821 6165 2822 6165 2723 6165 2819 6166 2821 6166 2723 6166 2820 6167 2819 6167 2723 6167 2677 6168 2713 6168 2714 6168 2673 6169 2677 6169 2714 6169 2766 6170 2673 6170 2714 6170 2764 6171 2766 6171 2714 6171 2763 6172 2764 6172 2714 6172 2762 6173 2763 6173 2714 6173 2677 6174 2678 6174 2713 6174 2689 6175 2704 6175 2705 6175 2692 6176 2703 6176 2704 6176 2689 6177 2692 6177 2704 6177 2695 6178 2702 6178 2703 6178 2692 6179 2695 6179 2703 6179 2698 6180 2701 6180 2702 6180 2695 6181 2698 6181 2702 6181 2699 6182 2700 6182 2701 6182 2698 6183 2699 6183 2701 6183 2770 6184 2771 6184 2673 6184 2769 6185 2770 6185 2673 6185 2768 6186 2769 6186 2673 6186 2767 6187 2768 6187 2673 6187 2765 6188 2767 6188 2673 6188 2766 6189 2765 6189 2673 6189 2807 6190 2673 6190 2776 6190 2809 6191 2810 6191 2673 6191 2808 6192 2809 6192 2673 6192 2807 6193 2808 6193 2673 6193 2818 6194 2820 6194 2662 6194 2817 6195 2818 6195 2662 6195 2815 6196 2817 6196 2662 6196 2828 6197 2659 6197 2660 6197 2829 6198 2828 6198 2660 6198 2830 6199 2657 6199 2659 6199 2830 6200 2659 6200 2828 6200 2830 6201 2655 6201 2657 6201 2802 6202 2782 6202 2788 6202 2803 6203 2783 6203 2782 6203 2802 6204 2803 6204 2782 6204 2806 6205 2779 6205 2783 6205 2804 6206 2806 6206 2783 6206 2803 6207 2804 6207 2783 6207 2806 6208 2777 6208 2779 6208 2805 6209 2776 6209 2777 6209 2806 6210 2805 6210 2777 6210 2805 6211 2807 6211 2776 6211 2832 6212 2833 6212 2834 6212 2835 6213 2834 6213 2833 6213 2836 6214 2834 6214 2837 6214 2838 6215 2837 6215 2834 6215 2839 6216 2832 6216 2834 6216 2836 6217 2839 6217 2834 6217 2838 6218 2834 6218 2835 6218 2832 6219 2840 6219 2833 6219 2841 6220 2833 6220 2840 6220 2841 6221 2835 6221 2833 6221 2832 6222 2842 6222 2840 6222 2843 6223 2840 6223 2842 6223 2841 6224 2840 6224 2843 6224 2844 6225 2845 6225 2842 6225 2846 6226 2842 6226 2845 6226 2847 6227 2844 6227 2842 6227 2848 6228 2847 6228 2842 6228 2849 6229 2842 6229 2832 6229 2850 6230 2848 6230 2842 6230 2849 6231 2850 6231 2842 6231 2843 6232 2842 6232 2846 6232 2851 6233 2852 6233 2845 6233 2853 6234 2845 6234 2852 6234 2844 6235 2851 6235 2845 6235 2846 6236 2845 6236 2853 6236 2854 6237 2855 6237 2852 6237 2856 6238 2852 6238 2855 6238 2854 6239 2852 6239 2851 6239 2853 6240 2852 6240 2856 6240 2857 6241 2858 6241 2855 6241 2859 6242 2855 6242 2858 6242 2854 6243 2857 6243 2855 6243 2856 6244 2855 6244 2859 6244 2860 6245 2861 6245 2858 6245 2862 6246 2858 6246 2861 6246 2860 6247 2858 6247 2857 6247 2859 6248 2858 6248 2862 6248 2863 6249 2837 6249 2861 6249 2864 6250 2861 6250 2837 6250 2860 6251 2865 6251 2861 6251 2863 6252 2861 6252 2865 6252 2862 6253 2861 6253 2864 6253 2866 6254 2836 6254 2837 6254 2867 6255 2866 6255 2837 6255 2868 6256 2867 6256 2837 6256 2863 6257 2868 6257 2837 6257 2864 6258 2837 6258 2838 6258 2832 6259 2869 6259 2870 6259 2871 6260 2870 6260 2869 6260 2872 6261 2870 6261 2873 6261 2874 6262 2873 6262 2870 6262 2872 6263 2832 6263 2870 6263 2874 6264 2870 6264 2871 6264 2832 6265 2875 6265 2869 6265 2876 6266 2869 6266 2875 6266 2876 6267 2871 6267 2869 6267 2832 6268 2877 6268 2875 6268 2878 6269 2875 6269 2877 6269 2876 6270 2875 6270 2878 6270 2879 6271 2880 6271 2877 6271 2881 6272 2877 6272 2880 6272 2882 6273 2879 6273 2877 6273 2883 6274 2882 6274 2877 6274 2884 6275 2877 6275 2832 6275 2884 6276 2883 6276 2877 6276 2878 6277 2877 6277 2881 6277 2885 6278 2886 6278 2880 6278 2887 6279 2880 6279 2886 6279 2879 6280 2885 6280 2880 6280 2881 6281 2880 6281 2887 6281 2888 6282 2889 6282 2886 6282 2890 6283 2886 6283 2889 6283 2888 6284 2886 6284 2885 6284 2887 6285 2886 6285 2890 6285 2891 6286 2892 6286 2889 6286 2893 6287 2889 6287 2892 6287 2888 6288 2891 6288 2889 6288 2890 6289 2889 6289 2893 6289 2894 6290 2895 6290 2892 6290 2896 6291 2892 6291 2895 6291 2894 6292 2892 6292 2891 6292 2893 6293 2892 6293 2896 6293 2897 6294 2873 6294 2895 6294 2898 6295 2895 6295 2873 6295 2894 6296 2899 6296 2895 6296 2897 6297 2895 6297 2899 6297 2896 6298 2895 6298 2898 6298 2900 6299 2872 6299 2873 6299 2901 6300 2900 6300 2873 6300 2902 6301 2901 6301 2873 6301 2897 6302 2902 6302 2873 6302 2898 6303 2873 6303 2874 6303 2903 6304 2885 6304 2879 6304 2904 6305 2888 6305 2885 6305 2904 6306 2885 6306 2903 6306 2905 6307 2879 6307 2882 6307 2905 6308 2903 6308 2879 6308 2883 6309 2906 6309 2882 6309 2907 6310 2882 6310 2906 6310 2905 6311 2882 6311 2907 6311 2908 6312 2909 6312 2906 6312 2910 6313 2906 6313 2909 6313 2911 6314 2912 6314 2906 6314 2908 6315 2906 6315 2912 6315 2883 6316 2911 6316 2906 6316 2907 6317 2906 6317 2910 6317 2913 6318 2914 6318 2909 6318 2915 6319 2909 6319 2914 6319 2916 6320 2913 6320 2909 6320 2917 6321 2916 6321 2909 6321 2908 6322 2917 6322 2909 6322 2910 6323 2909 6323 2915 6323 2918 6324 2919 6324 2914 6324 2920 6325 2914 6325 2919 6325 2921 6326 2918 6326 2914 6326 2913 6327 2921 6327 2914 6327 2915 6328 2914 6328 2920 6328 2918 6329 2922 6329 2919 6329 2923 6330 2919 6330 2922 6330 2920 6331 2919 6331 2923 6331 2918 6332 2891 6332 2922 6332 2924 6333 2922 6333 2891 6333 2923 6334 2922 6334 2924 6334 2925 6335 2891 6335 2888 6335 2926 6336 2891 6336 2918 6336 2927 6337 2894 6337 2891 6337 2926 6338 2927 6338 2891 6338 2924 6339 2891 6339 2925 6339 2925 6340 2888 6340 2904 6340 2928 6341 2851 6341 2844 6341 2929 6342 2854 6342 2851 6342 2929 6343 2851 6343 2928 6343 2930 6344 2844 6344 2847 6344 2930 6345 2928 6345 2844 6345 2848 6346 2931 6346 2847 6346 2932 6347 2847 6347 2931 6347 2930 6348 2847 6348 2932 6348 2933 6349 2934 6349 2931 6349 2935 6350 2931 6350 2934 6350 2936 6351 2937 6351 2931 6351 2933 6352 2931 6352 2937 6352 2848 6353 2936 6353 2931 6353 2932 6354 2931 6354 2935 6354 2938 6355 2939 6355 2934 6355 2940 6356 2934 6356 2939 6356 2941 6357 2938 6357 2934 6357 2942 6358 2941 6358 2934 6358 2933 6359 2942 6359 2934 6359 2935 6360 2934 6360 2940 6360 2918 6361 2943 6361 2939 6361 2944 6362 2939 6362 2943 6362 2938 6363 2918 6363 2939 6363 2940 6364 2939 6364 2944 6364 2918 6365 2945 6365 2943 6365 2946 6366 2943 6366 2945 6366 2944 6367 2943 6367 2946 6367 2918 6368 2857 6368 2945 6368 2947 6369 2945 6369 2857 6369 2946 6370 2945 6370 2947 6370 2948 6371 2857 6371 2854 6371 2949 6372 2857 6372 2918 6372 2949 6373 2860 6373 2857 6373 2947 6374 2857 6374 2948 6374 2948 6375 2854 6375 2929 6375 2950 6376 2951 6376 2952 6376 2953 6377 2952 6377 2951 6377 2950 6378 2952 6378 2954 6378 2955 6379 2954 6379 2952 6379 2955 6380 2952 6380 2953 6380 2956 6381 2957 6381 2951 6381 2958 6382 2951 6382 2957 6382 2950 6383 2956 6383 2951 6383 2958 6384 2953 6384 2951 6384 2956 6385 2959 6385 2957 6385 2960 6386 2957 6386 2959 6386 2958 6387 2957 6387 2960 6387 2956 6388 2961 6388 2959 6388 2962 6389 2959 6389 2961 6389 2960 6390 2959 6390 2962 6390 2956 6391 2963 6391 2961 6391 2964 6392 2961 6392 2963 6392 2962 6393 2961 6393 2964 6393 2965 6394 2966 6394 2963 6394 2967 6395 2963 6395 2966 6395 2956 6396 2965 6396 2963 6396 2964 6397 2963 6397 2967 6397 2965 6398 2968 6398 2966 6398 2969 6399 2966 6399 2968 6399 2967 6400 2966 6400 2969 6400 2965 6401 2970 6401 2968 6401 2971 6402 2968 6402 2970 6402 2969 6403 2968 6403 2971 6403 2972 6404 2973 6404 2970 6404 2974 6405 2970 6405 2973 6405 2975 6406 2976 6406 2970 6406 2972 6407 2970 6407 2976 6407 2965 6408 2975 6408 2970 6408 2971 6409 2970 6409 2974 6409 2972 6410 2977 6410 2973 6410 2978 6411 2973 6411 2977 6411 2974 6412 2973 6412 2978 6412 2972 6413 2979 6413 2977 6413 2980 6414 2977 6414 2979 6414 2978 6415 2977 6415 2980 6415 2972 6416 2981 6416 2979 6416 2982 6417 2979 6417 2981 6417 2980 6418 2979 6418 2982 6418 2983 6419 2984 6419 2981 6419 2985 6420 2981 6420 2984 6420 2972 6421 2983 6421 2981 6421 2982 6422 2981 6422 2985 6422 2983 6423 2986 6423 2984 6423 2987 6424 2984 6424 2986 6424 2985 6425 2984 6425 2987 6425 2983 6426 2988 6426 2986 6426 2989 6427 2986 6427 2988 6427 2987 6428 2986 6428 2989 6428 2983 6429 2990 6429 2988 6429 2991 6430 2988 6430 2990 6430 2989 6431 2988 6431 2991 6431 2992 6432 2993 6432 2990 6432 2994 6433 2990 6433 2993 6433 2983 6434 2992 6434 2990 6434 2991 6435 2990 6435 2994 6435 2992 6436 2995 6436 2993 6436 2996 6437 2993 6437 2995 6437 2994 6438 2993 6438 2996 6438 2992 6439 2997 6439 2995 6439 2998 6440 2995 6440 2997 6440 2996 6441 2995 6441 2998 6441 2992 6442 2999 6442 2997 6442 3000 6443 2997 6443 2999 6443 2998 6444 2997 6444 3000 6444 3001 6445 3002 6445 2999 6445 3003 6446 2999 6446 3002 6446 2992 6447 3001 6447 2999 6447 3000 6448 2999 6448 3003 6448 3004 6449 3005 6449 3002 6449 3006 6450 3002 6450 3005 6450 3001 6451 3004 6451 3002 6451 3003 6452 3002 6452 3006 6452 3004 6453 3007 6453 3005 6453 3008 6454 3005 6454 3007 6454 3006 6455 3005 6455 3008 6455 3004 6456 3009 6456 3007 6456 3010 6457 3007 6457 3009 6457 3008 6458 3007 6458 3010 6458 3011 6459 3012 6459 3009 6459 3013 6460 3009 6460 3012 6460 3014 6461 3011 6461 3009 6461 3004 6462 3014 6462 3009 6462 3010 6463 3009 6463 3013 6463 3015 6464 3016 6464 3012 6464 3017 6465 3012 6465 3016 6465 3015 6466 3012 6466 3011 6466 3013 6467 3012 6467 3017 6467 3015 6468 3018 6468 3016 6468 3019 6469 3016 6469 3018 6469 3017 6470 3016 6470 3019 6470 3015 6471 3020 6471 3018 6471 3021 6472 3018 6472 3020 6472 3019 6473 3018 6473 3021 6473 3015 6474 3022 6474 3020 6474 3023 6475 3020 6475 3022 6475 3021 6476 3020 6476 3023 6476 2950 6477 3024 6477 3022 6477 3025 6478 3022 6478 3024 6478 3015 6479 2950 6479 3022 6479 3023 6480 3022 6480 3025 6480 2950 6481 2954 6481 3024 6481 3026 6482 3024 6482 2954 6482 3025 6483 3024 6483 3026 6483 3026 6484 2954 6484 2955 6484 3027 6485 3028 6485 3029 6485 3030 6486 3029 6486 3028 6486 3027 6487 3029 6487 3031 6487 3032 6488 3031 6488 3029 6488 3032 6489 3029 6489 3030 6489 3015 6490 3033 6490 3028 6490 3034 6491 3028 6491 3033 6491 3027 6492 3015 6492 3028 6492 3034 6493 3030 6493 3028 6493 3015 6494 3011 6494 3033 6494 3035 6495 3033 6495 3011 6495 3034 6496 3033 6496 3035 6496 3036 6497 3037 6497 3011 6497 3038 6498 3011 6498 3037 6498 3014 6499 3036 6499 3011 6499 3035 6500 3011 6500 3038 6500 3039 6501 3040 6501 3037 6501 3041 6502 3037 6502 3040 6502 3036 6503 3039 6503 3037 6503 3038 6504 3037 6504 3041 6504 3042 6505 3043 6505 3040 6505 3044 6506 3040 6506 3043 6506 3042 6507 3040 6507 3039 6507 3041 6508 3040 6508 3044 6508 3045 6509 3046 6509 3043 6509 3047 6510 3043 6510 3046 6510 3042 6511 3045 6511 3043 6511 3044 6512 3043 6512 3047 6512 3048 6513 3049 6513 3046 6513 3050 6514 3046 6514 3049 6514 3048 6515 3046 6515 3045 6515 3047 6516 3046 6516 3050 6516 3027 6517 3031 6517 3049 6517 3051 6518 3049 6518 3031 6518 3052 6519 3049 6519 3048 6519 3052 6520 3027 6520 3049 6520 3050 6521 3049 6521 3051 6521 3051 6522 3031 6522 3032 6522 3053 6523 3039 6523 3036 6523 3054 6524 3042 6524 3039 6524 3054 6525 3039 6525 3053 6525 3055 6526 3036 6526 3014 6526 3055 6527 3053 6527 3036 6527 3056 6528 3014 6528 3004 6528 3055 6529 3014 6529 3056 6529 3001 6530 3057 6530 3004 6530 3058 6531 3004 6531 3057 6531 3056 6532 3004 6532 3058 6532 3001 6533 3059 6533 3057 6533 3060 6534 3057 6534 3059 6534 3058 6535 3057 6535 3060 6535 3048 6536 3061 6536 3059 6536 3062 6537 3059 6537 3061 6537 3001 6538 3048 6538 3059 6538 3060 6539 3059 6539 3062 6539 3048 6540 3063 6540 3061 6540 3064 6541 3061 6541 3063 6541 3062 6542 3061 6542 3064 6542 3048 6543 3045 6543 3063 6543 3065 6544 3063 6544 3045 6544 3064 6545 3063 6545 3065 6545 3066 6546 3045 6546 3042 6546 3065 6547 3045 6547 3066 6547 3066 6548 3042 6548 3054 6548 3067 6549 3068 6549 3069 6549 3070 6550 3069 6550 3068 6550 3071 6551 3069 6551 3072 6551 3073 6552 3072 6552 3069 6552 3071 6553 3067 6553 3069 6553 3073 6554 3069 6554 3070 6554 3074 6555 3075 6555 3068 6555 3076 6556 3068 6556 3075 6556 3067 6557 3074 6557 3068 6557 3076 6558 3070 6558 3068 6558 3077 6559 3078 6559 3075 6559 3079 6560 3075 6560 3078 6560 3077 6561 3075 6561 3074 6561 3076 6562 3075 6562 3079 6562 3080 6563 3081 6563 3078 6563 3082 6564 3078 6564 3081 6564 3077 6565 3080 6565 3078 6565 3079 6566 3078 6566 3082 6566 3080 6567 3083 6567 3081 6567 3084 6568 3081 6568 3083 6568 3082 6569 3081 6569 3084 6569 2972 6570 3085 6570 3083 6570 3086 6571 3083 6571 3085 6571 3080 6572 2972 6572 3083 6572 3084 6573 3083 6573 3086 6573 2972 6574 3087 6574 3085 6574 3088 6575 3085 6575 3087 6575 3086 6576 3085 6576 3088 6576 2972 6577 2976 6577 3087 6577 3089 6578 3087 6578 2976 6578 3088 6579 3087 6579 3089 6579 3090 6580 3072 6580 2976 6580 3091 6581 2976 6581 3072 6581 2975 6582 3090 6582 2976 6582 3089 6583 2976 6583 3091 6583 3090 6584 3071 6584 3072 6584 3091 6585 3072 6585 3073 6585 3092 6586 3093 6586 3094 6586 3095 6587 3094 6587 3093 6587 3092 6588 3094 6588 3096 6588 3097 6589 3096 6589 3094 6589 3097 6590 3094 6590 3095 6590 3077 6591 3098 6591 3093 6591 3099 6592 3093 6592 3098 6592 3092 6593 3077 6593 3093 6593 3099 6594 3095 6594 3093 6594 3077 6595 3074 6595 3098 6595 3100 6596 3098 6596 3074 6596 3099 6597 3098 6597 3100 6597 3101 6598 3074 6598 3067 6598 3100 6599 3074 6599 3101 6599 3102 6600 3067 6600 3071 6600 3101 6601 3067 6601 3102 6601 3103 6602 3071 6602 3090 6602 3102 6603 3071 6603 3103 6603 3104 6604 3090 6604 2975 6604 3103 6605 3090 6605 3104 6605 3105 6606 2975 6606 2965 6606 3104 6607 2975 6607 3105 6607 3092 6608 3096 6608 2965 6608 3106 6609 2965 6609 3096 6609 2956 6610 3092 6610 2965 6610 3105 6611 2965 6611 3106 6611 3106 6612 3096 6612 3097 6612 3107 6613 3108 6613 3109 6613 3110 6614 3109 6614 3108 6614 3107 6615 3109 6615 3111 6615 3112 6616 3111 6616 3109 6616 3112 6617 3109 6617 3110 6617 3052 6618 3113 6618 3108 6618 3114 6619 3108 6619 3113 6619 3107 6620 3052 6620 3108 6620 3114 6621 3110 6621 3108 6621 3052 6622 3115 6622 3113 6622 3116 6623 3113 6623 3115 6623 3114 6624 3113 6624 3116 6624 3052 6625 3117 6625 3115 6625 3118 6626 3115 6626 3117 6626 3116 6627 3115 6627 3118 6627 3048 6628 3119 6628 3117 6628 3120 6629 3117 6629 3119 6629 3052 6630 3048 6630 3117 6630 3118 6631 3117 6631 3120 6631 3121 6632 3122 6632 3119 6632 3123 6633 3119 6633 3122 6633 3048 6634 3121 6634 3119 6634 3120 6635 3119 6635 3123 6635 3121 6636 3124 6636 3122 6636 3125 6637 3122 6637 3124 6637 3123 6638 3122 6638 3125 6638 3121 6639 3126 6639 3124 6639 3127 6640 3124 6640 3126 6640 3125 6641 3124 6641 3127 6641 3128 6642 3129 6642 3126 6642 3130 6643 3126 6643 3129 6643 3121 6644 3128 6644 3126 6644 3127 6645 3126 6645 3130 6645 3128 6646 3131 6646 3129 6646 3132 6647 3129 6647 3131 6647 3130 6648 3129 6648 3132 6648 3128 6649 3133 6649 3131 6649 3134 6650 3131 6650 3133 6650 3132 6651 3131 6651 3134 6651 3128 6652 3135 6652 3133 6652 3136 6653 3133 6653 3135 6653 3134 6654 3133 6654 3136 6654 3137 6655 3138 6655 3135 6655 3139 6656 3135 6656 3138 6656 3128 6657 3140 6657 3135 6657 3137 6658 3135 6658 3140 6658 3136 6659 3135 6659 3139 6659 3107 6660 3141 6660 3138 6660 3142 6661 3138 6661 3141 6661 3137 6662 3107 6662 3138 6662 3139 6663 3138 6663 3142 6663 3107 6664 3111 6664 3141 6664 3143 6665 3141 6665 3111 6665 3142 6666 3141 6666 3143 6666 3143 6667 3111 6667 3112 6667 3144 6668 3145 6668 3146 6668 3147 6669 3146 6669 3145 6669 3144 6670 3146 6670 3148 6670 3149 6671 3148 6671 3146 6671 3149 6672 3146 6672 3147 6672 3150 6673 3151 6673 3145 6673 3152 6674 3145 6674 3151 6674 3144 6675 3150 6675 3145 6675 3152 6676 3147 6676 3145 6676 3150 6677 3153 6677 3151 6677 3154 6678 3151 6678 3153 6678 3152 6679 3151 6679 3154 6679 3155 6680 3156 6680 3153 6680 3157 6681 3153 6681 3156 6681 3155 6682 3153 6682 3150 6682 3154 6683 3153 6683 3157 6683 3158 6684 3159 6684 3156 6684 3160 6685 3156 6685 3159 6685 3155 6686 3158 6686 3156 6686 3157 6687 3156 6687 3160 6687 3158 6688 3161 6688 3159 6688 3162 6689 3159 6689 3161 6689 3160 6690 3159 6690 3162 6690 3158 6691 3163 6691 3161 6691 3164 6692 3161 6692 3163 6692 3162 6693 3161 6693 3164 6693 3158 6694 3165 6694 3163 6694 3166 6695 3163 6695 3165 6695 3164 6696 3163 6696 3166 6696 3167 6697 3148 6697 3165 6697 3168 6698 3165 6698 3148 6698 3169 6699 3167 6699 3165 6699 3158 6700 3169 6700 3165 6700 3166 6701 3165 6701 3168 6701 3167 6702 3144 6702 3148 6702 3168 6703 3148 6703 3149 6703 3170 6704 3171 6704 3172 6704 3173 6705 3172 6705 3171 6705 3170 6706 3172 6706 3174 6706 3175 6707 3174 6707 3172 6707 3175 6708 3172 6708 3173 6708 3170 6709 3176 6709 3171 6709 3177 6710 3171 6710 3176 6710 3177 6711 3173 6711 3171 6711 3170 6712 3178 6712 3176 6712 3179 6713 3176 6713 3178 6713 3177 6714 3176 6714 3179 6714 3180 6715 3181 6715 3178 6715 3182 6716 3178 6716 3181 6716 3170 6717 3180 6717 3178 6717 3179 6718 3178 6718 3182 6718 3180 6719 3183 6719 3181 6719 3184 6720 3181 6720 3183 6720 3182 6721 3181 6721 3184 6721 3185 6722 3186 6722 3183 6722 3187 6723 3183 6723 3186 6723 3180 6724 3185 6724 3183 6724 3184 6725 3183 6725 3187 6725 3185 6726 3188 6726 3186 6726 3189 6727 3186 6727 3188 6727 3187 6728 3186 6728 3189 6728 3190 6729 3191 6729 3188 6729 3192 6730 3188 6730 3191 6730 3185 6731 3190 6731 3188 6731 3189 6732 3188 6732 3192 6732 3193 6733 3174 6733 3191 6733 3194 6734 3191 6734 3174 6734 3195 6735 3193 6735 3191 6735 3196 6736 3195 6736 3191 6736 3190 6737 3196 6737 3191 6737 3192 6738 3191 6738 3194 6738 3193 6739 3197 6739 3174 6739 3170 6740 3174 6740 3197 6740 3194 6741 3174 6741 3175 6741 3150 6742 3198 6742 3199 6742 3200 6743 3199 6743 3198 6743 3150 6744 3199 6744 3201 6744 3202 6745 3201 6745 3199 6745 3202 6746 3199 6746 3200 6746 3203 6747 3204 6747 3198 6747 3205 6748 3198 6748 3204 6748 3150 6749 3203 6749 3198 6749 3205 6750 3200 6750 3198 6750 3203 6751 3206 6751 3204 6751 3207 6752 3204 6752 3206 6752 3205 6753 3204 6753 3207 6753 3208 6754 3209 6754 3206 6754 3210 6755 3206 6755 3209 6755 3208 6756 3206 6756 3203 6756 3207 6757 3206 6757 3210 6757 3208 6758 3211 6758 3209 6758 3212 6759 3209 6759 3211 6759 3210 6760 3209 6760 3212 6760 3213 6761 3214 6761 3211 6761 3215 6762 3211 6762 3214 6762 3213 6763 3211 6763 3216 6763 3208 6764 3216 6764 3211 6764 3212 6765 3211 6765 3215 6765 3217 6766 3218 6766 3214 6766 3219 6767 3214 6767 3218 6767 3213 6768 3217 6768 3214 6768 3215 6769 3214 6769 3219 6769 3170 6770 3220 6770 3218 6770 3221 6771 3218 6771 3220 6771 3170 6772 3218 6772 3217 6772 3219 6773 3218 6773 3221 6773 3150 6774 3201 6774 3220 6774 3222 6775 3220 6775 3201 6775 3155 6776 3150 6776 3220 6776 3170 6777 3155 6777 3220 6777 3221 6778 3220 6778 3222 6778 3222 6779 3201 6779 3202 6779 3223 6780 3224 6780 3216 6780 3225 6781 3216 6781 3224 6781 3226 6782 3213 6782 3216 6782 3208 6783 3223 6783 3216 6783 3226 6784 3216 6784 3225 6784 3227 6785 3228 6785 3224 6785 3229 6786 3224 6786 3228 6786 3223 6787 3227 6787 3224 6787 3229 6788 3225 6788 3224 6788 3227 6789 3230 6789 3228 6789 3231 6790 3228 6790 3230 6790 3229 6791 3228 6791 3231 6791 3232 6792 3233 6792 3230 6792 3234 6793 3230 6793 3233 6793 3235 6794 3232 6794 3230 6794 3227 6795 3235 6795 3230 6795 3231 6796 3230 6796 3234 6796 3232 6797 3236 6797 3233 6797 3237 6798 3233 6798 3236 6798 3234 6799 3233 6799 3237 6799 3180 6800 3238 6800 3236 6800 3239 6801 3236 6801 3238 6801 3232 6802 3180 6802 3236 6802 3237 6803 3236 6803 3239 6803 3180 6804 3240 6804 3238 6804 3241 6805 3238 6805 3240 6805 3239 6806 3238 6806 3241 6806 3180 6807 3217 6807 3240 6807 3242 6808 3240 6808 3217 6808 3241 6809 3240 6809 3242 6809 3243 6810 3217 6810 3213 6810 3170 6811 3217 6811 3180 6811 3242 6812 3217 6812 3243 6812 3243 6813 3213 6813 3226 6813 2839 6814 3244 6814 3245 6814 3246 6815 3245 6815 3244 6815 2839 6816 3245 6816 3247 6816 3248 6817 3247 6817 3245 6817 3248 6818 3245 6818 3246 6818 2839 6819 3249 6819 3244 6819 3250 6820 3244 6820 3249 6820 3250 6821 3246 6821 3244 6821 2839 6822 3251 6822 3249 6822 3252 6823 3249 6823 3251 6823 3250 6824 3249 6824 3252 6824 2839 6825 3253 6825 3251 6825 3254 6826 3251 6826 3253 6826 3252 6827 3251 6827 3254 6827 2839 6828 3255 6828 3253 6828 3256 6829 3253 6829 3255 6829 3254 6830 3253 6830 3256 6830 2918 6831 3257 6831 3255 6831 3258 6832 3255 6832 3257 6832 2839 6833 2918 6833 3255 6833 3256 6834 3255 6834 3258 6834 3259 6835 3260 6835 3257 6835 3261 6836 3257 6836 3260 6836 2918 6837 3259 6837 3257 6837 3258 6838 3257 6838 3261 6838 3259 6839 3262 6839 3260 6839 3263 6840 3260 6840 3262 6840 3261 6841 3260 6841 3263 6841 3259 6842 3264 6842 3262 6842 3265 6843 3262 6843 3264 6843 3263 6844 3262 6844 3265 6844 3259 6845 3266 6845 3264 6845 3267 6846 3264 6846 3266 6846 3265 6847 3264 6847 3267 6847 3259 6848 3268 6848 3266 6848 3269 6849 3266 6849 3268 6849 3267 6850 3266 6850 3269 6850 3259 6851 3270 6851 3268 6851 3271 6852 3268 6852 3270 6852 3269 6853 3268 6853 3271 6853 3272 6854 3273 6854 3270 6854 3274 6855 3270 6855 3273 6855 3259 6856 3272 6856 3270 6856 3271 6857 3270 6857 3274 6857 3272 6858 3275 6858 3273 6858 3276 6859 3273 6859 3275 6859 3274 6860 3273 6860 3276 6860 3272 6861 3277 6861 3275 6861 3278 6862 3275 6862 3277 6862 3276 6863 3275 6863 3278 6863 3279 6864 3280 6864 3277 6864 3281 6865 3277 6865 3280 6865 3279 6866 3277 6866 3272 6866 3278 6867 3277 6867 3281 6867 3279 6868 3282 6868 3280 6868 3283 6869 3280 6869 3282 6869 3281 6870 3280 6870 3283 6870 3279 6871 3284 6871 3282 6871 3285 6872 3282 6872 3284 6872 3283 6873 3282 6873 3285 6873 3279 6874 3247 6874 3284 6874 3286 6875 3284 6875 3247 6875 3285 6876 3284 6876 3286 6876 3279 6877 2839 6877 3247 6877 3286 6878 3247 6878 3248 6878 3170 6879 3287 6879 3288 6879 3289 6880 3288 6880 3287 6880 3290 6881 3170 6881 3288 6881 3289 6882 3290 6882 3288 6882 3170 6883 3291 6883 3287 6883 3292 6884 3287 6884 3291 6884 3292 6885 3289 6885 3287 6885 3170 6886 3197 6886 3291 6886 3293 6887 3291 6887 3197 6887 3292 6888 3291 6888 3293 6888 3294 6889 3197 6889 3193 6889 3293 6890 3197 6890 3294 6890 3295 6891 3193 6891 3195 6891 3296 6892 3193 6892 3295 6892 3294 6893 3193 6893 3296 6893 3295 6894 3195 6894 3196 6894 3297 6895 3196 6895 3190 6895 3295 6896 3196 6896 3297 6896 3298 6897 3190 6897 3185 6897 3297 6898 3190 6898 3298 6898 3299 6899 3185 6899 3180 6899 3298 6900 3185 6900 3299 6900 3300 6901 3180 6901 3232 6901 3299 6902 3180 6902 3300 6902 3301 6903 3232 6903 3235 6903 3300 6904 3232 6904 3301 6904 3227 6905 3302 6905 3235 6905 3303 6906 3235 6906 3302 6906 3301 6907 3235 6907 3303 6907 3227 6908 3304 6908 3302 6908 3305 6909 3302 6909 3304 6909 3303 6910 3302 6910 3305 6910 3306 6911 3272 6911 3304 6911 3307 6912 3304 6912 3272 6912 3227 6913 3306 6913 3304 6913 3305 6914 3304 6914 3307 6914 3308 6915 3272 6915 3259 6915 3306 6916 3279 6916 3272 6916 3307 6917 3272 6917 3308 6917 3309 6918 3259 6918 2918 6918 3308 6919 3259 6919 3309 6919 3310 6920 2918 6920 2921 6920 3311 6921 2918 6921 2839 6921 3312 6922 2926 6922 2918 6922 3313 6923 3312 6923 2918 6923 3314 6924 3313 6924 2918 6924 2938 6925 3314 6925 2918 6925 3315 6926 2949 6926 2918 6926 3316 6927 3315 6927 2918 6927 3317 6928 3316 6928 2918 6928 3318 6929 3317 6929 2918 6929 3319 6930 3318 6930 2918 6930 3311 6931 3319 6931 2918 6931 3309 6932 2918 6932 3310 6932 3320 6933 3140 6933 2921 6933 3321 6934 2921 6934 3140 6934 2832 6935 3320 6935 2921 6935 3322 6936 2832 6936 2921 6936 3323 6937 3322 6937 2921 6937 3324 6938 3323 6938 2921 6938 2913 6939 3324 6939 2921 6939 3310 6940 2921 6940 3321 6940 3325 6941 3140 6941 3128 6941 3320 6942 3137 6942 3140 6942 3321 6943 3140 6943 3325 6943 3326 6944 3128 6944 3121 6944 3325 6945 3128 6945 3326 6945 3327 6946 3121 6946 3048 6946 3326 6947 3121 6947 3327 6947 3328 6948 3048 6948 3001 6948 3327 6949 3048 6949 3328 6949 3329 6950 3001 6950 2992 6950 3328 6951 3001 6951 3329 6951 3330 6952 2992 6952 2983 6952 3329 6953 2992 6953 3330 6953 3331 6954 2983 6954 2972 6954 3330 6955 2983 6955 3331 6955 3332 6956 2972 6956 3080 6956 3331 6957 2972 6957 3332 6957 3077 6958 3333 6958 3080 6958 3334 6959 3080 6959 3333 6959 3332 6960 3080 6960 3334 6960 3335 6961 3336 6961 3333 6961 3337 6962 3333 6962 3336 6962 3077 6963 3335 6963 3333 6963 3334 6964 3333 6964 3337 6964 3338 6965 3339 6965 3336 6965 3340 6966 3336 6966 3339 6966 3335 6967 3338 6967 3336 6967 3337 6968 3336 6968 3340 6968 3341 6969 3342 6969 3339 6969 3343 6970 3339 6970 3342 6970 3338 6971 3341 6971 3339 6971 3340 6972 3339 6972 3343 6972 3344 6973 3345 6973 3342 6973 3346 6974 3342 6974 3345 6974 3341 6975 3344 6975 3342 6975 3343 6976 3342 6976 3346 6976 3347 6977 3345 6977 3344 6977 3346 6978 3345 6978 3347 6978 3348 6979 3344 6979 3341 6979 3347 6980 3344 6980 3348 6980 3349 6981 3341 6981 3338 6981 3348 6982 3341 6982 3349 6982 3350 6983 3338 6983 3335 6983 3349 6984 3338 6984 3350 6984 3351 6985 3335 6985 3077 6985 3350 6986 3335 6986 3351 6986 3352 6987 3077 6987 3092 6987 3351 6988 3077 6988 3352 6988 3353 6989 3092 6989 2956 6989 3352 6990 3092 6990 3353 6990 3354 6991 2956 6991 2950 6991 3353 6992 2956 6992 3354 6992 3355 6993 2950 6993 3015 6993 3354 6994 2950 6994 3355 6994 3356 6995 3015 6995 3027 6995 3355 6996 3015 6996 3356 6996 3357 6997 3027 6997 3052 6997 3356 6998 3027 6998 3357 6998 3358 6999 3052 6999 3107 6999 3357 7000 3052 7000 3358 7000 3359 7001 3107 7001 3137 7001 3358 7002 3107 7002 3359 7002 3360 7003 3137 7003 3320 7003 3359 7004 3137 7004 3360 7004 3361 7005 3320 7005 2832 7005 3360 7006 3320 7006 3361 7006 3362 7007 2832 7007 2839 7007 3363 7008 2884 7008 2832 7008 3364 7009 3363 7009 2832 7009 3365 7010 3364 7010 2832 7010 3366 7011 3365 7011 2832 7011 3367 7012 3366 7012 2832 7012 3322 7013 3367 7013 2832 7013 3368 7014 2832 7014 2872 7014 3369 7015 2849 7015 2832 7015 3370 7016 3369 7016 2832 7016 3368 7017 3370 7017 2832 7017 3361 7018 2832 7018 3362 7018 3371 7019 2839 7019 3279 7019 3372 7020 3311 7020 2839 7020 3373 7021 3372 7021 2839 7021 2836 7022 3373 7022 2839 7022 3362 7023 2839 7023 3371 7023 3374 7024 3279 7024 3306 7024 3371 7025 3279 7025 3374 7025 3375 7026 3376 7026 3306 7026 3377 7027 3306 7027 3376 7027 3375 7028 3306 7028 3227 7028 3374 7029 3306 7029 3377 7029 3208 7030 3378 7030 3376 7030 3379 7031 3376 7031 3378 7031 3375 7032 3208 7032 3376 7032 3377 7033 3376 7033 3379 7033 3208 7034 3203 7034 3378 7034 3380 7035 3378 7035 3203 7035 3379 7036 3378 7036 3380 7036 3381 7037 3203 7037 3150 7037 3380 7038 3203 7038 3381 7038 3382 7039 3150 7039 3144 7039 3381 7040 3150 7040 3382 7040 3383 7041 3144 7041 3167 7041 3382 7042 3144 7042 3383 7042 3384 7043 3167 7043 3169 7043 3383 7044 3167 7044 3384 7044 3158 7045 3385 7045 3169 7045 3386 7046 3169 7046 3385 7046 3384 7047 3169 7047 3386 7047 3158 7048 3387 7048 3385 7048 3388 7049 3385 7049 3387 7049 3386 7050 3385 7050 3388 7050 3158 7051 3389 7051 3387 7051 3390 7052 3387 7052 3389 7052 3391 7053 3387 7053 3390 7053 3388 7054 3387 7054 3391 7054 3158 7055 3392 7055 3389 7055 3390 7056 3389 7056 3392 7056 3158 7057 3393 7057 3392 7057 3394 7058 3392 7058 3393 7058 3390 7059 3392 7059 3394 7059 3158 7060 3395 7060 3393 7060 3396 7061 3393 7061 3395 7061 3394 7062 3393 7062 3396 7062 3158 7063 3397 7063 3395 7063 3398 7064 3395 7064 3397 7064 3396 7065 3395 7065 3398 7065 3399 7066 3397 7066 3158 7066 3400 7067 3397 7067 3399 7067 3398 7068 3397 7068 3400 7068 3399 7069 3158 7069 3155 7069 3401 7070 3155 7070 3170 7070 3399 7071 3155 7071 3401 7071 3402 7072 3170 7072 3290 7072 3401 7073 3170 7073 3402 7073 3403 7074 3290 7074 3289 7074 3402 7075 3290 7075 3403 7075 3404 7076 2912 7076 2911 7076 3405 7077 2908 7077 2912 7077 3405 7078 2912 7078 3406 7078 3404 7079 3406 7079 2912 7079 3404 7080 2911 7080 2883 7080 3407 7081 2883 7081 2884 7081 3404 7082 2883 7082 3407 7082 3408 7083 2884 7083 3363 7083 3407 7084 2884 7084 3408 7084 3409 7085 3363 7085 3364 7085 3408 7086 3363 7086 3409 7086 3410 7087 3364 7087 3365 7087 3409 7088 3364 7088 3410 7088 3411 7089 3365 7089 3366 7089 3410 7090 3365 7090 3411 7090 3412 7091 3366 7091 3367 7091 3411 7092 3366 7092 3412 7092 3413 7093 3367 7093 3322 7093 3414 7094 3367 7094 3413 7094 3412 7095 3367 7095 3414 7095 3413 7096 3322 7096 3323 7096 3415 7097 3323 7097 3324 7097 3413 7098 3323 7098 3415 7098 3416 7099 3324 7099 2913 7099 3415 7100 3324 7100 3416 7100 3417 7101 2913 7101 2916 7101 3416 7102 2913 7102 3417 7102 3418 7103 2916 7103 2917 7103 3417 7104 2916 7104 3418 7104 3419 7105 2917 7105 2908 7105 3418 7106 2917 7106 3419 7106 3419 7107 2908 7107 3405 7107 3420 7108 2899 7108 2894 7108 3420 7109 2897 7109 2899 7109 3421 7110 2894 7110 2927 7110 3421 7111 3420 7111 2894 7111 3422 7112 2927 7112 2926 7112 3421 7113 2927 7113 3422 7113 3423 7114 2926 7114 3312 7114 3422 7115 2926 7115 3423 7115 3424 7116 3312 7116 3313 7116 3423 7117 3312 7117 3424 7117 3425 7118 3313 7118 3314 7118 3424 7119 3313 7119 3425 7119 2938 7120 3426 7120 3314 7120 3427 7121 3314 7121 3426 7121 3425 7122 3314 7122 3427 7122 3428 7123 3429 7123 3426 7123 3430 7124 3426 7124 3429 7124 2938 7125 3428 7125 3426 7125 3431 7126 3426 7126 3430 7126 3427 7127 3426 7127 3431 7127 3432 7128 3433 7128 3429 7128 3430 7129 3429 7129 3433 7129 3434 7130 3432 7130 3429 7130 3428 7131 3434 7131 3429 7131 3432 7132 3435 7132 3433 7132 3436 7133 3433 7133 3435 7133 3430 7134 3433 7134 3436 7134 3437 7135 2872 7135 3435 7135 3438 7136 3435 7136 2872 7136 3432 7137 3437 7137 3435 7137 3436 7138 3435 7138 3438 7138 3439 7139 2872 7139 2900 7139 3437 7140 3368 7140 2872 7140 3438 7141 2872 7141 3439 7141 3440 7142 2900 7142 2901 7142 3439 7143 2900 7143 3440 7143 3441 7144 2901 7144 2902 7144 3440 7145 2901 7145 3441 7145 3442 7146 2902 7146 2897 7146 3441 7147 2902 7147 3442 7147 3443 7148 2897 7148 3420 7148 3442 7149 2897 7149 3443 7149 3444 7150 2937 7150 2936 7150 3445 7151 2933 7151 2937 7151 3445 7152 2937 7152 3446 7152 3444 7153 3446 7153 2937 7153 3444 7154 2936 7154 2848 7154 3447 7155 2848 7155 2850 7155 3444 7156 2848 7156 3447 7156 3448 7157 2850 7157 2849 7157 3447 7158 2850 7158 3448 7158 3449 7159 2849 7159 3369 7159 3448 7160 2849 7160 3449 7160 3450 7161 3369 7161 3370 7161 3449 7162 3369 7162 3450 7162 3451 7163 3370 7163 3368 7163 3450 7164 3370 7164 3451 7164 3452 7165 3368 7165 3437 7165 3451 7166 3368 7166 3452 7166 3453 7167 3437 7167 3432 7167 3454 7168 3437 7168 3453 7168 3452 7169 3437 7169 3454 7169 3453 7170 3432 7170 3434 7170 3455 7171 3434 7171 3428 7171 3453 7172 3434 7172 3455 7172 3456 7173 3428 7173 2938 7173 3455 7174 3428 7174 3456 7174 3457 7175 2938 7175 2941 7175 3456 7176 2938 7176 3457 7176 3458 7177 2941 7177 2942 7177 3457 7178 2941 7178 3458 7178 3459 7179 2942 7179 2933 7179 3458 7180 2942 7180 3459 7180 3459 7181 2933 7181 3445 7181 3460 7182 2865 7182 2860 7182 3460 7183 2863 7183 2865 7183 3461 7184 2860 7184 2949 7184 3461 7185 3460 7185 2860 7185 3462 7186 2949 7186 3315 7186 3461 7187 2949 7187 3462 7187 3463 7188 3315 7188 3316 7188 3464 7189 3315 7189 3463 7189 3462 7190 3315 7190 3464 7190 3463 7191 3316 7191 3317 7191 3465 7192 3317 7192 3318 7192 3463 7193 3317 7193 3465 7193 3466 7194 3318 7194 3319 7194 3465 7195 3318 7195 3466 7195 3467 7196 3319 7196 3311 7196 3468 7197 3319 7197 3467 7197 3466 7198 3319 7198 3468 7198 3467 7199 3311 7199 3372 7199 3469 7200 3372 7200 3373 7200 3467 7201 3372 7201 3469 7201 3470 7202 3373 7202 2836 7202 3469 7203 3373 7203 3470 7203 3471 7204 2836 7204 2866 7204 3472 7205 2836 7205 3471 7205 3470 7206 2836 7206 3472 7206 3471 7207 2866 7207 2867 7207 3473 7208 2867 7208 2868 7208 3471 7209 2867 7209 3473 7209 3474 7210 2868 7210 2863 7210 3473 7211 2868 7211 3474 7211 3475 7212 2863 7212 3460 7212 3474 7213 2863 7213 3475 7213 3476 7214 3227 7214 3223 7214 3477 7215 3375 7215 3227 7215 3477 7216 3227 7216 3476 7216 3478 7217 3223 7217 3208 7217 3478 7218 3476 7218 3223 7218 3479 7219 3208 7219 3375 7219 3478 7220 3208 7220 3479 7220 3479 7221 3375 7221 3477 7221 3371 7222 2838 7222 2835 7222 3450 7223 2835 7223 2841 7223 3450 7224 3371 7224 2835 7224 3371 7225 2864 7225 2838 7225 3371 7226 2862 7226 2864 7226 2929 7227 2859 7227 2862 7227 2948 7228 2929 7228 2862 7228 3474 7229 2948 7229 2862 7229 3473 7230 2862 7230 3371 7230 3473 7231 3474 7231 2862 7231 2928 7232 2856 7232 2859 7232 2929 7233 2928 7233 2859 7233 2930 7234 2853 7234 2856 7234 2930 7235 2856 7235 2928 7235 2932 7236 2846 7236 2853 7236 2930 7237 2932 7237 2853 7237 3445 7238 2843 7238 2846 7238 3445 7239 2846 7239 2932 7239 3447 7240 2841 7240 2843 7240 3445 7241 3446 7241 2843 7241 3444 7242 2843 7242 3446 7242 3444 7243 3447 7243 2843 7243 3449 7244 3450 7244 2841 7244 3448 7245 3449 7245 2841 7245 3447 7246 3448 7246 2841 7246 3371 7247 2874 7247 2871 7247 3410 7248 2871 7248 2876 7248 3362 7249 3371 7249 2871 7249 3410 7250 3362 7250 2871 7250 3371 7251 2898 7251 2874 7251 3371 7252 2896 7252 2898 7252 2904 7253 2893 7253 2896 7253 2925 7254 2904 7254 2896 7254 3442 7255 2925 7255 2896 7255 3440 7256 2896 7256 3371 7256 3441 7257 3442 7257 2896 7257 3440 7258 3441 7258 2896 7258 2903 7259 2890 7259 2893 7259 2904 7260 2903 7260 2893 7260 2905 7261 2887 7261 2890 7261 2905 7262 2890 7262 2903 7262 2907 7263 2881 7263 2887 7263 2905 7264 2907 7264 2887 7264 3405 7265 2878 7265 2881 7265 3405 7266 2881 7266 2907 7266 3407 7267 2876 7267 2878 7267 3405 7268 3406 7268 2878 7268 3404 7269 2878 7269 3406 7269 3404 7270 3407 7270 2878 7270 3409 7271 3410 7271 2876 7271 3408 7272 3409 7272 2876 7272 3407 7273 3408 7273 2876 7273 3442 7274 2924 7274 2925 7274 3420 7275 2923 7275 2924 7275 3443 7276 3420 7276 2924 7276 3442 7277 3443 7277 2924 7277 3424 7278 2920 7278 2923 7278 3421 7279 2923 7279 3420 7279 3423 7280 3424 7280 2923 7280 3422 7281 3423 7281 2923 7281 3421 7282 3422 7282 2923 7282 3321 7283 2915 7283 2920 7283 3424 7284 3321 7284 2920 7284 3321 7285 2910 7285 2915 7285 3321 7286 2907 7286 2910 7286 3419 7287 2907 7287 3321 7287 3419 7288 3405 7288 2907 7288 3474 7289 2947 7289 2948 7289 3460 7290 2946 7290 2947 7290 3475 7291 3460 7291 2947 7291 3474 7292 3475 7292 2947 7292 3463 7293 2944 7293 2946 7293 3461 7294 2946 7294 3460 7294 3464 7295 3463 7295 2946 7295 3462 7296 3464 7296 2946 7296 3461 7297 3462 7297 2946 7297 3321 7298 2940 7298 2944 7298 3310 7299 3321 7299 2944 7299 3463 7300 3310 7300 2944 7300 3321 7301 2935 7301 2940 7301 3321 7302 2932 7302 2935 7302 3458 7303 2932 7303 3321 7303 3459 7304 3445 7304 2932 7304 3458 7305 3459 7305 2932 7305 3356 7306 2955 7306 2953 7306 3355 7307 2953 7307 2958 7307 3355 7308 3356 7308 2953 7308 3356 7309 3026 7309 2955 7309 3356 7310 3025 7310 3026 7310 3356 7311 3023 7311 3025 7311 3357 7312 3021 7312 3023 7312 3356 7313 3357 7313 3023 7313 3035 7314 3019 7314 3021 7314 3357 7315 3035 7315 3021 7315 3035 7316 3017 7316 3019 7316 3035 7317 3013 7317 3017 7317 3056 7318 3010 7318 3013 7318 3035 7319 3038 7319 3013 7319 3056 7320 3013 7320 3038 7320 3330 7321 3008 7321 3010 7321 3330 7322 3010 7322 3056 7322 3330 7323 3006 7323 3008 7323 3330 7324 3003 7324 3006 7324 3330 7325 3000 7325 3003 7325 3331 7326 2998 7326 3000 7326 3330 7327 3331 7327 3000 7327 3331 7328 2996 7328 2998 7328 3331 7329 2994 7329 2996 7329 3331 7330 2991 7330 2994 7330 3332 7331 2989 7331 2991 7331 3331 7332 3332 7332 2991 7332 3332 7333 2987 7333 2989 7333 3332 7334 2985 7334 2987 7334 3332 7335 2982 7335 2985 7335 3089 7336 2980 7336 2982 7336 3332 7337 3089 7337 2982 7337 3089 7338 2978 7338 2980 7338 3089 7339 2974 7339 2978 7339 3354 7340 2971 7340 2974 7340 3089 7341 3091 7341 2974 7341 3105 7342 2974 7342 3091 7342 3354 7343 2974 7343 3105 7343 3354 7344 2969 7344 2971 7344 3354 7345 2967 7345 2969 7345 3354 7346 2964 7346 2967 7346 3355 7347 2962 7347 2964 7347 3354 7348 3355 7348 2964 7348 3355 7349 2960 7349 2962 7349 3355 7350 2958 7350 2960 7350 3358 7351 3032 7351 3030 7351 3357 7352 3030 7352 3034 7352 3357 7353 3358 7353 3030 7353 3358 7354 3051 7354 3032 7354 3358 7355 3050 7355 3051 7355 3054 7356 3047 7356 3050 7356 3066 7357 3054 7357 3050 7357 3358 7358 3066 7358 3050 7358 3053 7359 3044 7359 3047 7359 3054 7360 3053 7360 3047 7360 3055 7361 3041 7361 3044 7361 3055 7362 3044 7362 3053 7362 3056 7363 3038 7363 3041 7363 3055 7364 3056 7364 3041 7364 3357 7365 3034 7365 3035 7365 3358 7366 3065 7366 3066 7366 3329 7367 3064 7367 3065 7367 3328 7368 3065 7368 3358 7368 3328 7369 3329 7369 3065 7369 3329 7370 3062 7370 3064 7370 3329 7371 3060 7371 3062 7371 3330 7372 3058 7372 3060 7372 3329 7373 3330 7373 3060 7373 3330 7374 3056 7374 3058 7374 3104 7375 3073 7375 3070 7375 3103 7376 3070 7376 3076 7376 3103 7377 3104 7377 3070 7377 3105 7378 3091 7378 3073 7378 3104 7379 3105 7379 3073 7379 3334 7380 3088 7380 3089 7380 3332 7381 3334 7381 3089 7381 3334 7382 3086 7382 3088 7382 3334 7383 3084 7383 3086 7383 3337 7384 3082 7384 3084 7384 3334 7385 3337 7385 3084 7385 3337 7386 3079 7386 3082 7386 3102 7387 3076 7387 3079 7387 3101 7388 3102 7388 3079 7388 3337 7389 3101 7389 3079 7389 3102 7390 3103 7390 3076 7390 3354 7391 3097 7391 3095 7391 3353 7392 3095 7392 3099 7392 3353 7393 3354 7393 3095 7393 3354 7394 3106 7394 3097 7394 3354 7395 3105 7395 3106 7395 3337 7396 3100 7396 3101 7396 3353 7397 3099 7397 3100 7397 3337 7398 3353 7398 3100 7398 3360 7399 3112 7399 3110 7399 3359 7400 3110 7400 3114 7400 3359 7401 3360 7401 3110 7401 3360 7402 3143 7402 3112 7402 3360 7403 3142 7403 3143 7403 3360 7404 3139 7404 3142 7404 3326 7405 3136 7405 3139 7405 3360 7406 3361 7406 3139 7406 3326 7407 3139 7407 3361 7407 3327 7408 3134 7408 3136 7408 3326 7409 3327 7409 3136 7409 3327 7410 3132 7410 3134 7410 3327 7411 3130 7411 3132 7411 3327 7412 3127 7412 3130 7412 3328 7413 3125 7413 3127 7413 3327 7414 3328 7414 3127 7414 3328 7415 3123 7415 3125 7415 3328 7416 3120 7416 3123 7416 3358 7417 3118 7417 3120 7417 3328 7418 3358 7418 3120 7418 3359 7419 3116 7419 3118 7419 3358 7420 3359 7420 3118 7420 3359 7421 3114 7421 3116 7421 3384 7422 3149 7422 3147 7422 3383 7423 3147 7423 3152 7423 3383 7424 3384 7424 3147 7424 3384 7425 3168 7425 3149 7425 3386 7426 3166 7426 3168 7426 3384 7427 3386 7427 3168 7427 3390 7428 3164 7428 3166 7428 3391 7429 3390 7429 3166 7429 3388 7430 3391 7430 3166 7430 3386 7431 3388 7431 3166 7431 3401 7432 3162 7432 3164 7432 3394 7433 3401 7433 3164 7433 3390 7434 3394 7434 3164 7434 3401 7435 3160 7435 3162 7435 3401 7436 3157 7436 3160 7436 3401 7437 3154 7437 3157 7437 3383 7438 3152 7438 3154 7438 3383 7439 3154 7439 3401 7439 3403 7440 3175 7440 3173 7440 3403 7441 3173 7441 3177 7441 3403 7442 3194 7442 3175 7442 3403 7443 3192 7443 3194 7443 3299 7444 3189 7444 3192 7444 3298 7445 3192 7445 3403 7445 3298 7446 3299 7446 3192 7446 3300 7447 3187 7447 3189 7447 3299 7448 3300 7448 3189 7448 3300 7449 3184 7449 3187 7449 3301 7450 3182 7450 3184 7450 3300 7451 3301 7451 3184 7451 3301 7452 3179 7452 3182 7452 3402 7453 3177 7453 3179 7453 3301 7454 3402 7454 3179 7454 3402 7455 3403 7455 3177 7455 3383 7456 3202 7456 3200 7456 3382 7457 3200 7457 3205 7457 3382 7458 3383 7458 3200 7458 3383 7459 3222 7459 3202 7459 3383 7460 3221 7460 3222 7460 3226 7461 3219 7461 3221 7461 3243 7462 3226 7462 3221 7462 3401 7463 3243 7463 3221 7463 3383 7464 3401 7464 3221 7464 3225 7465 3215 7465 3219 7465 3226 7466 3225 7466 3219 7466 3479 7467 3212 7467 3215 7467 3478 7468 3215 7468 3225 7468 3478 7469 3479 7469 3215 7469 3477 7470 3210 7470 3212 7470 3479 7471 3477 7471 3212 7471 3477 7472 3207 7472 3210 7472 3382 7473 3205 7473 3207 7473 3381 7474 3382 7474 3207 7474 3477 7475 3381 7475 3207 7475 3478 7476 3225 7476 3229 7476 3401 7477 3242 7477 3243 7477 3301 7478 3241 7478 3242 7478 3401 7479 3402 7479 3242 7479 3301 7480 3242 7480 3402 7480 3301 7481 3239 7481 3241 7481 3301 7482 3237 7482 3239 7482 3303 7483 3234 7483 3237 7483 3301 7484 3303 7484 3237 7484 3303 7485 3231 7485 3234 7485 3478 7486 3229 7486 3231 7486 3478 7487 3231 7487 3303 7487 3374 7488 3248 7488 3246 7488 3374 7489 3246 7489 3250 7489 3374 7490 3286 7490 3248 7490 3377 7491 3285 7491 3286 7491 3374 7492 3377 7492 3286 7492 3377 7493 3283 7493 3285 7493 3377 7494 3281 7494 3283 7494 3309 7495 3278 7495 3281 7495 3309 7496 3281 7496 3377 7496 3309 7497 3276 7497 3278 7497 3309 7498 3274 7498 3276 7498 3309 7499 3271 7499 3274 7499 3310 7500 3269 7500 3271 7500 3309 7501 3310 7501 3271 7501 3310 7502 3267 7502 3269 7502 3310 7503 3265 7503 3267 7503 3310 7504 3263 7504 3265 7504 3310 7505 3261 7505 3263 7505 3310 7506 3258 7506 3261 7506 3371 7507 3256 7507 3258 7507 3310 7508 3371 7508 3258 7508 3374 7509 3254 7509 3256 7509 3371 7510 3374 7510 3256 7510 3374 7511 3252 7511 3254 7511 3374 7512 3250 7512 3252 7512 3292 7513 3403 7513 3289 7513 3297 7514 3298 7514 3403 7514 3295 7515 3297 7515 3403 7515 3296 7516 3295 7516 3403 7516 3294 7517 3296 7517 3403 7517 3293 7518 3294 7518 3403 7518 3292 7519 3293 7519 3403 7519 3400 7520 3399 7520 3401 7520 3398 7521 3400 7521 3401 7521 3396 7522 3398 7522 3401 7522 3394 7523 3396 7523 3401 7523 3477 7524 3380 7524 3381 7524 3477 7525 3379 7525 3380 7525 3308 7526 3377 7526 3379 7526 3477 7527 3308 7527 3379 7527 3308 7528 3309 7528 3377 7528 3468 7529 3371 7529 3310 7529 3439 7530 3440 7530 3371 7530 3438 7531 3439 7531 3371 7531 3436 7532 3438 7532 3371 7532 3450 7533 3436 7533 3371 7533 3471 7534 3473 7534 3371 7534 3472 7535 3471 7535 3371 7535 3470 7536 3472 7536 3371 7536 3469 7537 3470 7537 3371 7537 3467 7538 3469 7538 3371 7538 3468 7539 3467 7539 3371 7539 3325 7540 3361 7540 3362 7540 3321 7541 3325 7541 3362 7541 3414 7542 3321 7542 3362 7542 3412 7543 3414 7543 3362 7543 3411 7544 3412 7544 3362 7544 3410 7545 3411 7545 3362 7545 3325 7546 3326 7546 3361 7546 3337 7547 3352 7547 3353 7547 3340 7548 3351 7548 3352 7548 3337 7549 3340 7549 3352 7549 3343 7550 3350 7550 3351 7550 3340 7551 3343 7551 3351 7551 3346 7552 3349 7552 3350 7552 3343 7553 3346 7553 3350 7553 3347 7554 3348 7554 3349 7554 3346 7555 3347 7555 3349 7555 3418 7556 3419 7556 3321 7556 3417 7557 3418 7557 3321 7557 3416 7558 3417 7558 3321 7558 3415 7559 3416 7559 3321 7559 3413 7560 3415 7560 3321 7560 3414 7561 3413 7561 3321 7561 3455 7562 3321 7562 3424 7562 3457 7563 3458 7563 3321 7563 3456 7564 3457 7564 3321 7564 3455 7565 3456 7565 3321 7565 3466 7566 3468 7566 3310 7566 3465 7567 3466 7567 3310 7567 3463 7568 3465 7568 3310 7568 3476 7569 3307 7569 3308 7569 3477 7570 3476 7570 3308 7570 3478 7571 3305 7571 3307 7571 3478 7572 3307 7572 3476 7572 3478 7573 3303 7573 3305 7573 3450 7574 3430 7574 3436 7574 3451 7575 3431 7575 3430 7575 3450 7576 3451 7576 3430 7576 3454 7577 3427 7577 3431 7577 3452 7578 3454 7578 3431 7578 3451 7579 3452 7579 3431 7579 3454 7580 3425 7580 3427 7580 3453 7581 3424 7581 3425 7581 3454 7582 3453 7582 3425 7582 3453 7583 3455 7583 3424 7583 3480 7584 3481 7584 3482 7584 3483 7585 3482 7585 3481 7585 3484 7586 3482 7586 3485 7586 3486 7587 3485 7587 3482 7587 3484 7588 3480 7588 3482 7588 3486 7589 3482 7589 3483 7589 3487 7590 3488 7590 3481 7590 3489 7591 3481 7591 3488 7591 3480 7592 3487 7592 3481 7592 3489 7593 3483 7593 3481 7593 3490 7594 3491 7594 3488 7594 3492 7595 3488 7595 3491 7595 3487 7596 3490 7596 3488 7596 3489 7597 3488 7597 3492 7597 3493 7598 3494 7598 3491 7598 3495 7599 3491 7599 3494 7599 3496 7600 3491 7600 3490 7600 3497 7601 3491 7601 3496 7601 3497 7602 3493 7602 3491 7602 3492 7603 3491 7603 3495 7603 3493 7604 3498 7604 3494 7604 3499 7605 3494 7605 3498 7605 3495 7606 3494 7606 3499 7606 3500 7607 3501 7607 3498 7607 3502 7608 3498 7608 3501 7608 3493 7609 3500 7609 3498 7609 3499 7610 3498 7610 3502 7610 3500 7611 3503 7611 3501 7611 3504 7612 3501 7612 3503 7612 3502 7613 3501 7613 3504 7613 3500 7614 3505 7614 3503 7614 3506 7615 3503 7615 3505 7615 3504 7616 3503 7616 3506 7616 3500 7617 3507 7617 3505 7617 3508 7618 3505 7618 3507 7618 3506 7619 3505 7619 3508 7619 3500 7620 3509 7620 3507 7620 3510 7621 3507 7621 3509 7621 3508 7622 3507 7622 3510 7622 3511 7623 3512 7623 3509 7623 3513 7624 3509 7624 3512 7624 3511 7625 3509 7625 3514 7625 3500 7626 3514 7626 3509 7626 3510 7627 3509 7627 3513 7627 3515 7628 3516 7628 3512 7628 3517 7629 3512 7629 3516 7629 3511 7630 3515 7630 3512 7630 3513 7631 3512 7631 3517 7631 3518 7632 3485 7632 3516 7632 3519 7633 3516 7633 3485 7633 3515 7634 3518 7634 3516 7634 3517 7635 3516 7635 3519 7635 3518 7636 3484 7636 3485 7636 3519 7637 3485 7637 3486 7637 3520 7638 3521 7638 3522 7638 3523 7639 3522 7639 3521 7639 3524 7640 3522 7640 3525 7640 3526 7641 3525 7641 3522 7641 3520 7642 3522 7642 3524 7642 3526 7643 3522 7643 3523 7643 3527 7644 3528 7644 3521 7644 3529 7645 3521 7645 3528 7645 3530 7646 3521 7646 3520 7646 3530 7647 3527 7647 3521 7647 3529 7648 3523 7648 3521 7648 3527 7649 3531 7649 3528 7649 3532 7650 3528 7650 3531 7650 3529 7651 3528 7651 3532 7651 3533 7652 3534 7652 3531 7652 3535 7653 3531 7653 3534 7653 3527 7654 3533 7654 3531 7654 3532 7655 3531 7655 3535 7655 3536 7656 3537 7656 3534 7656 3538 7657 3534 7657 3537 7657 3533 7658 3536 7658 3534 7658 3535 7659 3534 7659 3538 7659 3539 7660 3540 7660 3537 7660 3541 7661 3537 7661 3540 7661 3542 7662 3539 7662 3537 7662 3543 7663 3542 7663 3537 7663 3544 7664 3543 7664 3537 7664 3545 7665 3544 7665 3537 7665 3536 7666 3545 7666 3537 7666 3538 7667 3537 7667 3541 7667 3546 7668 3547 7668 3540 7668 3548 7669 3540 7669 3547 7669 3539 7670 3546 7670 3540 7670 3541 7671 3540 7671 3548 7671 3549 7672 3550 7672 3547 7672 3551 7673 3547 7673 3550 7673 3552 7674 3549 7674 3547 7674 3546 7675 3552 7675 3547 7675 3548 7676 3547 7676 3551 7676 3553 7677 3554 7677 3550 7677 3555 7678 3550 7678 3554 7678 3549 7679 3553 7679 3550 7679 3551 7680 3550 7680 3555 7680 3556 7681 3557 7681 3554 7681 3558 7682 3554 7682 3557 7682 3553 7683 3556 7683 3554 7683 3555 7684 3554 7684 3558 7684 3559 7685 3560 7685 3557 7685 3561 7686 3557 7686 3560 7686 3556 7687 3559 7687 3557 7687 3558 7688 3557 7688 3561 7688 3562 7689 3563 7689 3560 7689 3564 7690 3560 7690 3563 7690 3559 7691 3562 7691 3560 7691 3561 7692 3560 7692 3564 7692 3565 7693 3525 7693 3563 7693 3566 7694 3563 7694 3525 7694 3562 7695 3565 7695 3563 7695 3564 7696 3563 7696 3566 7696 3565 7697 3524 7697 3525 7697 3566 7698 3525 7698 3526 7698 3567 7699 3524 7699 3565 7699 3520 7700 3524 7700 3568 7700 3569 7701 3568 7701 3524 7701 3569 7702 3524 7702 3567 7702 3570 7703 3565 7703 3562 7703 3570 7704 3567 7704 3565 7704 3571 7705 3562 7705 3559 7705 3570 7706 3562 7706 3571 7706 3572 7707 3559 7707 3556 7707 3571 7708 3559 7708 3572 7708 3573 7709 3556 7709 3553 7709 3572 7710 3556 7710 3573 7710 3574 7711 3553 7711 3549 7711 3573 7712 3553 7712 3574 7712 3575 7713 3549 7713 3552 7713 3574 7714 3549 7714 3575 7714 3576 7715 3577 7715 3552 7715 3578 7716 3552 7716 3577 7716 3579 7717 3576 7717 3552 7717 3546 7718 3579 7718 3552 7718 3575 7719 3552 7719 3578 7719 3576 7720 3580 7720 3577 7720 3581 7721 3577 7721 3580 7721 3578 7722 3577 7722 3581 7722 3520 7723 3582 7723 3580 7723 3583 7724 3580 7724 3582 7724 3576 7725 3520 7725 3580 7725 3581 7726 3580 7726 3583 7726 3520 7727 3584 7727 3582 7727 3585 7728 3582 7728 3584 7728 3583 7729 3582 7729 3585 7729 3520 7730 3586 7730 3584 7730 3587 7731 3584 7731 3586 7731 3585 7732 3584 7732 3587 7732 3520 7733 3568 7733 3586 7733 3588 7734 3586 7734 3568 7734 3587 7735 3586 7735 3588 7735 3588 7736 3568 7736 3569 7736 3500 7737 3589 7737 3514 7737 3590 7738 3514 7738 3589 7738 3591 7739 3511 7739 3514 7739 3591 7740 3514 7740 3590 7740 3592 7741 3593 7741 3589 7741 3594 7742 3589 7742 3593 7742 3595 7743 3592 7743 3589 7743 3500 7744 3595 7744 3589 7744 3594 7745 3590 7745 3589 7745 3592 7746 3596 7746 3593 7746 3597 7747 3593 7747 3596 7747 3594 7748 3593 7748 3597 7748 3592 7749 3598 7749 3596 7749 3599 7750 3596 7750 3598 7750 3597 7751 3596 7751 3599 7751 3600 7752 3601 7752 3598 7752 3602 7753 3598 7753 3601 7753 3592 7754 3600 7754 3598 7754 3599 7755 3598 7755 3602 7755 3603 7756 3604 7756 3601 7756 3605 7757 3601 7757 3604 7757 3606 7758 3603 7758 3601 7758 3607 7759 3606 7759 3601 7759 3608 7760 3607 7760 3601 7760 3609 7761 3608 7761 3601 7761 3600 7762 3609 7762 3601 7762 3602 7763 3601 7763 3605 7763 3496 7764 3490 7764 3604 7764 3610 7765 3604 7765 3490 7765 3603 7766 3496 7766 3604 7766 3605 7767 3604 7767 3610 7767 3611 7768 3490 7768 3487 7768 3610 7769 3490 7769 3611 7769 3612 7770 3487 7770 3480 7770 3611 7771 3487 7771 3612 7771 3613 7772 3480 7772 3484 7772 3612 7773 3480 7773 3613 7773 3614 7774 3484 7774 3518 7774 3613 7775 3484 7775 3614 7775 3615 7776 3518 7776 3515 7776 3614 7777 3518 7777 3615 7777 3616 7778 3515 7778 3511 7778 3615 7779 3515 7779 3616 7779 3616 7780 3511 7780 3591 7780 3617 7781 3618 7781 3619 7781 3620 7782 3619 7782 3618 7782 3621 7783 3617 7783 3619 7783 3621 7784 3619 7784 3620 7784 3622 7785 3623 7785 3618 7785 3624 7786 3618 7786 3623 7786 3625 7787 3622 7787 3618 7787 3617 7788 3625 7788 3618 7788 3624 7789 3620 7789 3618 7789 3626 7790 3627 7790 3623 7790 3628 7791 3623 7791 3627 7791 3622 7792 3626 7792 3623 7792 3624 7793 3623 7793 3628 7793 3497 7794 3496 7794 3627 7794 3629 7795 3627 7795 3496 7795 3630 7796 3497 7796 3627 7796 3631 7797 3630 7797 3627 7797 3626 7798 3631 7798 3627 7798 3628 7799 3627 7799 3629 7799 3632 7800 3496 7800 3603 7800 3629 7801 3496 7801 3632 7801 3633 7802 3603 7802 3606 7802 3632 7803 3603 7803 3633 7803 3634 7804 3606 7804 3607 7804 3633 7805 3606 7805 3634 7805 3635 7806 3607 7806 3608 7806 3634 7807 3607 7807 3635 7807 3636 7808 3608 7808 3609 7808 3635 7809 3608 7809 3636 7809 3637 7810 3609 7810 3600 7810 3636 7811 3609 7811 3637 7811 3638 7812 3600 7812 3592 7812 3637 7813 3600 7813 3638 7813 3639 7814 3592 7814 3595 7814 3638 7815 3592 7815 3639 7815 3640 7816 3641 7816 3595 7816 3642 7817 3595 7817 3641 7817 3643 7818 3640 7818 3595 7818 3500 7819 3643 7819 3595 7819 3639 7820 3595 7820 3642 7820 3644 7821 3645 7821 3641 7821 3646 7822 3641 7822 3645 7822 3640 7823 3644 7823 3641 7823 3642 7824 3641 7824 3646 7824 3647 7825 3645 7825 3644 7825 3646 7826 3645 7826 3647 7826 3648 7827 3644 7827 3640 7827 3647 7828 3644 7828 3648 7828 3649 7829 3640 7829 3643 7829 3648 7830 3640 7830 3649 7830 3650 7831 3520 7831 3643 7831 3651 7832 3643 7832 3520 7832 3500 7833 3650 7833 3643 7833 3649 7834 3643 7834 3651 7834 3652 7835 3520 7835 3576 7835 3650 7836 3530 7836 3520 7836 3651 7837 3520 7837 3652 7837 3653 7838 3576 7838 3579 7838 3652 7839 3576 7839 3653 7839 3546 7840 3654 7840 3579 7840 3655 7841 3579 7841 3654 7841 3653 7842 3579 7842 3655 7842 3546 7843 3656 7843 3654 7843 3657 7844 3654 7844 3656 7844 3655 7845 3654 7845 3657 7845 3546 7846 3658 7846 3656 7846 3659 7847 3656 7847 3658 7847 3657 7848 3656 7848 3659 7848 3660 7849 3661 7849 3658 7849 3662 7850 3658 7850 3661 7850 3546 7851 3660 7851 3658 7851 3659 7852 3658 7852 3662 7852 3663 7853 3664 7853 3661 7853 3665 7854 3661 7854 3664 7854 3660 7855 3663 7855 3661 7855 3662 7856 3661 7856 3665 7856 3666 7857 3667 7857 3664 7857 3668 7858 3664 7858 3667 7858 3663 7859 3666 7859 3664 7859 3665 7860 3664 7860 3668 7860 3666 7861 3669 7861 3667 7861 3670 7862 3667 7862 3669 7862 3668 7863 3667 7863 3670 7863 3666 7864 3671 7864 3669 7864 3672 7865 3669 7865 3671 7865 3670 7866 3669 7866 3672 7866 3673 7867 3671 7867 3666 7867 3672 7868 3671 7868 3673 7868 3663 7869 3674 7869 3666 7869 3675 7870 3666 7870 3674 7870 3673 7871 3666 7871 3675 7871 3676 7872 3674 7872 3663 7872 3675 7873 3674 7873 3676 7873 3677 7874 3663 7874 3660 7874 3676 7875 3663 7875 3677 7875 3678 7876 3660 7876 3546 7876 3677 7877 3660 7877 3678 7877 3679 7878 3546 7878 3539 7878 3678 7879 3546 7879 3679 7879 3680 7880 3539 7880 3542 7880 3679 7881 3539 7881 3680 7881 3681 7882 3542 7882 3543 7882 3680 7883 3542 7883 3681 7883 3682 7884 3543 7884 3544 7884 3681 7885 3543 7885 3682 7885 3683 7886 3544 7886 3545 7886 3682 7887 3544 7887 3683 7887 3684 7888 3545 7888 3536 7888 3683 7889 3545 7889 3684 7889 3685 7890 3536 7890 3533 7890 3684 7891 3536 7891 3685 7891 3686 7892 3533 7892 3527 7892 3685 7893 3533 7893 3686 7893 3687 7894 3527 7894 3530 7894 3686 7895 3527 7895 3687 7895 3688 7896 3689 7896 3530 7896 3690 7897 3530 7897 3689 7897 3650 7898 3688 7898 3530 7898 3687 7899 3530 7899 3690 7899 3691 7900 3692 7900 3689 7900 3693 7901 3689 7901 3692 7901 3688 7902 3691 7902 3689 7902 3690 7903 3689 7903 3693 7903 3694 7904 3692 7904 3691 7904 3693 7905 3692 7905 3694 7905 3695 7906 3691 7906 3688 7906 3694 7907 3691 7907 3695 7907 3696 7908 3688 7908 3650 7908 3695 7909 3688 7909 3696 7909 3697 7910 3650 7910 3500 7910 3696 7911 3650 7911 3697 7911 3698 7912 3500 7912 3493 7912 3697 7913 3500 7913 3698 7913 3699 7914 3493 7914 3497 7914 3698 7915 3493 7915 3699 7915 3700 7916 3497 7916 3630 7916 3699 7917 3497 7917 3700 7917 3701 7918 3630 7918 3631 7918 3700 7919 3630 7919 3701 7919 3702 7920 3631 7920 3626 7920 3701 7921 3631 7921 3702 7921 3703 7922 3626 7922 3622 7922 3702 7923 3626 7923 3703 7923 3704 7924 3622 7924 3625 7924 3703 7925 3622 7925 3704 7925 3617 7926 3705 7926 3625 7926 3706 7927 3625 7927 3705 7927 3704 7928 3625 7928 3706 7928 3617 7929 3707 7929 3705 7929 3708 7930 3705 7930 3707 7930 3706 7931 3705 7931 3708 7931 3617 7932 3709 7932 3707 7932 3710 7933 3707 7933 3709 7933 3708 7934 3707 7934 3710 7934 3711 7935 3709 7935 3617 7935 3710 7936 3709 7936 3711 7936 3711 7937 3617 7937 3621 7937 3615 7938 3486 7938 3483 7938 3614 7939 3483 7939 3489 7939 3614 7940 3615 7940 3483 7940 3616 7941 3519 7941 3486 7941 3615 7942 3616 7942 3486 7942 3591 7943 3517 7943 3519 7943 3616 7944 3591 7944 3519 7944 3590 7945 3513 7945 3517 7945 3591 7946 3590 7946 3517 7946 3642 7947 3510 7947 3513 7947 3642 7948 3513 7948 3590 7948 3698 7949 3508 7949 3510 7949 3642 7950 3698 7950 3510 7950 3698 7951 3506 7951 3508 7951 3698 7952 3504 7952 3506 7952 3699 7953 3502 7953 3504 7953 3698 7954 3699 7954 3504 7954 3699 7955 3499 7955 3502 7955 3700 7956 3495 7956 3499 7956 3699 7957 3700 7957 3499 7957 3612 7958 3492 7958 3495 7958 3611 7959 3612 7959 3495 7959 3700 7960 3611 7960 3495 7960 3613 7961 3489 7961 3492 7961 3612 7962 3613 7962 3492 7962 3613 7963 3614 7963 3489 7963 3570 7964 3526 7964 3523 7964 3690 7965 3523 7965 3529 7965 3570 7966 3523 7966 3567 7966 3690 7967 3567 7967 3523 7967 3571 7968 3566 7968 3526 7968 3570 7969 3571 7969 3526 7969 3572 7970 3564 7970 3566 7970 3571 7971 3572 7971 3566 7971 3573 7972 3561 7972 3564 7972 3572 7973 3573 7973 3564 7973 3574 7974 3558 7974 3561 7974 3573 7975 3574 7975 3561 7975 3575 7976 3555 7976 3558 7976 3574 7977 3575 7977 3558 7977 3578 7978 3551 7978 3555 7978 3575 7979 3578 7979 3555 7979 3680 7980 3548 7980 3551 7980 3655 7981 3551 7981 3578 7981 3659 7982 3680 7982 3551 7982 3657 7983 3659 7983 3551 7983 3655 7984 3657 7984 3551 7984 3683 7985 3541 7985 3548 7985 3682 7986 3683 7986 3548 7986 3681 7987 3682 7987 3548 7987 3680 7988 3681 7988 3548 7988 3685 7989 3538 7989 3541 7989 3684 7990 3685 7990 3541 7990 3683 7991 3684 7991 3541 7991 3687 7992 3535 7992 3538 7992 3686 7993 3687 7993 3538 7993 3685 7994 3686 7994 3538 7994 3690 7995 3532 7995 3535 7995 3687 7996 3690 7996 3535 7996 3690 7997 3529 7997 3532 7997 3690 7998 3569 7998 3567 7998 3652 7999 3588 7999 3569 7999 3652 8000 3569 8000 3690 8000 3652 8001 3587 8001 3588 8001 3652 8002 3585 8002 3587 8002 3653 8003 3583 8003 3585 8003 3652 8004 3653 8004 3585 8004 3653 8005 3581 8005 3583 8005 3655 8006 3578 8006 3581 8006 3653 8007 3655 8007 3581 8007 3642 8008 3590 8008 3594 8008 3633 8009 3610 8009 3611 8009 3632 8010 3611 8010 3700 8010 3632 8011 3633 8011 3611 8011 3637 8012 3605 8012 3610 8012 3636 8013 3637 8013 3610 8013 3635 8014 3636 8014 3610 8014 3634 8015 3635 8015 3610 8015 3633 8016 3634 8016 3610 8016 3639 8017 3602 8017 3605 8017 3638 8018 3639 8018 3605 8018 3637 8019 3638 8019 3605 8019 3639 8020 3599 8020 3602 8020 3642 8021 3597 8021 3599 8021 3639 8022 3642 8022 3599 8022 3642 8023 3594 8023 3597 8023 3708 8024 3621 8024 3620 8024 3706 8025 3708 8025 3620 8025 3624 8026 3706 8026 3620 8026 3710 8027 3711 8027 3621 8027 3708 8028 3710 8028 3621 8028 3624 8029 3704 8029 3706 8029 3628 8030 3703 8030 3704 8030 3624 8031 3628 8031 3704 8031 3632 8032 3702 8032 3703 8032 3628 8033 3632 8033 3703 8033 3632 8034 3701 8034 3702 8034 3632 8035 3700 8035 3701 8035 3651 8036 3697 8036 3698 8036 3651 8037 3698 8037 3642 8037 3642 8038 3649 8038 3651 8038 3697 8039 3652 8039 3690 8039 3651 8040 3652 8040 3697 8040 3694 8041 3695 8041 3696 8041 3693 8042 3694 8042 3696 8042 3690 8043 3693 8043 3696 8043 3690 8044 3696 8044 3697 8044 3678 8045 3679 8045 3680 8045 3662 8046 3678 8046 3680 8046 3659 8047 3662 8047 3680 8047 3665 8048 3677 8048 3678 8048 3662 8049 3665 8049 3678 8049 3668 8050 3676 8050 3677 8050 3665 8051 3668 8051 3677 8051 3670 8052 3675 8052 3676 8052 3668 8053 3670 8053 3676 8053 3672 8054 3673 8054 3675 8054 3670 8055 3672 8055 3675 8055 3647 8056 3648 8056 3649 8056 3646 8057 3647 8057 3649 8057 3642 8058 3646 8058 3649 8058 3628 8059 3629 8059 3632 8059 3712 8060 3713 8060 3714 8060 3715 8061 3714 8061 3713 8061 3716 8062 3714 8062 3717 8062 3718 8063 3717 8063 3714 8063 3716 8064 3712 8064 3714 8064 3718 8065 3714 8065 3715 8065 3719 8066 3720 8066 3713 8066 3721 8067 3713 8067 3720 8067 3712 8068 3719 8068 3713 8068 3721 8069 3715 8069 3713 8069 3722 8070 3723 8070 3720 8070 3724 8071 3720 8071 3723 8071 3719 8072 3722 8072 3720 8072 3721 8073 3720 8073 3724 8073 3725 8074 3726 8074 3723 8074 3727 8075 3723 8075 3726 8075 3728 8076 3723 8076 3722 8076 3729 8077 3723 8077 3728 8077 3729 8078 3725 8078 3723 8078 3724 8079 3723 8079 3727 8079 3725 8080 3730 8080 3726 8080 3731 8081 3726 8081 3730 8081 3727 8082 3726 8082 3731 8082 3732 8083 3733 8083 3730 8083 3734 8084 3730 8084 3733 8084 3725 8085 3732 8085 3730 8085 3731 8086 3730 8086 3734 8086 3732 8087 3735 8087 3733 8087 3736 8088 3733 8088 3735 8088 3734 8089 3733 8089 3736 8089 3732 8090 3737 8090 3735 8090 3738 8091 3735 8091 3737 8091 3736 8092 3735 8092 3738 8092 3732 8093 3739 8093 3737 8093 3740 8094 3737 8094 3739 8094 3738 8095 3737 8095 3740 8095 3732 8096 3741 8096 3739 8096 3742 8097 3739 8097 3741 8097 3740 8098 3739 8098 3742 8098 3743 8099 3744 8099 3741 8099 3745 8100 3741 8100 3744 8100 3743 8101 3741 8101 3746 8101 3732 8102 3746 8102 3741 8102 3742 8103 3741 8103 3745 8103 3747 8104 3748 8104 3744 8104 3749 8105 3744 8105 3748 8105 3743 8106 3747 8106 3744 8106 3745 8107 3744 8107 3749 8107 3750 8108 3717 8108 3748 8108 3751 8109 3748 8109 3717 8109 3747 8110 3750 8110 3748 8110 3749 8111 3748 8111 3751 8111 3750 8112 3716 8112 3717 8112 3751 8113 3717 8113 3718 8113 3752 8114 3753 8114 3754 8114 3755 8115 3754 8115 3753 8115 3756 8116 3754 8116 3757 8116 3758 8117 3757 8117 3754 8117 3752 8118 3754 8118 3756 8118 3758 8119 3754 8119 3755 8119 3759 8120 3760 8120 3753 8120 3761 8121 3753 8121 3760 8121 3762 8122 3753 8122 3752 8122 3762 8123 3759 8123 3753 8123 3761 8124 3755 8124 3753 8124 3759 8125 3763 8125 3760 8125 3764 8126 3760 8126 3763 8126 3761 8127 3760 8127 3764 8127 3765 8128 3766 8128 3763 8128 3767 8129 3763 8129 3766 8129 3759 8130 3765 8130 3763 8130 3764 8131 3763 8131 3767 8131 3768 8132 3769 8132 3766 8132 3770 8133 3766 8133 3769 8133 3765 8134 3768 8134 3766 8134 3767 8135 3766 8135 3770 8135 3771 8136 3772 8136 3769 8136 3773 8137 3769 8137 3772 8137 3774 8138 3771 8138 3769 8138 3775 8139 3774 8139 3769 8139 3776 8140 3775 8140 3769 8140 3777 8141 3776 8141 3769 8141 3768 8142 3777 8142 3769 8142 3770 8143 3769 8143 3773 8143 3778 8144 3779 8144 3772 8144 3780 8145 3772 8145 3779 8145 3771 8146 3778 8146 3772 8146 3773 8147 3772 8147 3780 8147 3781 8148 3782 8148 3779 8148 3783 8149 3779 8149 3782 8149 3784 8150 3781 8150 3779 8150 3778 8151 3784 8151 3779 8151 3780 8152 3779 8152 3783 8152 3785 8153 3786 8153 3782 8153 3787 8154 3782 8154 3786 8154 3781 8155 3785 8155 3782 8155 3783 8156 3782 8156 3787 8156 3788 8157 3789 8157 3786 8157 3790 8158 3786 8158 3789 8158 3785 8159 3788 8159 3786 8159 3787 8160 3786 8160 3790 8160 3791 8161 3792 8161 3789 8161 3793 8162 3789 8162 3792 8162 3788 8163 3791 8163 3789 8163 3790 8164 3789 8164 3793 8164 3794 8165 3795 8165 3792 8165 3796 8166 3792 8166 3795 8166 3791 8167 3794 8167 3792 8167 3793 8168 3792 8168 3796 8168 3797 8169 3757 8169 3795 8169 3798 8170 3795 8170 3757 8170 3794 8171 3797 8171 3795 8171 3796 8172 3795 8172 3798 8172 3797 8173 3756 8173 3757 8173 3798 8174 3757 8174 3758 8174 3799 8175 3756 8175 3797 8175 3752 8176 3756 8176 3800 8176 3801 8177 3800 8177 3756 8177 3801 8178 3756 8178 3799 8178 3802 8179 3797 8179 3794 8179 3802 8180 3799 8180 3797 8180 3803 8181 3794 8181 3791 8181 3802 8182 3794 8182 3803 8182 3804 8183 3791 8183 3788 8183 3803 8184 3791 8184 3804 8184 3805 8185 3788 8185 3785 8185 3804 8186 3788 8186 3805 8186 3806 8187 3785 8187 3781 8187 3805 8188 3785 8188 3806 8188 3807 8189 3781 8189 3784 8189 3806 8190 3781 8190 3807 8190 3808 8191 3809 8191 3784 8191 3810 8192 3784 8192 3809 8192 3811 8193 3808 8193 3784 8193 3778 8194 3811 8194 3784 8194 3807 8195 3784 8195 3810 8195 3808 8196 3812 8196 3809 8196 3813 8197 3809 8197 3812 8197 3810 8198 3809 8198 3813 8198 3752 8199 3814 8199 3812 8199 3815 8200 3812 8200 3814 8200 3808 8201 3752 8201 3812 8201 3813 8202 3812 8202 3815 8202 3752 8203 3816 8203 3814 8203 3817 8204 3814 8204 3816 8204 3815 8205 3814 8205 3817 8205 3752 8206 3818 8206 3816 8206 3819 8207 3816 8207 3818 8207 3817 8208 3816 8208 3819 8208 3752 8209 3800 8209 3818 8209 3820 8210 3818 8210 3800 8210 3819 8211 3818 8211 3820 8211 3820 8212 3800 8212 3801 8212 3732 8213 3821 8213 3746 8213 3822 8214 3746 8214 3821 8214 3823 8215 3743 8215 3746 8215 3823 8216 3746 8216 3822 8216 3824 8217 3825 8217 3821 8217 3826 8218 3821 8218 3825 8218 3827 8219 3824 8219 3821 8219 3732 8220 3827 8220 3821 8220 3826 8221 3822 8221 3821 8221 3824 8222 3828 8222 3825 8222 3829 8223 3825 8223 3828 8223 3826 8224 3825 8224 3829 8224 3824 8225 3830 8225 3828 8225 3831 8226 3828 8226 3830 8226 3829 8227 3828 8227 3831 8227 3832 8228 3833 8228 3830 8228 3834 8229 3830 8229 3833 8229 3824 8230 3832 8230 3830 8230 3831 8231 3830 8231 3834 8231 3835 8232 3836 8232 3833 8232 3837 8233 3833 8233 3836 8233 3838 8234 3835 8234 3833 8234 3839 8235 3838 8235 3833 8235 3840 8236 3839 8236 3833 8236 3841 8237 3840 8237 3833 8237 3832 8238 3841 8238 3833 8238 3834 8239 3833 8239 3837 8239 3728 8240 3722 8240 3836 8240 3842 8241 3836 8241 3722 8241 3835 8242 3728 8242 3836 8242 3837 8243 3836 8243 3842 8243 3843 8244 3722 8244 3719 8244 3842 8245 3722 8245 3843 8245 3844 8246 3719 8246 3712 8246 3843 8247 3719 8247 3844 8247 3845 8248 3712 8248 3716 8248 3844 8249 3712 8249 3845 8249 3846 8250 3716 8250 3750 8250 3845 8251 3716 8251 3846 8251 3847 8252 3750 8252 3747 8252 3846 8253 3750 8253 3847 8253 3848 8254 3747 8254 3743 8254 3847 8255 3747 8255 3848 8255 3848 8256 3743 8256 3823 8256 3849 8257 3850 8257 3851 8257 3852 8258 3851 8258 3850 8258 3853 8259 3849 8259 3851 8259 3853 8260 3851 8260 3852 8260 3854 8261 3855 8261 3850 8261 3856 8262 3850 8262 3855 8262 3857 8263 3854 8263 3850 8263 3849 8264 3857 8264 3850 8264 3856 8265 3852 8265 3850 8265 3858 8266 3859 8266 3855 8266 3860 8267 3855 8267 3859 8267 3854 8268 3858 8268 3855 8268 3856 8269 3855 8269 3860 8269 3729 8270 3728 8270 3859 8270 3861 8271 3859 8271 3728 8271 3862 8272 3729 8272 3859 8272 3863 8273 3862 8273 3859 8273 3858 8274 3863 8274 3859 8274 3860 8275 3859 8275 3861 8275 3864 8276 3728 8276 3835 8276 3861 8277 3728 8277 3864 8277 3865 8278 3835 8278 3838 8278 3864 8279 3835 8279 3865 8279 3866 8280 3838 8280 3839 8280 3865 8281 3838 8281 3866 8281 3867 8282 3839 8282 3840 8282 3866 8283 3839 8283 3867 8283 3868 8284 3840 8284 3841 8284 3867 8285 3840 8285 3868 8285 3869 8286 3841 8286 3832 8286 3868 8287 3841 8287 3869 8287 3870 8288 3832 8288 3824 8288 3869 8289 3832 8289 3870 8289 3871 8290 3824 8290 3827 8290 3870 8291 3824 8291 3871 8291 3872 8292 3873 8292 3827 8292 3874 8293 3827 8293 3873 8293 3875 8294 3872 8294 3827 8294 3732 8295 3875 8295 3827 8295 3871 8296 3827 8296 3874 8296 3876 8297 3877 8297 3873 8297 3878 8298 3873 8298 3877 8298 3872 8299 3876 8299 3873 8299 3874 8300 3873 8300 3878 8300 3879 8301 3877 8301 3876 8301 3878 8302 3877 8302 3879 8302 3880 8303 3876 8303 3872 8303 3879 8304 3876 8304 3880 8304 3881 8305 3872 8305 3875 8305 3880 8306 3872 8306 3881 8306 3882 8307 3752 8307 3875 8307 3883 8308 3875 8308 3752 8308 3732 8309 3882 8309 3875 8309 3881 8310 3875 8310 3883 8310 3884 8311 3752 8311 3808 8311 3882 8312 3762 8312 3752 8312 3883 8313 3752 8313 3884 8313 3885 8314 3808 8314 3811 8314 3884 8315 3808 8315 3885 8315 3778 8316 3886 8316 3811 8316 3887 8317 3811 8317 3886 8317 3885 8318 3811 8318 3887 8318 3778 8319 3888 8319 3886 8319 3889 8320 3886 8320 3888 8320 3887 8321 3886 8321 3889 8321 3778 8322 3890 8322 3888 8322 3891 8323 3888 8323 3890 8323 3889 8324 3888 8324 3891 8324 3892 8325 3893 8325 3890 8325 3894 8326 3890 8326 3893 8326 3778 8327 3892 8327 3890 8327 3891 8328 3890 8328 3894 8328 3895 8329 3896 8329 3893 8329 3897 8330 3893 8330 3896 8330 3892 8331 3895 8331 3893 8331 3894 8332 3893 8332 3897 8332 3898 8333 3899 8333 3896 8333 3900 8334 3896 8334 3899 8334 3895 8335 3898 8335 3896 8335 3897 8336 3896 8336 3900 8336 3898 8337 3901 8337 3899 8337 3902 8338 3899 8338 3901 8338 3900 8339 3899 8339 3902 8339 3898 8340 3903 8340 3901 8340 3904 8341 3901 8341 3903 8341 3902 8342 3901 8342 3904 8342 3905 8343 3903 8343 3898 8343 3904 8344 3903 8344 3905 8344 3895 8345 3906 8345 3898 8345 3907 8346 3898 8346 3906 8346 3905 8347 3898 8347 3907 8347 3908 8348 3906 8348 3895 8348 3907 8349 3906 8349 3908 8349 3909 8350 3895 8350 3892 8350 3908 8351 3895 8351 3909 8351 3910 8352 3892 8352 3778 8352 3909 8353 3892 8353 3910 8353 3911 8354 3778 8354 3771 8354 3910 8355 3778 8355 3911 8355 3912 8356 3771 8356 3774 8356 3911 8357 3771 8357 3912 8357 3913 8358 3774 8358 3775 8358 3912 8359 3774 8359 3913 8359 3914 8360 3775 8360 3776 8360 3913 8361 3775 8361 3914 8361 3915 8362 3776 8362 3777 8362 3914 8363 3776 8363 3915 8363 3916 8364 3777 8364 3768 8364 3915 8365 3777 8365 3916 8365 3917 8366 3768 8366 3765 8366 3916 8367 3768 8367 3917 8367 3918 8368 3765 8368 3759 8368 3917 8369 3765 8369 3918 8369 3919 8370 3759 8370 3762 8370 3918 8371 3759 8371 3919 8371 3920 8372 3921 8372 3762 8372 3922 8373 3762 8373 3921 8373 3882 8374 3920 8374 3762 8374 3919 8375 3762 8375 3922 8375 3923 8376 3924 8376 3921 8376 3925 8377 3921 8377 3924 8377 3920 8378 3923 8378 3921 8378 3922 8379 3921 8379 3925 8379 3926 8380 3924 8380 3923 8380 3925 8381 3924 8381 3926 8381 3927 8382 3923 8382 3920 8382 3926 8383 3923 8383 3927 8383 3928 8384 3920 8384 3882 8384 3927 8385 3920 8385 3928 8385 3929 8386 3882 8386 3732 8386 3928 8387 3882 8387 3929 8387 3930 8388 3732 8388 3725 8388 3929 8389 3732 8389 3930 8389 3931 8390 3725 8390 3729 8390 3930 8391 3725 8391 3931 8391 3932 8392 3729 8392 3862 8392 3931 8393 3729 8393 3932 8393 3933 8394 3862 8394 3863 8394 3932 8395 3862 8395 3933 8395 3934 8396 3863 8396 3858 8396 3933 8397 3863 8397 3934 8397 3935 8398 3858 8398 3854 8398 3934 8399 3858 8399 3935 8399 3936 8400 3854 8400 3857 8400 3935 8401 3854 8401 3936 8401 3849 8402 3937 8402 3857 8402 3938 8403 3857 8403 3937 8403 3936 8404 3857 8404 3938 8404 3849 8405 3939 8405 3937 8405 3940 8406 3937 8406 3939 8406 3938 8407 3937 8407 3940 8407 3849 8408 3941 8408 3939 8408 3942 8409 3939 8409 3941 8409 3940 8410 3939 8410 3942 8410 3943 8411 3941 8411 3849 8411 3942 8412 3941 8412 3943 8412 3943 8413 3849 8413 3853 8413 3847 8414 3718 8414 3715 8414 3846 8415 3715 8415 3721 8415 3846 8416 3847 8416 3715 8416 3848 8417 3751 8417 3718 8417 3847 8418 3848 8418 3718 8418 3823 8419 3749 8419 3751 8419 3848 8420 3823 8420 3751 8420 3822 8421 3745 8421 3749 8421 3823 8422 3822 8422 3749 8422 3874 8423 3742 8423 3745 8423 3874 8424 3745 8424 3822 8424 3930 8425 3740 8425 3742 8425 3874 8426 3930 8426 3742 8426 3930 8427 3738 8427 3740 8427 3930 8428 3736 8428 3738 8428 3931 8429 3734 8429 3736 8429 3930 8430 3931 8430 3736 8430 3931 8431 3731 8431 3734 8431 3932 8432 3727 8432 3731 8432 3931 8433 3932 8433 3731 8433 3844 8434 3724 8434 3727 8434 3843 8435 3844 8435 3727 8435 3932 8436 3843 8436 3727 8436 3845 8437 3721 8437 3724 8437 3844 8438 3845 8438 3724 8438 3845 8439 3846 8439 3721 8439 3802 8440 3758 8440 3755 8440 3922 8441 3755 8441 3761 8441 3802 8442 3755 8442 3799 8442 3922 8443 3799 8443 3755 8443 3803 8444 3798 8444 3758 8444 3802 8445 3803 8445 3758 8445 3804 8446 3796 8446 3798 8446 3803 8447 3804 8447 3798 8447 3805 8448 3793 8448 3796 8448 3804 8449 3805 8449 3796 8449 3806 8450 3790 8450 3793 8450 3805 8451 3806 8451 3793 8451 3807 8452 3787 8452 3790 8452 3806 8453 3807 8453 3790 8453 3810 8454 3783 8454 3787 8454 3807 8455 3810 8455 3787 8455 3912 8456 3780 8456 3783 8456 3887 8457 3783 8457 3810 8457 3891 8458 3912 8458 3783 8458 3889 8459 3891 8459 3783 8459 3887 8460 3889 8460 3783 8460 3915 8461 3773 8461 3780 8461 3914 8462 3915 8462 3780 8462 3913 8463 3914 8463 3780 8463 3912 8464 3913 8464 3780 8464 3917 8465 3770 8465 3773 8465 3916 8466 3917 8466 3773 8466 3915 8467 3916 8467 3773 8467 3919 8468 3767 8468 3770 8468 3918 8469 3919 8469 3770 8469 3917 8470 3918 8470 3770 8470 3922 8471 3764 8471 3767 8471 3919 8472 3922 8472 3767 8472 3922 8473 3761 8473 3764 8473 3922 8474 3801 8474 3799 8474 3884 8475 3820 8475 3801 8475 3884 8476 3801 8476 3922 8476 3884 8477 3819 8477 3820 8477 3884 8478 3817 8478 3819 8478 3885 8479 3815 8479 3817 8479 3884 8480 3885 8480 3817 8480 3885 8481 3813 8481 3815 8481 3887 8482 3810 8482 3813 8482 3885 8483 3887 8483 3813 8483 3874 8484 3822 8484 3826 8484 3865 8485 3842 8485 3843 8485 3864 8486 3843 8486 3932 8486 3864 8487 3865 8487 3843 8487 3869 8488 3837 8488 3842 8488 3868 8489 3869 8489 3842 8489 3867 8490 3868 8490 3842 8490 3866 8491 3867 8491 3842 8491 3865 8492 3866 8492 3842 8492 3871 8493 3834 8493 3837 8493 3870 8494 3871 8494 3837 8494 3869 8495 3870 8495 3837 8495 3871 8496 3831 8496 3834 8496 3874 8497 3829 8497 3831 8497 3871 8498 3874 8498 3831 8498 3874 8499 3826 8499 3829 8499 3940 8500 3853 8500 3852 8500 3938 8501 3940 8501 3852 8501 3856 8502 3938 8502 3852 8502 3942 8503 3943 8503 3853 8503 3940 8504 3942 8504 3853 8504 3856 8505 3936 8505 3938 8505 3860 8506 3935 8506 3936 8506 3856 8507 3860 8507 3936 8507 3864 8508 3934 8508 3935 8508 3860 8509 3864 8509 3935 8509 3864 8510 3933 8510 3934 8510 3864 8511 3932 8511 3933 8511 3883 8512 3929 8512 3930 8512 3883 8513 3930 8513 3874 8513 3874 8514 3881 8514 3883 8514 3929 8515 3884 8515 3922 8515 3883 8516 3884 8516 3929 8516 3926 8517 3927 8517 3928 8517 3925 8518 3926 8518 3928 8518 3922 8519 3925 8519 3928 8519 3922 8520 3928 8520 3929 8520 3910 8521 3911 8521 3912 8521 3894 8522 3910 8522 3912 8522 3891 8523 3894 8523 3912 8523 3897 8524 3909 8524 3910 8524 3894 8525 3897 8525 3910 8525 3900 8526 3908 8526 3909 8526 3897 8527 3900 8527 3909 8527 3902 8528 3907 8528 3908 8528 3900 8529 3902 8529 3908 8529 3904 8530 3905 8530 3907 8530 3902 8531 3904 8531 3907 8531 3879 8532 3880 8532 3881 8532 3878 8533 3879 8533 3881 8533 3874 8534 3878 8534 3881 8534 3860 8535 3861 8535 3864 8535 3944 8536 3945 8536 3946 8536 3947 8537 3946 8537 3945 8537 3944 8538 3946 8538 3948 8538 3949 8539 3948 8539 3946 8539 3949 8540 3946 8540 3947 8540 3950 8541 3951 8541 3945 8541 3952 8542 3945 8542 3951 8542 3950 8543 3945 8543 3944 8543 3952 8544 3947 8544 3945 8544 3950 8545 3953 8545 3951 8545 3954 8546 3951 8546 3953 8546 3952 8547 3951 8547 3954 8547 3955 8548 3956 8548 3953 8548 3957 8549 3953 8549 3956 8549 3950 8550 3955 8550 3953 8550 3954 8551 3953 8551 3957 8551 3955 8552 3958 8552 3956 8552 3959 8553 3956 8553 3958 8553 3957 8554 3956 8554 3959 8554 3955 8555 3960 8555 3958 8555 3961 8556 3958 8556 3960 8556 3959 8557 3958 8557 3961 8557 3944 8558 3948 8558 3960 8558 3962 8559 3960 8559 3948 8559 3963 8560 3964 8560 3960 8560 3965 8561 3960 8561 3964 8561 3966 8562 3963 8562 3960 8562 3967 8563 3966 8563 3960 8563 3968 8564 3960 8564 3965 8564 3969 8565 3967 8565 3960 8565 3970 8566 3969 8566 3960 8566 3955 8567 3970 8567 3960 8567 3968 8568 3944 8568 3960 8568 3961 8569 3960 8569 3962 8569 3962 8570 3948 8570 3949 8570 3971 8571 3972 8571 3973 8571 3974 8572 3973 8572 3972 8572 3971 8573 3973 8573 3975 8573 3976 8574 3975 8574 3973 8574 3976 8575 3973 8575 3974 8575 3971 8576 3977 8576 3972 8576 3978 8577 3972 8577 3977 8577 3978 8578 3974 8578 3972 8578 3979 8579 3980 8579 3977 8579 3981 8580 3977 8580 3980 8580 3982 8581 3979 8581 3977 8581 3971 8582 3982 8582 3977 8582 3978 8583 3977 8583 3981 8583 3979 8584 3983 8584 3980 8584 3984 8585 3980 8585 3983 8585 3981 8586 3980 8586 3984 8586 3985 8587 3986 8587 3983 8587 3987 8588 3983 8588 3986 8588 3979 8589 3985 8589 3983 8589 3984 8590 3983 8590 3987 8590 3988 8591 3989 8591 3986 8591 3990 8592 3986 8592 3989 8592 3991 8593 3988 8593 3986 8593 3985 8594 3991 8594 3986 8594 3987 8595 3986 8595 3990 8595 3992 8596 3975 8596 3989 8596 3993 8597 3989 8597 3975 8597 3992 8598 3989 8598 3988 8598 3990 8599 3989 8599 3993 8599 3992 8600 3971 8600 3975 8600 3993 8601 3975 8601 3976 8601 3994 8602 3995 8602 3996 8602 3997 8603 3996 8603 3995 8603 3998 8604 3996 8604 3999 8604 4000 8605 3999 8605 3996 8605 4001 8606 3994 8606 3996 8606 4001 8607 3996 8607 3998 8607 4000 8608 3996 8608 3997 8608 3994 8609 4002 8609 3995 8609 4003 8610 3995 8610 4002 8610 4003 8611 3997 8611 3995 8611 3994 8612 4004 8612 4002 8612 4005 8613 4002 8613 4004 8613 4003 8614 4002 8614 4005 8614 3994 8615 4006 8615 4004 8615 4007 8616 4004 8616 4006 8616 4005 8617 4004 8617 4007 8617 3994 8618 4008 8618 4006 8618 4009 8619 4006 8619 4008 8619 4007 8620 4006 8620 4009 8620 4010 8621 4011 8621 4008 8621 4012 8622 4008 8622 4011 8622 4013 8623 4010 8623 4008 8623 3994 8624 4013 8624 4008 8624 4009 8625 4008 8625 4012 8625 4014 8626 4015 8626 4011 8626 4016 8627 4011 8627 4015 8627 4010 8628 4014 8628 4011 8628 4012 8629 4011 8629 4016 8629 4014 8630 4017 8630 4015 8630 4018 8631 4015 8631 4017 8631 4016 8632 4015 8632 4018 8632 4019 8633 4020 8633 4017 8633 4021 8634 4017 8634 4020 8634 4022 8635 4017 8635 4014 8635 4022 8636 4023 8636 4017 8636 4019 8637 4017 8637 4023 8637 4018 8638 4017 8638 4021 8638 4019 8639 4024 8639 4020 8639 4025 8640 4020 8640 4024 8640 4021 8641 4020 8641 4025 8641 3998 8642 4026 8642 4024 8642 4027 8643 4024 8643 4026 8643 4019 8644 3998 8644 4024 8644 4025 8645 4024 8645 4027 8645 3998 8646 4028 8646 4026 8646 4029 8647 4026 8647 4028 8647 4027 8648 4026 8648 4029 8648 3998 8649 4030 8649 4028 8649 4031 8650 4028 8650 4030 8650 4029 8651 4028 8651 4031 8651 3998 8652 4032 8652 4030 8652 4033 8653 4030 8653 4032 8653 4031 8654 4030 8654 4033 8654 3998 8655 3999 8655 4032 8655 4034 8656 4032 8656 3999 8656 4033 8657 4032 8657 4034 8657 4034 8658 3999 8658 4000 8658 4035 8659 4036 8659 4037 8659 4038 8660 4037 8660 4036 8660 4035 8661 4037 8661 4039 8661 4040 8662 4039 8662 4037 8662 4040 8663 4037 8663 4038 8663 4041 8664 4042 8664 4036 8664 4043 8665 4036 8665 4042 8665 4041 8666 4036 8666 4035 8666 4043 8667 4038 8667 4036 8667 4044 8668 4045 8668 4042 8668 4046 8669 4042 8669 4045 8669 4041 8670 4044 8670 4042 8670 4043 8671 4042 8671 4046 8671 4044 8672 4047 8672 4045 8672 4048 8673 4045 8673 4047 8673 4046 8674 4045 8674 4048 8674 4044 8675 4049 8675 4047 8675 4050 8676 4047 8676 4049 8676 4048 8677 4047 8677 4050 8677 4044 8678 4051 8678 4049 8678 4052 8679 4049 8679 4051 8679 4050 8680 4049 8680 4052 8680 4044 8681 4053 8681 4051 8681 4054 8682 4051 8682 4053 8682 4052 8683 4051 8683 4054 8683 4044 8684 4055 8684 4053 8684 4056 8685 4053 8685 4055 8685 4054 8686 4053 8686 4056 8686 4057 8687 4058 8687 4055 8687 4059 8688 4055 8688 4058 8688 4044 8689 4057 8689 4055 8689 4056 8690 4055 8690 4059 8690 4057 8691 4060 8691 4058 8691 4061 8692 4058 8692 4060 8692 4059 8693 4058 8693 4061 8693 4057 8694 4062 8694 4060 8694 4063 8695 4060 8695 4062 8695 4061 8696 4060 8696 4063 8696 4035 8697 4064 8697 4062 8697 4065 8698 4062 8698 4064 8698 4057 8699 4035 8699 4062 8699 4063 8700 4062 8700 4065 8700 4035 8701 4066 8701 4064 8701 4067 8702 4064 8702 4066 8702 4065 8703 4064 8703 4067 8703 4035 8704 4068 8704 4066 8704 4069 8705 4066 8705 4068 8705 4067 8706 4066 8706 4069 8706 4035 8707 4039 8707 4068 8707 4070 8708 4068 8708 4039 8708 4069 8709 4068 8709 4070 8709 4070 8710 4039 8710 4040 8710 4071 8711 4072 8711 4073 8711 4074 8712 4073 8712 4072 8712 4071 8713 4073 8713 4075 8713 4076 8714 4075 8714 4073 8714 4076 8715 4073 8715 4074 8715 4071 8716 4077 8716 4072 8716 4078 8717 4072 8717 4077 8717 4078 8718 4074 8718 4072 8718 4071 8719 4079 8719 4077 8719 4080 8720 4077 8720 4079 8720 4078 8721 4077 8721 4080 8721 4071 8722 4081 8722 4079 8722 4082 8723 4079 8723 4081 8723 4080 8724 4079 8724 4082 8724 4083 8725 4084 8725 4081 8725 4085 8726 4081 8726 4084 8726 4086 8727 4083 8727 4081 8727 4087 8728 4086 8728 4081 8728 4087 8729 4081 8729 4071 8729 4082 8730 4081 8730 4085 8730 4088 8731 4089 8731 4084 8731 4090 8732 4084 8732 4089 8732 4083 8733 4088 8733 4084 8733 4085 8734 4084 8734 4090 8734 4091 8735 4092 8735 4089 8735 4093 8736 4089 8736 4092 8736 4088 8737 4091 8737 4089 8737 4090 8738 4089 8738 4093 8738 4094 8739 4095 8739 4092 8739 4096 8740 4092 8740 4095 8740 4091 8741 4094 8741 4092 8741 4093 8742 4092 8742 4096 8742 4097 8743 4098 8743 4095 8743 4099 8744 4095 8744 4098 8744 4097 8745 4095 8745 4094 8745 4096 8746 4095 8746 4099 8746 4100 8747 4101 8747 4098 8747 4102 8748 4098 8748 4101 8748 4097 8749 4100 8749 4098 8749 4099 8750 4098 8750 4102 8750 4103 8751 4104 8751 4101 8751 4105 8752 4101 8752 4104 8752 4100 8753 4103 8753 4101 8753 4102 8754 4101 8754 4105 8754 4106 8755 4107 8755 4104 8755 4108 8756 4104 8756 4107 8756 4103 8757 4106 8757 4104 8757 4105 8758 4104 8758 4108 8758 4109 8759 4110 8759 4107 8759 4111 8760 4107 8760 4110 8760 4112 8761 4107 8761 4106 8761 4112 8762 4109 8762 4107 8762 4108 8763 4107 8763 4111 8763 4109 8764 4113 8764 4110 8764 4114 8765 4110 8765 4113 8765 4111 8766 4110 8766 4114 8766 4109 8767 4075 8767 4113 8767 4115 8768 4113 8768 4075 8768 4114 8769 4113 8769 4115 8769 4109 8770 4071 8770 4075 8770 4115 8771 4075 8771 4076 8771 4116 8772 4094 8772 4091 8772 4117 8773 4097 8773 4094 8773 4117 8774 4094 8774 4116 8774 4118 8775 4091 8775 4088 8775 4118 8776 4116 8776 4091 8776 4119 8777 4088 8777 4083 8777 4118 8778 4088 8778 4119 8778 4120 8779 4083 8779 4086 8779 4119 8780 4083 8780 4120 8780 4121 8781 4122 8781 4086 8781 4123 8782 4086 8782 4122 8782 4087 8783 4121 8783 4086 8783 4120 8784 4086 8784 4123 8784 4121 8785 4124 8785 4122 8785 4125 8786 4122 8786 4124 8786 4123 8787 4122 8787 4125 8787 4126 8788 4127 8788 4124 8788 4128 8789 4124 8789 4127 8789 4121 8790 4126 8790 4124 8790 4125 8791 4124 8791 4128 8791 4126 8792 4129 8792 4127 8792 4130 8793 4127 8793 4129 8793 4128 8794 4127 8794 4130 8794 4126 8795 4131 8795 4129 8795 4132 8796 4129 8796 4131 8796 4130 8797 4129 8797 4132 8797 4126 8798 4133 8798 4131 8798 4134 8799 4131 8799 4133 8799 4132 8800 4131 8800 4134 8800 4126 8801 4135 8801 4133 8801 4136 8802 4133 8802 4135 8802 4134 8803 4133 8803 4136 8803 4126 8804 4106 8804 4135 8804 4137 8805 4135 8805 4106 8805 4136 8806 4135 8806 4137 8806 4138 8807 4106 8807 4103 8807 4126 8808 4112 8808 4106 8808 4137 8809 4106 8809 4138 8809 4139 8810 4103 8810 4100 8810 4138 8811 4103 8811 4139 8811 4140 8812 4100 8812 4097 8812 4139 8813 4100 8813 4140 8813 4140 8814 4097 8814 4117 8814 4141 8815 4142 8815 4143 8815 4144 8816 4143 8816 4142 8816 4145 8817 4143 8817 4146 8817 4147 8818 4146 8818 4143 8818 4148 8819 4141 8819 4143 8819 4145 8820 4148 8820 4143 8820 4147 8821 4143 8821 4144 8821 4141 8822 4149 8822 4142 8822 4150 8823 4142 8823 4149 8823 4150 8824 4144 8824 4142 8824 4141 8825 4151 8825 4149 8825 4152 8826 4149 8826 4151 8826 4150 8827 4149 8827 4152 8827 4141 8828 4153 8828 4151 8828 4154 8829 4151 8829 4153 8829 4152 8830 4151 8830 4154 8830 4141 8831 4155 8831 4153 8831 4156 8832 4153 8832 4155 8832 4154 8833 4153 8833 4156 8833 4157 8834 4158 8834 4155 8834 4159 8835 4155 8835 4158 8835 4160 8836 4155 8836 4141 8836 4160 8837 4157 8837 4155 8837 4156 8838 4155 8838 4159 8838 4161 8839 4162 8839 4158 8839 4163 8840 4158 8840 4162 8840 4157 8841 4161 8841 4158 8841 4159 8842 4158 8842 4163 8842 4161 8843 4164 8843 4162 8843 4165 8844 4162 8844 4164 8844 4163 8845 4162 8845 4165 8845 4166 8846 4167 8846 4164 8846 4168 8847 4164 8847 4167 8847 4169 8848 4170 8848 4164 8848 4166 8849 4164 8849 4170 8849 4161 8850 4169 8850 4164 8850 4165 8851 4164 8851 4168 8851 4166 8852 4171 8852 4167 8852 4172 8853 4167 8853 4171 8853 4168 8854 4167 8854 4172 8854 4145 8855 4173 8855 4171 8855 4174 8856 4171 8856 4173 8856 4166 8857 4145 8857 4171 8857 4172 8858 4171 8858 4174 8858 4145 8859 4175 8859 4173 8859 4176 8860 4173 8860 4175 8860 4174 8861 4173 8861 4176 8861 4145 8862 4177 8862 4175 8862 4178 8863 4175 8863 4177 8863 4176 8864 4175 8864 4178 8864 4145 8865 4179 8865 4177 8865 4180 8866 4177 8866 4179 8866 4178 8867 4177 8867 4180 8867 4145 8868 4146 8868 4179 8868 4181 8869 4179 8869 4146 8869 4180 8870 4179 8870 4181 8870 4181 8871 4146 8871 4147 8871 4182 8872 4183 8872 4184 8872 4185 8873 4184 8873 4183 8873 4182 8874 4184 8874 4186 8874 4187 8875 4186 8875 4184 8875 4187 8876 4184 8876 4185 8876 4188 8877 4189 8877 4183 8877 4190 8878 4183 8878 4189 8878 4188 8879 4183 8879 4182 8879 4190 8880 4185 8880 4183 8880 4191 8881 4192 8881 4189 8881 4193 8882 4189 8882 4192 8882 4188 8883 4191 8883 4189 8883 4190 8884 4189 8884 4193 8884 4191 8885 4194 8885 4192 8885 4195 8886 4192 8886 4194 8886 4193 8887 4192 8887 4195 8887 4191 8888 4196 8888 4194 8888 4197 8889 4194 8889 4196 8889 4195 8890 4194 8890 4197 8890 4191 8891 4198 8891 4196 8891 4199 8892 4196 8892 4198 8892 4197 8893 4196 8893 4199 8893 4191 8894 4200 8894 4198 8894 4201 8895 4198 8895 4200 8895 4199 8896 4198 8896 4201 8896 4191 8897 4202 8897 4200 8897 4203 8898 4200 8898 4202 8898 4201 8899 4200 8899 4203 8899 4204 8900 4205 8900 4202 8900 4206 8901 4202 8901 4205 8901 4191 8902 4204 8902 4202 8902 4203 8903 4202 8903 4206 8903 4204 8904 4207 8904 4205 8904 4208 8905 4205 8905 4207 8905 4206 8906 4205 8906 4208 8906 4204 8907 4209 8907 4207 8907 4210 8908 4207 8908 4209 8908 4208 8909 4207 8909 4210 8909 4182 8910 4211 8910 4209 8910 4212 8911 4209 8911 4211 8911 4204 8912 4182 8912 4209 8912 4210 8913 4209 8913 4212 8913 4182 8914 4213 8914 4211 8914 4214 8915 4211 8915 4213 8915 4212 8916 4211 8916 4214 8916 4182 8917 4215 8917 4213 8917 4216 8918 4213 8918 4215 8918 4214 8919 4213 8919 4216 8919 4182 8920 4186 8920 4215 8920 4217 8921 4215 8921 4186 8921 4216 8922 4215 8922 4217 8922 4217 8923 4186 8923 4187 8923 4218 8924 4219 8924 4220 8924 4221 8925 4220 8925 4219 8925 4218 8926 4220 8926 4222 8926 4223 8927 4222 8927 4220 8927 4223 8928 4220 8928 4221 8928 4218 8929 4224 8929 4219 8929 4225 8930 4219 8930 4224 8930 4225 8931 4221 8931 4219 8931 4218 8932 4226 8932 4224 8932 4227 8933 4224 8933 4226 8933 4225 8934 4224 8934 4227 8934 4218 8935 4228 8935 4226 8935 4229 8936 4226 8936 4228 8936 4227 8937 4226 8937 4229 8937 4230 8938 4231 8938 4228 8938 4232 8939 4228 8939 4231 8939 4233 8940 4230 8940 4228 8940 4234 8941 4233 8941 4228 8941 4234 8942 4228 8942 4218 8942 4229 8943 4228 8943 4232 8943 4235 8944 4236 8944 4231 8944 4237 8945 4231 8945 4236 8945 4230 8946 4235 8946 4231 8946 4232 8947 4231 8947 4237 8947 4238 8948 4239 8948 4236 8948 4240 8949 4236 8949 4239 8949 4235 8950 4238 8950 4236 8950 4237 8951 4236 8951 4240 8951 4241 8952 4242 8952 4239 8952 4243 8953 4239 8953 4242 8953 4238 8954 4241 8954 4239 8954 4240 8955 4239 8955 4243 8955 4244 8956 4245 8956 4242 8956 4246 8957 4242 8957 4245 8957 4244 8958 4242 8958 4241 8958 4243 8959 4242 8959 4246 8959 4247 8960 4248 8960 4245 8960 4249 8961 4245 8961 4248 8961 4244 8962 4247 8962 4245 8962 4246 8963 4245 8963 4249 8963 4250 8964 4251 8964 4248 8964 4252 8965 4248 8965 4251 8965 4247 8966 4250 8966 4248 8966 4249 8967 4248 8967 4252 8967 4253 8968 4254 8968 4251 8968 4255 8969 4251 8969 4254 8969 4250 8970 4253 8970 4251 8970 4252 8971 4251 8971 4255 8971 4256 8972 4257 8972 4254 8972 4258 8973 4254 8973 4257 8973 4259 8974 4254 8974 4253 8974 4259 8975 4256 8975 4254 8975 4255 8976 4254 8976 4258 8976 4256 8977 4260 8977 4257 8977 4261 8978 4257 8978 4260 8978 4258 8979 4257 8979 4261 8979 4256 8980 4222 8980 4260 8980 4262 8981 4260 8981 4222 8981 4261 8982 4260 8982 4262 8982 4256 8983 4218 8983 4222 8983 4262 8984 4222 8984 4223 8984 4263 8985 4241 8985 4238 8985 4264 8986 4244 8986 4241 8986 4264 8987 4241 8987 4263 8987 4265 8988 4238 8988 4235 8988 4265 8989 4263 8989 4238 8989 4266 8990 4235 8990 4230 8990 4265 8991 4235 8991 4266 8991 4267 8992 4230 8992 4233 8992 4266 8993 4230 8993 4267 8993 4268 8994 4269 8994 4233 8994 4270 8995 4233 8995 4269 8995 4234 8996 4268 8996 4233 8996 4267 8997 4233 8997 4270 8997 4268 8998 4271 8998 4269 8998 4272 8999 4269 8999 4271 8999 4270 9000 4269 9000 4272 9000 4273 9001 4274 9001 4271 9001 4275 9002 4271 9002 4274 9002 4268 9003 4273 9003 4271 9003 4272 9004 4271 9004 4275 9004 4273 9005 4276 9005 4274 9005 4277 9006 4274 9006 4276 9006 4275 9007 4274 9007 4277 9007 4273 9008 4278 9008 4276 9008 4279 9009 4276 9009 4278 9009 4277 9010 4276 9010 4279 9010 4273 9011 4280 9011 4278 9011 4281 9012 4278 9012 4280 9012 4279 9013 4278 9013 4281 9013 4273 9014 4282 9014 4280 9014 4283 9015 4280 9015 4282 9015 4281 9016 4280 9016 4283 9016 4273 9017 4253 9017 4282 9017 4284 9018 4282 9018 4253 9018 4283 9019 4282 9019 4284 9019 4285 9020 4253 9020 4250 9020 4273 9021 4259 9021 4253 9021 4284 9022 4253 9022 4285 9022 4286 9023 4250 9023 4247 9023 4285 9024 4250 9024 4286 9024 4287 9025 4247 9025 4244 9025 4286 9026 4247 9026 4287 9026 4287 9027 4244 9027 4264 9027 4288 9028 4289 9028 4290 9028 4291 9029 4290 9029 4289 9029 4288 9030 4290 9030 4292 9030 4293 9031 4292 9031 4290 9031 4293 9032 4290 9032 4291 9032 4288 9033 4294 9033 4289 9033 4295 9034 4289 9034 4294 9034 4295 9035 4291 9035 4289 9035 4288 9036 4296 9036 4294 9036 4297 9037 4294 9037 4296 9037 4295 9038 4294 9038 4297 9038 4298 9039 4299 9039 4296 9039 4300 9040 4296 9040 4299 9040 4298 9041 4296 9041 4288 9041 4297 9042 4296 9042 4300 9042 4301 9043 4302 9043 4299 9043 4303 9044 4299 9044 4302 9044 4298 9045 4301 9045 4299 9045 4300 9046 4299 9046 4303 9046 4301 9047 4304 9047 4302 9047 4305 9048 4302 9048 4304 9048 4303 9049 4302 9049 4305 9049 4301 9050 4306 9050 4304 9050 4307 9051 4304 9051 4306 9051 4305 9052 4304 9052 4307 9052 4301 9053 4308 9053 4306 9053 4309 9054 4306 9054 4308 9054 4307 9055 4306 9055 4309 9055 4288 9056 4292 9056 4308 9056 4310 9057 4308 9057 4292 9057 4288 9058 4308 9058 4311 9058 4301 9059 4311 9059 4308 9059 4309 9060 4308 9060 4310 9060 4310 9061 4292 9061 4293 9061 4312 9062 4313 9062 4314 9062 4315 9063 4314 9063 4313 9063 4312 9064 4314 9064 4316 9064 4317 9065 4316 9065 4314 9065 4317 9066 4314 9066 4315 9066 4148 9067 4318 9067 4313 9067 4319 9068 4313 9068 4318 9068 4312 9069 4148 9069 4313 9069 4319 9070 4315 9070 4313 9070 4148 9071 4320 9071 4318 9071 4321 9072 4318 9072 4320 9072 4319 9073 4318 9073 4321 9073 4148 9074 4322 9074 4320 9074 4323 9075 4320 9075 4322 9075 4321 9076 4320 9076 4323 9076 4148 9077 4324 9077 4322 9077 4325 9078 4322 9078 4324 9078 4323 9079 4322 9079 4325 9079 4326 9080 4327 9080 4324 9080 4328 9081 4324 9081 4327 9081 4145 9082 4324 9082 4148 9082 4329 9083 4326 9083 4324 9083 4145 9084 4329 9084 4324 9084 4325 9085 4324 9085 4328 9085 4330 9086 4331 9086 4327 9086 4332 9087 4327 9087 4331 9087 4333 9088 4330 9088 4327 9088 4326 9089 4333 9089 4327 9089 4328 9090 4327 9090 4332 9090 4334 9091 4335 9091 4331 9091 4336 9092 4331 9092 4335 9092 4330 9093 4334 9093 4331 9093 4332 9094 4331 9094 4336 9094 4334 9095 4337 9095 4335 9095 4338 9096 4335 9096 4337 9096 4336 9097 4335 9097 4338 9097 4334 9098 4339 9098 4337 9098 4340 9099 4337 9099 4339 9099 4338 9100 4337 9100 4340 9100 4341 9101 4342 9101 4339 9101 4343 9102 4339 9102 4342 9102 4334 9103 4341 9103 4339 9103 4340 9104 4339 9104 4343 9104 4341 9105 4344 9105 4342 9105 4345 9106 4342 9106 4344 9106 4343 9107 4342 9107 4345 9107 4341 9108 4346 9108 4344 9108 4347 9109 4344 9109 4346 9109 4345 9110 4344 9110 4347 9110 4348 9111 4349 9111 4346 9111 4350 9112 4346 9112 4349 9112 4341 9113 4348 9113 4346 9113 4347 9114 4346 9114 4350 9114 4351 9115 4352 9115 4349 9115 4353 9116 4349 9116 4352 9116 4354 9117 4349 9117 4348 9117 4354 9118 4351 9118 4349 9118 4350 9119 4349 9119 4353 9119 4351 9120 4355 9120 4352 9120 4356 9121 4352 9121 4355 9121 4353 9122 4352 9122 4356 9122 4351 9123 4316 9123 4355 9123 4357 9124 4355 9124 4316 9124 4356 9125 4355 9125 4357 9125 4351 9126 4312 9126 4316 9126 4357 9127 4316 9127 4317 9127 4358 9128 4359 9128 4360 9128 4361 9129 4360 9129 4359 9129 4362 9130 4360 9130 4363 9130 4364 9131 4363 9131 4360 9131 4362 9132 4358 9132 4360 9132 4364 9133 4360 9133 4361 9133 4358 9134 4365 9134 4359 9134 4366 9135 4359 9135 4365 9135 4366 9136 4361 9136 4359 9136 4367 9137 4368 9137 4365 9137 4369 9138 4365 9138 4368 9138 4358 9139 4367 9139 4365 9139 4366 9140 4365 9140 4369 9140 4367 9141 4370 9141 4368 9141 4371 9142 4368 9142 4370 9142 4369 9143 4368 9143 4371 9143 4367 9144 4372 9144 4370 9144 4373 9145 4370 9145 4372 9145 4371 9146 4370 9146 4373 9146 4374 9147 4375 9147 4372 9147 4376 9148 4372 9148 4375 9148 4374 9149 4372 9149 4367 9149 4373 9150 4372 9150 4376 9150 4374 9151 4377 9151 4375 9151 4378 9152 4375 9152 4377 9152 4376 9153 4375 9153 4378 9153 4374 9154 4379 9154 4377 9154 4380 9155 4377 9155 4379 9155 4378 9156 4377 9156 4380 9156 4381 9157 4382 9157 4379 9157 4383 9158 4379 9158 4382 9158 4374 9159 4381 9159 4379 9159 4380 9160 4379 9160 4383 9160 4381 9161 4384 9161 4382 9161 4385 9162 4382 9162 4384 9162 4383 9163 4382 9163 4385 9163 4001 9164 4386 9164 4384 9164 4387 9165 4384 9165 4386 9165 4381 9166 4001 9166 4384 9166 4385 9167 4384 9167 4387 9167 4001 9168 4388 9168 4386 9168 4389 9169 4386 9169 4388 9169 4387 9170 4386 9170 4389 9170 4001 9171 4390 9171 4388 9171 4391 9172 4388 9172 4390 9172 4389 9173 4388 9173 4391 9173 4001 9174 4392 9174 4390 9174 4393 9175 4390 9175 4392 9175 4391 9176 4390 9176 4393 9176 4394 9177 4395 9177 4392 9177 4396 9178 4392 9178 4395 9178 4397 9179 4394 9179 4392 9179 3998 9180 4397 9180 4392 9180 4001 9181 3998 9181 4392 9181 4393 9182 4392 9182 4396 9182 4398 9183 4399 9183 4395 9183 4400 9184 4395 9184 4399 9184 4401 9185 4398 9185 4395 9185 4394 9186 4401 9186 4395 9186 4396 9187 4395 9187 4400 9187 4362 9188 4363 9188 4399 9188 4402 9189 4399 9189 4363 9189 4398 9190 4362 9190 4399 9190 4400 9191 4399 9191 4402 9191 4402 9192 4363 9192 4364 9192 4301 9193 4403 9193 4311 9193 4404 9194 4311 9194 4403 9194 4405 9195 4288 9195 4311 9195 4405 9196 4311 9196 4404 9196 4406 9197 4407 9197 4403 9197 4408 9198 4403 9198 4407 9198 4409 9199 4406 9199 4403 9199 4301 9200 4409 9200 4403 9200 4408 9201 4404 9201 4403 9201 4406 9202 4288 9202 4407 9202 4410 9203 4407 9203 4288 9203 4408 9204 4407 9204 4410 9204 4298 9205 4288 9205 4406 9205 4410 9206 4288 9206 4405 9206 4354 9207 4411 9207 4412 9207 4413 9208 4412 9208 4411 9208 4354 9209 4412 9209 4414 9209 4415 9210 4414 9210 4412 9210 4415 9211 4412 9211 4413 9211 4354 9212 4416 9212 4411 9212 4417 9213 4411 9213 4416 9213 4417 9214 4413 9214 4411 9214 4418 9215 4419 9215 4416 9215 4420 9216 4416 9216 4419 9216 4354 9217 4418 9217 4416 9217 4417 9218 4416 9218 4420 9218 4421 9219 4422 9219 4419 9219 4423 9220 4419 9220 4422 9220 4418 9221 4421 9221 4419 9221 4420 9222 4419 9222 4423 9222 4424 9223 4425 9223 4422 9223 4426 9224 4422 9224 4425 9224 4424 9225 4422 9225 4421 9225 4423 9226 4422 9226 4426 9226 4424 9227 4427 9227 4425 9227 4428 9228 4425 9228 4427 9228 4426 9229 4425 9229 4428 9229 4354 9230 4414 9230 4427 9230 4429 9231 4427 9231 4414 9231 4424 9232 4430 9232 4427 9232 4431 9233 4427 9233 4430 9233 4431 9234 4354 9234 4427 9234 4428 9235 4427 9235 4429 9235 4429 9236 4414 9236 4415 9236 4432 9237 4433 9237 4434 9237 4435 9238 4434 9238 4433 9238 4436 9239 4434 9239 4437 9239 4438 9240 4437 9240 4434 9240 4436 9241 4432 9241 4434 9241 4438 9242 4434 9242 4435 9242 4432 9243 4439 9243 4433 9243 4440 9244 4433 9244 4439 9244 4440 9245 4435 9245 4433 9245 4441 9246 4442 9246 4439 9246 4443 9247 4439 9247 4442 9247 4444 9248 4441 9248 4439 9248 4439 9249 4432 9249 4445 9249 4440 9250 4439 9250 4443 9250 4441 9251 4446 9251 4442 9251 4447 9252 4442 9252 4446 9252 4443 9253 4442 9253 4447 9253 4448 9254 4449 9254 4446 9254 4450 9255 4446 9255 4449 9255 4448 9256 4446 9256 4441 9256 4447 9257 4446 9257 4450 9257 4448 9258 4451 9258 4449 9258 4452 9259 4449 9259 4451 9259 4450 9260 4449 9260 4452 9260 4436 9261 4437 9261 4451 9261 4453 9262 4451 9262 4437 9262 4451 9263 4448 9263 4454 9263 4455 9264 4436 9264 4451 9264 4452 9265 4451 9265 4453 9265 4453 9266 4437 9266 4438 9266 4409 9267 4456 9267 4457 9267 4458 9268 4457 9268 4456 9268 4409 9269 4457 9269 4459 9269 4460 9270 4459 9270 4457 9270 4460 9271 4457 9271 4458 9271 4409 9272 4461 9272 4456 9272 4462 9273 4456 9273 4461 9273 4462 9274 4458 9274 4456 9274 4463 9275 4464 9275 4461 9275 4465 9276 4461 9276 4464 9276 4170 9277 4463 9277 4461 9277 4409 9278 4170 9278 4461 9278 4462 9279 4461 9279 4465 9279 4466 9280 4467 9280 4464 9280 4468 9281 4464 9281 4467 9281 4463 9282 4466 9282 4464 9282 4465 9283 4464 9283 4468 9283 4469 9284 4470 9284 4467 9284 4471 9285 4467 9285 4470 9285 4469 9286 4467 9286 4466 9286 4468 9287 4467 9287 4471 9287 4160 9288 4141 9288 4470 9288 4472 9289 4470 9289 4141 9289 4469 9290 4160 9290 4470 9290 4471 9291 4470 9291 4472 9291 4409 9292 4459 9292 4141 9292 4473 9293 4141 9293 4459 9293 4148 9294 4409 9294 4141 9294 4472 9295 4141 9295 4473 9295 4473 9296 4459 9296 4460 9296 4474 9297 4466 9297 4463 9297 4475 9298 4469 9298 4466 9298 4475 9299 4466 9299 4474 9299 4476 9300 4463 9300 4170 9300 4476 9301 4474 9301 4463 9301 4477 9302 4170 9302 4169 9302 4166 9303 4170 9303 4409 9303 4476 9304 4170 9304 4477 9304 4478 9305 4169 9305 4161 9305 4477 9306 4169 9306 4478 9306 4479 9307 4161 9307 4157 9307 4478 9308 4161 9308 4479 9308 4480 9309 4157 9309 4160 9309 4479 9310 4157 9310 4480 9310 4481 9311 4160 9311 4469 9311 4480 9312 4160 9312 4481 9312 4481 9313 4469 9313 4475 9313 4482 9314 4014 9314 4010 9314 4483 9315 4022 9315 4014 9315 4483 9316 4014 9316 4482 9316 4484 9317 4010 9317 4013 9317 4484 9318 4482 9318 4010 9318 4485 9319 4486 9319 4013 9319 4487 9320 4013 9320 4486 9320 3994 9321 4485 9321 4013 9321 4484 9322 4013 9322 4487 9322 4488 9323 4489 9323 4486 9323 4490 9324 4486 9324 4489 9324 4485 9325 4488 9325 4486 9325 4487 9326 4486 9326 4490 9326 4491 9327 4492 9327 4489 9327 4493 9328 4489 9328 4492 9328 4491 9329 4489 9329 4488 9329 4490 9330 4489 9330 4493 9330 4494 9331 4023 9331 4492 9331 4495 9332 4492 9332 4023 9332 4491 9333 4494 9333 4492 9333 4493 9334 4492 9334 4495 9334 4496 9335 4023 9335 4022 9335 4298 9336 4023 9336 4494 9336 4298 9337 4019 9337 4023 9337 4495 9338 4023 9338 4496 9338 4496 9339 4022 9339 4483 9339 4497 9340 3964 9340 3963 9340 4498 9341 3965 9341 3964 9341 4498 9342 3964 9342 4497 9342 4499 9343 3963 9343 3966 9343 4499 9344 4497 9344 3963 9344 3967 9345 4500 9345 3966 9345 4501 9346 3966 9346 4500 9346 4499 9347 3966 9347 4501 9347 4502 9348 4503 9348 4500 9348 4504 9349 4500 9349 4503 9349 3967 9350 4502 9350 4500 9350 4501 9351 4500 9351 4504 9351 4505 9352 4506 9352 4503 9352 4507 9353 4503 9353 4506 9353 4505 9354 4503 9354 4502 9354 4504 9355 4503 9355 4507 9355 4505 9356 4508 9356 4506 9356 4509 9357 4506 9357 4508 9357 4507 9358 4506 9358 4509 9358 3968 9359 3965 9359 4508 9359 4510 9360 4508 9360 3965 9360 4511 9361 4508 9361 4505 9361 4511 9362 3968 9362 4508 9362 4509 9363 4508 9363 4510 9363 4510 9364 3965 9364 4498 9364 4512 9365 4513 9365 4514 9365 4515 9366 4514 9366 4513 9366 4516 9367 4514 9367 4517 9367 4518 9368 4517 9368 4514 9368 4516 9369 4512 9369 4514 9369 4518 9370 4514 9370 4515 9370 4512 9371 4519 9371 4513 9371 4520 9372 4513 9372 4519 9372 4520 9373 4515 9373 4513 9373 4521 9374 4522 9374 4519 9374 4523 9375 4519 9375 4522 9375 4519 9376 4512 9376 3970 9376 4524 9377 4521 9377 4519 9377 4520 9378 4519 9378 4523 9378 4521 9379 4525 9379 4522 9379 4526 9380 4522 9380 4525 9380 4523 9381 4522 9381 4526 9381 4527 9382 4528 9382 4525 9382 4529 9383 4525 9383 4528 9383 4527 9384 4525 9384 4521 9384 4526 9385 4525 9385 4529 9385 4527 9386 4530 9386 4528 9386 4531 9387 4528 9387 4530 9387 4529 9388 4528 9388 4531 9388 4516 9389 4517 9389 4530 9389 4532 9390 4530 9390 4517 9390 4533 9391 4516 9391 4530 9391 4530 9392 4527 9392 4534 9392 4531 9393 4530 9393 4532 9393 4532 9394 4517 9394 4518 9394 4535 9395 4488 9395 4485 9395 4536 9396 4491 9396 4488 9396 4536 9397 4488 9397 4535 9397 4537 9398 4485 9398 3994 9398 4537 9399 4535 9399 4485 9399 4298 9400 4538 9400 3994 9400 4539 9401 3994 9401 4538 9401 4001 9402 4298 9402 3994 9402 4537 9403 3994 9403 4539 9403 4298 9404 4540 9404 4538 9404 4541 9405 4538 9405 4540 9405 4539 9406 4538 9406 4541 9406 4298 9407 4542 9407 4540 9407 4543 9408 4540 9408 4542 9408 4541 9409 4540 9409 4543 9409 4298 9410 4494 9410 4542 9410 4544 9411 4542 9411 4494 9411 4543 9412 4542 9412 4544 9412 4545 9413 4494 9413 4491 9413 4544 9414 4494 9414 4545 9414 4545 9415 4491 9415 4536 9415 4546 9416 4441 9416 4444 9416 4547 9417 4448 9417 4441 9417 4547 9418 4441 9418 4546 9418 4445 9419 4548 9419 4444 9419 4549 9420 4444 9420 4548 9420 4445 9421 4444 9421 4439 9421 4549 9422 4546 9422 4444 9422 4354 9423 4348 9423 4548 9423 4550 9424 4548 9424 4348 9424 4354 9425 4548 9425 4445 9425 4549 9426 4548 9426 4550 9426 4551 9427 4552 9427 4348 9427 4553 9428 4348 9428 4552 9428 4341 9429 4551 9429 4348 9429 4550 9430 4348 9430 4553 9430 4551 9431 4554 9431 4552 9431 4555 9432 4552 9432 4554 9432 4553 9433 4552 9433 4555 9433 4551 9434 4556 9434 4554 9434 4557 9435 4554 9435 4556 9435 4555 9436 4554 9436 4557 9436 4558 9437 4559 9437 4556 9437 4560 9438 4556 9438 4559 9438 4551 9439 4558 9439 4556 9439 4557 9440 4556 9440 4560 9440 4558 9441 4454 9441 4559 9441 4561 9442 4559 9442 4454 9442 4560 9443 4559 9443 4561 9443 4454 9444 4455 9444 4451 9444 4562 9445 4454 9445 4448 9445 4563 9446 4455 9446 4454 9446 4558 9447 4563 9447 4454 9447 4561 9448 4454 9448 4562 9448 4562 9449 4448 9449 4547 9449 4564 9450 4421 9450 4418 9450 4565 9451 4424 9451 4421 9451 4565 9452 4421 9452 4564 9452 4354 9453 4566 9453 4418 9453 4567 9454 4418 9454 4566 9454 4567 9455 4564 9455 4418 9455 4354 9456 4445 9456 4566 9456 4568 9457 4566 9457 4445 9457 4567 9458 4566 9458 4568 9458 4569 9459 4445 9459 4432 9459 4568 9460 4445 9460 4569 9460 4570 9461 4432 9461 4436 9461 4569 9462 4432 9462 4570 9462 4571 9463 4436 9463 4455 9463 4570 9464 4436 9464 4571 9464 4572 9465 4455 9465 4563 9465 4571 9466 4455 9466 4572 9466 4558 9467 4430 9467 4563 9467 4573 9468 4563 9468 4430 9468 4572 9469 4563 9469 4573 9469 4574 9470 4430 9470 4424 9470 4558 9471 4431 9471 4430 9471 4573 9472 4430 9472 4574 9472 4574 9473 4424 9473 4565 9473 4575 9474 4502 9474 3967 9474 4576 9475 4505 9475 4502 9475 4576 9476 4502 9476 4575 9476 4577 9477 3967 9477 3969 9477 4577 9478 4575 9478 3967 9478 4578 9479 3969 9479 3970 9479 4577 9480 3969 9480 4578 9480 3970 9481 4524 9481 4519 9481 4579 9482 3970 9482 4512 9482 4580 9483 4524 9483 3970 9483 3955 9484 4580 9484 3970 9484 4578 9485 3970 9485 4579 9485 4581 9486 4512 9486 4516 9486 4579 9487 4512 9487 4581 9487 4582 9488 4516 9488 4533 9488 4581 9489 4516 9489 4582 9489 4534 9490 4583 9490 4533 9490 4584 9491 4533 9491 4583 9491 4534 9492 4533 9492 4530 9492 4582 9493 4533 9493 4584 9493 4585 9494 4586 9494 4583 9494 4587 9495 4583 9495 4586 9495 4585 9496 4583 9496 4534 9496 4584 9497 4583 9497 4587 9497 4511 9498 4505 9498 4586 9498 4588 9499 4586 9499 4505 9499 4585 9500 4511 9500 4586 9500 4587 9501 4586 9501 4588 9501 4588 9502 4505 9502 4576 9502 4589 9503 4521 9503 4524 9503 4590 9504 4527 9504 4521 9504 4590 9505 4521 9505 4589 9505 4591 9506 4524 9506 4580 9506 4591 9507 4589 9507 4524 9507 3955 9508 4592 9508 4580 9508 4593 9509 4580 9509 4592 9509 4591 9510 4580 9510 4593 9510 4585 9511 4594 9511 4592 9511 4595 9512 4592 9512 4594 9512 4596 9513 4585 9513 4592 9513 3955 9514 4596 9514 4592 9514 4593 9515 4592 9515 4595 9515 4585 9516 4597 9516 4594 9516 4598 9517 4594 9517 4597 9517 4595 9518 4594 9518 4598 9518 4585 9519 4599 9519 4597 9519 4600 9520 4597 9520 4599 9520 4598 9521 4597 9521 4600 9521 4585 9522 4601 9522 4599 9522 4602 9523 4599 9523 4601 9523 4600 9524 4599 9524 4602 9524 4585 9525 4534 9525 4601 9525 4603 9526 4601 9526 4534 9526 4602 9527 4601 9527 4603 9527 4604 9528 4534 9528 4527 9528 4603 9529 4534 9529 4604 9529 4604 9530 4527 9530 4590 9530 4605 9531 3944 9531 3968 9531 4606 9532 3950 9532 3944 9532 4606 9533 3944 9533 4605 9533 4607 9534 3968 9534 4511 9534 4605 9535 3968 9535 4607 9535 4585 9536 4608 9536 4511 9536 4609 9537 4511 9537 4608 9537 4607 9538 4511 9538 4609 9538 4374 9539 4367 9539 4608 9539 4610 9540 4608 9540 4367 9540 4585 9541 4374 9541 4608 9541 4609 9542 4608 9542 4610 9542 4611 9543 4367 9543 4358 9543 4610 9544 4367 9544 4611 9544 4612 9545 4358 9545 4362 9545 4612 9546 4611 9546 4358 9546 4613 9547 4362 9547 4398 9547 4612 9548 4362 9548 4613 9548 4614 9549 4398 9549 4401 9549 4613 9550 4398 9550 4614 9550 4615 9551 4401 9551 4394 9551 4614 9552 4401 9552 4615 9552 4616 9553 4394 9553 4397 9553 4615 9554 4394 9554 4616 9554 4617 9555 4397 9555 3998 9555 4616 9556 4397 9556 4617 9556 4618 9557 3998 9557 4019 9557 4617 9558 3998 9558 4618 9558 4041 9559 4035 9559 4019 9559 4619 9560 4019 9560 4035 9560 4406 9561 4041 9561 4019 9561 4298 9562 4406 9562 4019 9562 4618 9563 4019 9563 4619 9563 4620 9564 4035 9564 4057 9564 4619 9565 4035 9565 4620 9565 4621 9566 4622 9566 4057 9566 4623 9567 4057 9567 4622 9567 4044 9568 4621 9568 4057 9568 4620 9569 4057 9569 4623 9569 4624 9570 4625 9570 4622 9570 4626 9571 4622 9571 4625 9571 4621 9572 4624 9572 4622 9572 4623 9573 4622 9573 4626 9573 4627 9574 4628 9574 4625 9574 4629 9575 4625 9575 4628 9575 4624 9576 4627 9576 4625 9576 4626 9577 4625 9577 4629 9577 4630 9578 4628 9578 4627 9578 4629 9579 4628 9579 4630 9579 4631 9580 4627 9580 4624 9580 4630 9581 4627 9581 4631 9581 4632 9582 4624 9582 4621 9582 4631 9583 4624 9583 4632 9583 4633 9584 4621 9584 4044 9584 4632 9585 4621 9585 4633 9585 4634 9586 4044 9586 4041 9586 4633 9587 4044 9587 4634 9587 4635 9588 4041 9588 4406 9588 4634 9589 4041 9589 4635 9589 4636 9590 4406 9590 4409 9590 4635 9591 4406 9591 4636 9591 4637 9592 4409 9592 4148 9592 4301 9593 4166 9593 4409 9593 4636 9594 4409 9594 4637 9594 4638 9595 4148 9595 4312 9595 4637 9596 4148 9596 4638 9596 4639 9597 4312 9597 4351 9597 4638 9598 4312 9598 4639 9598 4640 9599 4351 9599 4354 9599 4639 9600 4351 9600 4640 9600 4641 9601 4354 9601 4431 9601 4640 9602 4354 9602 4641 9602 4558 9603 4642 9603 4431 9603 4643 9604 4431 9604 4642 9604 4641 9605 4431 9605 4643 9605 4644 9606 4645 9606 4642 9606 4646 9607 4642 9607 4645 9607 4558 9608 4644 9608 4642 9608 4643 9609 4642 9609 4646 9609 4647 9610 4648 9610 4645 9610 4649 9611 4645 9611 4648 9611 4644 9612 4647 9612 4645 9612 4646 9613 4645 9613 4649 9613 4650 9614 4651 9614 4648 9614 4652 9615 4648 9615 4651 9615 4647 9616 4650 9616 4648 9616 4649 9617 4648 9617 4652 9617 4653 9618 4218 9618 4651 9618 4654 9619 4651 9619 4218 9619 4650 9620 4653 9620 4651 9620 4652 9621 4651 9621 4654 9621 4655 9622 4218 9622 4256 9622 4656 9623 4234 9623 4218 9623 4657 9624 4656 9624 4218 9624 4653 9625 4657 9625 4218 9625 4654 9626 4218 9626 4655 9626 4259 9627 4658 9627 4256 9627 4659 9628 4256 9628 4658 9628 4655 9629 4256 9629 4659 9629 4660 9630 4661 9630 4658 9630 4662 9631 4658 9631 4661 9631 4259 9632 4660 9632 4658 9632 4659 9633 4658 9633 4662 9633 4663 9634 4664 9634 4661 9634 4665 9635 4661 9635 4664 9635 4660 9636 4663 9636 4661 9636 4662 9637 4661 9637 4665 9637 4666 9638 4667 9638 4664 9638 4668 9639 4664 9639 4667 9639 4663 9640 4666 9640 4664 9640 4665 9641 4664 9641 4668 9641 4669 9642 4667 9642 4666 9642 4668 9643 4667 9643 4669 9643 4670 9644 4666 9644 4663 9644 4669 9645 4666 9645 4670 9645 4671 9646 4663 9646 4660 9646 4670 9647 4663 9647 4671 9647 4672 9648 4660 9648 4259 9648 4671 9649 4660 9649 4672 9649 4673 9650 4259 9650 4273 9650 4672 9651 4259 9651 4673 9651 4674 9652 4273 9652 4268 9652 4673 9653 4273 9653 4674 9653 4234 9654 4675 9654 4268 9654 4676 9655 4268 9655 4675 9655 4674 9656 4268 9656 4676 9656 4234 9657 4677 9657 4675 9657 4678 9658 4675 9658 4677 9658 4676 9659 4675 9659 4678 9659 4234 9660 4679 9660 4677 9660 4680 9661 4677 9661 4679 9661 4678 9662 4677 9662 4680 9662 4681 9663 4679 9663 4234 9663 4680 9664 4679 9664 4681 9664 4682 9665 4234 9665 4656 9665 4681 9666 4234 9666 4682 9666 4657 9667 4683 9667 4656 9667 4684 9668 4656 9668 4683 9668 4682 9669 4656 9669 4684 9669 4685 9670 4683 9670 4657 9670 4684 9671 4683 9671 4685 9671 4686 9672 4657 9672 4653 9672 4685 9673 4657 9673 4686 9673 4687 9674 4653 9674 4650 9674 4686 9675 4653 9675 4687 9675 4688 9676 4650 9676 4647 9676 4687 9677 4650 9677 4688 9677 4689 9678 4647 9678 4644 9678 4688 9679 4647 9679 4689 9679 4690 9680 4644 9680 4558 9680 4689 9681 4644 9681 4690 9681 4691 9682 4558 9682 4551 9682 4690 9683 4558 9683 4691 9683 4692 9684 4551 9684 4341 9684 4691 9685 4551 9685 4692 9685 4693 9686 4341 9686 4334 9686 4692 9687 4341 9687 4693 9687 4694 9688 4334 9688 4330 9688 4693 9689 4334 9689 4694 9689 4695 9690 4330 9690 4333 9690 4694 9691 4330 9691 4695 9691 4696 9692 4333 9692 4326 9692 4695 9693 4333 9693 4696 9693 4697 9694 4326 9694 4329 9694 4696 9695 4326 9695 4697 9695 4698 9696 4329 9696 4145 9696 4697 9697 4329 9697 4698 9697 4699 9698 4145 9698 4166 9698 4698 9699 4145 9699 4699 9699 4188 9700 4182 9700 4166 9700 4700 9701 4166 9701 4182 9701 4301 9702 4188 9702 4166 9702 4699 9703 4166 9703 4700 9703 4701 9704 4182 9704 4204 9704 4700 9705 4182 9705 4701 9705 4702 9706 4703 9706 4204 9706 4704 9707 4204 9707 4703 9707 4191 9708 4702 9708 4204 9708 4701 9709 4204 9709 4704 9709 4705 9710 4706 9710 4703 9710 4707 9711 4703 9711 4706 9711 4702 9712 4705 9712 4703 9712 4704 9713 4703 9713 4707 9713 4708 9714 4709 9714 4706 9714 4710 9715 4706 9715 4709 9715 4705 9716 4708 9716 4706 9716 4707 9717 4706 9717 4710 9717 4711 9718 4709 9718 4708 9718 4710 9719 4709 9719 4711 9719 4712 9720 4708 9720 4705 9720 4711 9721 4708 9721 4712 9721 4713 9722 4705 9722 4702 9722 4712 9723 4705 9723 4713 9723 4714 9724 4702 9724 4191 9724 4713 9725 4702 9725 4714 9725 4715 9726 4191 9726 4188 9726 4714 9727 4191 9727 4715 9727 4716 9728 4188 9728 4301 9728 4715 9729 4188 9729 4716 9729 4717 9730 4301 9730 4298 9730 4716 9731 4301 9731 4717 9731 4718 9732 4298 9732 4001 9732 4717 9733 4298 9733 4718 9733 4719 9734 4001 9734 4381 9734 4718 9735 4001 9735 4719 9735 4720 9736 4381 9736 4374 9736 4719 9737 4381 9737 4720 9737 4721 9738 4374 9738 4585 9738 4720 9739 4374 9739 4721 9739 4722 9740 4585 9740 4596 9740 4721 9741 4585 9741 4722 9741 3992 9742 4723 9742 4596 9742 4724 9743 4596 9743 4723 9743 3955 9744 3992 9744 4596 9744 4722 9745 4596 9745 4724 9745 3992 9746 3988 9746 4723 9746 4725 9747 4723 9747 3988 9747 4724 9748 4723 9748 4725 9748 4726 9749 4727 9749 3988 9749 4728 9750 3988 9750 4727 9750 3991 9751 4726 9751 3988 9751 4725 9752 3988 9752 4728 9752 4729 9753 4730 9753 4727 9753 4731 9754 4727 9754 4730 9754 4726 9755 4729 9755 4727 9755 4728 9756 4727 9756 4731 9756 4732 9757 4071 9757 4730 9757 4733 9758 4730 9758 4071 9758 4729 9759 4732 9759 4730 9759 4731 9760 4730 9760 4733 9760 4734 9761 4071 9761 4109 9761 4735 9762 4087 9762 4071 9762 4736 9763 4735 9763 4071 9763 4732 9764 4736 9764 4071 9764 4733 9765 4071 9765 4734 9765 4112 9766 4737 9766 4109 9766 4738 9767 4109 9767 4737 9767 4734 9768 4109 9768 4738 9768 4739 9769 4740 9769 4737 9769 4741 9770 4737 9770 4740 9770 4112 9771 4739 9771 4737 9771 4738 9772 4737 9772 4741 9772 4742 9773 4743 9773 4740 9773 4744 9774 4740 9774 4743 9774 4739 9775 4742 9775 4740 9775 4741 9776 4740 9776 4744 9776 4745 9777 4746 9777 4743 9777 4747 9778 4743 9778 4746 9778 4742 9779 4745 9779 4743 9779 4744 9780 4743 9780 4747 9780 4748 9781 4746 9781 4745 9781 4747 9782 4746 9782 4748 9782 4749 9783 4745 9783 4742 9783 4748 9784 4745 9784 4749 9784 4750 9785 4742 9785 4739 9785 4749 9786 4742 9786 4750 9786 4751 9787 4739 9787 4112 9787 4750 9788 4739 9788 4751 9788 4752 9789 4112 9789 4126 9789 4751 9790 4112 9790 4752 9790 4753 9791 4126 9791 4121 9791 4752 9792 4126 9792 4753 9792 4087 9793 4754 9793 4121 9793 4755 9794 4121 9794 4754 9794 4753 9795 4121 9795 4755 9795 4087 9796 4756 9796 4754 9796 4757 9797 4754 9797 4756 9797 4755 9798 4754 9798 4757 9798 4087 9799 4758 9799 4756 9799 4759 9800 4756 9800 4758 9800 4757 9801 4756 9801 4759 9801 4760 9802 4758 9802 4087 9802 4759 9803 4758 9803 4760 9803 4761 9804 4087 9804 4735 9804 4760 9805 4087 9805 4761 9805 4736 9806 4762 9806 4735 9806 4763 9807 4735 9807 4762 9807 4761 9808 4735 9808 4763 9808 4764 9809 4762 9809 4736 9809 4763 9810 4762 9810 4764 9810 4765 9811 4736 9811 4732 9811 4764 9812 4736 9812 4765 9812 4766 9813 4732 9813 4729 9813 4765 9814 4732 9814 4766 9814 4767 9815 4729 9815 4726 9815 4766 9816 4729 9816 4767 9816 4768 9817 4726 9817 3991 9817 4767 9818 4726 9818 4768 9818 4769 9819 3991 9819 3985 9819 4768 9820 3991 9820 4769 9820 4770 9821 3985 9821 3979 9821 4769 9822 3985 9822 4770 9822 4771 9823 3979 9823 3982 9823 4770 9824 3979 9824 4771 9824 4772 9825 3982 9825 3971 9825 4771 9826 3982 9826 4772 9826 4773 9827 3971 9827 3992 9827 4772 9828 3971 9828 4773 9828 4774 9829 3992 9829 3955 9829 4773 9830 3992 9830 4774 9830 4775 9831 3955 9831 3950 9831 4774 9832 3955 9832 4775 9832 4775 9833 3950 9833 4606 9833 4607 9834 3949 9834 3947 9834 4606 9835 3947 9835 3952 9835 4605 9836 4607 9836 3947 9836 4606 9837 4605 9837 3947 9837 4607 9838 3962 9838 3949 9838 4609 9839 3961 9839 3962 9839 4607 9840 4609 9840 3962 9840 4641 9841 3959 9841 3961 9841 4609 9842 4610 9842 3961 9842 4641 9843 3961 9843 4610 9843 4775 9844 3957 9844 3959 9844 4641 9845 4775 9845 3959 9845 4606 9846 3954 9846 3957 9846 4775 9847 4606 9847 3957 9847 4606 9848 3952 9848 3954 9848 4773 9849 3976 9849 3974 9849 4773 9850 3974 9850 3978 9850 4774 9851 3993 9851 3976 9851 4773 9852 4774 9852 3976 9852 4774 9853 3990 9853 3993 9853 4774 9854 3987 9854 3990 9854 4772 9855 3984 9855 3987 9855 4577 9856 3987 9856 4575 9856 4774 9857 4575 9857 3987 9857 4578 9858 4579 9858 3987 9858 4771 9859 3987 9859 4579 9859 4577 9860 4578 9860 3987 9860 4771 9861 4772 9861 3987 9861 4772 9862 3981 9862 3984 9862 4772 9863 3978 9863 3981 9863 4772 9864 4773 9864 3978 9864 4615 9865 4000 9865 3997 9865 4615 9866 3997 9866 4003 9866 4615 9867 4034 9867 4000 9867 4615 9868 4033 9868 4034 9868 4615 9869 4031 9869 4033 9869 4069 9870 4029 9870 4031 9870 4067 9871 4069 9871 4031 9871 4616 9872 4067 9872 4031 9872 4615 9873 4616 9873 4031 9873 4070 9874 4027 9874 4029 9874 4069 9875 4070 9875 4029 9875 4040 9876 4025 9876 4027 9876 4070 9877 4040 9877 4027 9877 4038 9878 4021 9878 4025 9878 4040 9879 4038 9879 4025 9879 4043 9880 4018 9880 4021 9880 4043 9881 4021 9881 4038 9881 4046 9882 4016 9882 4018 9882 4043 9883 4046 9883 4018 9883 4048 9884 4012 9884 4016 9884 4046 9885 4048 9885 4016 9885 4050 9886 4009 9886 4012 9886 4048 9887 4050 9887 4012 9887 4635 9888 4007 9888 4009 9888 4631 9889 4009 9889 4050 9889 4634 9890 4635 9890 4009 9890 4633 9891 4634 9891 4009 9891 4632 9892 4633 9892 4009 9892 4631 9893 4632 9893 4009 9893 4636 9894 4005 9894 4007 9894 4635 9895 4636 9895 4007 9895 4615 9896 4003 9896 4005 9896 4615 9897 4005 9897 4636 9897 4630 9898 4065 9898 4067 9898 4616 9899 4630 9899 4067 9899 4630 9900 4063 9900 4065 9900 4631 9901 4061 9901 4063 9901 4630 9902 4631 9902 4063 9902 4631 9903 4059 9903 4061 9903 4631 9904 4056 9904 4059 9904 4631 9905 4054 9905 4056 9905 4631 9906 4052 9906 4054 9906 4631 9907 4050 9907 4052 9907 4747 9908 4076 9908 4074 9908 4686 9909 4074 9909 4078 9909 4686 9910 4747 9910 4074 9910 4747 9911 4115 9911 4076 9911 4747 9912 4114 9912 4115 9912 4748 9913 4111 9913 4114 9913 4747 9914 4748 9914 4114 9914 4748 9915 4108 9915 4111 9915 4748 9916 4105 9916 4108 9916 4748 9917 4102 9917 4105 9917 4748 9918 4099 9918 4102 9918 4686 9919 4096 9919 4099 9919 4686 9920 4099 9920 4748 9920 4686 9921 4093 9921 4096 9921 4686 9922 4090 9922 4093 9922 4686 9923 4085 9923 4090 9923 4686 9924 4082 9924 4085 9924 4686 9925 4080 9925 4082 9925 4686 9926 4078 9926 4080 9926 4749 9927 4117 9927 4116 9927 4761 9928 4116 9928 4118 9928 4749 9929 4116 9929 4761 9929 4749 9930 4140 9930 4117 9930 4750 9931 4139 9931 4140 9931 4749 9932 4750 9932 4140 9932 4750 9933 4138 9933 4139 9933 4750 9934 4137 9934 4138 9934 4750 9935 4136 9935 4137 9935 4750 9936 4134 9936 4136 9936 4750 9937 4132 9937 4134 9937 4760 9938 4130 9938 4132 9938 4750 9939 4760 9939 4132 9939 4760 9940 4128 9940 4130 9940 4760 9941 4125 9941 4128 9941 4761 9942 4123 9942 4125 9942 4760 9943 4761 9943 4125 9943 4761 9944 4120 9944 4123 9944 4761 9945 4119 9945 4120 9945 4761 9946 4118 9946 4119 9946 4696 9947 4147 9947 4144 9947 4696 9948 4144 9948 4150 9948 4696 9949 4181 9949 4147 9949 4696 9950 4180 9950 4181 9950 4696 9951 4178 9951 4180 9951 4216 9952 4176 9952 4178 9952 4214 9953 4216 9953 4178 9953 4697 9954 4214 9954 4178 9954 4696 9955 4697 9955 4178 9955 4217 9956 4174 9956 4176 9956 4216 9957 4217 9957 4176 9957 4187 9958 4172 9958 4174 9958 4217 9959 4187 9959 4174 9959 4185 9960 4168 9960 4172 9960 4187 9961 4185 9961 4172 9961 4190 9962 4165 9962 4168 9962 4190 9963 4168 9963 4185 9963 4193 9964 4163 9964 4165 9964 4190 9965 4193 9965 4165 9965 4195 9966 4159 9966 4163 9966 4193 9967 4195 9967 4163 9967 4197 9968 4156 9968 4159 9968 4195 9969 4197 9969 4159 9969 4716 9970 4154 9970 4156 9970 4712 9971 4156 9971 4197 9971 4715 9972 4716 9972 4156 9972 4714 9973 4715 9973 4156 9973 4713 9974 4714 9974 4156 9974 4712 9975 4713 9975 4156 9975 4717 9976 4152 9976 4154 9976 4716 9977 4717 9977 4154 9977 4696 9978 4150 9978 4152 9978 4696 9979 4152 9979 4717 9979 4711 9980 4212 9980 4214 9980 4697 9981 4711 9981 4214 9981 4711 9982 4210 9982 4212 9982 4712 9983 4208 9983 4210 9983 4711 9984 4712 9984 4210 9984 4712 9985 4206 9985 4208 9985 4712 9986 4203 9986 4206 9986 4712 9987 4201 9987 4203 9987 4712 9988 4199 9988 4201 9988 4712 9989 4197 9989 4199 9989 4668 9990 4223 9990 4221 9990 4452 9991 4221 9991 4225 9991 4452 9992 4453 9992 4221 9992 4668 9993 4221 9993 4453 9993 4668 9994 4262 9994 4223 9994 4668 9995 4261 9995 4262 9995 4669 9996 4258 9996 4261 9996 4668 9997 4669 9997 4261 9997 4669 9998 4255 9998 4258 9998 4669 9999 4252 9999 4255 9999 4669 10000 4249 10000 4252 10000 4669 10001 4246 10001 4249 10001 4765 10002 4243 10002 4246 10002 4669 10003 4765 10003 4246 10003 4765 10004 4240 10004 4243 10004 4765 10005 4237 10005 4240 10005 4765 10006 4232 10006 4237 10006 4765 10007 4229 10007 4232 10007 4765 10008 4227 10008 4229 10008 4450 10009 4225 10009 4227 10009 4479 10010 4450 10010 4227 10010 4543 10011 4479 10011 4227 10011 4543 10012 4227 10012 4529 10012 4765 10013 4529 10013 4227 10013 4450 10014 4452 10014 4225 10014 4670 10015 4264 10015 4263 10015 4682 10016 4263 10016 4265 10016 4670 10017 4263 10017 4682 10017 4670 10018 4287 10018 4264 10018 4671 10019 4286 10019 4287 10019 4670 10020 4671 10020 4287 10020 4671 10021 4285 10021 4286 10021 4671 10022 4284 10022 4285 10022 4671 10023 4283 10023 4284 10023 4671 10024 4281 10024 4283 10024 4671 10025 4279 10025 4281 10025 4681 10026 4277 10026 4279 10026 4671 10027 4681 10027 4279 10027 4681 10028 4275 10028 4277 10028 4681 10029 4272 10029 4275 10029 4682 10030 4270 10030 4272 10030 4681 10031 4682 10031 4272 10031 4682 10032 4267 10032 4270 10032 4682 10033 4266 10033 4267 10033 4682 10034 4265 10034 4266 10034 4693 10035 4293 10035 4291 10035 4722 10036 4291 10036 4295 10036 4722 10037 4724 10037 4291 10037 4692 10038 4291 10038 4724 10038 4692 10039 4693 10039 4291 10039 4693 10040 4310 10040 4293 10040 4693 10041 4309 10041 4310 10041 4693 10042 4307 10042 4309 10042 4694 10043 4305 10043 4307 10043 4693 10044 4694 10044 4307 10044 4722 10045 4303 10045 4305 10045 4721 10046 4722 10046 4305 10046 4694 10047 4721 10047 4305 10047 4722 10048 4300 10048 4303 10048 4722 10049 4297 10049 4300 10049 4722 10050 4295 10050 4297 10050 4570 10051 4317 10051 4315 10051 4361 10052 4315 10052 4319 10052 4587 10053 4315 10053 4361 10053 4569 10054 4570 10054 4315 10054 4587 10055 4569 10055 4315 10055 4571 10056 4357 10056 4317 10056 4570 10057 4571 10057 4317 10057 4652 10058 4356 10058 4357 10058 4652 10059 4357 10059 4571 10059 4652 10060 4353 10060 4356 10060 4654 10061 4350 10061 4353 10061 4652 10062 4654 10062 4353 10062 4654 10063 4347 10063 4350 10063 4655 10064 4345 10064 4347 10064 4654 10065 4655 10065 4347 10065 4655 10066 4343 10066 4345 10066 4655 10067 4340 10067 4343 10067 4387 10068 4338 10068 4340 10068 4385 10069 4387 10069 4340 10069 4655 10070 4385 10070 4340 10070 4389 10071 4336 10071 4338 10071 4387 10072 4389 10072 4338 10072 4391 10073 4332 10073 4336 10073 4389 10074 4391 10074 4336 10074 4393 10075 4328 10075 4332 10075 4391 10076 4393 10076 4332 10076 4396 10077 4325 10077 4328 10077 4393 10078 4396 10078 4328 10078 4400 10079 4323 10079 4325 10079 4396 10080 4400 10080 4325 10080 4402 10081 4321 10081 4323 10081 4400 10082 4402 10082 4323 10082 4364 10083 4319 10083 4321 10083 4402 10084 4364 10084 4321 10084 4364 10085 4361 10085 4319 10085 4584 10086 4361 10086 4366 10086 4584 10087 4587 10087 4361 10087 4766 10088 4383 10088 4385 10088 4655 10089 4766 10089 4385 10089 4767 10090 4380 10090 4383 10090 4766 10091 4767 10091 4383 10091 4767 10092 4378 10092 4380 10092 4767 10093 4376 10093 4378 10093 4767 10094 4373 10094 4376 10094 4768 10095 4371 10095 4373 10095 4767 10096 4768 10096 4373 10096 4768 10097 4369 10097 4371 10097 4582 10098 4366 10098 4369 10098 4769 10099 4582 10099 4369 10099 4768 10100 4769 10100 4369 10100 4582 10101 4584 10101 4366 10101 4685 10102 4405 10102 4404 10102 4685 10103 4404 10103 4408 10103 4764 10104 4410 10104 4405 10104 4763 10105 4764 10105 4405 10105 4685 10106 4763 10106 4405 10106 4764 10107 4408 10107 4410 10107 4684 10108 4408 10108 4764 10108 4684 10109 4685 10109 4408 10109 4649 10110 4415 10110 4413 10110 4458 10111 4413 10111 4417 10111 4775 10112 4413 10112 4458 10112 4646 10113 4413 10113 4775 10113 4646 10114 4649 10114 4413 10114 4649 10115 4429 10115 4415 10115 4649 10116 4428 10116 4429 10116 4649 10117 4426 10117 4428 10117 4472 10118 4423 10118 4426 10118 4471 10119 4472 10119 4426 10119 4564 10120 4471 10120 4426 10120 4649 10121 4564 10121 4426 10121 4473 10122 4420 10122 4423 10122 4472 10123 4473 10123 4423 10123 4460 10124 4417 10124 4420 10124 4473 10125 4460 10125 4420 10125 4460 10126 4458 10126 4417 10126 4668 10127 4438 10127 4435 10127 4474 10128 4435 10128 4440 10128 4766 10129 4435 10129 4474 10129 4665 10130 4435 10130 4766 10130 4665 10131 4668 10131 4435 10131 4668 10132 4453 10132 4438 10132 4480 10133 4447 10133 4450 10133 4479 10134 4480 10134 4450 10134 4481 10135 4443 10135 4447 10135 4480 10136 4481 10136 4447 10136 4475 10137 4440 10137 4443 10137 4481 10138 4475 10138 4443 10138 4475 10139 4474 10139 4440 10139 4482 10140 4458 10140 4462 10140 4775 10141 4458 10141 4482 10141 4495 10142 4468 10142 4471 10142 4493 10143 4495 10143 4471 10143 4564 10144 4493 10144 4471 10144 4496 10145 4465 10145 4468 10145 4495 10146 4496 10146 4468 10146 4483 10147 4462 10147 4465 10147 4496 10148 4483 10148 4465 10148 4483 10149 4482 10149 4462 10149 4535 10150 4474 10150 4476 10150 4766 10151 4474 10151 4535 10151 4544 10152 4478 10152 4479 10152 4543 10153 4544 10153 4479 10153 4545 10154 4477 10154 4478 10154 4544 10155 4545 10155 4478 10155 4536 10156 4476 10156 4477 10156 4545 10157 4536 10157 4477 10157 4536 10158 4535 10158 4476 10158 4497 10159 4482 10159 4484 10159 4775 10160 4482 10160 4497 10160 4509 10161 4490 10161 4493 10161 4507 10162 4509 10162 4493 10162 4564 10163 4507 10163 4493 10163 4510 10164 4487 10164 4490 10164 4509 10165 4510 10165 4490 10165 4498 10166 4484 10166 4487 10166 4510 10167 4498 10167 4487 10167 4498 10168 4497 10168 4484 10168 4775 10169 4497 10169 4499 10169 4774 10170 4504 10170 4507 10170 4774 10171 4507 10171 4564 10171 4774 10172 4501 10172 4504 10172 4775 10173 4499 10173 4501 10173 4774 10174 4775 10174 4501 10174 4537 10175 4518 10175 4515 10175 4766 10176 4515 10176 4520 10176 4537 10177 4515 10177 4535 10177 4766 10178 4535 10178 4515 10178 4539 10179 4532 10179 4518 10179 4537 10180 4539 10180 4518 10180 4541 10181 4531 10181 4532 10181 4539 10182 4541 10182 4532 10182 4543 10183 4529 10183 4531 10183 4541 10184 4543 10184 4531 10184 4766 10185 4526 10185 4529 10185 4765 10186 4766 10186 4529 10186 4766 10187 4523 10187 4526 10187 4766 10188 4520 10188 4523 10188 4689 10189 4547 10189 4546 10189 4589 10190 4546 10190 4549 10190 4731 10191 4546 10191 4589 10191 4689 10192 4546 10192 4731 10192 4690 10193 4562 10193 4547 10193 4689 10194 4690 10194 4547 10194 4690 10195 4561 10195 4562 10195 4690 10196 4560 10196 4561 10196 4690 10197 4557 10197 4560 10197 4602 10198 4555 10198 4557 10198 4600 10199 4602 10199 4557 10199 4690 10200 4600 10200 4557 10200 4603 10201 4553 10201 4555 10201 4602 10202 4603 10202 4555 10202 4604 10203 4550 10203 4553 10203 4603 10204 4604 10204 4553 10204 4590 10205 4549 10205 4550 10205 4604 10206 4590 10206 4550 10206 4590 10207 4589 10207 4549 10207 4649 10208 4565 10208 4564 10208 4575 10209 4564 10209 4567 10209 4774 10210 4564 10210 4575 10210 4649 10211 4574 10211 4565 10211 4649 10212 4573 10212 4574 10212 4652 10213 4572 10213 4573 10213 4649 10214 4652 10214 4573 10214 4652 10215 4571 10215 4572 10215 4588 10216 4568 10216 4569 10216 4587 10217 4588 10217 4569 10217 4576 10218 4567 10218 4568 10218 4588 10219 4576 10219 4568 10219 4576 10220 4575 10220 4567 10220 4770 10221 4581 10221 4582 10221 4769 10222 4770 10222 4582 10222 4771 10223 4579 10223 4581 10223 4770 10224 4771 10224 4581 10224 4731 10225 4589 10225 4591 10225 4728 10226 4598 10226 4600 10226 4725 10227 4728 10227 4600 10227 4690 10228 4725 10228 4600 10228 4728 10229 4595 10229 4598 10229 4728 10230 4593 10230 4595 10230 4731 10231 4591 10231 4593 10231 4728 10232 4731 10232 4593 10232 4641 10233 4610 10233 4611 10233 4640 10234 4641 10234 4611 10234 4612 10235 4640 10235 4611 10235 4643 10236 4646 10236 4775 10236 4641 10237 4643 10237 4775 10237 4655 10238 4665 10238 4766 10238 4684 10239 4764 10239 4765 10239 4682 10240 4684 10240 4765 10240 4669 10241 4682 10241 4765 10241 4686 10242 4761 10242 4763 10242 4685 10243 4686 10243 4763 10243 4748 10244 4749 10244 4761 10244 4686 10245 4748 10245 4761 10245 4750 10246 4759 10246 4760 10246 4751 10247 4757 10247 4759 10247 4750 10248 4751 10248 4759 10248 4753 10249 4755 10249 4757 10249 4752 10250 4753 10250 4757 10250 4751 10251 4752 10251 4757 10251 4687 10252 4744 10252 4747 10252 4686 10253 4687 10253 4747 10253 4734 10254 4741 10254 4744 10254 4687 10255 4734 10255 4744 10255 4734 10256 4738 10256 4741 10256 4687 10257 4733 10257 4734 10257 4688 10258 4731 10258 4733 10258 4687 10259 4688 10259 4733 10259 4688 10260 4689 10260 4731 10260 4691 10261 4724 10261 4725 10261 4690 10262 4691 10262 4725 10262 4691 10263 4692 10263 4724 10263 4694 10264 4720 10264 4721 10264 4695 10265 4719 10265 4720 10265 4694 10266 4695 10266 4720 10266 4717 10267 4718 10267 4719 10267 4695 10268 4717 10268 4719 10268 4695 10269 4696 10269 4717 10269 4697 10270 4710 10270 4711 10270 4698 10271 4707 10271 4710 10271 4697 10272 4698 10272 4710 10272 4699 10273 4704 10273 4707 10273 4698 10274 4699 10274 4707 10274 4700 10275 4701 10275 4704 10275 4699 10276 4700 10276 4704 10276 4669 10277 4670 10277 4682 10277 4671 10278 4680 10278 4681 10278 4672 10279 4678 10279 4680 10279 4671 10280 4672 10280 4680 10280 4674 10281 4676 10281 4678 10281 4673 10282 4674 10282 4678 10282 4672 10283 4673 10283 4678 10283 4655 10284 4662 10284 4665 10284 4655 10285 4659 10285 4662 10285 4613 10286 4639 10286 4640 10286 4612 10287 4613 10287 4640 10287 4614 10288 4638 10288 4639 10288 4613 10289 4614 10289 4639 10289 4636 10290 4637 10290 4638 10290 4614 10291 4636 10291 4638 10291 4614 10292 4615 10292 4636 10292 4616 10293 4629 10293 4630 10293 4617 10294 4626 10294 4629 10294 4616 10295 4617 10295 4629 10295 4618 10296 4623 10296 4626 10296 4617 10297 4618 10297 4626 10297 4619 10298 4620 10298 4623 10298 4618 10299 4619 10299 4623 10299 4776 10300 4777 10300 4778 10300 4779 10301 4778 10301 4777 10301 4780 10302 4778 10302 4781 10302 4782 10303 4781 10303 4778 10303 4780 10304 4776 10304 4778 10304 4782 10305 4778 10305 4779 10305 4776 10306 4783 10306 4777 10306 4784 10307 4777 10307 4783 10307 4784 10308 4779 10308 4777 10308 4776 10309 4785 10309 4783 10309 4786 10310 4783 10310 4785 10310 4784 10311 4783 10311 4786 10311 4776 10312 4787 10312 4785 10312 4788 10313 4785 10313 4787 10313 4786 10314 4785 10314 4788 10314 4776 10315 4789 10315 4787 10315 4790 10316 4787 10316 4789 10316 4788 10317 4787 10317 4790 10317 4776 10318 4791 10318 4789 10318 4792 10319 4789 10319 4791 10319 4790 10320 4789 10320 4792 10320 4776 10321 4793 10321 4791 10321 4794 10322 4791 10322 4793 10322 4792 10323 4791 10323 4794 10323 4776 10324 4795 10324 4793 10324 4796 10325 4793 10325 4795 10325 4794 10326 4793 10326 4796 10326 4776 10327 4797 10327 4795 10327 4798 10328 4795 10328 4797 10328 4796 10329 4795 10329 4798 10329 4799 10330 4800 10330 4797 10330 4801 10331 4797 10331 4800 10331 4776 10332 4799 10332 4797 10332 4798 10333 4797 10333 4801 10333 4802 10334 4803 10334 4800 10334 4804 10335 4800 10335 4803 10335 4799 10336 4802 10336 4800 10336 4801 10337 4800 10337 4804 10337 4802 10338 4805 10338 4803 10338 4806 10339 4803 10339 4805 10339 4804 10340 4803 10340 4806 10340 4802 10341 4807 10341 4805 10341 4808 10342 4805 10342 4807 10342 4806 10343 4805 10343 4808 10343 4802 10344 4809 10344 4807 10344 4810 10345 4807 10345 4809 10345 4808 10346 4807 10346 4810 10346 4811 10347 4812 10347 4809 10347 4813 10348 4809 10348 4812 10348 4802 10349 4811 10349 4809 10349 4810 10350 4809 10350 4813 10350 4814 10351 4815 10351 4812 10351 4816 10352 4812 10352 4815 10352 4811 10353 4814 10353 4812 10353 4813 10354 4812 10354 4816 10354 4817 10355 4818 10355 4815 10355 4819 10356 4815 10356 4818 10356 4814 10357 4817 10357 4815 10357 4816 10358 4815 10358 4819 10358 4820 10359 4821 10359 4818 10359 4822 10360 4818 10360 4821 10360 4817 10361 4820 10361 4818 10361 4819 10362 4818 10362 4822 10362 4820 10363 4823 10363 4821 10363 4824 10364 4821 10364 4823 10364 4822 10365 4821 10365 4824 10365 4825 10366 4826 10366 4823 10366 4827 10367 4823 10367 4826 10367 4825 10368 4823 10368 4820 10368 4824 10369 4823 10369 4827 10369 4825 10370 4828 10370 4826 10370 4829 10371 4826 10371 4828 10371 4827 10372 4826 10372 4829 10372 4830 10373 4831 10373 4828 10373 4832 10374 4828 10374 4831 10374 4825 10375 4830 10375 4828 10375 4829 10376 4828 10376 4832 10376 4830 10377 4833 10377 4831 10377 4834 10378 4831 10378 4833 10378 4832 10379 4831 10379 4834 10379 4830 10380 4835 10380 4833 10380 4836 10381 4833 10381 4835 10381 4834 10382 4833 10382 4836 10382 4837 10383 4838 10383 4835 10383 4839 10384 4835 10384 4838 10384 4840 10385 4837 10385 4835 10385 4830 10386 4840 10386 4835 10386 4836 10387 4835 10387 4839 10387 4841 10388 4842 10388 4838 10388 4843 10389 4838 10389 4842 10389 4837 10390 4841 10390 4838 10390 4839 10391 4838 10391 4843 10391 4844 10392 4845 10392 4842 10392 4846 10393 4842 10393 4845 10393 4841 10394 4844 10394 4842 10394 4843 10395 4842 10395 4846 10395 4847 10396 4848 10396 4845 10396 4849 10397 4845 10397 4848 10397 4844 10398 4847 10398 4845 10398 4846 10399 4845 10399 4849 10399 4850 10400 4851 10400 4848 10400 4852 10401 4848 10401 4851 10401 4847 10402 4850 10402 4848 10402 4849 10403 4848 10403 4852 10403 4853 10404 4854 10404 4851 10404 4855 10405 4851 10405 4854 10405 4850 10406 4856 10406 4851 10406 4857 10407 4851 10407 4856 10407 4857 10408 4853 10408 4851 10408 4852 10409 4851 10409 4855 10409 4858 10410 4781 10410 4854 10410 4859 10411 4854 10411 4781 10411 4860 10412 4854 10412 4853 10412 4860 10413 4858 10413 4854 10413 4855 10414 4854 10414 4859 10414 4858 10415 4780 10415 4781 10415 4859 10416 4781 10416 4782 10416 4861 10417 4862 10417 4863 10417 4864 10418 4863 10418 4862 10418 4865 10419 4863 10419 4866 10419 4867 10420 4866 10420 4863 10420 4865 10421 4861 10421 4863 10421 4867 10422 4863 10422 4864 10422 4868 10423 4869 10423 4862 10423 4870 10424 4862 10424 4869 10424 4871 10425 4868 10425 4862 10425 4861 10426 4871 10426 4862 10426 4870 10427 4864 10427 4862 10427 4872 10428 4873 10428 4869 10428 4874 10429 4869 10429 4873 10429 4875 10430 4872 10430 4869 10430 4868 10431 4875 10431 4869 10431 4870 10432 4869 10432 4874 10432 4872 10433 4876 10433 4873 10433 4877 10434 4873 10434 4876 10434 4874 10435 4873 10435 4877 10435 4872 10436 4878 10436 4876 10436 4879 10437 4876 10437 4878 10437 4877 10438 4876 10438 4879 10438 4872 10439 4880 10439 4878 10439 4881 10440 4878 10440 4880 10440 4879 10441 4878 10441 4881 10441 4872 10442 4882 10442 4880 10442 4883 10443 4880 10443 4882 10443 4881 10444 4880 10444 4883 10444 4872 10445 4884 10445 4882 10445 4885 10446 4882 10446 4884 10446 4883 10447 4882 10447 4885 10447 4886 10448 4887 10448 4884 10448 4888 10449 4884 10449 4887 10449 4889 10450 4884 10450 4872 10450 4890 10451 4891 10451 4884 10451 4886 10452 4884 10452 4891 10452 4889 10453 4890 10453 4884 10453 4885 10454 4884 10454 4888 10454 4886 10455 4892 10455 4887 10455 4893 10456 4887 10456 4892 10456 4888 10457 4887 10457 4893 10457 4894 10458 4895 10458 4892 10458 4896 10459 4892 10459 4895 10459 4886 10460 4894 10460 4892 10460 4893 10461 4892 10461 4896 10461 4894 10462 4897 10462 4895 10462 4898 10463 4895 10463 4897 10463 4896 10464 4895 10464 4898 10464 4894 10465 4899 10465 4897 10465 4900 10466 4897 10466 4899 10466 4898 10467 4897 10467 4900 10467 4894 10468 4901 10468 4899 10468 4902 10469 4899 10469 4901 10469 4900 10470 4899 10470 4902 10470 4894 10471 4903 10471 4901 10471 4904 10472 4901 10472 4903 10472 4902 10473 4901 10473 4904 10473 4894 10474 4905 10474 4903 10474 4906 10475 4903 10475 4905 10475 4904 10476 4903 10476 4906 10476 4907 10477 4908 10477 4905 10477 4909 10478 4905 10478 4908 10478 4894 10479 4907 10479 4905 10479 4906 10480 4905 10480 4909 10480 4910 10481 4856 10481 4908 10481 4911 10482 4908 10482 4856 10482 4907 10483 4910 10483 4908 10483 4909 10484 4908 10484 4911 10484 4912 10485 4856 10485 4850 10485 4910 10486 4857 10486 4856 10486 4911 10487 4856 10487 4912 10487 4913 10488 4850 10488 4847 10488 4912 10489 4850 10489 4913 10489 4914 10490 4847 10490 4844 10490 4913 10491 4847 10491 4914 10491 4915 10492 4844 10492 4841 10492 4914 10493 4844 10493 4915 10493 4916 10494 4841 10494 4837 10494 4915 10495 4841 10495 4916 10495 4917 10496 4837 10496 4840 10496 4916 10497 4837 10497 4917 10497 4918 10498 4919 10498 4840 10498 4920 10499 4840 10499 4919 10499 4830 10500 4918 10500 4840 10500 4917 10501 4840 10501 4920 10501 4921 10502 4922 10502 4919 10502 4923 10503 4919 10503 4922 10503 4918 10504 4921 10504 4919 10504 4920 10505 4919 10505 4923 10505 4921 10506 4924 10506 4922 10506 4925 10507 4922 10507 4924 10507 4923 10508 4922 10508 4925 10508 4921 10509 4926 10509 4924 10509 4927 10510 4924 10510 4926 10510 4925 10511 4924 10511 4927 10511 4928 10512 4929 10512 4926 10512 4930 10513 4926 10513 4929 10513 4921 10514 4928 10514 4926 10514 4927 10515 4926 10515 4930 10515 4928 10516 4931 10516 4929 10516 4932 10517 4929 10517 4931 10517 4930 10518 4929 10518 4932 10518 4865 10519 4866 10519 4931 10519 4933 10520 4931 10520 4866 10520 4928 10521 4865 10521 4931 10521 4932 10522 4931 10522 4933 10522 4933 10523 4866 10523 4867 10523 4934 10524 4935 10524 4936 10524 4937 10525 4936 10525 4935 10525 4938 10526 4936 10526 4939 10526 4940 10527 4939 10527 4936 10527 4938 10528 4934 10528 4936 10528 4940 10529 4936 10529 4937 10529 4941 10530 4942 10530 4935 10530 4943 10531 4935 10531 4942 10531 4934 10532 4941 10532 4935 10532 4943 10533 4937 10533 4935 10533 4941 10534 4944 10534 4942 10534 4945 10535 4942 10535 4944 10535 4943 10536 4942 10536 4945 10536 4946 10537 4947 10537 4944 10537 4948 10538 4944 10538 4947 10538 4941 10539 4946 10539 4944 10539 4945 10540 4944 10540 4948 10540 4946 10541 4949 10541 4947 10541 4950 10542 4947 10542 4949 10542 4948 10543 4947 10543 4950 10543 4951 10544 4952 10544 4949 10544 4953 10545 4949 10545 4952 10545 4946 10546 4951 10546 4949 10546 4950 10547 4949 10547 4953 10547 4951 10548 4954 10548 4952 10548 4955 10549 4952 10549 4954 10549 4953 10550 4952 10550 4955 10550 4951 10551 4956 10551 4954 10551 4957 10552 4954 10552 4956 10552 4955 10553 4954 10553 4957 10553 4958 10554 4959 10554 4956 10554 4960 10555 4956 10555 4959 10555 4961 10556 4958 10556 4956 10556 4951 10557 4961 10557 4956 10557 4957 10558 4956 10558 4960 10558 4962 10559 4963 10559 4959 10559 4964 10560 4959 10560 4963 10560 4958 10561 4962 10561 4959 10561 4960 10562 4959 10562 4964 10562 4965 10563 4966 10563 4963 10563 4967 10564 4963 10564 4966 10564 4962 10565 4965 10565 4963 10565 4964 10566 4963 10566 4967 10566 4968 10567 4969 10567 4966 10567 4970 10568 4966 10568 4969 10568 4965 10569 4968 10569 4966 10569 4967 10570 4966 10570 4970 10570 4971 10571 4972 10571 4969 10571 4973 10572 4969 10572 4972 10572 4968 10573 4971 10573 4969 10573 4970 10574 4969 10574 4973 10574 4974 10575 4975 10575 4972 10575 4976 10576 4972 10576 4975 10576 4971 10577 4977 10577 4972 10577 4978 10578 4972 10578 4977 10578 4978 10579 4974 10579 4972 10579 4973 10580 4972 10580 4976 10580 4979 10581 4980 10581 4975 10581 4981 10582 4975 10582 4980 10582 4982 10583 4979 10583 4975 10583 4974 10584 4982 10584 4975 10584 4976 10585 4975 10585 4981 10585 4983 10586 4984 10586 4980 10586 4985 10587 4980 10587 4984 10587 4979 10588 4983 10588 4980 10588 4981 10589 4980 10589 4985 10589 4986 10590 4987 10590 4984 10590 4988 10591 4984 10591 4987 10591 4983 10592 4986 10592 4984 10592 4985 10593 4984 10593 4988 10593 4986 10594 4989 10594 4987 10594 4990 10595 4987 10595 4989 10595 4988 10596 4987 10596 4990 10596 4986 10597 4991 10597 4989 10597 4992 10598 4989 10598 4991 10598 4990 10599 4989 10599 4992 10599 4986 10600 4993 10600 4991 10600 4994 10601 4991 10601 4993 10601 4992 10602 4991 10602 4994 10602 4986 10603 4995 10603 4993 10603 4996 10604 4993 10604 4995 10604 4994 10605 4993 10605 4996 10605 4986 10606 4997 10606 4995 10606 4998 10607 4995 10607 4997 10607 4996 10608 4995 10608 4998 10608 4986 10609 4999 10609 4997 10609 5000 10610 4997 10610 4999 10610 4998 10611 4997 10611 5000 10611 4986 10612 5001 10612 4999 10612 5002 10613 4999 10613 5001 10613 5000 10614 4999 10614 5002 10614 4986 10615 5003 10615 5001 10615 5004 10616 5001 10616 5003 10616 5002 10617 5001 10617 5004 10617 5005 10618 5006 10618 5003 10618 5007 10619 5003 10619 5006 10619 4986 10620 5005 10620 5003 10620 5004 10621 5003 10621 5007 10621 5008 10622 5009 10622 5006 10622 5010 10623 5006 10623 5009 10623 5005 10624 5008 10624 5006 10624 5007 10625 5006 10625 5010 10625 5008 10626 5011 10626 5009 10626 5012 10627 5009 10627 5011 10627 5010 10628 5009 10628 5012 10628 5008 10629 5013 10629 5011 10629 5014 10630 5011 10630 5013 10630 5012 10631 5011 10631 5014 10631 5008 10632 5015 10632 5013 10632 5016 10633 5013 10633 5015 10633 5014 10634 5013 10634 5016 10634 5017 10635 4939 10635 5015 10635 5018 10636 5015 10636 4939 10636 5008 10637 5017 10637 5015 10637 5016 10638 5015 10638 5018 10638 5017 10639 4938 10639 4939 10639 5018 10640 4939 10640 4940 10640 5019 10641 5020 10641 5021 10641 5022 10642 5021 10642 5020 10642 5023 10643 5021 10643 5024 10643 5025 10644 5024 10644 5021 10644 5023 10645 5019 10645 5021 10645 5025 10646 5021 10646 5022 10646 5026 10647 4977 10647 5020 10647 5027 10648 5020 10648 4977 10648 5019 10649 5026 10649 5020 10649 5027 10650 5022 10650 5020 10650 5028 10651 4977 10651 4971 10651 5026 10652 4978 10652 4977 10652 5027 10653 4977 10653 5028 10653 5029 10654 4971 10654 4968 10654 5028 10655 4971 10655 5029 10655 5030 10656 4968 10656 4965 10656 5029 10657 4968 10657 5030 10657 5031 10658 4965 10658 4962 10658 5030 10659 4965 10659 5031 10659 5032 10660 4962 10660 4958 10660 5031 10661 4962 10661 5032 10661 5033 10662 4958 10662 4961 10662 5032 10663 4958 10663 5033 10663 5034 10664 5035 10664 4961 10664 5036 10665 4961 10665 5035 10665 4951 10666 5034 10666 4961 10666 5033 10667 4961 10667 5036 10667 5037 10668 5038 10668 5035 10668 5039 10669 5035 10669 5038 10669 5034 10670 5037 10670 5035 10670 5036 10671 5035 10671 5039 10671 5037 10672 5040 10672 5038 10672 5041 10673 5038 10673 5040 10673 5039 10674 5038 10674 5041 10674 5037 10675 5042 10675 5040 10675 5043 10676 5040 10676 5042 10676 5041 10677 5040 10677 5043 10677 5044 10678 5045 10678 5042 10678 5046 10679 5042 10679 5045 10679 5037 10680 5044 10680 5042 10680 5043 10681 5042 10681 5046 10681 5044 10682 5047 10682 5045 10682 5048 10683 5045 10683 5047 10683 5046 10684 5045 10684 5048 10684 5049 10685 5050 10685 5047 10685 5051 10686 5047 10686 5050 10686 5049 10687 5047 10687 5044 10687 5048 10688 5047 10688 5051 10688 5049 10689 5052 10689 5050 10689 5053 10690 5050 10690 5052 10690 5051 10691 5050 10691 5053 10691 5054 10692 5055 10692 5052 10692 5056 10693 5052 10693 5055 10693 5049 10694 5054 10694 5052 10694 5053 10695 5052 10695 5056 10695 5057 10696 5058 10696 5055 10696 5059 10697 5055 10697 5058 10697 5060 10698 5057 10698 5055 10698 5054 10699 5060 10699 5055 10699 5056 10700 5055 10700 5059 10700 5061 10701 5062 10701 5058 10701 5063 10702 5058 10702 5062 10702 5064 10703 5058 10703 5057 10703 5064 10704 5061 10704 5058 10704 5059 10705 5058 10705 5063 10705 5061 10706 5065 10706 5062 10706 5066 10707 5062 10707 5065 10707 5063 10708 5062 10708 5066 10708 5061 10709 5067 10709 5065 10709 5068 10710 5065 10710 5067 10710 5066 10711 5065 10711 5068 10711 5061 10712 5069 10712 5067 10712 5070 10713 5067 10713 5069 10713 5068 10714 5067 10714 5070 10714 5061 10715 5071 10715 5069 10715 5072 10716 5069 10716 5071 10716 5070 10717 5069 10717 5072 10717 5061 10718 5073 10718 5071 10718 5074 10719 5071 10719 5073 10719 5072 10720 5071 10720 5074 10720 5075 10721 5076 10721 5073 10721 5077 10722 5073 10722 5076 10722 5078 10723 5079 10723 5073 10723 5075 10724 5073 10724 5079 10724 5080 10725 5078 10725 5073 10725 5061 10726 5080 10726 5073 10726 5074 10727 5073 10727 5077 10727 5075 10728 5081 10728 5076 10728 5082 10729 5076 10729 5081 10729 5077 10730 5076 10730 5082 10730 5023 10731 5083 10731 5081 10731 5084 10732 5081 10732 5083 10732 5075 10733 5023 10733 5081 10733 5082 10734 5081 10734 5084 10734 5023 10735 5085 10735 5083 10735 5086 10736 5083 10736 5085 10736 5084 10737 5083 10737 5086 10737 5023 10738 5087 10738 5085 10738 5088 10739 5085 10739 5087 10739 5086 10740 5085 10740 5088 10740 5023 10741 5089 10741 5087 10741 5090 10742 5087 10742 5089 10742 5088 10743 5087 10743 5090 10743 5023 10744 5024 10744 5089 10744 5091 10745 5089 10745 5024 10745 5090 10746 5089 10746 5091 10746 5091 10747 5024 10747 5025 10747 5092 10748 4872 10748 4875 10748 5093 10749 4889 10749 4872 10749 5093 10750 4872 10750 5092 10750 5094 10751 5095 10751 4875 10751 5096 10752 4875 10752 5095 10752 5094 10753 4875 10753 4868 10753 5096 10754 5092 10754 4875 10754 5094 10755 5097 10755 5095 10755 5098 10756 5095 10756 5097 10756 5096 10757 5095 10757 5098 10757 5094 10758 5099 10758 5097 10758 5100 10759 5097 10759 5099 10759 5098 10760 5097 10760 5100 10760 5101 10761 5102 10761 5099 10761 5103 10762 5099 10762 5102 10762 5104 10763 5101 10763 5099 10763 5094 10764 5104 10764 5099 10764 5100 10765 5099 10765 5103 10765 5105 10766 5106 10766 5102 10766 5107 10767 5102 10767 5106 10767 5101 10768 5105 10768 5102 10768 5103 10769 5102 10769 5107 10769 5108 10770 5109 10770 5106 10770 5110 10771 5106 10771 5109 10771 5105 10772 5108 10772 5106 10772 5107 10773 5106 10773 5110 10773 5111 10774 5112 10774 5109 10774 5113 10775 5109 10775 5112 10775 5108 10776 5111 10776 5109 10776 5110 10777 5109 10777 5113 10777 5114 10778 5115 10778 5112 10778 5116 10779 5112 10779 5115 10779 5114 10780 5112 10780 5111 10780 5113 10781 5112 10781 5116 10781 5117 10782 5118 10782 5115 10782 5119 10783 5115 10783 5118 10783 5114 10784 5117 10784 5115 10784 5116 10785 5115 10785 5119 10785 5120 10786 5121 10786 5118 10786 5122 10787 5118 10787 5121 10787 5117 10788 5120 10788 5118 10788 5119 10789 5118 10789 5122 10789 5123 10790 5124 10790 5121 10790 5125 10791 5121 10791 5124 10791 5120 10792 5123 10792 5121 10792 5122 10793 5121 10793 5125 10793 4886 10794 4891 10794 5124 10794 5126 10795 5124 10795 4891 10795 5127 10796 5124 10796 5123 10796 5128 10797 4886 10797 5124 10797 5129 10798 5128 10798 5124 10798 5130 10799 5129 10799 5124 10799 5127 10800 5130 10800 5124 10800 5125 10801 5124 10801 5126 10801 5131 10802 4891 10802 4890 10802 5126 10803 4891 10803 5131 10803 5132 10804 4890 10804 4889 10804 5131 10805 4890 10805 5132 10805 5132 10806 4889 10806 5093 10806 5133 10807 5134 10807 5135 10807 5136 10808 5135 10808 5134 10808 5137 10809 5135 10809 5138 10809 5139 10810 5138 10810 5135 10810 5137 10811 5133 10811 5135 10811 5139 10812 5135 10812 5136 10812 5140 10813 5141 10813 5134 10813 5142 10814 5134 10814 5141 10814 5143 10815 5140 10815 5134 10815 5133 10816 5143 10816 5134 10816 5142 10817 5136 10817 5134 10817 5094 10818 5144 10818 5141 10818 5145 10819 5141 10819 5144 10819 5094 10820 5141 10820 5140 10820 5142 10821 5141 10821 5145 10821 5094 10822 4868 10822 5144 10822 5146 10823 5144 10823 4868 10823 5145 10824 5144 10824 5146 10824 5147 10825 4868 10825 4871 10825 5146 10826 4868 10826 5147 10826 5148 10827 4871 10827 4861 10827 5147 10828 4871 10828 5148 10828 5149 10829 4861 10829 4865 10829 5148 10830 4861 10830 5149 10830 5150 10831 4865 10831 4928 10831 5149 10832 4865 10832 5150 10832 5151 10833 4928 10833 4921 10833 5150 10834 4928 10834 5151 10834 5152 10835 4921 10835 4918 10835 5151 10836 4921 10836 5152 10836 5153 10837 5154 10837 4918 10837 5155 10838 4918 10838 5154 10838 4830 10839 5153 10839 4918 10839 5152 10840 4918 10840 5155 10840 5156 10841 5157 10841 5154 10841 5158 10842 5154 10842 5157 10842 5153 10843 5156 10843 5154 10843 5155 10844 5154 10844 5158 10844 5159 10845 5160 10845 5157 10845 5161 10846 5157 10846 5160 10846 5162 10847 5157 10847 5156 10847 5163 10848 5159 10848 5157 10848 5162 10849 5163 10849 5157 10849 5158 10850 5157 10850 5161 10850 5159 10851 5164 10851 5160 10851 5165 10852 5160 10852 5164 10852 5161 10853 5160 10853 5165 10853 5166 10854 5138 10854 5164 10854 5167 10855 5164 10855 5138 10855 5159 10856 5166 10856 5164 10856 5165 10857 5164 10857 5167 10857 5168 10858 5137 10858 5138 10858 5169 10859 5168 10859 5138 10859 5170 10860 5169 10860 5138 10860 5166 10861 5170 10861 5138 10861 5167 10862 5138 10862 5139 10862 5171 10863 5044 10863 5037 10863 5172 10864 5049 10864 5044 10864 5172 10865 5044 10865 5171 10865 5173 10866 5037 10866 5034 10866 5173 10867 5171 10867 5037 10867 5174 10868 5175 10868 5034 10868 5176 10869 5034 10869 5175 10869 4951 10870 5174 10870 5034 10870 5173 10871 5034 10871 5176 10871 5177 10872 5178 10872 5175 10872 5179 10873 5175 10873 5178 10873 5174 10874 5177 10874 5175 10874 5176 10875 5175 10875 5179 10875 5180 10876 5181 10876 5178 10876 5182 10877 5178 10877 5181 10877 5183 10878 5178 10878 5177 10878 5184 10879 5178 10879 5183 10879 5184 10880 5180 10880 5178 10880 5179 10881 5178 10881 5182 10881 5180 10882 5185 10882 5181 10882 5186 10883 5181 10883 5185 10883 5182 10884 5181 10884 5186 10884 5187 10885 5188 10885 5185 10885 5189 10886 5185 10886 5188 10886 5180 10887 5187 10887 5185 10887 5186 10888 5185 10888 5189 10888 5190 10889 5191 10889 5188 10889 5192 10890 5188 10890 5191 10890 5193 10891 5190 10891 5188 10891 5194 10892 5193 10892 5188 10892 5195 10893 5194 10893 5188 10893 5187 10894 5195 10894 5188 10894 5189 10895 5188 10895 5192 10895 5196 10896 5197 10896 5191 10896 5198 10897 5191 10897 5197 10897 5190 10898 5196 10898 5191 10898 5192 10899 5191 10899 5198 10899 5199 10900 5200 10900 5197 10900 5201 10901 5197 10901 5200 10901 5202 10902 5197 10902 5196 10902 5202 10903 5199 10903 5197 10903 5198 10904 5197 10904 5201 10904 5203 10905 5204 10905 5200 10905 5205 10906 5200 10906 5204 10906 5203 10907 5200 10907 5199 10907 5201 10908 5200 10908 5205 10908 5203 10909 5057 10909 5204 10909 5206 10910 5204 10910 5057 10910 5205 10911 5204 10911 5206 10911 5207 10912 5057 10912 5060 10912 5203 10913 5064 10913 5057 10913 5206 10914 5057 10914 5207 10914 5208 10915 5060 10915 5054 10915 5207 10916 5060 10916 5208 10916 5209 10917 5054 10917 5049 10917 5208 10918 5054 10918 5209 10918 5209 10919 5049 10919 5172 10919 5210 10920 5211 10920 5212 10920 5213 10921 5212 10921 5211 10921 5214 10922 5212 10922 5215 10922 5216 10923 5215 10923 5212 10923 5214 10924 5210 10924 5212 10924 5216 10925 5212 10925 5213 10925 5217 10926 5218 10926 5211 10926 5219 10927 5211 10927 5218 10927 5210 10928 5217 10928 5211 10928 5219 10929 5213 10929 5211 10929 5220 10930 5221 10930 5218 10930 5222 10931 5218 10931 5221 10931 5217 10932 5220 10932 5218 10932 5219 10933 5218 10933 5222 10933 5223 10934 5224 10934 5221 10934 5225 10935 5221 10935 5224 10935 5220 10936 5223 10936 5221 10936 5222 10937 5221 10937 5225 10937 5075 10938 5079 10938 5224 10938 5226 10939 5224 10939 5079 10939 5227 10940 5224 10940 5223 10940 5228 10941 5224 10941 5227 10941 5229 10942 5075 10942 5224 10942 5230 10943 5229 10943 5224 10943 5228 10944 5230 10944 5224 10944 5225 10945 5224 10945 5226 10945 5231 10946 5079 10946 5078 10946 5226 10947 5079 10947 5231 10947 5232 10948 5078 10948 5080 10948 5231 10949 5078 10949 5232 10949 5233 10950 5080 10950 5061 10950 5232 10951 5080 10951 5233 10951 5234 10952 5061 10952 5064 10952 5233 10953 5061 10953 5234 10953 5203 10954 5235 10954 5064 10954 5236 10955 5064 10955 5235 10955 5234 10956 5064 10956 5236 10956 5203 10957 5237 10957 5235 10957 5238 10958 5235 10958 5237 10958 5236 10959 5235 10959 5238 10959 5203 10960 5239 10960 5237 10960 5240 10961 5237 10961 5239 10961 5238 10962 5237 10962 5240 10962 5241 10963 5242 10963 5239 10963 5243 10964 5239 10964 5242 10964 5244 10965 5241 10965 5239 10965 5203 10966 5244 10966 5239 10966 5240 10967 5239 10967 5243 10967 5245 10968 5246 10968 5242 10968 5247 10969 5242 10969 5246 10969 5241 10970 5245 10970 5242 10970 5243 10971 5242 10971 5247 10971 5248 10972 5215 10972 5246 10972 5249 10973 5246 10973 5215 10973 5245 10974 5248 10974 5246 10974 5247 10975 5246 10975 5249 10975 5248 10976 5214 10976 5215 10976 5249 10977 5215 10977 5216 10977 5250 10978 5111 10978 5108 10978 5251 10979 5114 10979 5111 10979 5251 10980 5111 10980 5250 10980 5252 10981 5108 10981 5105 10981 5252 10982 5250 10982 5108 10982 5253 10983 5105 10983 5101 10983 5252 10984 5105 10984 5253 10984 5254 10985 5101 10985 5104 10985 5253 10986 5101 10986 5254 10986 5255 10987 5256 10987 5104 10987 5257 10988 5104 10988 5256 10988 5255 10989 5104 10989 5094 10989 5254 10990 5104 10990 5257 10990 5255 10991 5258 10991 5256 10991 5259 10992 5256 10992 5258 10992 5257 10993 5256 10993 5259 10993 5260 10994 5261 10994 5258 10994 5262 10995 5258 10995 5261 10995 5255 10996 5260 10996 5258 10996 5259 10997 5258 10997 5262 10997 5260 10998 5263 10998 5261 10998 5264 10999 5261 10999 5263 10999 5262 11000 5261 11000 5264 11000 5260 11001 5265 11001 5263 11001 5266 11002 5263 11002 5265 11002 5264 11003 5263 11003 5266 11003 5260 11004 5267 11004 5265 11004 5268 11005 5265 11005 5267 11005 5266 11006 5265 11006 5268 11006 5260 11007 5269 11007 5267 11007 5270 11008 5267 11008 5269 11008 5268 11009 5267 11009 5270 11009 5260 11010 5123 11010 5269 11010 5271 11011 5269 11011 5123 11011 5270 11012 5269 11012 5271 11012 5272 11013 5123 11013 5120 11013 5260 11014 4799 11014 5123 11014 5273 11015 5123 11015 4799 11015 5273 11016 5127 11016 5123 11016 5271 11017 5123 11017 5272 11017 5274 11018 5120 11018 5117 11018 5272 11019 5120 11019 5274 11019 5275 11020 5117 11020 5114 11020 5274 11021 5117 11021 5275 11021 5275 11022 5114 11022 5251 11022 5276 11023 4820 11023 4817 11023 5277 11024 4825 11024 4820 11024 5277 11025 4820 11025 5276 11025 5278 11026 4817 11026 4814 11026 5278 11027 5276 11027 4817 11027 5279 11028 4814 11028 4811 11028 5278 11029 4814 11029 5279 11029 5280 11030 4811 11030 4802 11030 5279 11031 4811 11031 5280 11031 5281 11032 4802 11032 4799 11032 5280 11033 4802 11033 5281 11033 5260 11034 5282 11034 4799 11034 5283 11035 4799 11035 5282 11035 5284 11036 5273 11036 4799 11036 4776 11037 5284 11037 4799 11037 5281 11038 4799 11038 5283 11038 5260 11039 5285 11039 5282 11039 5286 11040 5282 11040 5285 11040 5283 11041 5282 11041 5286 11041 5287 11042 5288 11042 5285 11042 5289 11043 5285 11043 5288 11043 5287 11044 5285 11044 5260 11044 5286 11045 5285 11045 5289 11045 5290 11046 5291 11046 5288 11046 5292 11047 5288 11047 5291 11047 5293 11048 5290 11048 5288 11048 5294 11049 5293 11049 5288 11049 5287 11050 5294 11050 5288 11050 5289 11051 5288 11051 5292 11051 5295 11052 5296 11052 5291 11052 5297 11053 5291 11053 5296 11053 5298 11054 5295 11054 5291 11054 5290 11055 5298 11055 5291 11055 5292 11056 5291 11056 5297 11056 5162 11057 5299 11057 5296 11057 5300 11058 5296 11058 5299 11058 5295 11059 5162 11059 5296 11059 5297 11060 5296 11060 5300 11060 5162 11061 5156 11061 5299 11061 5301 11062 5299 11062 5156 11062 5300 11063 5299 11063 5301 11063 5302 11064 5156 11064 5153 11064 5301 11065 5156 11065 5302 11065 5303 11066 5153 11066 4830 11066 5302 11067 5153 11067 5303 11067 5304 11068 4830 11068 4825 11068 5303 11069 4830 11069 5304 11069 5304 11070 4825 11070 5277 11070 5305 11071 5306 11071 5307 11071 5308 11072 5307 11072 5306 11072 5305 11073 5307 11073 5309 11073 5310 11074 5309 11074 5307 11074 5310 11075 5307 11075 5308 11075 5305 11076 5311 11076 5306 11076 5312 11077 5306 11077 5311 11077 5312 11078 5308 11078 5306 11078 5305 11079 5313 11079 5311 11079 5314 11080 5311 11080 5313 11080 5312 11081 5311 11081 5314 11081 5305 11082 5223 11082 5313 11082 5315 11083 5313 11083 5223 11083 5314 11084 5313 11084 5315 11084 5316 11085 5223 11085 5220 11085 5305 11086 5005 11086 5223 11086 5317 11087 5223 11087 5005 11087 5317 11088 5227 11088 5223 11088 5315 11089 5223 11089 5316 11089 5318 11090 5220 11090 5217 11090 5316 11091 5220 11091 5318 11091 5319 11092 5217 11092 5210 11092 5318 11093 5217 11093 5319 11093 5320 11094 5210 11094 5214 11094 5319 11095 5210 11095 5320 11095 5321 11096 5214 11096 5248 11096 5320 11097 5214 11097 5321 11097 5322 11098 5248 11098 5245 11098 5321 11099 5248 11099 5322 11099 5323 11100 5245 11100 5241 11100 5322 11101 5245 11101 5323 11101 5324 11102 5241 11102 5244 11102 5323 11103 5241 11103 5324 11103 5325 11104 5326 11104 5244 11104 5327 11105 5244 11105 5326 11105 5203 11106 5325 11106 5244 11106 5324 11107 5244 11107 5327 11107 5325 11108 5328 11108 5326 11108 5329 11109 5326 11109 5328 11109 5327 11110 5326 11110 5329 11110 5305 11111 5309 11111 5328 11111 5330 11112 5328 11112 5309 11112 5325 11113 5305 11113 5328 11113 5329 11114 5328 11114 5330 11114 5330 11115 5309 11115 5310 11115 5331 11116 5332 11116 5333 11116 5334 11117 5333 11117 5332 11117 5335 11118 5333 11118 5336 11118 5337 11119 5336 11119 5333 11119 5338 11120 5331 11120 5333 11120 5339 11121 5338 11121 5333 11121 5335 11122 5339 11122 5333 11122 5337 11123 5333 11123 5334 11123 5340 11124 5341 11124 5332 11124 5342 11125 5332 11125 5341 11125 5343 11126 5340 11126 5332 11126 5331 11127 5343 11127 5332 11127 5342 11128 5334 11128 5332 11128 5183 11129 5344 11129 5341 11129 5345 11130 5341 11130 5344 11130 5340 11131 5183 11131 5341 11131 5342 11132 5341 11132 5345 11132 5183 11133 5177 11133 5344 11133 5346 11134 5344 11134 5177 11134 5345 11135 5344 11135 5346 11135 5347 11136 5177 11136 5174 11136 5346 11137 5177 11137 5347 11137 5348 11138 5174 11138 4951 11138 5347 11139 5174 11139 5348 11139 5349 11140 4951 11140 4946 11140 5348 11141 4951 11141 5349 11141 5350 11142 4946 11142 4941 11142 5349 11143 4946 11143 5350 11143 5351 11144 4941 11144 4934 11144 5350 11145 4941 11145 5351 11145 5352 11146 4934 11146 4938 11146 5351 11147 4934 11147 5352 11147 5353 11148 4938 11148 5017 11148 5352 11149 4938 11149 5353 11149 5354 11150 5017 11150 5008 11150 5353 11151 5017 11151 5354 11151 5355 11152 5008 11152 5005 11152 5354 11153 5008 11153 5355 11153 5305 11154 5356 11154 5005 11154 5357 11155 5005 11155 5356 11155 5358 11156 5317 11156 5005 11156 4986 11157 5358 11157 5005 11157 5355 11158 5005 11158 5357 11158 5305 11159 5336 11159 5356 11159 5359 11160 5356 11160 5336 11160 5357 11161 5356 11161 5359 11161 5305 11162 5335 11162 5336 11162 5359 11163 5336 11163 5337 11163 5360 11164 5361 11164 5362 11164 5363 11165 5362 11165 5361 11165 5360 11166 5362 11166 5364 11166 5365 11167 5364 11167 5362 11167 5365 11168 5362 11168 5366 11168 5363 11169 5366 11169 5362 11169 5367 11170 5368 11170 5361 11170 5363 11171 5361 11171 5368 11171 5360 11172 5369 11172 5361 11172 5367 11173 5361 11173 5369 11173 5370 11174 5371 11174 5368 11174 5372 11175 5368 11175 5371 11175 5373 11176 5368 11176 5367 11176 5373 11177 5370 11177 5368 11177 5363 11178 5368 11178 5372 11178 5374 11179 5375 11179 5371 11179 5376 11180 5371 11180 5375 11180 5370 11181 5374 11181 5371 11181 5372 11182 5371 11182 5376 11182 5377 11183 5378 11183 5375 11183 5379 11184 5375 11184 5378 11184 5380 11185 5377 11185 5375 11185 5381 11186 5380 11186 5375 11186 5382 11187 5381 11187 5375 11187 5374 11188 5382 11188 5375 11188 5383 11189 5375 11189 5379 11189 5376 11190 5375 11190 5383 11190 5384 11191 5385 11191 5378 11191 5379 11192 5378 11192 5385 11192 5377 11193 5384 11193 5378 11193 5386 11194 5387 11194 5385 11194 5388 11195 5385 11195 5387 11195 5384 11196 5386 11196 5385 11196 5379 11197 5385 11197 5388 11197 5389 11198 5390 11198 5387 11198 5391 11199 5387 11199 5390 11199 5386 11200 5389 11200 5387 11200 5388 11201 5387 11201 5391 11201 5389 11202 5392 11202 5390 11202 5393 11203 5390 11203 5392 11203 5394 11204 5390 11204 5393 11204 5391 11205 5390 11205 5394 11205 5395 11206 5396 11206 5392 11206 5393 11207 5392 11207 5396 11207 5397 11208 5392 11208 5389 11208 5395 11209 5392 11209 5397 11209 5398 11210 5399 11210 5396 11210 5400 11211 5396 11211 5399 11211 5401 11212 5396 11212 5395 11212 5401 11213 5398 11213 5396 11213 5393 11214 5396 11214 5400 11214 5402 11215 5403 11215 5399 11215 5404 11216 5399 11216 5403 11216 5398 11217 5402 11217 5399 11217 5400 11218 5399 11218 5404 11218 5405 11219 5406 11219 5403 11219 5407 11220 5403 11220 5406 11220 5408 11221 5405 11221 5403 11221 5409 11222 5408 11222 5403 11222 5410 11223 5409 11223 5403 11223 5402 11224 5410 11224 5403 11224 5411 11225 5403 11225 5407 11225 5404 11226 5403 11226 5411 11226 5412 11227 5413 11227 5406 11227 5407 11228 5406 11228 5413 11228 5405 11229 5412 11229 5406 11229 5414 11230 5364 11230 5413 11230 5415 11231 5413 11231 5364 11231 5412 11232 5414 11232 5413 11232 5407 11233 5413 11233 5415 11233 5414 11234 5360 11234 5364 11234 5415 11235 5364 11235 5365 11235 5416 11236 5140 11236 5143 11236 5417 11237 5094 11237 5140 11237 5417 11238 5140 11238 5416 11238 5418 11239 5419 11239 5143 11239 5420 11240 5143 11240 5419 11240 5133 11241 5418 11241 5143 11241 5420 11242 5416 11242 5143 11242 5418 11243 5421 11243 5419 11243 5422 11244 5419 11244 5421 11244 5420 11245 5419 11245 5422 11245 5418 11246 5423 11246 5421 11246 5424 11247 5421 11247 5423 11247 5422 11248 5421 11248 5424 11248 5425 11249 5426 11249 5423 11249 5427 11250 5423 11250 5426 11250 5418 11251 5425 11251 5423 11251 5424 11252 5423 11252 5427 11252 5425 11253 5428 11253 5426 11253 5429 11254 5426 11254 5428 11254 5427 11255 5426 11255 5429 11255 5430 11256 5431 11256 5428 11256 5432 11257 5428 11257 5431 11257 5430 11258 5428 11258 5425 11258 5429 11259 5428 11259 5432 11259 5430 11260 5433 11260 5431 11260 5434 11261 5431 11261 5433 11261 5432 11262 5431 11262 5434 11262 5430 11263 5435 11263 5433 11263 5436 11264 5433 11264 5435 11264 5434 11265 5433 11265 5436 11265 5430 11266 5437 11266 5435 11266 5438 11267 5435 11267 5437 11267 5436 11268 5435 11268 5438 11268 5439 11269 5440 11269 5437 11269 5441 11270 5437 11270 5440 11270 5439 11271 5437 11271 5430 11271 5438 11272 5437 11272 5441 11272 5439 11273 5442 11273 5440 11273 5443 11274 5440 11274 5442 11274 5441 11275 5440 11275 5443 11275 5439 11276 5094 11276 5442 11276 5444 11277 5442 11277 5094 11277 5443 11278 5442 11278 5444 11278 5439 11279 5255 11279 5094 11279 5444 11280 5094 11280 5417 11280 5445 11281 5446 11281 5447 11281 5448 11282 5447 11282 5446 11282 5449 11283 5447 11283 5450 11283 5451 11284 5450 11284 5447 11284 5449 11285 5445 11285 5447 11285 5451 11286 5447 11286 5448 11286 5445 11287 5452 11287 5446 11287 5453 11288 5446 11288 5452 11288 5453 11289 5448 11289 5446 11289 5454 11290 5455 11290 5452 11290 5456 11291 5452 11291 5455 11291 5445 11292 5454 11292 5452 11292 5453 11293 5452 11293 5456 11293 5454 11294 5457 11294 5455 11294 5458 11295 5455 11295 5457 11295 5456 11296 5455 11296 5458 11296 5287 11297 5459 11297 5457 11297 5460 11298 5457 11298 5459 11298 5454 11299 5287 11299 5457 11299 5458 11300 5457 11300 5460 11300 5287 11301 5461 11301 5459 11301 5462 11302 5459 11302 5461 11302 5460 11303 5459 11303 5462 11303 5287 11304 5260 11304 5461 11304 5463 11305 5461 11305 5260 11305 5462 11306 5461 11306 5463 11306 5464 11307 5260 11307 5255 11307 5463 11308 5260 11308 5464 11308 5465 11309 5466 11309 5255 11309 5467 11310 5255 11310 5466 11310 5439 11311 5465 11311 5255 11311 5464 11312 5255 11312 5467 11312 5468 11313 5469 11313 5466 11313 5470 11314 5466 11314 5469 11314 5465 11315 5468 11315 5466 11315 5467 11316 5466 11316 5470 11316 5468 11317 5471 11317 5469 11317 5472 11318 5469 11318 5471 11318 5470 11319 5469 11319 5472 11319 5468 11320 5473 11320 5471 11320 5474 11321 5471 11321 5473 11321 5472 11322 5471 11322 5474 11322 5449 11323 5450 11323 5473 11323 5475 11324 5473 11324 5450 11324 5468 11325 5449 11325 5473 11325 5474 11326 5473 11326 5475 11326 5475 11327 5450 11327 5451 11327 5476 11328 5425 11328 5418 11328 5477 11329 5430 11329 5425 11329 5477 11330 5425 11330 5476 11330 5478 11331 5418 11331 5133 11331 5478 11332 5476 11332 5418 11332 5479 11333 5133 11333 5137 11333 5478 11334 5133 11334 5479 11334 5480 11335 5137 11335 5168 11335 5479 11336 5137 11336 5480 11336 5481 11337 5168 11337 5169 11337 5480 11338 5168 11338 5481 11338 5482 11339 5169 11339 5170 11339 5483 11340 5169 11340 5482 11340 5481 11341 5169 11341 5483 11341 5482 11342 5170 11342 5166 11342 5484 11343 5166 11343 5159 11343 5482 11344 5166 11344 5484 11344 5485 11345 5159 11345 5163 11345 5484 11346 5159 11346 5485 11346 5486 11347 5487 11347 5163 11347 5488 11348 5163 11348 5487 11348 5162 11349 5486 11349 5163 11349 5485 11350 5163 11350 5488 11350 5397 11351 5389 11351 5487 11351 5489 11352 5487 11352 5389 11352 5486 11353 5397 11353 5487 11353 5488 11354 5487 11354 5489 11354 5490 11355 5491 11355 5389 11355 5492 11356 5389 11356 5491 11356 5493 11357 5490 11357 5389 11357 5494 11358 5493 11358 5389 11358 5495 11359 5494 11359 5389 11359 5386 11360 5495 11360 5389 11360 5489 11361 5389 11361 5492 11361 5367 11362 5496 11362 5491 11362 5497 11363 5491 11363 5496 11363 5490 11364 5367 11364 5491 11364 5498 11365 5491 11365 5497 11365 5492 11366 5491 11366 5498 11366 5367 11367 5369 11367 5496 11367 5497 11368 5496 11368 5369 11368 5499 11369 5500 11369 5369 11369 5501 11370 5369 11370 5500 11370 5360 11371 5499 11371 5369 11371 5497 11372 5369 11372 5501 11372 5184 11373 5183 11373 5500 11373 5502 11374 5500 11374 5183 11374 5499 11375 5184 11375 5500 11375 5501 11376 5500 11376 5502 11376 5503 11377 5183 11377 5340 11377 5502 11378 5183 11378 5503 11378 5504 11379 5340 11379 5343 11379 5503 11380 5340 11380 5504 11380 5331 11381 5505 11381 5343 11381 5506 11382 5343 11382 5505 11382 5504 11383 5343 11383 5506 11383 5507 11384 5505 11384 5331 11384 5508 11385 5505 11385 5507 11385 5506 11386 5505 11386 5508 11386 5507 11387 5331 11387 5338 11387 5509 11388 5338 11388 5339 11388 5507 11389 5338 11389 5509 11389 5510 11390 5339 11390 5335 11390 5509 11391 5339 11391 5510 11391 5511 11392 5512 11392 5335 11392 5513 11393 5335 11393 5512 11393 5514 11394 5511 11394 5335 11394 5515 11395 5514 11395 5335 11395 5305 11396 5515 11396 5335 11396 5510 11397 5335 11397 5513 11397 5516 11398 5517 11398 5512 11398 5518 11399 5512 11399 5517 11399 5519 11400 5516 11400 5512 11400 5511 11401 5519 11401 5512 11401 5513 11402 5512 11402 5518 11402 5520 11403 5521 11403 5517 11403 5522 11404 5517 11404 5521 11404 5523 11405 5520 11405 5517 11405 5516 11406 5523 11406 5517 11406 5518 11407 5517 11407 5522 11407 5524 11408 5525 11408 5521 11408 5526 11409 5521 11409 5525 11409 5527 11410 5521 11410 5520 11410 5527 11411 5528 11411 5521 11411 5524 11412 5521 11412 5528 11412 5522 11413 5521 11413 5526 11413 5524 11414 5529 11414 5525 11414 5530 11415 5525 11415 5529 11415 5526 11416 5525 11416 5530 11416 5524 11417 5531 11417 5529 11417 5532 11418 5529 11418 5531 11418 5530 11419 5529 11419 5532 11419 5524 11420 5533 11420 5531 11420 5534 11421 5531 11421 5533 11421 5532 11422 5531 11422 5534 11422 5524 11423 5535 11423 5533 11423 5536 11424 5533 11424 5535 11424 5534 11425 5533 11425 5536 11425 5537 11426 5538 11426 5535 11426 5539 11427 5535 11427 5538 11427 5540 11428 5537 11428 5535 11428 5524 11429 5540 11429 5535 11429 5541 11430 5535 11430 5539 11430 5536 11431 5535 11431 5541 11431 5542 11432 5543 11432 5538 11432 5539 11433 5538 11433 5543 11433 5537 11434 5542 11434 5538 11434 5544 11435 5545 11435 5543 11435 5546 11436 5543 11436 5545 11436 5542 11437 5544 11437 5543 11437 5539 11438 5543 11438 5546 11438 5547 11439 5548 11439 5545 11439 5549 11440 5545 11440 5548 11440 5544 11441 5547 11441 5545 11441 5546 11442 5545 11442 5549 11442 5550 11443 5551 11443 5548 11443 5552 11444 5548 11444 5551 11444 5547 11445 5550 11445 5548 11445 5549 11446 5548 11446 5552 11446 5553 11447 5554 11447 5551 11447 5555 11448 5551 11448 5554 11448 5550 11449 5553 11449 5551 11449 5552 11450 5551 11450 5555 11450 5556 11451 5557 11451 5554 11451 5558 11452 5554 11452 5557 11452 5553 11453 5556 11453 5554 11453 5555 11454 5554 11454 5558 11454 5559 11455 5557 11455 5556 11455 5560 11456 5557 11456 5559 11456 5558 11457 5557 11457 5560 11457 5559 11458 5556 11458 5553 11458 5561 11459 5553 11459 5550 11459 5559 11460 5553 11460 5561 11460 5562 11461 5550 11461 5547 11461 5561 11462 5550 11462 5562 11462 5563 11463 5547 11463 5544 11463 5562 11464 5547 11464 5563 11464 5564 11465 5544 11465 5542 11465 5563 11466 5544 11466 5564 11466 5565 11467 5542 11467 5537 11467 5564 11468 5542 11468 5565 11468 5566 11469 5537 11469 5540 11469 5567 11470 5537 11470 5566 11470 5565 11471 5537 11471 5567 11471 5568 11472 5569 11472 5540 11472 5566 11473 5540 11473 5569 11473 5524 11474 5568 11474 5540 11474 5570 11475 5571 11475 5569 11475 5572 11476 5569 11476 5571 11476 5568 11477 5570 11477 5569 11477 5566 11478 5569 11478 5572 11478 5570 11479 5573 11479 5571 11479 5574 11480 5571 11480 5573 11480 5572 11481 5571 11481 5574 11481 5570 11482 5575 11482 5573 11482 5576 11483 5573 11483 5575 11483 5574 11484 5573 11484 5576 11484 5570 11485 5577 11485 5575 11485 5578 11486 5575 11486 5577 11486 5576 11487 5575 11487 5578 11487 5579 11488 5580 11488 5577 11488 5581 11489 5577 11489 5580 11489 5582 11490 5579 11490 5577 11490 5583 11491 5582 11491 5577 11491 5584 11492 5583 11492 5577 11492 5585 11493 5584 11493 5577 11493 5570 11494 5585 11494 5577 11494 5578 11495 5577 11495 5581 11495 5586 11496 5587 11496 5580 11496 5588 11497 5580 11497 5587 11497 5589 11498 5586 11498 5580 11498 5579 11499 5589 11499 5580 11499 5581 11500 5580 11500 5588 11500 5202 11501 5196 11501 5587 11501 5590 11502 5587 11502 5196 11502 5591 11503 5202 11503 5587 11503 5592 11504 5591 11504 5587 11504 5586 11505 5592 11505 5587 11505 5588 11506 5587 11506 5590 11506 5593 11507 5196 11507 5190 11507 5590 11508 5196 11508 5593 11508 5594 11509 5190 11509 5193 11509 5593 11510 5190 11510 5594 11510 5595 11511 5193 11511 5194 11511 5594 11512 5193 11512 5595 11512 5596 11513 5194 11513 5195 11513 5597 11514 5194 11514 5596 11514 5595 11515 5194 11515 5597 11515 5596 11516 5195 11516 5187 11516 5598 11517 5187 11517 5180 11517 5596 11518 5187 11518 5598 11518 5599 11519 5180 11519 5184 11519 5598 11520 5180 11520 5599 11520 5600 11521 5184 11521 5499 11521 5599 11522 5184 11522 5600 11522 5601 11523 5499 11523 5360 11523 5600 11524 5499 11524 5601 11524 5602 11525 5603 11525 5360 11525 5604 11526 5360 11526 5603 11526 5605 11527 5602 11527 5360 11527 5606 11528 5605 11528 5360 11528 5607 11529 5606 11529 5360 11529 5414 11530 5607 11530 5360 11530 5601 11531 5360 11531 5604 11531 5395 11532 5608 11532 5603 11532 5609 11533 5603 11533 5608 11533 5602 11534 5395 11534 5603 11534 5610 11535 5603 11535 5609 11535 5604 11536 5603 11536 5610 11536 5395 11537 5397 11537 5608 11537 5609 11538 5608 11538 5397 11538 5611 11539 5397 11539 5486 11539 5609 11540 5397 11540 5611 11540 5612 11541 5486 11541 5162 11541 5611 11542 5486 11542 5612 11542 5613 11543 5162 11543 5295 11543 5612 11544 5162 11544 5613 11544 5614 11545 5295 11545 5298 11545 5613 11546 5295 11546 5614 11546 5290 11547 5615 11547 5298 11547 5616 11548 5298 11548 5615 11548 5614 11549 5298 11549 5616 11549 5617 11550 5615 11550 5290 11550 5618 11551 5615 11551 5617 11551 5616 11552 5615 11552 5618 11552 5617 11553 5290 11553 5293 11553 5619 11554 5293 11554 5294 11554 5617 11555 5293 11555 5619 11555 5620 11556 5294 11556 5287 11556 5619 11557 5294 11557 5620 11557 5621 11558 5287 11558 5454 11558 5620 11559 5287 11559 5621 11559 5622 11560 5454 11560 5445 11560 5621 11561 5454 11561 5622 11561 5623 11562 5445 11562 5449 11562 5622 11563 5445 11563 5623 11563 5468 11564 5624 11564 5449 11564 5625 11565 5449 11565 5624 11565 5623 11566 5449 11566 5625 11566 5468 11567 5626 11567 5624 11567 5627 11568 5624 11568 5626 11568 5625 11569 5624 11569 5627 11569 5468 11570 5628 11570 5626 11570 5629 11571 5626 11571 5628 11571 5627 11572 5626 11572 5629 11572 5468 11573 5630 11573 5628 11573 5631 11574 5628 11574 5630 11574 5629 11575 5628 11575 5631 11575 5468 11576 5632 11576 5630 11576 5633 11577 5630 11577 5632 11577 5631 11578 5630 11578 5633 11578 5634 11579 5635 11579 5632 11579 5636 11580 5632 11580 5635 11580 5637 11581 5634 11581 5632 11581 5468 11582 5637 11582 5632 11582 5638 11583 5632 11583 5636 11583 5633 11584 5632 11584 5638 11584 5639 11585 5640 11585 5635 11585 5636 11586 5635 11586 5640 11586 5634 11587 5639 11587 5635 11587 5641 11588 5642 11588 5640 11588 5643 11589 5640 11589 5642 11589 5639 11590 5641 11590 5640 11590 5636 11591 5640 11591 5643 11591 5644 11592 5645 11592 5642 11592 5646 11593 5642 11593 5645 11593 5641 11594 5644 11594 5642 11594 5643 11595 5642 11595 5646 11595 5647 11596 5648 11596 5645 11596 5649 11597 5645 11597 5648 11597 5644 11598 5647 11598 5645 11598 5646 11599 5645 11599 5649 11599 5650 11600 5651 11600 5648 11600 5652 11601 5648 11601 5651 11601 5647 11602 5650 11602 5648 11602 5649 11603 5648 11603 5652 11603 5653 11604 5654 11604 5651 11604 5655 11605 5651 11605 5654 11605 5650 11606 5653 11606 5651 11606 5652 11607 5651 11607 5655 11607 5656 11608 5654 11608 5653 11608 5657 11609 5654 11609 5656 11609 5655 11610 5654 11610 5657 11610 5656 11611 5653 11611 5650 11611 5658 11612 5650 11612 5647 11612 5656 11613 5650 11613 5658 11613 5659 11614 5647 11614 5644 11614 5658 11615 5647 11615 5659 11615 5660 11616 5644 11616 5641 11616 5659 11617 5644 11617 5660 11617 5661 11618 5641 11618 5639 11618 5660 11619 5641 11619 5661 11619 5662 11620 5639 11620 5634 11620 5661 11621 5639 11621 5662 11621 5663 11622 5634 11622 5637 11622 5664 11623 5634 11623 5663 11623 5662 11624 5634 11624 5664 11624 5665 11625 5666 11625 5637 11625 5663 11626 5637 11626 5666 11626 5665 11627 5637 11627 5468 11627 5439 11628 5667 11628 5666 11628 5668 11629 5666 11629 5667 11629 5665 11630 5439 11630 5666 11630 5663 11631 5666 11631 5668 11631 5439 11632 5669 11632 5667 11632 5670 11633 5667 11633 5669 11633 5668 11634 5667 11634 5670 11634 5439 11635 5671 11635 5669 11635 5672 11636 5669 11636 5671 11636 5670 11637 5669 11637 5672 11637 5439 11638 5430 11638 5671 11638 5673 11639 5671 11639 5430 11639 5672 11640 5671 11640 5673 11640 5673 11641 5430 11641 5477 11641 5674 11642 5520 11642 5523 11642 5675 11643 5527 11643 5520 11643 5675 11644 5520 11644 5674 11644 5676 11645 5523 11645 5516 11645 5676 11646 5674 11646 5523 11646 5677 11647 5516 11647 5519 11647 5676 11648 5516 11648 5677 11648 5678 11649 5519 11649 5511 11649 5677 11650 5519 11650 5678 11650 5679 11651 5511 11651 5514 11651 5678 11652 5511 11652 5679 11652 5680 11653 5514 11653 5515 11653 5679 11654 5514 11654 5680 11654 5681 11655 5515 11655 5305 11655 5680 11656 5515 11656 5681 11656 5682 11657 5305 11657 5325 11657 5681 11658 5305 11658 5682 11658 5683 11659 5684 11659 5325 11659 5685 11660 5325 11660 5684 11660 5570 11661 5325 11661 5203 11661 5683 11662 5325 11662 5570 11662 5682 11663 5325 11663 5685 11663 5524 11664 5686 11664 5684 11664 5687 11665 5684 11665 5686 11665 5683 11666 5524 11666 5684 11666 5685 11667 5684 11667 5687 11667 5524 11668 5688 11668 5686 11668 5689 11669 5686 11669 5688 11669 5687 11670 5686 11670 5689 11670 5524 11671 5528 11671 5688 11671 5690 11672 5688 11672 5528 11672 5689 11673 5688 11673 5690 11673 5691 11674 5528 11674 5527 11674 5690 11675 5528 11675 5691 11675 5691 11676 5527 11676 5675 11676 5692 11677 5199 11677 5202 11677 5693 11678 5203 11678 5199 11678 5693 11679 5199 11679 5692 11679 5694 11680 5202 11680 5591 11680 5694 11681 5692 11681 5202 11681 5695 11682 5591 11682 5592 11682 5694 11683 5591 11683 5695 11683 5696 11684 5592 11684 5586 11684 5695 11685 5592 11685 5696 11685 5697 11686 5586 11686 5589 11686 5696 11687 5586 11687 5697 11687 5698 11688 5589 11688 5579 11688 5697 11689 5589 11689 5698 11689 5699 11690 5579 11690 5582 11690 5698 11691 5579 11691 5699 11691 5700 11692 5582 11692 5583 11692 5699 11693 5582 11693 5700 11693 5701 11694 5583 11694 5584 11694 5700 11695 5583 11695 5701 11695 5702 11696 5584 11696 5585 11696 5701 11697 5584 11697 5702 11697 5570 11698 5703 11698 5585 11698 5704 11699 5585 11699 5703 11699 5702 11700 5585 11700 5704 11700 5570 11701 5705 11701 5703 11701 5706 11702 5703 11702 5705 11702 5704 11703 5703 11703 5706 11703 5570 11704 5203 11704 5705 11704 5707 11705 5705 11705 5203 11705 5706 11706 5705 11706 5707 11706 5707 11707 5203 11707 5693 11707 5708 11708 5468 11708 5465 11708 5708 11709 5665 11709 5468 11709 5709 11710 5465 11710 5439 11710 5710 11711 5708 11711 5465 11711 5710 11712 5465 11712 5709 11712 5709 11713 5439 11713 5665 11713 5711 11714 5665 11714 5708 11714 5709 11715 5665 11715 5711 11715 5712 11716 5395 11716 5602 11716 5713 11717 5395 11717 5714 11717 5715 11718 5714 11718 5395 11718 5713 11719 5401 11719 5395 11719 5715 11720 5395 11720 5716 11720 5712 11721 5716 11721 5395 11721 5712 11722 5602 11722 5605 11722 5717 11723 5714 11723 5605 11723 5715 11724 5605 11724 5714 11724 5718 11725 5719 11725 5605 11725 5720 11726 5605 11726 5719 11726 5606 11727 5718 11727 5605 11727 5720 11728 5717 11728 5605 11728 5721 11729 5605 11729 5715 11729 5712 11730 5605 11730 5721 11730 5717 11731 5713 11731 5714 11731 5722 11732 5367 11732 5490 11732 5723 11733 5367 11733 5724 11733 5725 11734 5724 11734 5367 11734 5723 11735 5373 11735 5367 11735 5725 11736 5367 11736 5722 11736 5726 11737 5490 11737 5493 11737 5726 11738 5722 11738 5490 11738 5727 11739 5724 11739 5493 11739 5725 11740 5493 11740 5724 11740 5728 11741 5729 11741 5493 11741 5727 11742 5493 11742 5729 11742 5730 11743 5728 11743 5493 11743 5494 11744 5730 11744 5493 11744 5731 11745 5493 11745 5725 11745 5726 11746 5493 11746 5731 11746 5727 11747 5723 11747 5724 11747 5732 11748 5570 11748 5568 11748 5732 11749 5683 11749 5570 11749 5733 11750 5568 11750 5524 11750 5734 11751 5732 11751 5568 11751 5734 11752 5568 11752 5733 11752 5733 11753 5524 11753 5683 11753 5735 11754 5683 11754 5732 11754 5733 11755 5683 11755 5735 11755 5736 11756 4853 11756 4857 11756 5737 11757 4860 11757 4853 11757 5737 11758 4853 11758 5738 11758 5736 11759 5738 11759 4853 11759 5736 11760 4857 11760 4910 11760 5739 11761 4910 11761 4907 11761 5736 11762 4910 11762 5739 11762 5740 11763 4907 11763 4894 11763 5739 11764 4907 11764 5740 11764 5741 11765 4894 11765 4886 11765 5740 11766 4894 11766 5741 11766 5742 11767 4886 11767 5128 11767 5741 11768 4886 11768 5742 11768 5743 11769 5128 11769 5129 11769 5742 11770 5128 11770 5743 11770 5744 11771 5129 11771 5130 11771 5743 11772 5129 11772 5744 11772 5745 11773 5130 11773 5127 11773 5746 11774 5130 11774 5745 11774 5744 11775 5130 11775 5746 11775 5745 11776 5127 11776 5273 11776 5747 11777 5273 11777 5284 11777 5745 11778 5273 11778 5747 11778 5748 11779 5284 11779 4776 11779 5747 11780 5284 11780 5748 11780 5749 11781 4776 11781 4780 11781 5748 11782 4776 11782 5749 11782 5750 11783 4780 11783 4858 11783 5749 11784 4780 11784 5750 11784 5751 11785 4858 11785 4860 11785 5750 11786 4858 11786 5751 11786 5751 11787 4860 11787 5737 11787 5752 11788 5227 11788 5317 11788 5752 11789 5228 11789 5227 11789 5753 11790 5317 11790 5358 11790 5753 11791 5752 11791 5317 11791 5754 11792 5358 11792 4986 11792 5753 11793 5358 11793 5754 11793 5755 11794 4986 11794 4983 11794 5754 11795 4986 11795 5755 11795 5756 11796 4983 11796 4979 11796 5755 11797 4983 11797 5756 11797 5757 11798 4979 11798 4982 11798 5756 11799 4979 11799 5757 11799 5758 11800 4982 11800 4974 11800 5757 11801 4982 11801 5758 11801 5759 11802 4974 11802 4978 11802 5760 11803 4974 11803 5759 11803 5758 11804 4974 11804 5760 11804 5759 11805 4978 11805 5026 11805 5761 11806 5026 11806 5019 11806 5759 11807 5026 11807 5761 11807 5762 11808 5019 11808 5023 11808 5761 11809 5019 11809 5762 11809 5763 11810 5023 11810 5075 11810 5762 11811 5023 11811 5763 11811 5764 11812 5075 11812 5229 11812 5763 11813 5075 11813 5764 11813 5765 11814 5229 11814 5230 11814 5764 11815 5229 11815 5765 11815 5766 11816 5230 11816 5228 11816 5765 11817 5230 11817 5766 11817 5767 11818 5228 11818 5752 11818 5766 11819 5228 11819 5767 11819 5768 11820 5729 11820 5728 11820 5769 11821 5727 11821 5729 11821 5769 11822 5729 11822 5770 11822 5768 11823 5770 11823 5729 11823 5768 11824 5728 11824 5730 11824 5771 11825 5730 11825 5494 11825 5768 11826 5730 11826 5771 11826 5772 11827 5494 11827 5495 11827 5771 11828 5494 11828 5772 11828 5773 11829 5495 11829 5386 11829 5772 11830 5495 11830 5773 11830 5774 11831 5386 11831 5384 11831 5773 11832 5386 11832 5774 11832 5775 11833 5384 11833 5377 11833 5774 11834 5384 11834 5775 11834 5776 11835 5377 11835 5380 11835 5775 11836 5377 11836 5776 11836 5777 11837 5380 11837 5381 11837 5778 11838 5380 11838 5777 11838 5776 11839 5380 11839 5778 11839 5777 11840 5381 11840 5382 11840 5779 11841 5382 11841 5374 11841 5777 11842 5382 11842 5779 11842 5780 11843 5374 11843 5370 11843 5779 11844 5374 11844 5780 11844 5781 11845 5370 11845 5373 11845 5780 11846 5370 11846 5781 11846 5782 11847 5373 11847 5723 11847 5781 11848 5373 11848 5782 11848 5783 11849 5723 11849 5727 11849 5782 11850 5723 11850 5783 11850 5783 11851 5727 11851 5769 11851 5784 11852 5719 11852 5718 11852 5784 11853 5720 11853 5719 11853 5785 11854 5718 11854 5606 11854 5785 11855 5784 11855 5718 11855 5786 11856 5606 11856 5607 11856 5785 11857 5606 11857 5786 11857 5787 11858 5607 11858 5414 11858 5786 11859 5607 11859 5787 11859 5788 11860 5414 11860 5412 11860 5787 11861 5414 11861 5788 11861 5789 11862 5412 11862 5405 11862 5788 11863 5412 11863 5789 11863 5790 11864 5405 11864 5408 11864 5789 11865 5405 11865 5790 11865 5791 11866 5408 11866 5409 11866 5792 11867 5408 11867 5791 11867 5790 11868 5408 11868 5792 11868 5791 11869 5409 11869 5410 11869 5793 11870 5410 11870 5402 11870 5791 11871 5410 11871 5793 11871 5794 11872 5402 11872 5398 11872 5793 11873 5402 11873 5794 11873 5795 11874 5398 11874 5401 11874 5794 11875 5398 11875 5795 11875 5796 11876 5401 11876 5713 11876 5795 11877 5401 11877 5796 11877 5797 11878 5713 11878 5717 11878 5796 11879 5713 11879 5797 11879 5798 11880 5717 11880 5720 11880 5797 11881 5717 11881 5798 11881 5799 11882 5720 11882 5784 11882 5798 11883 5720 11883 5799 11883 5751 11884 4782 11884 4779 11884 5750 11885 4779 11885 4784 11885 5750 11886 5751 11886 4779 11886 5737 11887 4859 11887 4782 11887 5751 11888 5737 11888 4782 11888 4913 11889 4855 11889 4859 11889 5738 11890 4913 11890 4859 11890 5737 11891 5738 11891 4859 11891 4914 11892 4852 11892 4855 11892 4913 11893 4914 11893 4855 11893 4915 11894 4849 11894 4852 11894 4914 11895 4915 11895 4852 11895 4916 11896 4846 11896 4849 11896 4915 11897 4916 11897 4849 11897 4917 11898 4843 11898 4846 11898 4916 11899 4917 11899 4846 11899 4920 11900 4839 11900 4843 11900 4917 11901 4920 11901 4843 11901 5304 11902 4836 11902 4839 11902 5155 11903 4839 11903 4920 11903 5304 11904 4839 11904 5155 11904 5277 11905 4834 11905 4836 11905 5304 11906 5277 11906 4836 11906 5277 11907 4832 11907 4834 11907 5277 11908 4829 11908 4832 11908 5276 11909 4827 11909 4829 11909 5277 11910 5276 11910 4829 11910 5276 11911 4824 11911 4827 11911 5278 11912 4822 11912 4824 11912 5278 11913 4824 11913 5276 11913 5278 11914 4819 11914 4822 11914 5279 11915 4816 11915 4819 11915 5278 11916 5279 11916 4819 11916 5281 11917 4813 11917 4816 11917 5280 11918 5281 11918 4816 11918 5279 11919 5280 11919 4816 11919 5266 11920 4810 11920 4813 11920 5264 11921 5266 11921 4813 11921 5281 11922 5264 11922 4813 11922 5266 11923 4808 11923 4810 11923 5266 11924 4806 11924 4808 11924 5266 11925 4804 11925 4806 11925 5266 11926 4801 11926 4804 11926 5266 11927 4798 11927 4801 11927 5749 11928 4796 11928 4798 11928 5270 11929 5271 11929 4798 11929 5749 11930 4798 11930 5271 11930 5268 11931 5270 11931 4798 11931 5266 11932 5268 11932 4798 11932 5749 11933 4794 11933 4796 11933 5750 11934 4792 11934 4794 11934 5749 11935 5750 11935 4794 11935 5750 11936 4790 11936 4792 11936 5750 11937 4788 11937 4790 11937 5750 11938 4786 11938 4788 11938 5750 11939 4784 11939 4786 11939 5150 11940 4867 11940 4864 11940 5149 11941 4864 11941 4870 11941 5149 11942 5150 11942 4864 11942 5151 11943 4933 11943 4867 11943 5150 11944 5151 11944 4867 11944 5151 11945 4932 11945 4933 11945 5152 11946 4930 11946 4932 11946 5151 11947 5152 11947 4932 11947 5152 11948 4927 11948 4930 11948 5155 11949 4925 11949 4927 11949 5152 11950 5155 11950 4927 11950 5155 11951 4923 11951 4925 11951 5155 11952 4920 11952 4923 11952 5736 11953 4912 11953 4913 11953 5736 11954 4913 11954 5738 11954 5740 11955 4911 11955 4912 11955 5739 11956 5740 11956 4912 11956 5736 11957 5739 11957 4912 11957 5741 11958 4909 11958 4911 11958 5740 11959 5741 11959 4911 11959 5742 11960 4906 11960 4909 11960 5741 11961 5742 11961 4909 11961 5742 11962 4904 11962 4906 11962 5742 11963 4902 11963 4904 11963 5742 11964 4900 11964 4902 11964 5742 11965 4898 11965 4900 11965 5742 11966 4896 11966 4898 11966 5742 11967 4893 11967 4896 11967 5742 11968 4888 11968 4893 11968 5742 11969 4885 11969 4888 11969 5146 11970 4883 11970 4885 11970 5742 11971 5146 11971 4885 11971 5147 11972 4881 11972 4883 11972 5146 11973 5147 11973 4883 11973 5147 11974 4879 11974 4881 11974 5147 11975 4877 11975 4879 11975 5147 11976 4874 11976 4877 11976 5148 11977 4870 11977 4874 11977 5147 11978 5148 11978 4874 11978 5148 11979 5149 11979 4870 11979 5353 11980 4940 11980 4937 11980 5352 11981 4937 11981 4943 11981 5352 11982 5353 11982 4937 11982 5355 11983 5018 11983 4940 11983 5354 11984 5355 11984 4940 11984 5353 11985 5354 11985 4940 11985 5308 11986 5016 11986 5018 11986 5310 11987 5308 11987 5018 11987 5355 11988 5310 11988 5018 11988 5308 11989 5014 11989 5016 11989 5308 11990 5012 11990 5014 11990 5308 11991 5010 11991 5012 11991 5308 11992 5007 11992 5010 11992 5308 11993 5004 11993 5007 11993 5755 11994 5002 11994 5004 11994 5312 11995 5004 11995 5308 11995 5314 11996 5315 11996 5004 11996 5755 11997 5004 11997 5315 11997 5312 11998 5314 11998 5004 11998 5755 11999 5000 11999 5002 11999 5756 12000 4998 12000 5000 12000 5755 12001 5756 12001 5000 12001 5756 12002 4996 12002 4998 12002 5756 12003 4994 12003 4996 12003 5756 12004 4992 12004 4994 12004 5756 12005 4990 12005 4992 12005 5756 12006 4988 12006 4990 12006 5757 12007 4985 12007 4988 12007 5756 12008 5757 12008 4988 12008 5758 12009 4981 12009 4985 12009 5757 12010 5758 12010 4985 12010 5029 12011 4976 12011 4981 12011 5760 12012 5029 12012 4981 12012 5758 12013 5760 12013 4981 12013 5030 12014 4973 12014 4976 12014 5029 12015 5030 12015 4976 12015 5031 12016 4970 12016 4973 12016 5030 12017 5031 12017 4973 12017 5032 12018 4967 12018 4970 12018 5031 12019 5032 12019 4970 12019 5033 12020 4964 12020 4967 12020 5032 12021 5033 12021 4967 12021 5036 12022 4960 12022 4964 12022 5033 12023 5036 12023 4964 12023 5349 12024 4957 12024 4960 12024 5176 12025 4960 12025 5036 12025 5349 12026 4960 12026 5176 12026 5350 12027 4955 12027 4957 12027 5349 12028 5350 12028 4957 12028 5350 12029 4953 12029 4955 12029 5350 12030 4950 12030 4953 12030 5351 12031 4948 12031 4950 12031 5350 12032 5351 12032 4950 12032 5351 12033 4945 12033 4948 12033 5352 12034 4943 12034 4945 12034 5351 12035 5352 12035 4945 12035 5764 12036 5025 12036 5022 12036 5763 12037 5022 12037 5027 12037 5763 12038 5764 12038 5022 12038 5764 12039 5091 12039 5025 12039 5764 12040 5090 12040 5091 12040 5764 12041 5088 12041 5090 12041 5764 12042 5086 12042 5088 12042 5764 12043 5084 12043 5086 12043 5764 12044 5082 12044 5084 12044 5764 12045 5077 12045 5082 12045 5764 12046 5074 12046 5077 12046 5206 12047 5072 12047 5074 12047 5764 12048 5206 12048 5074 12048 5207 12049 5070 12049 5072 12049 5206 12050 5207 12050 5072 12050 5207 12051 5068 12051 5070 12051 5207 12052 5066 12052 5068 12052 5207 12053 5063 12053 5066 12053 5208 12054 5059 12054 5063 12054 5207 12055 5208 12055 5063 12055 5209 12056 5056 12056 5059 12056 5208 12057 5209 12057 5059 12057 5172 12058 5053 12058 5056 12058 5209 12059 5172 12059 5056 12059 5171 12060 5051 12060 5053 12060 5172 12061 5171 12061 5053 12061 5171 12062 5048 12062 5051 12062 5173 12063 5046 12063 5048 12063 5173 12064 5048 12064 5171 12064 5173 12065 5043 12065 5046 12065 5176 12066 5041 12066 5043 12066 5173 12067 5176 12067 5043 12067 5176 12068 5039 12068 5041 12068 5176 12069 5036 12069 5039 12069 5759 12070 5028 12070 5029 12070 5760 12071 5759 12071 5029 12071 5762 12072 5027 12072 5028 12072 5761 12073 5762 12073 5028 12073 5759 12074 5761 12074 5028 12074 5762 12075 5763 12075 5027 12075 5416 12076 5093 12076 5092 12076 5416 12077 5092 12077 5096 12077 5416 12078 5132 12078 5093 12078 5416 12079 5131 12079 5132 12079 5416 12080 5126 12080 5131 12080 5274 12081 5125 12081 5126 12081 5416 12082 5146 12082 5126 12082 5744 12083 5126 12083 5146 12083 5272 12084 5274 12084 5126 12084 5746 12085 5272 12085 5126 12085 5744 12086 5746 12086 5126 12086 5275 12087 5122 12087 5125 12087 5274 12088 5275 12088 5125 12088 5251 12089 5119 12089 5122 12089 5275 12090 5251 12090 5122 12090 5250 12091 5116 12091 5119 12091 5251 12092 5250 12092 5119 12092 5252 12093 5113 12093 5116 12093 5252 12094 5116 12094 5250 12094 5253 12095 5110 12095 5113 12095 5252 12096 5253 12096 5113 12096 5254 12097 5107 12097 5110 12097 5253 12098 5254 12098 5110 12098 5257 12099 5103 12099 5107 12099 5254 12100 5257 12100 5107 12100 5417 12101 5100 12101 5103 12101 5467 12102 5103 12102 5257 12102 5467 12103 5417 12103 5103 12103 5417 12104 5098 12104 5100 12104 5416 12105 5096 12105 5098 12105 5417 12106 5416 12106 5098 12106 5483 12107 5139 12107 5136 12107 5479 12108 5136 12108 5142 12108 5481 12109 5483 12109 5136 12109 5480 12110 5481 12110 5136 12110 5479 12111 5480 12111 5136 12111 5485 12112 5167 12112 5139 12112 5484 12113 5485 12113 5139 12113 5483 12114 5484 12114 5139 12114 5488 12115 5165 12115 5167 12115 5485 12116 5488 12116 5167 12116 5488 12117 5161 12117 5165 12117 5303 12118 5158 12118 5161 12118 5302 12119 5303 12119 5161 12119 5488 12120 5302 12120 5161 12120 5304 12121 5155 12121 5158 12121 5303 12122 5304 12122 5158 12122 5416 12123 5145 12123 5146 12123 5743 12124 5744 12124 5146 12124 5742 12125 5743 12125 5146 12125 5416 12126 5142 12126 5145 12126 5479 12127 5142 12127 5416 12127 5692 12128 5205 12128 5206 12128 5692 12129 5206 12129 5226 12129 5766 12130 5226 12130 5206 12130 5765 12131 5766 12131 5206 12131 5764 12132 5765 12132 5206 12132 5692 12133 5201 12133 5205 12133 5593 12134 5198 12134 5201 12134 5692 12135 5593 12135 5201 12135 5597 12136 5192 12136 5198 12136 5595 12137 5597 12137 5198 12137 5594 12138 5595 12138 5198 12138 5593 12139 5594 12139 5198 12139 5599 12140 5189 12140 5192 12140 5598 12141 5599 12141 5192 12141 5597 12142 5598 12142 5192 12142 5600 12143 5186 12143 5189 12143 5599 12144 5600 12144 5189 12144 5600 12145 5182 12145 5186 12145 5348 12146 5179 12146 5182 12146 5347 12147 5348 12147 5182 12147 5600 12148 5347 12148 5182 12148 5349 12149 5176 12149 5179 12149 5348 12150 5349 12150 5179 12150 5322 12151 5216 12151 5213 12151 5321 12152 5213 12152 5219 12152 5321 12153 5322 12153 5213 12153 5323 12154 5249 12154 5216 12154 5322 12155 5323 12155 5216 12155 5324 12156 5247 12156 5249 12156 5323 12157 5324 12157 5249 12157 5327 12158 5243 12158 5247 12158 5324 12159 5327 12159 5247 12159 5693 12160 5240 12160 5243 12160 5685 12161 5243 12161 5327 12161 5693 12162 5243 12162 5685 12162 5693 12163 5238 12163 5240 12163 5692 12164 5236 12164 5238 12164 5693 12165 5692 12165 5238 12165 5692 12166 5234 12166 5236 12166 5692 12167 5233 12167 5234 12167 5692 12168 5232 12168 5233 12168 5692 12169 5231 12169 5232 12169 5692 12170 5226 12170 5231 12170 5318 12171 5225 12171 5226 12171 5316 12172 5318 12172 5226 12172 5767 12173 5316 12173 5226 12173 5766 12174 5767 12174 5226 12174 5319 12175 5222 12175 5225 12175 5318 12176 5319 12176 5225 12176 5320 12177 5219 12177 5222 12177 5319 12178 5320 12178 5222 12178 5320 12179 5321 12179 5219 12179 5749 12180 5271 12180 5272 12180 5748 12181 5749 12181 5272 12181 5747 12182 5748 12182 5272 12182 5745 12183 5747 12183 5272 12183 5746 12184 5745 12184 5272 12184 5467 12185 5262 12185 5264 12185 5467 12186 5264 12186 5281 12186 5467 12187 5259 12187 5262 12187 5467 12188 5257 12188 5259 12188 5614 12189 5301 12189 5302 12189 5613 12190 5614 12190 5302 12190 5488 12191 5613 12191 5302 12191 5614 12192 5300 12192 5301 12192 5616 12193 5297 12193 5300 12193 5614 12194 5616 12194 5300 12194 5620 12195 5292 12195 5297 12195 5619 12196 5620 12196 5297 12196 5617 12197 5619 12197 5297 12197 5618 12198 5617 12198 5297 12198 5616 12199 5618 12199 5297 12199 5621 12200 5289 12200 5292 12200 5620 12201 5621 12201 5292 12201 5464 12202 5286 12202 5289 12202 5463 12203 5464 12203 5289 12203 5621 12204 5463 12204 5289 12204 5467 12205 5283 12205 5286 12205 5464 12206 5467 12206 5286 12206 5467 12207 5281 12207 5283 12207 5685 12208 5330 12208 5310 12208 5685 12209 5310 12209 5355 12209 5685 12210 5329 12210 5330 12210 5685 12211 5327 12211 5329 12211 5755 12212 5315 12212 5316 12212 5767 12213 5752 12213 5316 12213 5753 12214 5316 12214 5752 12214 5754 12215 5755 12215 5316 12215 5753 12216 5754 12216 5316 12216 5513 12217 5337 12217 5334 12217 5510 12218 5334 12218 5342 12218 5510 12219 5513 12219 5334 12219 5682 12220 5359 12220 5337 12220 5681 12221 5337 12221 5513 12221 5681 12222 5682 12222 5337 12222 5685 12223 5357 12223 5359 12223 5682 12224 5685 12224 5359 12224 5685 12225 5355 12225 5357 12225 5504 12226 5346 12226 5347 12226 5503 12227 5347 12227 5600 12227 5503 12228 5504 12228 5347 12228 5504 12229 5345 12229 5346 12229 5506 12230 5342 12230 5345 12230 5504 12231 5506 12231 5345 12231 5509 12232 5510 12232 5342 12232 5507 12233 5509 12233 5342 12233 5508 12234 5507 12234 5342 12234 5506 12235 5508 12235 5342 12235 5712 12236 5365 12236 5366 12236 5501 12237 5366 12237 5363 12237 5501 12238 5604 12238 5366 12238 5712 12239 5366 12239 5604 12239 5788 12240 5415 12240 5365 12240 5787 12241 5365 12241 5712 12241 5787 12242 5788 12242 5365 12242 5789 12243 5407 12243 5415 12243 5788 12244 5789 12244 5415 12244 5793 12245 5411 12245 5407 12245 5791 12246 5793 12246 5407 12246 5792 12247 5791 12247 5407 12247 5790 12248 5792 12248 5407 12248 5789 12249 5790 12249 5407 12249 5794 12250 5404 12250 5411 12250 5793 12251 5794 12251 5411 12251 5795 12252 5400 12252 5404 12252 5794 12253 5795 12253 5404 12253 5611 12254 5393 12254 5400 12254 5795 12255 5611 12255 5400 12255 5611 12256 5394 12256 5393 12256 5726 12257 5391 12257 5394 12257 5492 12258 5394 12258 5611 12258 5726 12259 5394 12259 5492 12259 5774 12260 5388 12260 5391 12260 5773 12261 5391 12261 5726 12261 5773 12262 5774 12262 5391 12262 5775 12263 5379 12263 5388 12263 5774 12264 5775 12264 5388 12264 5779 12265 5383 12265 5379 12265 5777 12266 5779 12266 5379 12266 5778 12267 5777 12267 5379 12267 5776 12268 5778 12268 5379 12268 5775 12269 5776 12269 5379 12269 5780 12270 5376 12270 5383 12270 5779 12271 5780 12271 5383 12271 5781 12272 5372 12272 5376 12272 5780 12273 5781 12273 5376 12273 5501 12274 5363 12274 5372 12274 5781 12275 5501 12275 5372 12275 5479 12276 5416 12276 5420 12276 5709 12277 5444 12277 5417 12277 5710 12278 5417 12278 5467 12278 5710 12279 5709 12279 5417 12279 5711 12280 5443 12280 5444 12280 5709 12281 5711 12281 5444 12281 5711 12282 5441 12282 5443 12282 5711 12283 5438 12283 5441 12283 5477 12284 5436 12284 5438 12284 5711 12285 5477 12285 5438 12285 5477 12286 5434 12286 5436 12286 5476 12287 5432 12287 5434 12287 5477 12288 5476 12288 5434 12288 5476 12289 5429 12289 5432 12289 5478 12290 5427 12290 5429 12290 5478 12291 5429 12291 5476 12291 5478 12292 5424 12292 5427 12292 5479 12293 5422 12293 5424 12293 5478 12294 5479 12294 5424 12294 5479 12295 5420 12295 5422 12295 5625 12296 5451 12296 5448 12296 5625 12297 5448 12297 5453 12297 5625 12298 5475 12298 5451 12298 5625 12299 5474 12299 5475 12299 5710 12300 5472 12300 5474 12300 5710 12301 5474 12301 5625 12301 5710 12302 5470 12302 5472 12302 5710 12303 5467 12303 5470 12303 5622 12304 5462 12304 5463 12304 5621 12305 5622 12305 5463 12305 5622 12306 5460 12306 5462 12306 5622 12307 5458 12307 5460 12307 5623 12308 5456 12308 5458 12308 5622 12309 5623 12309 5458 12309 5623 12310 5453 12310 5456 12310 5623 12311 5625 12311 5453 12311 5711 12312 5673 12312 5477 12312 5711 12313 5672 12313 5673 12313 5711 12314 5670 12314 5672 12314 5711 12315 5668 12315 5670 12315 5711 12316 5663 12316 5668 12316 5636 12317 5664 12317 5663 12317 5638 12318 5636 12318 5663 12318 5711 12319 5638 12319 5663 12319 5643 12320 5662 12320 5664 12320 5636 12321 5643 12321 5664 12321 5646 12322 5661 12322 5662 12322 5643 12323 5646 12323 5662 12323 5649 12324 5660 12324 5661 12324 5646 12325 5649 12325 5661 12325 5652 12326 5659 12326 5660 12326 5649 12327 5652 12327 5660 12327 5655 12328 5658 12328 5659 12328 5652 12329 5655 12329 5659 12329 5657 12330 5656 12330 5658 12330 5655 12331 5657 12331 5658 12331 5708 12332 5633 12332 5638 12332 5711 12333 5708 12333 5638 12333 5710 12334 5631 12334 5633 12334 5710 12335 5633 12335 5708 12335 5710 12336 5629 12336 5631 12336 5710 12337 5627 12337 5629 12337 5710 12338 5625 12338 5627 12338 5489 12339 5612 12339 5613 12339 5488 12340 5489 12340 5613 12340 5492 12341 5611 12341 5612 12341 5489 12342 5492 12342 5612 12342 5716 12343 5609 12343 5611 12343 5715 12344 5716 12344 5611 12344 5797 12345 5715 12345 5611 12345 5796 12346 5797 12346 5611 12346 5795 12347 5796 12347 5611 12347 5712 12348 5610 12348 5609 12348 5712 12349 5609 12349 5716 12349 5712 12350 5604 12350 5610 12350 5502 12351 5601 12351 5604 12351 5501 12352 5502 12352 5604 12352 5503 12353 5600 12353 5601 12353 5502 12354 5503 12354 5601 12354 5597 12355 5596 12355 5598 12355 5696 12356 5590 12356 5593 12356 5694 12357 5593 12357 5692 12357 5695 12358 5696 12358 5593 12358 5694 12359 5695 12359 5593 12359 5698 12360 5588 12360 5590 12360 5697 12361 5698 12361 5590 12361 5696 12362 5697 12362 5590 12362 5700 12363 5581 12363 5588 12363 5699 12364 5700 12364 5588 12364 5698 12365 5699 12365 5588 12365 5734 12366 5578 12366 5581 12366 5701 12367 5702 12367 5581 12367 5734 12368 5581 12368 5702 12368 5700 12369 5701 12369 5581 12369 5734 12370 5576 12370 5578 12370 5734 12371 5574 12371 5576 12371 5734 12372 5572 12372 5574 12372 5734 12373 5566 12373 5572 12373 5539 12374 5567 12374 5566 12374 5541 12375 5539 12375 5566 12375 5734 12376 5541 12376 5566 12376 5546 12377 5565 12377 5567 12377 5539 12378 5546 12378 5567 12378 5549 12379 5564 12379 5565 12379 5546 12380 5549 12380 5565 12380 5552 12381 5563 12381 5564 12381 5549 12382 5552 12382 5564 12382 5555 12383 5562 12383 5563 12383 5552 12384 5555 12384 5563 12384 5558 12385 5561 12385 5562 12385 5555 12386 5558 12386 5562 12386 5560 12387 5559 12387 5561 12387 5558 12388 5560 12388 5561 12388 5733 12389 5536 12389 5541 12389 5734 12390 5733 12390 5541 12390 5735 12391 5534 12391 5536 12391 5733 12392 5735 12392 5536 12392 5735 12393 5532 12393 5534 12393 5735 12394 5530 12394 5532 12394 5735 12395 5526 12395 5530 12395 5676 12396 5522 12396 5526 12396 5675 12397 5674 12397 5526 12397 5676 12398 5526 12398 5674 12398 5691 12399 5675 12399 5526 12399 5690 12400 5691 12400 5526 12400 5735 12401 5690 12401 5526 12401 5678 12402 5518 12402 5522 12402 5677 12403 5678 12403 5522 12403 5676 12404 5677 12404 5522 12404 5681 12405 5513 12405 5518 12405 5680 12406 5681 12406 5518 12406 5679 12407 5680 12407 5518 12407 5678 12408 5679 12408 5518 12408 5722 12409 5497 12409 5501 12409 5725 12410 5722 12410 5501 12410 5783 12411 5725 12411 5501 12411 5782 12412 5783 12412 5501 12412 5781 12413 5782 12413 5501 12413 5726 12414 5498 12414 5497 12414 5726 12415 5497 12415 5722 12415 5726 12416 5492 12416 5498 12416 5483 12417 5482 12417 5484 12417 5735 12418 5689 12418 5690 12418 5735 12419 5687 12419 5689 12419 5735 12420 5685 12420 5687 12420 5735 12421 5693 12421 5685 12421 5732 12422 5707 12422 5693 12422 5735 12423 5732 12423 5693 12423 5734 12424 5706 12424 5707 12424 5734 12425 5707 12425 5732 12425 5734 12426 5704 12426 5706 12426 5734 12427 5702 12427 5704 12427 5785 12428 5721 12428 5715 12428 5799 12429 5784 12429 5715 12429 5785 12430 5715 12430 5784 12430 5798 12431 5799 12431 5715 12431 5797 12432 5798 12432 5715 12432 5786 12433 5712 12433 5721 12433 5785 12434 5786 12434 5721 12434 5786 12435 5787 12435 5712 12435 5771 12436 5731 12436 5725 12436 5769 12437 5770 12437 5725 12437 5768 12438 5725 12438 5770 12438 5783 12439 5769 12439 5725 12439 5768 12440 5771 12440 5725 12440 5772 12441 5726 12441 5731 12441 5771 12442 5772 12442 5731 12442 5772 12443 5773 12443 5726 12443 5800 12444 5801 12444 5802 12444 5803 12445 5802 12445 5801 12445 5804 12446 5800 12446 5802 12446 5805 12447 5804 12447 5802 12447 5806 12448 5805 12448 5802 12448 5806 12449 5802 12449 5803 12449 5807 12450 5808 12450 5801 12450 5809 12451 5801 12451 5808 12451 5800 12452 5807 12452 5801 12452 5809 12453 5803 12453 5801 12453 5810 12454 5811 12454 5808 12454 5809 12455 5808 12455 5811 12455 5807 12456 5810 12456 5808 12456 5812 12457 5813 12457 5811 12457 5814 12458 5811 12458 5813 12458 5810 12459 5812 12459 5811 12459 5809 12460 5811 12460 5814 12460 5815 12461 5816 12461 5813 12461 5814 12462 5813 12462 5816 12462 5812 12463 5815 12463 5813 12463 5817 12464 5818 12464 5816 12464 5819 12465 5816 12465 5818 12465 5815 12466 5817 12466 5816 12466 5814 12467 5816 12467 5819 12467 5820 12468 5821 12468 5818 12468 5819 12469 5818 12469 5821 12469 5817 12470 5820 12470 5818 12470 5822 12471 5823 12471 5821 12471 5824 12472 5821 12472 5823 12472 5820 12473 5822 12473 5821 12473 5819 12474 5821 12474 5824 12474 5825 12475 5826 12475 5823 12475 5824 12476 5823 12476 5826 12476 5822 12477 5825 12477 5823 12477 5827 12478 5828 12478 5826 12478 5829 12479 5826 12479 5828 12479 5825 12480 5827 12480 5826 12480 5824 12481 5826 12481 5829 12481 5830 12482 5831 12482 5828 12482 5829 12483 5828 12483 5831 12483 5827 12484 5830 12484 5828 12484 5832 12485 5833 12485 5831 12485 5834 12486 5831 12486 5833 12486 5830 12487 5832 12487 5831 12487 5829 12488 5831 12488 5834 12488 5832 12489 5835 12489 5833 12489 5834 12490 5833 12490 5835 12490 5836 12491 5835 12491 5832 12491 5834 12492 5835 12492 5836 12492 5837 12493 5832 12493 5830 12493 5836 12494 5832 12494 5837 12494 5837 12495 5830 12495 5827 12495 5838 12496 5827 12496 5825 12496 5837 12497 5827 12497 5838 12497 5838 12498 5825 12498 5822 12498 5839 12499 5822 12499 5820 12499 5838 12500 5822 12500 5839 12500 5839 12501 5820 12501 5817 12501 5840 12502 5817 12502 5815 12502 5839 12503 5817 12503 5840 12503 5840 12504 5815 12504 5812 12504 5841 12505 5812 12505 5810 12505 5840 12506 5812 12506 5841 12506 5841 12507 5810 12507 5807 12507 5842 12508 5807 12508 5800 12508 5841 12509 5807 12509 5842 12509 5842 12510 5800 12510 5804 12510 5805 12511 5843 12511 5804 12511 5844 12512 5804 12512 5843 12512 5842 12513 5804 12513 5844 12513 5845 12514 5846 12514 5843 12514 5847 12515 5843 12515 5846 12515 5805 12516 5845 12516 5843 12516 5844 12517 5843 12517 5847 12517 5848 12518 5849 12518 5846 12518 5847 12519 5846 12519 5849 12519 5845 12520 5848 12520 5846 12520 5850 12521 5851 12521 5849 12521 5852 12522 5849 12522 5851 12522 5848 12523 5850 12523 5849 12523 5847 12524 5849 12524 5852 12524 5853 12525 5854 12525 5851 12525 5852 12526 5851 12526 5854 12526 5850 12527 5853 12527 5851 12527 5855 12528 5856 12528 5854 12528 5857 12529 5854 12529 5856 12529 5853 12530 5855 12530 5854 12530 5852 12531 5854 12531 5857 12531 5858 12532 5859 12532 5856 12532 5857 12533 5856 12533 5859 12533 5855 12534 5858 12534 5856 12534 5860 12535 5861 12535 5859 12535 5862 12536 5859 12536 5861 12536 5858 12537 5860 12537 5859 12537 5857 12538 5859 12538 5862 12538 5863 12539 5864 12539 5861 12539 5862 12540 5861 12540 5864 12540 5860 12541 5863 12541 5861 12541 5865 12542 5866 12542 5864 12542 5867 12543 5864 12543 5866 12543 5863 12544 5865 12544 5864 12544 5862 12545 5864 12545 5867 12545 5868 12546 5869 12546 5866 12546 5867 12547 5866 12547 5869 12547 5865 12548 5868 12548 5866 12548 5870 12549 5871 12549 5869 12549 5872 12550 5869 12550 5871 12550 5868 12551 5870 12551 5869 12551 5867 12552 5869 12552 5872 12552 5870 12553 5873 12553 5871 12553 5872 12554 5871 12554 5873 12554 5874 12555 5873 12555 5870 12555 5872 12556 5873 12556 5874 12556 5875 12557 5870 12557 5868 12557 5874 12558 5870 12558 5875 12558 5875 12559 5868 12559 5865 12559 5876 12560 5865 12560 5863 12560 5875 12561 5865 12561 5876 12561 5876 12562 5863 12562 5860 12562 5877 12563 5860 12563 5858 12563 5876 12564 5860 12564 5877 12564 5877 12565 5858 12565 5855 12565 5878 12566 5855 12566 5853 12566 5877 12567 5855 12567 5878 12567 5878 12568 5853 12568 5850 12568 5879 12569 5850 12569 5848 12569 5878 12570 5850 12570 5879 12570 5879 12571 5848 12571 5845 12571 5806 12572 5845 12572 5805 12572 5879 12573 5845 12573 5806 12573 5880 12574 5881 12574 5882 12574 5883 12575 5882 12575 5881 12575 5884 12576 5880 12576 5882 12576 5884 12577 5882 12577 5883 12577 5885 12578 5886 12578 5881 12578 5887 12579 5881 12579 5886 12579 5880 12580 5885 12580 5881 12580 5887 12581 5883 12581 5881 12581 5888 12582 5889 12582 5886 12582 5887 12583 5886 12583 5889 12583 5885 12584 5888 12584 5886 12584 5890 12585 5891 12585 5889 12585 5892 12586 5889 12586 5891 12586 5888 12587 5890 12587 5889 12587 5887 12588 5889 12588 5892 12588 5893 12589 5894 12589 5891 12589 5895 12590 5891 12590 5894 12590 5890 12591 5893 12591 5891 12591 5892 12592 5891 12592 5895 12592 5896 12593 5897 12593 5894 12593 5895 12594 5894 12594 5897 12594 5893 12595 5896 12595 5894 12595 5898 12596 5899 12596 5897 12596 5900 12597 5897 12597 5899 12597 5896 12598 5898 12598 5897 12598 5895 12599 5897 12599 5900 12599 5901 12600 5902 12600 5899 12600 5903 12601 5899 12601 5902 12601 5898 12602 5901 12602 5899 12602 5900 12603 5899 12603 5903 12603 5904 12604 5905 12604 5902 12604 5903 12605 5902 12605 5905 12605 5901 12606 5904 12606 5902 12606 5906 12607 5907 12607 5905 12607 5908 12608 5905 12608 5907 12608 5909 12609 5905 12609 5904 12609 5906 12610 5905 12610 5909 12610 5903 12611 5905 12611 5908 12611 5910 12612 5911 12612 5907 12612 5908 12613 5907 12613 5911 12613 5912 12614 5910 12614 5907 12614 5906 12615 5912 12615 5907 12615 5913 12616 5914 12616 5911 12616 5915 12617 5911 12617 5914 12617 5910 12618 5913 12618 5911 12618 5908 12619 5911 12619 5915 12619 5916 12620 5917 12620 5914 12620 5918 12621 5914 12621 5917 12621 5919 12622 5916 12622 5914 12622 5913 12623 5919 12623 5914 12623 5915 12624 5914 12624 5918 12624 5920 12625 5921 12625 5917 12625 5918 12626 5917 12626 5921 12626 5922 12627 5920 12627 5917 12627 5916 12628 5922 12628 5917 12628 5923 12629 5924 12629 5921 12629 5925 12630 5921 12630 5924 12630 5920 12631 5923 12631 5921 12631 5918 12632 5921 12632 5925 12632 5926 12633 5927 12633 5924 12633 5928 12634 5924 12634 5927 12634 5923 12635 5926 12635 5924 12635 5925 12636 5924 12636 5928 12636 5929 12637 5930 12637 5927 12637 5928 12638 5927 12638 5930 12638 5926 12639 5929 12639 5927 12639 5931 12640 5932 12640 5930 12640 5933 12641 5930 12641 5932 12641 5929 12642 5931 12642 5930 12642 5928 12643 5930 12643 5933 12643 5934 12644 5935 12644 5932 12644 5936 12645 5932 12645 5935 12645 5931 12646 5934 12646 5932 12646 5933 12647 5932 12647 5936 12647 5937 12648 5938 12648 5935 12648 5936 12649 5935 12649 5938 12649 5934 12650 5937 12650 5935 12650 5939 12651 5940 12651 5938 12651 5941 12652 5938 12652 5940 12652 5937 12653 5939 12653 5938 12653 5936 12654 5938 12654 5941 12654 5939 12655 5942 12655 5940 12655 5941 12656 5940 12656 5942 12656 5943 12657 5942 12657 5939 12657 5941 12658 5942 12658 5943 12658 5944 12659 5939 12659 5937 12659 5943 12660 5939 12660 5944 12660 5944 12661 5937 12661 5934 12661 5945 12662 5934 12662 5931 12662 5944 12663 5934 12663 5945 12663 5946 12664 5931 12664 5929 12664 5945 12665 5931 12665 5946 12665 5946 12666 5929 12666 5926 12666 5947 12667 5926 12667 5923 12667 5946 12668 5926 12668 5947 12668 5948 12669 5923 12669 5920 12669 5947 12670 5923 12670 5948 12670 5948 12671 5920 12671 5922 12671 5949 12672 5950 12672 5922 12672 5951 12673 5922 12673 5950 12673 5916 12674 5949 12674 5922 12674 5948 12675 5922 12675 5951 12675 5952 12676 5953 12676 5950 12676 5951 12677 5950 12677 5953 12677 5954 12678 5952 12678 5950 12678 5949 12679 5954 12679 5950 12679 5955 12680 5956 12680 5953 12680 5957 12681 5953 12681 5956 12681 5952 12682 5955 12682 5953 12682 5951 12683 5953 12683 5957 12683 5909 12684 5904 12684 5956 12684 5958 12685 5956 12685 5904 12685 5959 12686 5909 12686 5956 12686 5955 12687 5959 12687 5956 12687 5957 12688 5956 12688 5958 12688 5958 12689 5904 12689 5901 12689 5960 12690 5901 12690 5898 12690 5958 12691 5901 12691 5960 12691 5961 12692 5898 12692 5896 12692 5960 12693 5898 12693 5961 12693 5961 12694 5896 12694 5893 12694 5962 12695 5893 12695 5890 12695 5961 12696 5893 12696 5962 12696 5963 12697 5890 12697 5888 12697 5962 12698 5890 12698 5963 12698 5963 12699 5888 12699 5885 12699 5884 12700 5885 12700 5880 12700 5963 12701 5885 12701 5884 12701 5964 12702 5909 12702 5959 12702 5965 12703 5906 12703 5909 12703 5965 12704 5909 12704 5964 12704 5966 12705 5959 12705 5955 12705 5966 12706 5964 12706 5959 12706 5967 12707 5955 12707 5952 12707 5966 12708 5955 12708 5967 12708 5968 12709 5952 12709 5954 12709 5967 12710 5952 12710 5968 12710 5969 12711 5954 12711 5949 12711 5968 12712 5954 12712 5969 12712 5970 12713 5949 12713 5916 12713 5969 12714 5949 12714 5970 12714 5971 12715 5916 12715 5919 12715 5970 12716 5916 12716 5971 12716 5972 12717 5919 12717 5913 12717 5971 12718 5919 12718 5972 12718 5973 12719 5913 12719 5910 12719 5972 12720 5913 12720 5973 12720 5974 12721 5910 12721 5912 12721 5973 12722 5910 12722 5974 12722 5975 12723 5912 12723 5906 12723 5974 12724 5912 12724 5975 12724 5975 12725 5906 12725 5965 12725 5847 12726 5884 12726 5883 12726 5844 12727 5847 12727 5883 12727 5887 12728 5844 12728 5883 12728 5852 12729 5963 12729 5884 12729 5847 12730 5852 12730 5884 12730 5857 12731 5962 12731 5963 12731 5852 12732 5857 12732 5963 12732 5862 12733 5961 12733 5962 12733 5857 12734 5862 12734 5962 12734 5867 12735 5960 12735 5961 12735 5862 12736 5867 12736 5961 12736 5872 12737 5958 12737 5960 12737 5867 12738 5872 12738 5960 12738 5874 12739 5957 12739 5958 12739 5872 12740 5874 12740 5958 12740 5875 12741 5951 12741 5957 12741 5874 12742 5875 12742 5957 12742 5876 12743 5948 12743 5951 12743 5875 12744 5876 12744 5951 12744 5877 12745 5947 12745 5948 12745 5876 12746 5877 12746 5948 12746 5878 12747 5946 12747 5947 12747 5877 12748 5878 12748 5947 12748 5879 12749 5945 12749 5946 12749 5878 12750 5879 12750 5946 12750 5806 12751 5944 12751 5945 12751 5879 12752 5806 12752 5945 12752 5803 12753 5943 12753 5944 12753 5806 12754 5803 12754 5944 12754 5809 12755 5943 12755 5803 12755 5809 12756 5941 12756 5943 12756 5842 12757 5844 12757 5887 12757 5814 12758 5936 12758 5941 12758 5809 12759 5814 12759 5941 12759 5819 12760 5933 12760 5936 12760 5814 12761 5819 12761 5936 12761 5824 12762 5928 12762 5933 12762 5819 12763 5824 12763 5933 12763 5829 12764 5925 12764 5928 12764 5824 12765 5829 12765 5928 12765 5834 12766 5918 12766 5925 12766 5829 12767 5834 12767 5925 12767 5836 12768 5915 12768 5918 12768 5834 12769 5836 12769 5918 12769 5837 12770 5908 12770 5915 12770 5836 12771 5837 12771 5915 12771 5838 12772 5903 12772 5908 12772 5837 12773 5838 12773 5908 12773 5839 12774 5900 12774 5903 12774 5838 12775 5839 12775 5903 12775 5840 12776 5895 12776 5900 12776 5839 12777 5840 12777 5900 12777 5841 12778 5892 12778 5895 12778 5840 12779 5841 12779 5895 12779 5842 12780 5887 12780 5892 12780 5841 12781 5842 12781 5892 12781 5972 12782 5965 12782 5964 12782 5971 12783 5972 12783 5964 12783 5966 12784 5971 12784 5964 12784 5973 12785 5975 12785 5965 12785 5972 12786 5973 12786 5965 12786 5973 12787 5974 12787 5975 12787 5966 12788 5970 12788 5971 12788 5967 12789 5969 12789 5970 12789 5966 12790 5967 12790 5970 12790 5967 12791 5968 12791 5969 12791 5976 12792 5977 12792 5978 12792 5979 12793 5978 12793 5977 12793 5980 12794 5976 12794 5978 12794 5981 12795 5980 12795 5978 12795 5982 12796 5981 12796 5978 12796 5982 12797 5978 12797 5979 12797 5983 12798 5984 12798 5977 12798 5985 12799 5977 12799 5984 12799 5976 12800 5983 12800 5977 12800 5985 12801 5979 12801 5977 12801 5986 12802 5987 12802 5984 12802 5985 12803 5984 12803 5987 12803 5983 12804 5986 12804 5984 12804 5988 12805 5989 12805 5987 12805 5990 12806 5987 12806 5989 12806 5986 12807 5988 12807 5987 12807 5985 12808 5987 12808 5990 12808 5991 12809 5992 12809 5989 12809 5990 12810 5989 12810 5992 12810 5988 12811 5991 12811 5989 12811 5993 12812 5994 12812 5992 12812 5995 12813 5992 12813 5994 12813 5991 12814 5993 12814 5992 12814 5990 12815 5992 12815 5995 12815 5996 12816 5997 12816 5994 12816 5995 12817 5994 12817 5997 12817 5993 12818 5996 12818 5994 12818 5998 12819 5999 12819 5997 12819 6000 12820 5997 12820 5999 12820 5996 12821 5998 12821 5997 12821 5995 12822 5997 12822 6000 12822 6001 12823 6002 12823 5999 12823 6000 12824 5999 12824 6002 12824 5998 12825 6001 12825 5999 12825 6003 12826 6004 12826 6002 12826 6005 12827 6002 12827 6004 12827 6001 12828 6003 12828 6002 12828 6000 12829 6002 12829 6005 12829 6006 12830 6007 12830 6004 12830 6005 12831 6004 12831 6007 12831 6003 12832 6006 12832 6004 12832 6008 12833 6009 12833 6007 12833 6010 12834 6007 12834 6009 12834 6006 12835 6008 12835 6007 12835 6005 12836 6007 12836 6010 12836 6008 12837 6011 12837 6009 12837 6010 12838 6009 12838 6011 12838 6012 12839 6011 12839 6008 12839 6010 12840 6011 12840 6012 12840 6013 12841 6008 12841 6006 12841 6012 12842 6008 12842 6013 12842 6013 12843 6006 12843 6003 12843 6014 12844 6003 12844 6001 12844 6013 12845 6003 12845 6014 12845 6014 12846 6001 12846 5998 12846 6015 12847 5998 12847 5996 12847 6014 12848 5998 12848 6015 12848 6015 12849 5996 12849 5993 12849 6016 12850 5993 12850 5991 12850 6015 12851 5993 12851 6016 12851 6016 12852 5991 12852 5988 12852 6017 12853 5988 12853 5986 12853 6016 12854 5988 12854 6017 12854 6017 12855 5986 12855 5983 12855 6018 12856 5983 12856 5976 12856 6017 12857 5983 12857 6018 12857 6018 12858 5976 12858 5980 12858 5981 12859 6019 12859 5980 12859 6020 12860 5980 12860 6019 12860 6018 12861 5980 12861 6020 12861 6021 12862 6022 12862 6019 12862 6023 12863 6019 12863 6022 12863 5981 12864 6021 12864 6019 12864 6020 12865 6019 12865 6023 12865 6024 12866 6025 12866 6022 12866 6023 12867 6022 12867 6025 12867 6021 12868 6024 12868 6022 12868 6026 12869 6027 12869 6025 12869 6028 12870 6025 12870 6027 12870 6024 12871 6026 12871 6025 12871 6023 12872 6025 12872 6028 12872 6029 12873 6030 12873 6027 12873 6028 12874 6027 12874 6030 12874 6026 12875 6029 12875 6027 12875 6031 12876 6032 12876 6030 12876 6033 12877 6030 12877 6032 12877 6029 12878 6031 12878 6030 12878 6028 12879 6030 12879 6033 12879 6034 12880 6035 12880 6032 12880 6033 12881 6032 12881 6035 12881 6031 12882 6034 12882 6032 12882 6036 12883 6037 12883 6035 12883 6038 12884 6035 12884 6037 12884 6034 12885 6036 12885 6035 12885 6033 12886 6035 12886 6038 12886 6039 12887 6040 12887 6037 12887 6038 12888 6037 12888 6040 12888 6036 12889 6039 12889 6037 12889 6041 12890 6042 12890 6040 12890 6043 12891 6040 12891 6042 12891 6039 12892 6041 12892 6040 12892 6038 12893 6040 12893 6043 12893 6044 12894 6045 12894 6042 12894 6043 12895 6042 12895 6045 12895 6041 12896 6044 12896 6042 12896 6046 12897 6047 12897 6045 12897 6048 12898 6045 12898 6047 12898 6044 12899 6046 12899 6045 12899 6043 12900 6045 12900 6048 12900 6046 12901 6049 12901 6047 12901 6048 12902 6047 12902 6049 12902 6050 12903 6049 12903 6046 12903 6048 12904 6049 12904 6050 12904 6051 12905 6046 12905 6044 12905 6050 12906 6046 12906 6051 12906 6051 12907 6044 12907 6041 12907 6052 12908 6041 12908 6039 12908 6051 12909 6041 12909 6052 12909 6052 12910 6039 12910 6036 12910 6053 12911 6036 12911 6034 12911 6052 12912 6036 12912 6053 12912 6053 12913 6034 12913 6031 12913 6054 12914 6031 12914 6029 12914 6053 12915 6031 12915 6054 12915 6054 12916 6029 12916 6026 12916 6055 12917 6026 12917 6024 12917 6054 12918 6026 12918 6055 12918 6055 12919 6024 12919 6021 12919 5982 12920 6021 12920 5981 12920 6055 12921 6021 12921 5982 12921 6056 12922 6057 12922 6058 12922 6059 12923 6058 12923 6057 12923 6060 12924 6056 12924 6058 12924 6060 12925 6058 12925 6059 12925 6061 12926 6062 12926 6057 12926 6063 12927 6057 12927 6062 12927 6056 12928 6061 12928 6057 12928 6063 12929 6059 12929 6057 12929 6064 12930 6065 12930 6062 12930 6063 12931 6062 12931 6065 12931 6061 12932 6064 12932 6062 12932 6066 12933 6067 12933 6065 12933 6068 12934 6065 12934 6067 12934 6064 12935 6066 12935 6065 12935 6063 12936 6065 12936 6068 12936 6069 12937 6070 12937 6067 12937 6071 12938 6067 12938 6070 12938 6066 12939 6069 12939 6067 12939 6068 12940 6067 12940 6071 12940 6072 12941 6073 12941 6070 12941 6071 12942 6070 12942 6073 12942 6069 12943 6072 12943 6070 12943 6074 12944 6075 12944 6073 12944 6076 12945 6073 12945 6075 12945 6072 12946 6074 12946 6073 12946 6071 12947 6073 12947 6076 12947 6077 12948 6078 12948 6075 12948 6079 12949 6075 12949 6078 12949 6074 12950 6077 12950 6075 12950 6076 12951 6075 12951 6079 12951 6080 12952 6081 12952 6078 12952 6079 12953 6078 12953 6081 12953 6077 12954 6080 12954 6078 12954 6082 12955 6083 12955 6081 12955 6084 12956 6081 12956 6083 12956 6085 12957 6081 12957 6080 12957 6082 12958 6081 12958 6085 12958 6079 12959 6081 12959 6084 12959 6086 12960 6087 12960 6083 12960 6084 12961 6083 12961 6087 12961 6088 12962 6086 12962 6083 12962 6082 12963 6088 12963 6083 12963 6089 12964 6090 12964 6087 12964 6091 12965 6087 12965 6090 12965 6086 12966 6089 12966 6087 12966 6084 12967 6087 12967 6091 12967 6092 12968 6093 12968 6090 12968 6094 12969 6090 12969 6093 12969 6095 12970 6092 12970 6090 12970 6089 12971 6095 12971 6090 12971 6091 12972 6090 12972 6094 12972 6096 12973 6097 12973 6093 12973 6094 12974 6093 12974 6097 12974 6098 12975 6096 12975 6093 12975 6092 12976 6098 12976 6093 12976 6099 12977 6100 12977 6097 12977 6101 12978 6097 12978 6100 12978 6096 12979 6099 12979 6097 12979 6094 12980 6097 12980 6101 12980 6102 12981 6103 12981 6100 12981 6104 12982 6100 12982 6103 12982 6099 12983 6102 12983 6100 12983 6101 12984 6100 12984 6104 12984 6105 12985 6106 12985 6103 12985 6104 12986 6103 12986 6106 12986 6102 12987 6105 12987 6103 12987 6107 12988 6108 12988 6106 12988 6109 12989 6106 12989 6108 12989 6105 12990 6107 12990 6106 12990 6104 12991 6106 12991 6109 12991 6110 12992 6111 12992 6108 12992 6112 12993 6108 12993 6111 12993 6107 12994 6110 12994 6108 12994 6109 12995 6108 12995 6112 12995 6113 12996 6114 12996 6111 12996 6112 12997 6111 12997 6114 12997 6110 12998 6113 12998 6111 12998 6115 12999 6116 12999 6114 12999 6117 13000 6114 13000 6116 13000 6113 13001 6115 13001 6114 13001 6112 13002 6114 13002 6117 13002 6115 13003 6118 13003 6116 13003 6117 13004 6116 13004 6118 13004 6119 13005 6118 13005 6115 13005 6117 13006 6118 13006 6119 13006 6120 13007 6115 13007 6113 13007 6119 13008 6115 13008 6120 13008 6120 13009 6113 13009 6110 13009 6121 13010 6110 13010 6107 13010 6120 13011 6110 13011 6121 13011 6122 13012 6107 13012 6105 13012 6121 13013 6107 13013 6122 13013 6122 13014 6105 13014 6102 13014 6123 13015 6102 13015 6099 13015 6122 13016 6102 13016 6123 13016 6124 13017 6099 13017 6096 13017 6123 13018 6099 13018 6124 13018 6124 13019 6096 13019 6098 13019 6125 13020 6126 13020 6098 13020 6127 13021 6098 13021 6126 13021 6092 13022 6125 13022 6098 13022 6124 13023 6098 13023 6127 13023 6128 13024 6129 13024 6126 13024 6127 13025 6126 13025 6129 13025 6130 13026 6128 13026 6126 13026 6125 13027 6130 13027 6126 13027 6131 13028 6132 13028 6129 13028 6133 13029 6129 13029 6132 13029 6128 13030 6131 13030 6129 13030 6127 13031 6129 13031 6133 13031 6085 13032 6080 13032 6132 13032 6134 13033 6132 13033 6080 13033 6135 13034 6085 13034 6132 13034 6131 13035 6135 13035 6132 13035 6133 13036 6132 13036 6134 13036 6134 13037 6080 13037 6077 13037 6136 13038 6077 13038 6074 13038 6134 13039 6077 13039 6136 13039 6137 13040 6074 13040 6072 13040 6136 13041 6074 13041 6137 13041 6137 13042 6072 13042 6069 13042 6138 13043 6069 13043 6066 13043 6137 13044 6069 13044 6138 13044 6139 13045 6066 13045 6064 13045 6138 13046 6066 13046 6139 13046 6139 13047 6064 13047 6061 13047 6060 13048 6061 13048 6056 13048 6139 13049 6061 13049 6060 13049 6140 13050 6085 13050 6135 13050 6141 13051 6082 13051 6085 13051 6141 13052 6085 13052 6140 13052 6142 13053 6135 13053 6131 13053 6142 13054 6140 13054 6135 13054 6143 13055 6131 13055 6128 13055 6142 13056 6131 13056 6143 13056 6144 13057 6128 13057 6130 13057 6143 13058 6128 13058 6144 13058 6145 13059 6130 13059 6125 13059 6144 13060 6130 13060 6145 13060 6146 13061 6125 13061 6092 13061 6145 13062 6125 13062 6146 13062 6147 13063 6092 13063 6095 13063 6146 13064 6092 13064 6147 13064 6148 13065 6095 13065 6089 13065 6147 13066 6095 13066 6148 13066 6149 13067 6089 13067 6086 13067 6148 13068 6089 13068 6149 13068 6150 13069 6086 13069 6088 13069 6149 13070 6086 13070 6150 13070 6151 13071 6088 13071 6082 13071 6150 13072 6088 13072 6151 13072 6151 13073 6082 13073 6141 13073 6023 13074 6060 13074 6059 13074 6020 13075 6023 13075 6059 13075 6063 13076 6020 13076 6059 13076 6028 13077 6139 13077 6060 13077 6023 13078 6028 13078 6060 13078 6033 13079 6138 13079 6139 13079 6028 13080 6033 13080 6139 13080 6038 13081 6137 13081 6138 13081 6033 13082 6038 13082 6138 13082 6043 13083 6136 13083 6137 13083 6038 13084 6043 13084 6137 13084 6048 13085 6134 13085 6136 13085 6043 13086 6048 13086 6136 13086 6050 13087 6133 13087 6134 13087 6048 13088 6050 13088 6134 13088 6051 13089 6127 13089 6133 13089 6050 13090 6051 13090 6133 13090 6052 13091 6124 13091 6127 13091 6051 13092 6052 13092 6127 13092 6053 13093 6123 13093 6124 13093 6052 13094 6053 13094 6124 13094 6054 13095 6122 13095 6123 13095 6053 13096 6054 13096 6123 13096 6055 13097 6121 13097 6122 13097 6054 13098 6055 13098 6122 13098 5982 13099 6120 13099 6121 13099 6055 13100 5982 13100 6121 13100 5979 13101 6119 13101 6120 13101 5982 13102 5979 13102 6120 13102 5985 13103 6119 13103 5979 13103 5985 13104 6117 13104 6119 13104 6018 13105 6020 13105 6063 13105 5990 13106 6112 13106 6117 13106 5985 13107 5990 13107 6117 13107 5995 13108 6109 13108 6112 13108 5990 13109 5995 13109 6112 13109 6000 13110 6104 13110 6109 13110 5995 13111 6000 13111 6109 13111 6005 13112 6101 13112 6104 13112 6000 13113 6005 13113 6104 13113 6010 13114 6094 13114 6101 13114 6005 13115 6010 13115 6101 13115 6012 13116 6091 13116 6094 13116 6010 13117 6012 13117 6094 13117 6013 13118 6084 13118 6091 13118 6012 13119 6013 13119 6091 13119 6014 13120 6079 13120 6084 13120 6013 13121 6014 13121 6084 13121 6015 13122 6076 13122 6079 13122 6014 13123 6015 13123 6079 13123 6016 13124 6071 13124 6076 13124 6015 13125 6016 13125 6076 13125 6017 13126 6068 13126 6071 13126 6016 13127 6017 13127 6071 13127 6018 13128 6063 13128 6068 13128 6017 13129 6018 13129 6068 13129 6148 13130 6141 13130 6140 13130 6147 13131 6148 13131 6140 13131 6142 13132 6147 13132 6140 13132 6149 13133 6151 13133 6141 13133 6148 13134 6149 13134 6141 13134 6149 13135 6150 13135 6151 13135 6142 13136 6146 13136 6147 13136 6143 13137 6145 13137 6146 13137 6142 13138 6143 13138 6146 13138 6143 13139 6144 13139 6145 13139 6152 13140 6153 13140 6154 13140 6155 13141 6154 13141 6153 13141 6156 13142 6152 13142 6154 13142 6157 13143 6156 13143 6154 13143 6158 13144 6157 13144 6154 13144 6158 13145 6154 13145 6155 13145 6159 13146 6160 13146 6153 13146 6161 13147 6153 13147 6160 13147 6152 13148 6159 13148 6153 13148 6161 13149 6155 13149 6153 13149 6162 13150 6163 13150 6160 13150 6161 13151 6160 13151 6163 13151 6159 13152 6162 13152 6160 13152 6164 13153 6165 13153 6163 13153 6166 13154 6163 13154 6165 13154 6162 13155 6164 13155 6163 13155 6161 13156 6163 13156 6166 13156 6167 13157 6168 13157 6165 13157 6166 13158 6165 13158 6168 13158 6164 13159 6167 13159 6165 13159 6169 13160 6170 13160 6168 13160 6171 13161 6168 13161 6170 13161 6167 13162 6169 13162 6168 13162 6166 13163 6168 13163 6171 13163 6172 13164 6173 13164 6170 13164 6171 13165 6170 13165 6173 13165 6169 13166 6172 13166 6170 13166 6174 13167 6175 13167 6173 13167 6176 13168 6173 13168 6175 13168 6172 13169 6174 13169 6173 13169 6171 13170 6173 13170 6176 13170 6177 13171 6178 13171 6175 13171 6176 13172 6175 13172 6178 13172 6174 13173 6177 13173 6175 13173 6179 13174 6180 13174 6178 13174 6181 13175 6178 13175 6180 13175 6177 13176 6179 13176 6178 13176 6176 13177 6178 13177 6181 13177 6182 13178 6183 13178 6180 13178 6181 13179 6180 13179 6183 13179 6179 13180 6182 13180 6180 13180 6184 13181 6185 13181 6183 13181 6186 13182 6183 13182 6185 13182 6182 13183 6184 13183 6183 13183 6181 13184 6183 13184 6186 13184 6184 13185 6187 13185 6185 13185 6186 13186 6185 13186 6187 13186 6188 13187 6187 13187 6184 13187 6186 13188 6187 13188 6188 13188 6189 13189 6184 13189 6182 13189 6188 13190 6184 13190 6189 13190 6189 13191 6182 13191 6179 13191 6190 13192 6179 13192 6177 13192 6189 13193 6179 13193 6190 13193 6190 13194 6177 13194 6174 13194 6191 13195 6174 13195 6172 13195 6190 13196 6174 13196 6191 13196 6191 13197 6172 13197 6169 13197 6192 13198 6169 13198 6167 13198 6191 13199 6169 13199 6192 13199 6192 13200 6167 13200 6164 13200 6193 13201 6164 13201 6162 13201 6192 13202 6164 13202 6193 13202 6193 13203 6162 13203 6159 13203 6194 13204 6159 13204 6152 13204 6193 13205 6159 13205 6194 13205 6194 13206 6152 13206 6156 13206 6157 13207 6195 13207 6156 13207 6196 13208 6156 13208 6195 13208 6194 13209 6156 13209 6196 13209 6197 13210 6198 13210 6195 13210 6199 13211 6195 13211 6198 13211 6157 13212 6197 13212 6195 13212 6196 13213 6195 13213 6199 13213 6200 13214 6201 13214 6198 13214 6199 13215 6198 13215 6201 13215 6197 13216 6200 13216 6198 13216 6202 13217 6203 13217 6201 13217 6204 13218 6201 13218 6203 13218 6200 13219 6202 13219 6201 13219 6199 13220 6201 13220 6204 13220 6205 13221 6206 13221 6203 13221 6204 13222 6203 13222 6206 13222 6202 13223 6205 13223 6203 13223 6207 13224 6208 13224 6206 13224 6209 13225 6206 13225 6208 13225 6205 13226 6207 13226 6206 13226 6204 13227 6206 13227 6209 13227 6210 13228 6211 13228 6208 13228 6209 13229 6208 13229 6211 13229 6207 13230 6210 13230 6208 13230 6212 13231 6213 13231 6211 13231 6214 13232 6211 13232 6213 13232 6210 13233 6212 13233 6211 13233 6209 13234 6211 13234 6214 13234 6215 13235 6216 13235 6213 13235 6214 13236 6213 13236 6216 13236 6212 13237 6215 13237 6213 13237 6217 13238 6218 13238 6216 13238 6219 13239 6216 13239 6218 13239 6215 13240 6217 13240 6216 13240 6214 13241 6216 13241 6219 13241 6220 13242 6221 13242 6218 13242 6219 13243 6218 13243 6221 13243 6217 13244 6220 13244 6218 13244 6222 13245 6223 13245 6221 13245 6224 13246 6221 13246 6223 13246 6220 13247 6222 13247 6221 13247 6219 13248 6221 13248 6224 13248 6222 13249 6225 13249 6223 13249 6224 13250 6223 13250 6225 13250 6226 13251 6225 13251 6222 13251 6224 13252 6225 13252 6226 13252 6227 13253 6222 13253 6220 13253 6226 13254 6222 13254 6227 13254 6227 13255 6220 13255 6217 13255 6228 13256 6217 13256 6215 13256 6227 13257 6217 13257 6228 13257 6228 13258 6215 13258 6212 13258 6229 13259 6212 13259 6210 13259 6228 13260 6212 13260 6229 13260 6229 13261 6210 13261 6207 13261 6230 13262 6207 13262 6205 13262 6229 13263 6207 13263 6230 13263 6230 13264 6205 13264 6202 13264 6231 13265 6202 13265 6200 13265 6230 13266 6202 13266 6231 13266 6231 13267 6200 13267 6197 13267 6158 13268 6197 13268 6157 13268 6231 13269 6197 13269 6158 13269 6232 13270 6233 13270 6234 13270 6235 13271 6234 13271 6233 13271 6236 13272 6232 13272 6234 13272 6236 13273 6234 13273 6235 13273 6237 13274 6238 13274 6233 13274 6239 13275 6233 13275 6238 13275 6232 13276 6237 13276 6233 13276 6239 13277 6235 13277 6233 13277 6240 13278 6241 13278 6238 13278 6239 13279 6238 13279 6241 13279 6237 13280 6240 13280 6238 13280 6242 13281 6243 13281 6241 13281 6244 13282 6241 13282 6243 13282 6240 13283 6242 13283 6241 13283 6239 13284 6241 13284 6244 13284 6245 13285 6246 13285 6243 13285 6247 13286 6243 13286 6246 13286 6242 13287 6245 13287 6243 13287 6244 13288 6243 13288 6247 13288 6248 13289 6249 13289 6246 13289 6247 13290 6246 13290 6249 13290 6245 13291 6248 13291 6246 13291 6250 13292 6251 13292 6249 13292 6252 13293 6249 13293 6251 13293 6248 13294 6250 13294 6249 13294 6247 13295 6249 13295 6252 13295 6253 13296 6254 13296 6251 13296 6255 13297 6251 13297 6254 13297 6250 13298 6253 13298 6251 13298 6252 13299 6251 13299 6255 13299 6256 13300 6257 13300 6254 13300 6255 13301 6254 13301 6257 13301 6253 13302 6256 13302 6254 13302 6258 13303 6259 13303 6257 13303 6260 13304 6257 13304 6259 13304 6261 13305 6257 13305 6256 13305 6258 13306 6257 13306 6261 13306 6255 13307 6257 13307 6260 13307 6262 13308 6263 13308 6259 13308 6260 13309 6259 13309 6263 13309 6264 13310 6262 13310 6259 13310 6258 13311 6264 13311 6259 13311 6265 13312 6266 13312 6263 13312 6267 13313 6263 13313 6266 13313 6262 13314 6265 13314 6263 13314 6260 13315 6263 13315 6267 13315 6268 13316 6269 13316 6266 13316 6270 13317 6266 13317 6269 13317 6271 13318 6268 13318 6266 13318 6265 13319 6271 13319 6266 13319 6267 13320 6266 13320 6270 13320 6272 13321 6273 13321 6269 13321 6270 13322 6269 13322 6273 13322 6274 13323 6272 13323 6269 13323 6268 13324 6274 13324 6269 13324 6275 13325 6276 13325 6273 13325 6277 13326 6273 13326 6276 13326 6272 13327 6275 13327 6273 13327 6270 13328 6273 13328 6277 13328 6278 13329 6279 13329 6276 13329 6280 13330 6276 13330 6279 13330 6275 13331 6278 13331 6276 13331 6277 13332 6276 13332 6280 13332 6281 13333 6282 13333 6279 13333 6280 13334 6279 13334 6282 13334 6278 13335 6281 13335 6279 13335 6283 13336 6284 13336 6282 13336 6285 13337 6282 13337 6284 13337 6281 13338 6283 13338 6282 13338 6280 13339 6282 13339 6285 13339 6286 13340 6287 13340 6284 13340 6288 13341 6284 13341 6287 13341 6283 13342 6286 13342 6284 13342 6285 13343 6284 13343 6288 13343 6289 13344 6290 13344 6287 13344 6288 13345 6287 13345 6290 13345 6286 13346 6289 13346 6287 13346 6291 13347 6292 13347 6290 13347 6293 13348 6290 13348 6292 13348 6289 13349 6291 13349 6290 13349 6288 13350 6290 13350 6293 13350 6291 13351 6294 13351 6292 13351 6293 13352 6292 13352 6294 13352 6295 13353 6294 13353 6291 13353 6293 13354 6294 13354 6295 13354 6296 13355 6291 13355 6289 13355 6295 13356 6291 13356 6296 13356 6296 13357 6289 13357 6286 13357 6297 13358 6286 13358 6283 13358 6296 13359 6286 13359 6297 13359 6298 13360 6283 13360 6281 13360 6297 13361 6283 13361 6298 13361 6298 13362 6281 13362 6278 13362 6299 13363 6278 13363 6275 13363 6298 13364 6278 13364 6299 13364 6300 13365 6275 13365 6272 13365 6299 13366 6275 13366 6300 13366 6300 13367 6272 13367 6274 13367 6301 13368 6302 13368 6274 13368 6303 13369 6274 13369 6302 13369 6268 13370 6301 13370 6274 13370 6300 13371 6274 13371 6303 13371 6304 13372 6305 13372 6302 13372 6303 13373 6302 13373 6305 13373 6306 13374 6304 13374 6302 13374 6301 13375 6306 13375 6302 13375 6307 13376 6308 13376 6305 13376 6309 13377 6305 13377 6308 13377 6304 13378 6307 13378 6305 13378 6303 13379 6305 13379 6309 13379 6261 13380 6256 13380 6308 13380 6310 13381 6308 13381 6256 13381 6311 13382 6261 13382 6308 13382 6307 13383 6311 13383 6308 13383 6309 13384 6308 13384 6310 13384 6310 13385 6256 13385 6253 13385 6312 13386 6253 13386 6250 13386 6310 13387 6253 13387 6312 13387 6313 13388 6250 13388 6248 13388 6312 13389 6250 13389 6313 13389 6313 13390 6248 13390 6245 13390 6314 13391 6245 13391 6242 13391 6313 13392 6245 13392 6314 13392 6315 13393 6242 13393 6240 13393 6314 13394 6242 13394 6315 13394 6315 13395 6240 13395 6237 13395 6236 13396 6237 13396 6232 13396 6315 13397 6237 13397 6236 13397 6316 13398 6261 13398 6311 13398 6317 13399 6258 13399 6261 13399 6317 13400 6261 13400 6316 13400 6318 13401 6311 13401 6307 13401 6318 13402 6316 13402 6311 13402 6319 13403 6307 13403 6304 13403 6318 13404 6307 13404 6319 13404 6320 13405 6304 13405 6306 13405 6319 13406 6304 13406 6320 13406 6321 13407 6306 13407 6301 13407 6320 13408 6306 13408 6321 13408 6322 13409 6301 13409 6268 13409 6321 13410 6301 13410 6322 13410 6323 13411 6268 13411 6271 13411 6322 13412 6268 13412 6323 13412 6324 13413 6271 13413 6265 13413 6323 13414 6271 13414 6324 13414 6325 13415 6265 13415 6262 13415 6324 13416 6265 13416 6325 13416 6326 13417 6262 13417 6264 13417 6325 13418 6262 13418 6326 13418 6327 13419 6264 13419 6258 13419 6326 13420 6264 13420 6327 13420 6327 13421 6258 13421 6317 13421 6199 13422 6236 13422 6235 13422 6196 13423 6199 13423 6235 13423 6239 13424 6196 13424 6235 13424 6204 13425 6315 13425 6236 13425 6199 13426 6204 13426 6236 13426 6209 13427 6314 13427 6315 13427 6204 13428 6209 13428 6315 13428 6214 13429 6313 13429 6314 13429 6209 13430 6214 13430 6314 13430 6219 13431 6312 13431 6313 13431 6214 13432 6219 13432 6313 13432 6224 13433 6310 13433 6312 13433 6219 13434 6224 13434 6312 13434 6226 13435 6309 13435 6310 13435 6224 13436 6226 13436 6310 13436 6227 13437 6303 13437 6309 13437 6226 13438 6227 13438 6309 13438 6228 13439 6300 13439 6303 13439 6227 13440 6228 13440 6303 13440 6229 13441 6299 13441 6300 13441 6228 13442 6229 13442 6300 13442 6230 13443 6298 13443 6299 13443 6229 13444 6230 13444 6299 13444 6231 13445 6297 13445 6298 13445 6230 13446 6231 13446 6298 13446 6158 13447 6296 13447 6297 13447 6231 13448 6158 13448 6297 13448 6155 13449 6295 13449 6296 13449 6158 13450 6155 13450 6296 13450 6161 13451 6295 13451 6155 13451 6161 13452 6293 13452 6295 13452 6194 13453 6196 13453 6239 13453 6166 13454 6288 13454 6293 13454 6161 13455 6166 13455 6293 13455 6171 13456 6285 13456 6288 13456 6166 13457 6171 13457 6288 13457 6176 13458 6280 13458 6285 13458 6171 13459 6176 13459 6285 13459 6181 13460 6277 13460 6280 13460 6176 13461 6181 13461 6280 13461 6186 13462 6270 13462 6277 13462 6181 13463 6186 13463 6277 13463 6188 13464 6267 13464 6270 13464 6186 13465 6188 13465 6270 13465 6189 13466 6260 13466 6267 13466 6188 13467 6189 13467 6267 13467 6190 13468 6255 13468 6260 13468 6189 13469 6190 13469 6260 13469 6191 13470 6252 13470 6255 13470 6190 13471 6191 13471 6255 13471 6192 13472 6247 13472 6252 13472 6191 13473 6192 13473 6252 13473 6193 13474 6244 13474 6247 13474 6192 13475 6193 13475 6247 13475 6194 13476 6239 13476 6244 13476 6193 13477 6194 13477 6244 13477 6324 13478 6317 13478 6316 13478 6323 13479 6324 13479 6316 13479 6318 13480 6323 13480 6316 13480 6325 13481 6327 13481 6317 13481 6324 13482 6325 13482 6317 13482 6325 13483 6326 13483 6327 13483 6318 13484 6322 13484 6323 13484 6319 13485 6321 13485 6322 13485 6318 13486 6319 13486 6322 13486 6319 13487 6320 13487 6321 13487 6328 13488 6329 13488 6330 13488 6331 13489 6330 13489 6329 13489 6332 13490 6328 13490 6330 13490 6333 13491 6332 13491 6330 13491 6334 13492 6333 13492 6330 13492 6334 13493 6330 13493 6331 13493 6335 13494 6336 13494 6329 13494 6337 13495 6329 13495 6336 13495 6328 13496 6335 13496 6329 13496 6337 13497 6331 13497 6329 13497 6338 13498 6339 13498 6336 13498 6337 13499 6336 13499 6339 13499 6335 13500 6338 13500 6336 13500 6340 13501 6341 13501 6339 13501 6342 13502 6339 13502 6341 13502 6338 13503 6340 13503 6339 13503 6337 13504 6339 13504 6342 13504 6343 13505 6344 13505 6341 13505 6342 13506 6341 13506 6344 13506 6340 13507 6343 13507 6341 13507 6345 13508 6346 13508 6344 13508 6347 13509 6344 13509 6346 13509 6343 13510 6345 13510 6344 13510 6342 13511 6344 13511 6347 13511 6348 13512 6349 13512 6346 13512 6347 13513 6346 13513 6349 13513 6345 13514 6348 13514 6346 13514 6350 13515 6351 13515 6349 13515 6352 13516 6349 13516 6351 13516 6348 13517 6350 13517 6349 13517 6347 13518 6349 13518 6352 13518 6353 13519 6354 13519 6351 13519 6352 13520 6351 13520 6354 13520 6350 13521 6353 13521 6351 13521 6355 13522 6356 13522 6354 13522 6357 13523 6354 13523 6356 13523 6353 13524 6355 13524 6354 13524 6352 13525 6354 13525 6357 13525 6358 13526 6359 13526 6356 13526 6357 13527 6356 13527 6359 13527 6355 13528 6358 13528 6356 13528 6360 13529 6361 13529 6359 13529 6362 13530 6359 13530 6361 13530 6358 13531 6360 13531 6359 13531 6357 13532 6359 13532 6362 13532 6360 13533 6363 13533 6361 13533 6362 13534 6361 13534 6363 13534 6364 13535 6363 13535 6360 13535 6362 13536 6363 13536 6364 13536 6365 13537 6360 13537 6358 13537 6364 13538 6360 13538 6365 13538 6365 13539 6358 13539 6355 13539 6366 13540 6355 13540 6353 13540 6365 13541 6355 13541 6366 13541 6366 13542 6353 13542 6350 13542 6367 13543 6350 13543 6348 13543 6366 13544 6350 13544 6367 13544 6367 13545 6348 13545 6345 13545 6368 13546 6345 13546 6343 13546 6367 13547 6345 13547 6368 13547 6368 13548 6343 13548 6340 13548 6369 13549 6340 13549 6338 13549 6368 13550 6340 13550 6369 13550 6369 13551 6338 13551 6335 13551 6370 13552 6335 13552 6328 13552 6369 13553 6335 13553 6370 13553 6370 13554 6328 13554 6332 13554 6333 13555 6371 13555 6332 13555 6372 13556 6332 13556 6371 13556 6370 13557 6332 13557 6372 13557 6373 13558 6374 13558 6371 13558 6375 13559 6371 13559 6374 13559 6333 13560 6373 13560 6371 13560 6372 13561 6371 13561 6375 13561 6376 13562 6377 13562 6374 13562 6375 13563 6374 13563 6377 13563 6373 13564 6376 13564 6374 13564 6378 13565 6379 13565 6377 13565 6380 13566 6377 13566 6379 13566 6376 13567 6378 13567 6377 13567 6375 13568 6377 13568 6380 13568 6381 13569 6382 13569 6379 13569 6380 13570 6379 13570 6382 13570 6378 13571 6381 13571 6379 13571 6383 13572 6384 13572 6382 13572 6385 13573 6382 13573 6384 13573 6381 13574 6383 13574 6382 13574 6380 13575 6382 13575 6385 13575 6386 13576 6387 13576 6384 13576 6385 13577 6384 13577 6387 13577 6383 13578 6386 13578 6384 13578 6388 13579 6389 13579 6387 13579 6390 13580 6387 13580 6389 13580 6386 13581 6388 13581 6387 13581 6385 13582 6387 13582 6390 13582 6391 13583 6392 13583 6389 13583 6390 13584 6389 13584 6392 13584 6388 13585 6391 13585 6389 13585 6393 13586 6394 13586 6392 13586 6395 13587 6392 13587 6394 13587 6391 13588 6393 13588 6392 13588 6390 13589 6392 13589 6395 13589 6396 13590 6397 13590 6394 13590 6395 13591 6394 13591 6397 13591 6393 13592 6396 13592 6394 13592 6398 13593 6399 13593 6397 13593 6400 13594 6397 13594 6399 13594 6396 13595 6398 13595 6397 13595 6395 13596 6397 13596 6400 13596 6398 13597 6401 13597 6399 13597 6400 13598 6399 13598 6401 13598 6402 13599 6401 13599 6398 13599 6400 13600 6401 13600 6402 13600 6403 13601 6398 13601 6396 13601 6402 13602 6398 13602 6403 13602 6403 13603 6396 13603 6393 13603 6404 13604 6393 13604 6391 13604 6403 13605 6393 13605 6404 13605 6404 13606 6391 13606 6388 13606 6405 13607 6388 13607 6386 13607 6404 13608 6388 13608 6405 13608 6405 13609 6386 13609 6383 13609 6406 13610 6383 13610 6381 13610 6405 13611 6383 13611 6406 13611 6406 13612 6381 13612 6378 13612 6407 13613 6378 13613 6376 13613 6406 13614 6378 13614 6407 13614 6407 13615 6376 13615 6373 13615 6334 13616 6373 13616 6333 13616 6407 13617 6373 13617 6334 13617 6408 13618 6409 13618 6410 13618 6411 13619 6410 13619 6409 13619 6412 13620 6408 13620 6410 13620 6412 13621 6410 13621 6411 13621 6413 13622 6414 13622 6409 13622 6415 13623 6409 13623 6414 13623 6408 13624 6413 13624 6409 13624 6415 13625 6411 13625 6409 13625 6416 13626 6417 13626 6414 13626 6415 13627 6414 13627 6417 13627 6413 13628 6416 13628 6414 13628 6418 13629 6419 13629 6417 13629 6420 13630 6417 13630 6419 13630 6416 13631 6418 13631 6417 13631 6415 13632 6417 13632 6420 13632 6421 13633 6422 13633 6419 13633 6423 13634 6419 13634 6422 13634 6418 13635 6421 13635 6419 13635 6420 13636 6419 13636 6423 13636 6424 13637 6425 13637 6422 13637 6423 13638 6422 13638 6425 13638 6421 13639 6424 13639 6422 13639 6426 13640 6427 13640 6425 13640 6428 13641 6425 13641 6427 13641 6424 13642 6426 13642 6425 13642 6423 13643 6425 13643 6428 13643 6429 13644 6430 13644 6427 13644 6431 13645 6427 13645 6430 13645 6426 13646 6429 13646 6427 13646 6428 13647 6427 13647 6431 13647 6432 13648 6433 13648 6430 13648 6431 13649 6430 13649 6433 13649 6429 13650 6432 13650 6430 13650 6434 13651 6435 13651 6433 13651 6436 13652 6433 13652 6435 13652 6437 13653 6433 13653 6432 13653 6434 13654 6433 13654 6437 13654 6431 13655 6433 13655 6436 13655 6438 13656 6439 13656 6435 13656 6436 13657 6435 13657 6439 13657 6440 13658 6438 13658 6435 13658 6434 13659 6440 13659 6435 13659 6441 13660 6442 13660 6439 13660 6443 13661 6439 13661 6442 13661 6438 13662 6441 13662 6439 13662 6436 13663 6439 13663 6443 13663 6444 13664 6445 13664 6442 13664 6446 13665 6442 13665 6445 13665 6447 13666 6444 13666 6442 13666 6441 13667 6447 13667 6442 13667 6443 13668 6442 13668 6446 13668 6448 13669 6449 13669 6445 13669 6446 13670 6445 13670 6449 13670 6450 13671 6448 13671 6445 13671 6444 13672 6450 13672 6445 13672 6451 13673 6452 13673 6449 13673 6453 13674 6449 13674 6452 13674 6448 13675 6451 13675 6449 13675 6446 13676 6449 13676 6453 13676 6454 13677 6455 13677 6452 13677 6456 13678 6452 13678 6455 13678 6451 13679 6454 13679 6452 13679 6453 13680 6452 13680 6456 13680 6457 13681 6458 13681 6455 13681 6456 13682 6455 13682 6458 13682 6454 13683 6457 13683 6455 13683 6459 13684 6460 13684 6458 13684 6461 13685 6458 13685 6460 13685 6457 13686 6459 13686 6458 13686 6456 13687 6458 13687 6461 13687 6462 13688 6463 13688 6460 13688 6464 13689 6460 13689 6463 13689 6459 13690 6462 13690 6460 13690 6461 13691 6460 13691 6464 13691 6465 13692 6466 13692 6463 13692 6464 13693 6463 13693 6466 13693 6462 13694 6465 13694 6463 13694 6467 13695 6468 13695 6466 13695 6469 13696 6466 13696 6468 13696 6465 13697 6467 13697 6466 13697 6464 13698 6466 13698 6469 13698 6467 13699 6470 13699 6468 13699 6469 13700 6468 13700 6470 13700 6471 13701 6470 13701 6467 13701 6469 13702 6470 13702 6471 13702 6472 13703 6467 13703 6465 13703 6471 13704 6467 13704 6472 13704 6472 13705 6465 13705 6462 13705 6473 13706 6462 13706 6459 13706 6472 13707 6462 13707 6473 13707 6474 13708 6459 13708 6457 13708 6473 13709 6459 13709 6474 13709 6474 13710 6457 13710 6454 13710 6475 13711 6454 13711 6451 13711 6474 13712 6454 13712 6475 13712 6476 13713 6451 13713 6448 13713 6475 13714 6451 13714 6476 13714 6476 13715 6448 13715 6450 13715 6477 13716 6478 13716 6450 13716 6479 13717 6450 13717 6478 13717 6444 13718 6477 13718 6450 13718 6476 13719 6450 13719 6479 13719 6480 13720 6481 13720 6478 13720 6479 13721 6478 13721 6481 13721 6482 13722 6480 13722 6478 13722 6477 13723 6482 13723 6478 13723 6483 13724 6484 13724 6481 13724 6485 13725 6481 13725 6484 13725 6480 13726 6483 13726 6481 13726 6479 13727 6481 13727 6485 13727 6437 13728 6432 13728 6484 13728 6486 13729 6484 13729 6432 13729 6487 13730 6437 13730 6484 13730 6483 13731 6487 13731 6484 13731 6485 13732 6484 13732 6486 13732 6486 13733 6432 13733 6429 13733 6488 13734 6429 13734 6426 13734 6486 13735 6429 13735 6488 13735 6489 13736 6426 13736 6424 13736 6488 13737 6426 13737 6489 13737 6489 13738 6424 13738 6421 13738 6490 13739 6421 13739 6418 13739 6489 13740 6421 13740 6490 13740 6491 13741 6418 13741 6416 13741 6490 13742 6418 13742 6491 13742 6491 13743 6416 13743 6413 13743 6412 13744 6413 13744 6408 13744 6491 13745 6413 13745 6412 13745 6492 13746 6437 13746 6487 13746 6493 13747 6434 13747 6437 13747 6493 13748 6437 13748 6492 13748 6494 13749 6487 13749 6483 13749 6494 13750 6492 13750 6487 13750 6495 13751 6483 13751 6480 13751 6494 13752 6483 13752 6495 13752 6496 13753 6480 13753 6482 13753 6495 13754 6480 13754 6496 13754 6497 13755 6482 13755 6477 13755 6496 13756 6482 13756 6497 13756 6498 13757 6477 13757 6444 13757 6497 13758 6477 13758 6498 13758 6499 13759 6444 13759 6447 13759 6498 13760 6444 13760 6499 13760 6500 13761 6447 13761 6441 13761 6499 13762 6447 13762 6500 13762 6501 13763 6441 13763 6438 13763 6500 13764 6441 13764 6501 13764 6502 13765 6438 13765 6440 13765 6501 13766 6438 13766 6502 13766 6503 13767 6440 13767 6434 13767 6502 13768 6440 13768 6503 13768 6503 13769 6434 13769 6493 13769 6375 13770 6412 13770 6411 13770 6372 13771 6375 13771 6411 13771 6415 13772 6372 13772 6411 13772 6380 13773 6491 13773 6412 13773 6375 13774 6380 13774 6412 13774 6385 13775 6490 13775 6491 13775 6380 13776 6385 13776 6491 13776 6390 13777 6489 13777 6490 13777 6385 13778 6390 13778 6490 13778 6395 13779 6488 13779 6489 13779 6390 13780 6395 13780 6489 13780 6400 13781 6486 13781 6488 13781 6395 13782 6400 13782 6488 13782 6402 13783 6485 13783 6486 13783 6400 13784 6402 13784 6486 13784 6403 13785 6479 13785 6485 13785 6402 13786 6403 13786 6485 13786 6404 13787 6476 13787 6479 13787 6403 13788 6404 13788 6479 13788 6405 13789 6475 13789 6476 13789 6404 13790 6405 13790 6476 13790 6406 13791 6474 13791 6475 13791 6405 13792 6406 13792 6475 13792 6407 13793 6473 13793 6474 13793 6406 13794 6407 13794 6474 13794 6334 13795 6472 13795 6473 13795 6407 13796 6334 13796 6473 13796 6331 13797 6471 13797 6472 13797 6334 13798 6331 13798 6472 13798 6337 13799 6471 13799 6331 13799 6337 13800 6469 13800 6471 13800 6370 13801 6372 13801 6415 13801 6342 13802 6464 13802 6469 13802 6337 13803 6342 13803 6469 13803 6347 13804 6461 13804 6464 13804 6342 13805 6347 13805 6464 13805 6352 13806 6456 13806 6461 13806 6347 13807 6352 13807 6461 13807 6357 13808 6453 13808 6456 13808 6352 13809 6357 13809 6456 13809 6362 13810 6446 13810 6453 13810 6357 13811 6362 13811 6453 13811 6364 13812 6443 13812 6446 13812 6362 13813 6364 13813 6446 13813 6365 13814 6436 13814 6443 13814 6364 13815 6365 13815 6443 13815 6366 13816 6431 13816 6436 13816 6365 13817 6366 13817 6436 13817 6367 13818 6428 13818 6431 13818 6366 13819 6367 13819 6431 13819 6368 13820 6423 13820 6428 13820 6367 13821 6368 13821 6428 13821 6369 13822 6420 13822 6423 13822 6368 13823 6369 13823 6423 13823 6370 13824 6415 13824 6420 13824 6369 13825 6370 13825 6420 13825 6500 13826 6493 13826 6492 13826 6499 13827 6500 13827 6492 13827 6494 13828 6499 13828 6492 13828 6501 13829 6503 13829 6493 13829 6500 13830 6501 13830 6493 13830 6501 13831 6502 13831 6503 13831 6494 13832 6498 13832 6499 13832 6495 13833 6497 13833 6498 13833 6494 13834 6495 13834 6498 13834 6495 13835 6496 13835 6497 13835 12337 13836 12336 13836 12341 13836 12341 13837 12342 13837 12337 13837 12342 13838 12343 13838 12339 13838 12336 13839 12339 13839 12343 13839 12336 13840 12337 13840 12338 13840 12343 13841 12342 13841 12340 13841 12336 13842 12340 13842 12341 13842 12342 13843 12338 13843 12337 13843 12338 13844 12342 13844 12339 13844 12340 13845 12336 13845 12343 13845 12339 13846 12336 13846 12338 13846 12342 13847 12341 13847 12340 13847</p> + </polylist> + <polylist material="mat_helix_front-material" count="5808"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>6504 13848 6505 13848 6506 13848 6507 13849 6506 13849 6505 13849 6508 13850 6506 13850 6509 13850 6510 13851 6509 13851 6506 13851 6504 13852 6506 13852 6508 13852 6511 13853 6506 13853 6507 13853 6512 13854 6510 13854 6506 13854 6513 13855 6512 13855 6506 13855 6511 13856 6513 13856 6506 13856 6514 13857 6515 13857 6505 13857 6516 13858 6505 13858 6515 13858 6517 13859 6514 13859 6505 13859 6518 13860 6517 13860 6505 13860 6504 13861 6518 13861 6505 13861 6519 13862 6505 13862 6516 13862 6520 13863 6521 13863 6505 13863 6522 13864 6505 13864 6521 13864 6519 13865 6520 13865 6505 13865 6522 13866 6507 13866 6505 13866 6523 13867 6524 13867 6515 13867 6525 13868 6515 13868 6524 13868 6514 13869 6523 13869 6515 13869 6516 13870 6515 13870 6525 13870 6526 13871 6527 13871 6524 13871 6528 13872 6524 13872 6527 13872 6523 13873 6526 13873 6524 13873 6525 13874 6524 13874 6528 13874 6529 13875 6527 13875 6526 13875 6528 13876 6527 13876 6529 13876 6530 13877 6526 13877 6523 13877 6529 13878 6526 13878 6530 13878 6531 13879 6523 13879 6514 13879 6530 13880 6523 13880 6531 13880 6532 13881 6533 13881 6514 13881 6534 13882 6514 13882 6533 13882 6517 13883 6532 13883 6514 13883 6531 13884 6514 13884 6534 13884 6535 13885 6536 13885 6533 13885 6537 13886 6533 13886 6536 13886 6538 13887 6535 13887 6533 13887 6532 13888 6538 13888 6533 13888 6534 13889 6533 13889 6539 13889 6537 13890 6539 13890 6533 13890 6540 13891 6541 13891 6536 13891 6542 13892 6536 13892 6541 13892 6535 13893 6540 13893 6536 13893 6543 13894 6537 13894 6536 13894 6544 13895 6543 13895 6536 13895 6545 13896 6544 13896 6536 13896 6542 13897 6545 13897 6536 13897 6546 13898 6547 13898 6541 13898 6548 13899 6541 13899 6547 13899 6549 13900 6546 13900 6541 13900 6550 13901 6549 13901 6541 13901 6540 13902 6550 13902 6541 13902 6551 13903 6541 13903 6548 13903 6552 13904 6542 13904 6541 13904 6553 13905 6554 13905 6541 13905 6552 13906 6541 13906 6554 13906 6551 13907 6553 13907 6541 13907 6555 13908 6556 13908 6547 13908 6557 13909 6547 13909 6556 13909 6546 13910 6555 13910 6547 13910 6548 13911 6547 13911 6557 13911 6558 13912 6559 13912 6556 13912 6560 13913 6556 13913 6559 13913 6555 13914 6558 13914 6556 13914 6557 13915 6556 13915 6560 13915 6561 13916 6559 13916 6558 13916 6560 13917 6559 13917 6561 13917 6562 13918 6558 13918 6555 13918 6561 13919 6558 13919 6562 13919 6563 13920 6555 13920 6546 13920 6562 13921 6555 13921 6563 13921 6564 13922 6509 13922 6546 13922 6565 13923 6546 13923 6509 13923 6549 13924 6564 13924 6546 13924 6563 13925 6546 13925 6565 13925 6566 13926 6508 13926 6509 13926 6564 13927 6566 13927 6509 13927 6565 13928 6509 13928 6567 13928 6510 13929 6567 13929 6509 13929 6568 13930 6508 13930 6566 13930 6569 13931 6504 13931 6508 13931 6569 13932 6508 13932 6568 13932 6570 13933 6566 13933 6564 13933 6570 13934 6568 13934 6566 13934 6571 13935 6564 13935 6549 13935 6570 13936 6564 13936 6571 13936 6572 13937 6549 13937 6550 13937 6571 13938 6549 13938 6572 13938 6573 13939 6550 13939 6540 13939 6572 13940 6550 13940 6573 13940 6574 13941 6540 13941 6535 13941 6573 13942 6540 13942 6574 13942 6575 13943 6535 13943 6538 13943 6574 13944 6535 13944 6575 13944 6576 13945 6538 13945 6532 13945 6575 13946 6538 13946 6576 13946 6577 13947 6532 13947 6517 13947 6576 13948 6532 13948 6577 13948 6578 13949 6517 13949 6518 13949 6577 13950 6517 13950 6578 13950 6518 13951 6504 13951 6579 13951 6578 13952 6518 13952 6579 13952 6579 13953 6504 13953 6569 13953 6570 13954 6567 13954 6580 13954 6581 13955 6580 13955 6567 13955 6568 13956 6580 13956 6516 13956 6519 13957 6516 13957 6580 13957 6570 13958 6580 13958 6568 13958 6582 13959 6519 13959 6580 13959 6583 13960 6582 13960 6580 13960 6584 13961 6583 13961 6580 13961 6585 13962 6584 13962 6580 13962 6586 13963 6585 13963 6580 13963 6581 13964 6586 13964 6580 13964 6557 13965 6565 13965 6567 13965 6572 13966 6557 13966 6567 13966 6571 13967 6572 13967 6567 13967 6570 13968 6571 13968 6567 13968 6587 13969 6581 13969 6567 13969 6510 13970 6587 13970 6567 13970 6560 13971 6563 13971 6565 13971 6557 13972 6560 13972 6565 13972 6561 13973 6562 13973 6563 13973 6560 13974 6561 13974 6563 13974 6573 13975 6548 13975 6557 13975 6572 13976 6573 13976 6557 13976 6575 13977 6588 13977 6548 13977 6551 13978 6548 13978 6588 13978 6574 13979 6575 13979 6548 13979 6573 13980 6574 13980 6548 13980 6576 13981 6539 13981 6588 13981 6589 13982 6588 13982 6539 13982 6575 13983 6576 13983 6588 13983 6590 13984 6588 13984 6589 13984 6591 13985 6551 13985 6588 13985 6592 13986 6591 13986 6588 13986 6593 13987 6592 13987 6588 13987 6594 13988 6593 13988 6588 13988 6590 13989 6594 13989 6588 13989 6525 13990 6534 13990 6539 13990 6578 13991 6525 13991 6539 13991 6577 13992 6578 13992 6539 13992 6576 13993 6577 13993 6539 13993 6595 13994 6589 13994 6539 13994 6537 13995 6595 13995 6539 13995 6528 13996 6531 13996 6534 13996 6525 13997 6528 13997 6534 13997 6529 13998 6530 13998 6531 13998 6528 13999 6529 13999 6531 13999 6579 14000 6516 14000 6525 14000 6578 14001 6579 14001 6525 14001 6569 14002 6568 14002 6516 14002 6579 14003 6569 14003 6516 14003 6596 14004 6521 14004 6520 14004 6596 14005 6522 14005 6521 14005 6597 14006 6520 14006 6519 14006 6598 14007 6596 14007 6520 14007 6597 14008 6598 14008 6520 14008 6599 14009 6519 14009 6582 14009 6600 14010 6519 14010 6599 14010 6600 14011 6597 14011 6519 14011 6601 14012 6582 14012 6583 14012 6602 14013 6599 14013 6582 14013 6601 14014 6602 14014 6582 14014 6603 14015 6583 14015 6584 14015 6604 14016 6601 14016 6583 14016 6605 14017 6604 14017 6583 14017 6603 14018 6605 14018 6583 14018 6606 14019 6584 14019 6585 14019 6607 14020 6603 14020 6584 14020 6606 14021 6607 14021 6584 14021 6608 14022 6585 14022 6586 14022 6606 14023 6585 14023 6608 14023 6608 14024 6586 14024 6581 14024 6609 14025 6581 14025 6587 14025 6609 14026 6610 14026 6581 14026 6608 14027 6581 14027 6610 14027 6611 14028 6589 14028 6595 14028 6612 14029 6590 14029 6589 14029 6611 14030 6613 14030 6589 14030 6612 14031 6589 14031 6613 14031 6611 14032 6595 14032 6537 14032 6611 14033 6537 14033 6543 14033 6611 14034 6543 14034 6544 14034 6614 14035 6544 14035 6545 14035 6614 14036 6611 14036 6544 14036 6614 14037 6545 14037 6542 14037 6615 14038 6542 14038 6552 14038 6614 14039 6542 14039 6615 14039 6596 14040 6507 14040 6522 14040 6616 14041 6511 14041 6507 14041 6616 14042 6507 14042 6596 14042 6615 14043 6554 14043 6553 14043 6615 14044 6552 14044 6554 14044 6617 14045 6553 14045 6551 14045 6618 14046 6615 14046 6553 14046 6619 14047 6618 14047 6553 14047 6617 14048 6619 14048 6553 14048 6620 14049 6551 14049 6591 14049 6621 14050 6551 14050 6620 14050 6622 14051 6617 14051 6551 14051 6621 14052 6622 14052 6551 14052 6623 14053 6591 14053 6592 14053 6624 14054 6620 14054 6591 14054 6623 14055 6624 14055 6591 14055 6625 14056 6592 14056 6593 14056 6626 14057 6623 14057 6592 14057 6627 14058 6626 14058 6592 14058 6625 14059 6627 14059 6592 14059 6628 14060 6593 14060 6594 14060 6629 14061 6625 14061 6593 14061 6628 14062 6629 14062 6593 14062 6612 14063 6594 14063 6590 14063 6630 14064 6594 14064 6612 14064 6630 14065 6628 14065 6594 14065 6609 14066 6587 14066 6510 14066 6609 14067 6510 14067 6512 14067 6609 14068 6512 14068 6513 14068 6616 14069 6513 14069 6511 14069 6616 14070 6609 14070 6513 14070 6631 14071 6613 14071 6611 14071 6632 14072 6612 14072 6613 14072 6633 14073 6632 14073 6613 14073 6634 14074 6633 14074 6613 14074 6635 14075 6634 14075 6613 14075 6636 14076 6635 14076 6613 14076 6637 14077 6636 14077 6613 14077 6638 14078 6637 14078 6613 14078 6638 14079 6613 14079 6631 14079 6639 14080 6611 14080 6614 14080 6640 14081 6641 14081 6611 14081 6642 14082 6611 14082 6641 14082 6639 14083 6640 14083 6611 14083 6643 14084 6631 14084 6611 14084 6644 14085 6643 14085 6611 14085 6645 14086 6644 14086 6611 14086 6646 14087 6645 14087 6611 14087 6647 14088 6646 14088 6611 14088 6648 14089 6647 14089 6611 14089 6642 14090 6648 14090 6611 14090 6630 14091 6612 14091 6632 14091 6649 14092 6632 14092 6633 14092 6649 14093 6630 14093 6632 14093 6650 14094 6633 14094 6634 14094 6649 14095 6633 14095 6650 14095 6650 14096 6634 14096 6635 14096 6651 14097 6635 14097 6636 14097 6650 14098 6635 14098 6651 14098 6637 14099 6652 14099 6636 14099 6651 14100 6636 14100 6652 14100 6637 14101 6653 14101 6652 14101 6654 14102 6652 14102 6653 14102 6651 14103 6652 14103 6654 14103 6637 14104 6655 14104 6653 14104 6654 14105 6653 14105 6655 14105 6637 14106 6656 14106 6655 14106 6657 14107 6655 14107 6656 14107 6654 14108 6655 14108 6657 14108 6637 14109 6658 14109 6656 14109 6657 14110 6656 14110 6658 14110 6637 14111 6659 14111 6658 14111 6657 14112 6658 14112 6659 14112 6660 14113 6661 14113 6659 14113 6662 14114 6659 14114 6661 14114 6637 14115 6660 14115 6659 14115 6657 14116 6659 14116 6662 14116 6660 14117 6663 14117 6661 14117 6662 14118 6661 14118 6663 14118 6660 14119 6664 14119 6663 14119 6665 14120 6663 14120 6664 14120 6662 14121 6663 14121 6665 14121 6660 14122 6666 14122 6664 14122 6665 14123 6664 14123 6666 14123 6660 14124 6667 14124 6666 14124 6668 14125 6666 14125 6667 14125 6665 14126 6666 14126 6668 14126 6660 14127 6669 14127 6667 14127 6668 14128 6667 14128 6669 14128 6670 14129 6671 14129 6669 14129 6672 14130 6669 14130 6671 14130 6660 14131 6670 14131 6669 14131 6668 14132 6669 14132 6672 14132 6670 14133 6673 14133 6671 14133 6674 14134 6671 14134 6673 14134 6672 14135 6671 14135 6674 14135 6670 14136 6675 14136 6673 14136 6674 14137 6673 14137 6675 14137 6676 14138 6677 14138 6675 14138 6678 14139 6675 14139 6677 14139 6670 14140 6676 14140 6675 14140 6674 14141 6675 14141 6678 14141 6676 14142 6679 14142 6677 14142 6678 14143 6677 14143 6679 14143 6676 14144 6680 14144 6679 14144 6681 14145 6679 14145 6680 14145 6678 14146 6679 14146 6681 14146 6682 14147 6683 14147 6680 14147 6684 14148 6680 14148 6683 14148 6676 14149 6682 14149 6680 14149 6681 14150 6680 14150 6684 14150 6682 14151 6685 14151 6683 14151 6686 14152 6683 14152 6685 14152 6684 14153 6683 14153 6686 14153 6687 14154 6688 14154 6685 14154 6689 14155 6685 14155 6688 14155 6682 14156 6687 14156 6685 14156 6686 14157 6685 14157 6689 14157 6687 14158 6690 14158 6688 14158 6691 14159 6688 14159 6690 14159 6689 14160 6688 14160 6691 14160 6692 14161 6693 14161 6690 14161 6694 14162 6690 14162 6693 14162 6687 14163 6692 14163 6690 14163 6695 14164 6690 14164 6694 14164 6691 14165 6690 14165 6695 14165 6696 14166 6697 14166 6693 14166 6698 14167 6693 14167 6697 14167 6692 14168 6696 14168 6693 14168 6694 14169 6693 14169 6698 14169 6699 14170 6700 14170 6697 14170 6701 14171 6697 14171 6700 14171 6696 14172 6699 14172 6697 14172 6702 14173 6697 14173 6701 14173 6698 14174 6697 14174 6702 14174 6703 14175 6704 14175 6700 14175 6705 14176 6700 14176 6704 14176 6706 14177 6703 14177 6700 14177 6699 14178 6706 14178 6700 14178 6701 14179 6700 14179 6705 14179 6707 14180 6708 14180 6704 14180 6709 14181 6704 14181 6708 14181 6710 14182 6707 14182 6704 14182 6703 14183 6710 14183 6704 14183 6711 14184 6704 14184 6709 14184 6705 14185 6704 14185 6711 14185 6712 14186 6713 14186 6708 14186 6714 14187 6708 14187 6713 14187 6707 14188 6712 14188 6708 14188 6715 14189 6708 14189 6714 14189 6716 14190 6708 14190 6715 14190 6709 14191 6708 14191 6716 14191 6717 14192 6718 14192 6713 14192 6719 14193 6713 14193 6718 14193 6720 14194 6717 14194 6713 14194 6712 14195 6720 14195 6713 14195 6721 14196 6713 14196 6719 14196 6714 14197 6713 14197 6721 14197 6722 14198 6723 14198 6718 14198 6724 14199 6718 14199 6723 14199 6725 14200 6722 14200 6718 14200 6717 14201 6725 14201 6718 14201 6726 14202 6718 14202 6724 14202 6719 14203 6718 14203 6726 14203 6727 14204 6728 14204 6723 14204 6729 14205 6723 14205 6728 14205 6722 14206 6727 14206 6723 14206 6730 14207 6723 14207 6729 14207 6724 14208 6723 14208 6730 14208 6731 14209 6732 14209 6728 14209 6733 14210 6728 14210 6732 14210 6734 14211 6731 14211 6728 14211 6735 14212 6734 14212 6728 14212 6736 14213 6735 14213 6728 14213 6737 14214 6736 14214 6728 14214 6727 14215 6737 14215 6728 14215 6729 14216 6728 14216 6733 14216 6738 14217 6732 14217 6731 14217 6739 14218 6732 14218 6738 14218 6733 14219 6732 14219 6739 14219 6738 14220 6731 14220 6734 14220 6740 14221 6734 14221 6735 14221 6740 14222 6738 14222 6734 14222 6741 14223 6735 14223 6736 14223 6741 14224 6740 14224 6735 14224 6741 14225 6736 14225 6737 14225 6742 14226 6737 14226 6727 14226 6741 14227 6737 14227 6742 14227 6742 14228 6727 14228 6722 14228 6743 14229 6722 14229 6725 14229 6743 14230 6742 14230 6722 14230 6743 14231 6725 14231 6717 14231 6744 14232 6717 14232 6720 14232 6744 14233 6743 14233 6717 14233 6744 14234 6720 14234 6712 14234 6744 14235 6712 14235 6707 14235 6745 14236 6707 14236 6710 14236 6745 14237 6744 14237 6707 14237 6745 14238 6710 14238 6703 14238 6746 14239 6703 14239 6706 14239 6746 14240 6745 14240 6703 14240 6746 14241 6706 14241 6699 14241 6747 14242 6699 14242 6696 14242 6747 14243 6746 14243 6699 14243 6747 14244 6696 14244 6692 14244 6748 14245 6692 14245 6687 14245 6748 14246 6747 14246 6692 14246 6748 14247 6687 14247 6682 14247 6749 14248 6682 14248 6676 14248 6749 14249 6748 14249 6682 14249 6750 14250 6676 14250 6670 14250 6750 14251 6749 14251 6676 14251 6750 14252 6670 14252 6660 14252 6751 14253 6660 14253 6637 14253 6751 14254 6750 14254 6660 14254 6638 14255 6751 14255 6637 14255 6752 14256 6614 14256 6615 14256 6753 14257 6752 14257 6615 14257 6753 14258 6615 14258 6618 14258 6754 14259 6755 14259 6614 14259 6756 14260 6614 14260 6755 14260 6757 14261 6754 14261 6614 14261 6752 14262 6757 14262 6614 14262 6758 14263 6639 14263 6614 14263 6759 14264 6758 14264 6614 14264 6760 14265 6759 14265 6614 14265 6761 14266 6760 14266 6614 14266 6762 14267 6761 14267 6614 14267 6756 14268 6762 14268 6614 14268 6763 14269 6764 14269 6755 14269 6765 14270 6755 14270 6764 14270 6766 14271 6763 14271 6755 14271 6767 14272 6766 14272 6755 14272 6768 14273 6767 14273 6755 14273 6769 14274 6768 14274 6755 14274 6770 14275 6769 14275 6755 14275 6771 14276 6770 14276 6755 14276 6772 14277 6771 14277 6755 14277 6773 14278 6772 14278 6755 14278 6754 14279 6773 14279 6755 14279 6756 14280 6755 14280 6760 14280 6765 14281 6760 14281 6755 14281 6774 14282 6775 14282 6764 14282 6776 14283 6764 14283 6775 14283 6777 14284 6774 14284 6764 14284 6778 14285 6777 14285 6764 14285 6779 14286 6778 14286 6764 14286 6780 14287 6779 14287 6764 14287 6781 14288 6780 14288 6764 14288 6763 14289 6781 14289 6764 14289 6765 14290 6764 14290 6776 14290 6782 14291 6783 14291 6775 14291 6784 14292 6775 14292 6783 14292 6785 14293 6782 14293 6775 14293 6786 14294 6785 14294 6775 14294 6787 14295 6786 14295 6775 14295 6774 14296 6787 14296 6775 14296 6776 14297 6775 14297 6784 14297 6788 14298 6789 14298 6783 14298 6790 14299 6783 14299 6789 14299 6791 14300 6788 14300 6783 14300 6782 14301 6791 14301 6783 14301 6784 14302 6783 14302 6790 14302 6792 14303 6793 14303 6789 14303 6794 14304 6789 14304 6793 14304 6795 14305 6792 14305 6789 14305 6788 14306 6795 14306 6789 14306 6790 14307 6789 14307 6794 14307 6796 14308 6797 14308 6793 14308 6798 14309 6793 14309 6797 14309 6792 14310 6796 14310 6793 14310 6794 14311 6793 14311 6798 14311 6799 14312 6800 14312 6797 14312 6798 14313 6797 14313 6800 14313 6796 14314 6799 14314 6797 14314 6801 14315 6802 14315 6800 14315 6803 14316 6800 14316 6802 14316 6799 14317 6801 14317 6800 14317 6798 14318 6800 14318 6803 14318 6804 14319 6805 14319 6802 14319 6803 14320 6802 14320 6805 14320 6801 14321 6804 14321 6802 14321 6806 14322 6807 14322 6805 14322 6808 14323 6805 14323 6807 14323 6804 14324 6806 14324 6805 14324 6803 14325 6805 14325 6808 14325 6806 14326 6809 14326 6807 14326 6810 14327 6807 14327 6809 14327 6808 14328 6807 14328 6810 14328 6811 14329 6812 14329 6809 14329 6810 14330 6809 14330 6812 14330 6806 14331 6811 14331 6809 14331 6811 14332 6813 14332 6812 14332 6810 14333 6812 14333 6813 14333 6814 14334 6815 14334 6813 14334 6816 14335 6813 14335 6815 14335 6811 14336 6814 14336 6813 14336 6810 14337 6813 14337 6816 14337 6817 14338 6818 14338 6815 14338 6816 14339 6815 14339 6818 14339 6814 14340 6817 14340 6815 14340 6819 14341 6820 14341 6818 14341 6821 14342 6818 14342 6820 14342 6817 14343 6819 14343 6818 14343 6816 14344 6818 14344 6821 14344 6819 14345 6822 14345 6820 14345 6823 14346 6820 14346 6822 14346 6823 14347 6821 14347 6820 14347 6819 14348 6824 14348 6822 14348 6825 14349 6822 14349 6824 14349 6825 14350 6823 14350 6822 14350 6819 14351 6826 14351 6824 14351 6825 14352 6824 14352 6826 14352 6827 14353 6826 14353 6819 14353 6828 14354 6825 14354 6826 14354 6829 14355 6828 14355 6826 14355 6830 14356 6829 14356 6826 14356 6827 14357 6830 14357 6826 14357 6831 14358 6819 14358 6817 14358 6831 14359 6827 14359 6819 14359 6832 14360 6817 14360 6814 14360 6832 14361 6831 14361 6817 14361 6833 14362 6814 14362 6811 14362 6834 14363 6832 14363 6814 14363 6833 14364 6834 14364 6814 14364 6835 14365 6811 14365 6806 14365 6835 14366 6833 14366 6811 14366 6836 14367 6806 14367 6804 14367 6837 14368 6835 14368 6806 14368 6838 14369 6837 14369 6806 14369 6836 14370 6838 14370 6806 14370 6839 14371 6804 14371 6801 14371 6840 14372 6836 14372 6804 14372 6839 14373 6840 14373 6804 14373 6841 14374 6801 14374 6799 14374 6842 14375 6839 14375 6801 14375 6843 14376 6842 14376 6801 14376 6841 14377 6843 14377 6801 14377 6844 14378 6799 14378 6796 14378 6845 14379 6841 14379 6799 14379 6844 14380 6845 14380 6799 14380 6846 14381 6796 14381 6792 14381 6847 14382 6844 14382 6796 14382 6846 14383 6847 14383 6796 14383 6848 14384 6792 14384 6795 14384 6848 14385 6846 14385 6792 14385 6849 14386 6795 14386 6788 14386 6850 14387 6848 14387 6795 14387 6849 14388 6850 14388 6795 14388 6851 14389 6788 14389 6791 14389 6851 14390 6849 14390 6788 14390 6852 14391 6791 14391 6782 14391 6852 14392 6851 14392 6791 14392 6853 14393 6782 14393 6785 14393 6853 14394 6852 14394 6782 14394 6854 14395 6785 14395 6786 14395 6854 14396 6853 14396 6785 14396 6854 14397 6786 14397 6787 14397 6855 14398 6787 14398 6774 14398 6855 14399 6854 14399 6787 14399 6855 14400 6774 14400 6777 14400 6856 14401 6777 14401 6778 14401 6856 14402 6855 14402 6777 14402 6856 14403 6778 14403 6779 14403 6857 14404 6779 14404 6780 14404 6857 14405 6856 14405 6779 14405 6857 14406 6780 14406 6781 14406 6858 14407 6781 14407 6763 14407 6858 14408 6857 14408 6781 14408 6858 14409 6763 14409 6766 14409 6859 14410 6766 14410 6767 14410 6859 14411 6858 14411 6766 14411 6859 14412 6767 14412 6768 14412 6860 14413 6768 14413 6769 14413 6860 14414 6859 14414 6768 14414 6861 14415 6769 14415 6770 14415 6861 14416 6860 14416 6769 14416 6861 14417 6770 14417 6771 14417 6861 14418 6771 14418 6772 14418 6862 14419 6772 14419 6773 14419 6862 14420 6861 14420 6772 14420 6862 14421 6773 14421 6754 14421 6863 14422 6754 14422 6757 14422 6863 14423 6862 14423 6754 14423 6753 14424 6757 14424 6752 14424 6753 14425 6863 14425 6757 14425 6621 14426 6620 14426 6624 14426 6864 14427 6624 14427 6623 14427 6865 14428 6624 14428 6864 14428 6621 14429 6624 14429 6865 14429 6864 14430 6623 14430 6626 14430 6627 14431 6864 14431 6626 14431 6866 14432 6865 14432 6864 14432 6866 14433 6864 14433 6867 14433 6868 14434 6867 14434 6864 14434 6868 14435 6864 14435 6627 14435 6621 14436 6865 14436 6866 14436 6869 14437 6870 14437 6871 14437 6872 14438 6871 14438 6870 14438 6873 14439 6869 14439 6871 14439 6874 14440 6873 14440 6871 14440 6872 14441 6874 14441 6871 14441 6875 14442 6876 14442 6870 14442 6877 14443 6870 14443 6876 14443 6869 14444 6875 14444 6870 14444 6878 14445 6872 14445 6870 14445 6877 14446 6878 14446 6870 14446 6879 14447 6880 14447 6876 14447 6881 14448 6876 14448 6880 14448 6875 14449 6879 14449 6876 14449 6881 14450 6877 14450 6876 14450 6879 14451 6882 14451 6880 14451 6883 14452 6880 14452 6882 14452 6883 14453 6881 14453 6880 14453 6884 14454 6885 14454 6882 14454 6883 14455 6882 14455 6885 14455 6879 14456 6884 14456 6882 14456 6886 14457 6887 14457 6885 14457 6888 14458 6885 14458 6887 14458 6884 14459 6886 14459 6885 14459 6888 14460 6883 14460 6885 14460 6889 14461 6890 14461 6887 14461 6891 14462 6887 14462 6890 14462 6886 14463 6889 14463 6887 14463 6891 14464 6888 14464 6887 14464 6892 14465 6893 14465 6890 14465 6894 14466 6890 14466 6893 14466 6889 14467 6892 14467 6890 14467 6894 14468 6891 14468 6890 14468 6895 14469 6896 14469 6893 14469 6894 14470 6893 14470 6896 14470 6892 14471 6895 14471 6893 14471 6897 14472 6898 14472 6896 14472 6899 14473 6896 14473 6898 14473 6895 14474 6897 14474 6896 14474 6899 14475 6894 14475 6896 14475 6900 14476 6901 14476 6898 14476 6899 14477 6898 14477 6901 14477 6897 14478 6900 14478 6898 14478 6902 14479 6903 14479 6901 14479 6904 14480 6901 14480 6903 14480 6900 14481 6902 14481 6901 14481 6904 14482 6899 14482 6901 14482 6905 14483 6906 14483 6903 14483 6904 14484 6903 14484 6906 14484 6902 14485 6905 14485 6903 14485 6907 14486 6908 14486 6906 14486 6909 14487 6906 14487 6908 14487 6905 14488 6907 14488 6906 14488 6909 14489 6904 14489 6906 14489 6910 14490 6911 14490 6908 14490 6912 14491 6908 14491 6911 14491 6907 14492 6910 14492 6908 14492 6912 14493 6909 14493 6908 14493 6913 14494 6914 14494 6911 14494 6912 14495 6911 14495 6914 14495 6910 14496 6913 14496 6911 14496 6915 14497 6916 14497 6914 14497 6917 14498 6914 14498 6916 14498 6918 14499 6915 14499 6914 14499 6913 14500 6918 14500 6914 14500 6917 14501 6912 14501 6914 14501 6919 14502 6920 14502 6916 14502 6921 14503 6916 14503 6920 14503 6915 14504 6919 14504 6916 14504 6921 14505 6917 14505 6916 14505 6922 14506 6923 14506 6920 14506 6921 14507 6920 14507 6923 14507 6919 14508 6922 14508 6920 14508 6924 14509 6925 14509 6923 14509 6926 14510 6923 14510 6925 14510 6922 14511 6924 14511 6923 14511 6926 14512 6921 14512 6923 14512 6927 14513 6928 14513 6925 14513 6926 14514 6925 14514 6928 14514 6924 14515 6927 14515 6925 14515 6929 14516 6930 14516 6928 14516 6931 14517 6928 14517 6930 14517 6927 14518 6929 14518 6928 14518 6931 14519 6926 14519 6928 14519 6932 14520 6933 14520 6930 14520 6934 14521 6930 14521 6933 14521 6929 14522 6932 14522 6930 14522 6934 14523 6931 14523 6930 14523 6935 14524 6936 14524 6933 14524 6934 14525 6933 14525 6936 14525 6932 14526 6935 14526 6933 14526 6935 14527 6937 14527 6936 14527 6938 14528 6936 14528 6937 14528 6938 14529 6934 14529 6936 14529 6935 14530 6939 14530 6937 14530 6940 14531 6937 14531 6939 14531 6940 14532 6938 14532 6937 14532 6941 14533 6942 14533 6939 14533 6943 14534 6939 14534 6942 14534 6944 14535 6941 14535 6939 14535 6935 14536 6944 14536 6939 14536 6943 14537 6940 14537 6939 14537 6945 14538 6946 14538 6942 14538 6947 14539 6942 14539 6946 14539 6941 14540 6945 14540 6942 14540 6947 14541 6943 14541 6942 14541 6948 14542 6949 14542 6946 14542 6950 14543 6946 14543 6949 14543 6945 14544 6948 14544 6946 14544 6951 14545 6947 14545 6946 14545 6950 14546 6951 14546 6946 14546 6952 14547 6953 14547 6949 14547 6950 14548 6949 14548 6953 14548 6948 14549 6952 14549 6949 14549 6954 14550 6955 14550 6953 14550 6956 14551 6953 14551 6955 14551 6952 14552 6954 14552 6953 14552 6956 14553 6950 14553 6953 14553 6957 14554 6958 14554 6955 14554 6959 14555 6955 14555 6958 14555 6954 14556 6957 14556 6955 14556 6959 14557 6956 14557 6955 14557 6960 14558 6961 14558 6958 14558 6959 14559 6958 14559 6961 14559 6957 14560 6960 14560 6958 14560 6962 14561 6963 14561 6961 14561 6964 14562 6961 14562 6963 14562 6965 14563 6962 14563 6961 14563 6960 14564 6965 14564 6961 14564 6964 14565 6959 14565 6961 14565 6966 14566 6967 14566 6963 14566 6968 14567 6963 14567 6967 14567 6962 14568 6966 14568 6963 14568 6968 14569 6964 14569 6963 14569 6969 14570 6970 14570 6967 14570 6968 14571 6967 14571 6970 14571 6966 14572 6969 14572 6967 14572 6971 14573 6972 14573 6970 14573 6973 14574 6970 14574 6972 14574 6974 14575 6971 14575 6970 14575 6969 14576 6974 14576 6970 14576 6973 14577 6968 14577 6970 14577 6975 14578 6976 14578 6972 14578 6973 14579 6972 14579 6976 14579 6971 14580 6975 14580 6972 14580 6977 14581 6978 14581 6976 14581 6979 14582 6976 14582 6978 14582 6975 14583 6977 14583 6976 14583 6979 14584 6973 14584 6976 14584 6980 14585 6981 14585 6978 14585 6979 14586 6978 14586 6981 14586 6977 14587 6980 14587 6978 14587 6982 14588 6983 14588 6981 14588 6984 14589 6981 14589 6983 14589 6980 14590 6982 14590 6981 14590 6984 14591 6979 14591 6981 14591 6985 14592 6986 14592 6983 14592 6984 14593 6983 14593 6986 14593 6982 14594 6985 14594 6983 14594 6987 14595 6988 14595 6986 14595 6989 14596 6986 14596 6988 14596 6985 14597 6987 14597 6986 14597 6989 14598 6984 14598 6986 14598 6990 14599 6991 14599 6988 14599 6989 14600 6988 14600 6991 14600 6987 14601 6990 14601 6988 14601 6992 14602 6993 14602 6991 14602 6994 14603 6991 14603 6993 14603 6990 14604 6992 14604 6991 14604 6994 14605 6989 14605 6991 14605 6995 14606 6996 14606 6993 14606 6994 14607 6993 14607 6996 14607 6992 14608 6995 14608 6993 14608 6997 14609 6998 14609 6996 14609 6999 14610 6996 14610 6998 14610 6995 14611 6997 14611 6996 14611 6999 14612 6994 14612 6996 14612 7000 14613 7001 14613 6998 14613 6999 14614 6998 14614 7001 14614 7002 14615 7000 14615 6998 14615 6997 14616 7002 14616 6998 14616 7003 14617 7004 14617 7001 14617 7005 14618 7001 14618 7004 14618 7000 14619 7003 14619 7001 14619 7005 14620 6999 14620 7001 14620 7006 14621 6867 14621 7004 14621 6868 14622 7004 14622 6867 14622 7003 14623 7006 14623 7004 14623 6868 14624 7005 14624 7004 14624 7006 14625 6866 14625 6867 14625 7007 14626 6866 14626 7006 14626 7007 14627 6621 14627 6866 14627 7007 14628 7006 14628 7003 14628 7008 14629 7003 14629 7000 14629 7008 14630 7007 14630 7003 14630 7008 14631 7000 14631 7002 14631 7009 14632 7002 14632 6997 14632 7009 14633 7008 14633 7002 14633 7009 14634 6997 14634 6995 14634 7009 14635 6995 14635 6992 14635 7010 14636 6992 14636 6990 14636 7010 14637 7009 14637 6992 14637 7010 14638 6990 14638 6987 14638 7011 14639 6987 14639 6985 14639 7011 14640 7010 14640 6987 14640 7012 14641 6985 14641 6982 14641 7012 14642 7011 14642 6985 14642 7012 14643 6982 14643 6980 14643 7012 14644 6980 14644 6977 14644 7013 14645 6977 14645 6975 14645 7013 14646 7012 14646 6977 14646 7013 14647 6975 14647 6971 14647 7014 14648 6971 14648 6974 14648 7014 14649 7013 14649 6971 14649 7014 14650 6974 14650 6969 14650 7014 14651 6969 14651 6966 14651 7015 14652 6966 14652 6962 14652 7015 14653 7014 14653 6966 14653 7015 14654 6962 14654 6965 14654 7016 14655 6965 14655 6960 14655 7016 14656 7015 14656 6965 14656 7017 14657 6960 14657 6957 14657 7017 14658 7016 14658 6960 14658 7017 14659 6957 14659 6954 14659 7018 14660 6954 14660 6952 14660 7018 14661 7017 14661 6954 14661 7019 14662 6952 14662 6948 14662 7019 14663 7018 14663 6952 14663 7020 14664 6948 14664 6945 14664 7020 14665 7019 14665 6948 14665 7021 14666 6945 14666 6941 14666 7021 14667 7020 14667 6945 14667 7022 14668 6941 14668 6944 14668 7022 14669 7021 14669 6941 14669 7023 14670 6944 14670 6935 14670 7023 14671 7022 14671 6944 14671 7024 14672 6935 14672 6932 14672 7024 14673 7023 14673 6935 14673 7025 14674 6932 14674 6929 14674 7025 14675 7024 14675 6932 14675 7026 14676 6929 14676 6927 14676 7026 14677 7025 14677 6929 14677 7026 14678 6927 14678 6924 14678 7027 14679 6924 14679 6922 14679 7027 14680 7026 14680 6924 14680 7028 14681 6922 14681 6919 14681 7028 14682 7027 14682 6922 14682 7028 14683 6919 14683 6915 14683 7029 14684 6915 14684 6918 14684 7029 14685 7028 14685 6915 14685 7029 14686 6918 14686 6913 14686 7030 14687 6913 14687 6910 14687 7030 14688 7029 14688 6913 14688 7030 14689 6910 14689 6907 14689 7031 14690 6907 14690 6905 14690 7031 14691 7030 14691 6907 14691 7032 14692 6905 14692 6902 14692 7032 14693 7031 14693 6905 14693 7032 14694 6902 14694 6900 14694 7033 14695 6900 14695 6897 14695 7033 14696 7032 14696 6900 14696 7033 14697 6897 14697 6895 14697 7034 14698 6895 14698 6892 14698 7034 14699 7033 14699 6895 14699 7035 14700 6892 14700 6889 14700 7035 14701 7034 14701 6892 14701 7035 14702 6889 14702 6886 14702 7036 14703 6886 14703 6884 14703 7036 14704 7035 14704 6886 14704 7036 14705 6884 14705 6879 14705 7037 14706 6879 14706 6875 14706 7037 14707 7036 14707 6879 14707 7038 14708 6875 14708 6869 14708 7039 14709 7037 14709 6875 14709 7038 14710 7039 14710 6875 14710 7040 14711 6869 14711 6873 14711 7040 14712 7038 14712 6869 14712 7041 14713 6873 14713 6874 14713 6828 14714 6873 14714 7041 14714 7042 14715 6873 14715 6828 14715 7040 14716 6873 14716 7042 14716 7043 14717 7041 14717 6874 14717 6740 14718 7043 14718 6874 14718 6740 14719 6874 14719 6738 14719 7044 14720 6738 14720 6874 14720 7045 14721 7044 14721 6874 14721 7046 14722 7047 14722 7048 14722 6872 14723 7045 14723 6874 14723 7049 14724 7041 14724 7043 14724 6828 14725 7041 14725 7049 14725 7050 14726 7051 14726 7052 14726 6742 14727 7052 14727 7051 14727 7053 14728 7050 14728 7052 14728 7054 14729 7053 14729 7052 14729 6743 14730 7054 14730 7052 14730 6743 14731 7052 14731 6742 14731 7049 14732 7043 14732 7051 14732 6741 14733 7051 14733 7043 14733 7050 14734 7049 14734 7051 14734 6741 14735 6742 14735 7051 14735 6741 14736 7043 14736 6740 14736 6825 14737 7049 14737 7050 14737 6828 14738 7049 14738 6825 14738 6823 14739 7050 14739 7053 14739 6825 14740 7050 14740 6823 14740 7055 14741 7053 14741 7054 14741 6821 14742 7053 14742 7055 14742 6823 14743 7053 14743 6821 14743 7056 14744 7057 14744 6641 14744 6642 14745 6641 14745 7057 14745 6640 14746 7056 14746 6641 14746 7058 14747 7059 14747 7057 14747 6638 14748 7057 14748 7059 14748 7056 14749 7058 14749 7057 14749 6646 14750 7057 14750 6645 14750 6638 14751 6645 14751 7057 14751 6647 14752 7057 14752 6646 14752 6648 14753 7057 14753 6647 14753 6642 14754 7057 14754 6648 14754 7060 14755 7061 14755 7059 14755 6751 14756 7059 14756 7061 14756 7058 14757 7060 14757 7059 14757 6638 14758 7059 14758 6751 14758 7062 14759 7063 14759 7061 14759 6750 14760 7061 14760 7063 14760 7060 14761 7062 14761 7061 14761 6751 14762 7061 14762 6750 14762 7062 14763 7064 14763 7063 14763 6750 14764 7063 14764 7064 14764 7065 14765 7066 14765 7064 14765 6749 14766 7064 14766 7066 14766 7062 14767 7065 14767 7064 14767 6750 14768 7064 14768 6749 14768 7067 14769 7068 14769 7066 14769 6748 14770 7066 14770 7068 14770 7065 14771 7067 14771 7066 14771 6749 14772 7066 14772 6748 14772 7069 14773 7070 14773 7068 14773 6748 14774 7068 14774 7070 14774 7067 14775 7069 14775 7068 14775 7069 14776 7071 14776 7070 14776 6747 14777 7070 14777 7071 14777 6748 14778 7070 14778 6747 14778 7072 14779 7073 14779 7071 14779 6747 14780 7071 14780 7073 14780 7069 14781 7072 14781 7071 14781 7074 14782 7075 14782 7073 14782 6746 14783 7073 14783 7075 14783 7072 14784 7074 14784 7073 14784 6747 14785 7073 14785 6746 14785 7074 14786 7076 14786 7075 14786 6746 14787 7075 14787 7076 14787 7077 14788 7078 14788 7076 14788 6745 14789 7076 14789 7078 14789 7074 14790 7077 14790 7076 14790 6746 14791 7076 14791 6745 14791 7079 14792 7080 14792 7078 14792 6745 14793 7078 14793 7080 14793 7077 14794 7079 14794 7078 14794 7081 14795 7082 14795 7080 14795 6745 14796 7080 14796 7082 14796 7079 14797 7081 14797 7080 14797 7081 14798 7083 14798 7082 14798 6744 14799 7082 14799 7083 14799 6745 14800 7082 14800 6744 14800 7084 14801 7085 14801 7083 14801 6744 14802 7083 14802 7085 14802 7081 14803 7084 14803 7083 14803 7086 14804 7087 14804 7085 14804 6743 14805 7085 14805 7087 14805 7084 14806 7086 14806 7085 14806 6744 14807 7085 14807 6743 14807 7055 14808 7054 14808 7087 14808 6743 14809 7087 14809 7054 14809 7086 14810 7055 14810 7087 14810 6816 14811 7055 14811 7086 14811 6816 14812 6821 14812 7055 14812 6816 14813 7086 14813 7084 14813 6810 14814 7084 14814 7081 14814 6810 14815 6816 14815 7084 14815 6810 14816 7081 14816 7079 14816 6808 14817 7079 14817 7077 14817 6808 14818 6810 14818 7079 14818 6808 14819 7077 14819 7074 14819 6803 14820 7074 14820 7072 14820 6803 14821 6808 14821 7074 14821 6798 14822 7072 14822 7069 14822 6798 14823 6803 14823 7072 14823 6798 14824 7069 14824 7067 14824 6794 14825 7067 14825 7065 14825 6794 14826 6798 14826 7067 14826 6790 14827 7065 14827 7062 14827 6790 14828 6794 14828 7065 14828 6784 14829 7062 14829 7060 14829 6784 14830 6790 14830 7062 14830 6776 14831 7060 14831 7058 14831 6776 14832 6784 14832 7060 14832 6765 14833 7058 14833 7056 14833 6765 14834 6776 14834 7058 14834 6760 14835 7056 14835 6640 14835 6765 14836 7056 14836 6760 14836 6758 14837 6640 14837 6639 14837 6759 14838 6640 14838 6758 14838 6760 14839 6640 14839 6759 14839 6762 14840 6760 14840 6761 14840 6756 14841 6760 14841 6762 14841 6638 14842 6631 14842 6643 14842 6638 14843 6643 14843 6644 14843 6638 14844 6644 14844 6645 14844 7088 14845 6610 14845 6609 14845 7089 14846 6608 14846 6610 14846 7090 14847 7089 14847 6610 14847 7091 14848 7090 14848 6610 14848 7092 14849 7091 14849 6610 14849 7093 14850 7092 14850 6610 14850 7094 14851 7093 14851 6610 14851 7094 14852 6610 14852 7088 14852 7095 14853 6609 14853 6616 14853 7096 14854 7097 14854 6609 14854 7098 14855 6609 14855 7097 14855 7099 14856 7096 14856 6609 14856 7100 14857 7099 14857 6609 14857 7095 14858 7100 14858 6609 14858 7101 14859 7088 14859 6609 14859 7102 14860 7101 14860 6609 14860 7103 14861 7102 14861 6609 14861 7104 14862 7103 14862 6609 14862 7105 14863 7104 14863 6609 14863 7106 14864 7105 14864 6609 14864 7098 14865 7106 14865 6609 14865 6606 14866 6608 14866 7089 14866 7107 14867 7089 14867 7090 14867 7107 14868 6606 14868 7089 14868 7108 14869 7090 14869 7091 14869 7107 14870 7090 14870 7108 14870 7108 14871 7091 14871 7092 14871 7093 14872 7109 14872 7092 14872 7110 14873 7092 14873 7109 14873 7108 14874 7092 14874 7110 14874 7093 14875 7111 14875 7109 14875 7110 14876 7109 14876 7111 14876 7112 14877 7113 14877 7111 14877 7114 14878 7111 14878 7113 14878 7093 14879 7112 14879 7111 14879 7110 14880 7111 14880 7114 14880 7112 14881 7115 14881 7113 14881 7114 14882 7113 14882 7115 14882 7112 14883 7116 14883 7115 14883 7117 14884 7115 14884 7116 14884 7114 14885 7115 14885 7117 14885 7112 14886 7118 14886 7116 14886 7117 14887 7116 14887 7118 14887 7112 14888 7119 14888 7118 14888 7117 14889 7118 14889 7119 14889 7120 14890 7121 14890 7119 14890 7122 14891 7119 14891 7121 14891 7112 14892 7120 14892 7119 14892 7117 14893 7119 14893 7122 14893 7120 14894 7123 14894 7121 14894 7122 14895 7121 14895 7123 14895 7120 14896 7124 14896 7123 14896 7125 14897 7123 14897 7124 14897 7122 14898 7123 14898 7125 14898 7120 14899 7126 14899 7124 14899 7127 14900 7124 14900 7126 14900 7125 14901 7124 14901 7127 14901 7128 14902 7129 14902 7126 14902 7127 14903 7126 14903 7129 14903 7120 14904 7128 14904 7126 14904 7128 14905 7130 14905 7129 14905 7131 14906 7129 14906 7130 14906 7127 14907 7129 14907 7131 14907 7128 14908 7132 14908 7130 14908 7133 14909 7130 14909 7132 14909 7131 14910 7130 14910 7133 14910 7134 14911 7135 14911 7132 14911 7136 14912 7132 14912 7135 14912 7128 14913 7134 14913 7132 14913 7133 14914 7132 14914 7136 14914 7134 14915 7137 14915 7135 14915 7138 14916 7135 14916 7137 14916 7136 14917 7135 14917 7138 14917 7139 14918 7140 14918 7137 14918 7141 14919 7137 14919 7140 14919 7134 14920 7139 14920 7137 14920 7138 14921 7137 14921 7141 14921 7139 14922 7142 14922 7140 14922 7143 14923 7140 14923 7142 14923 7141 14924 7140 14924 7143 14924 7144 14925 7145 14925 7142 14925 7146 14926 7142 14926 7145 14926 7139 14927 7144 14927 7142 14927 7143 14928 7142 14928 7146 14928 7147 14929 7148 14929 7145 14929 7149 14930 7145 14930 7148 14930 7144 14931 7147 14931 7145 14931 7146 14932 7145 14932 7149 14932 7150 14933 7151 14933 7148 14933 7152 14934 7148 14934 7151 14934 7147 14935 7150 14935 7148 14935 7149 14936 7148 14936 7152 14936 7153 14937 7154 14937 7151 14937 7155 14938 7151 14938 7154 14938 7150 14939 7153 14939 7151 14939 7156 14940 7151 14940 7155 14940 7152 14941 7151 14941 7156 14941 7157 14942 7158 14942 7154 14942 7159 14943 7154 14943 7158 14943 7160 14944 7157 14944 7154 14944 7153 14945 7160 14945 7154 14945 7161 14946 7154 14946 7159 14946 7155 14947 7154 14947 7161 14947 7162 14948 7163 14948 7158 14948 7164 14949 7158 14949 7163 14949 7165 14950 7162 14950 7158 14950 7157 14951 7165 14951 7158 14951 7159 14952 7158 14952 7164 14952 7166 14953 7167 14953 7163 14953 7168 14954 7163 14954 7167 14954 7169 14955 7166 14955 7163 14955 7170 14956 7169 14956 7163 14956 7162 14957 7170 14957 7163 14957 7171 14958 7163 14958 7168 14958 7164 14959 7163 14959 7171 14959 7172 14960 7173 14960 7167 14960 7174 14961 7167 14961 7173 14961 7175 14962 7172 14962 7167 14962 7176 14963 7175 14963 7167 14963 7177 14964 7176 14964 7167 14964 7166 14965 7177 14965 7167 14965 7178 14966 7167 14966 7174 14966 7179 14967 7167 14967 7178 14967 7168 14968 7167 14968 7179 14968 7180 14969 7181 14969 7173 14969 7182 14970 7173 14970 7181 14970 7183 14971 7180 14971 7173 14971 7184 14972 7183 14972 7173 14972 7185 14973 7184 14973 7173 14973 7172 14974 7185 14974 7173 14974 7186 14975 7173 14975 7182 14975 7174 14976 7173 14976 7186 14976 7187 14977 7188 14977 7181 14977 7189 14978 7181 14978 7188 14978 7190 14979 7187 14979 7181 14979 7191 14980 7190 14980 7181 14980 7192 14981 7191 14981 7181 14981 7193 14982 7192 14982 7181 14982 7194 14983 7193 14983 7181 14983 7195 14984 7194 14984 7181 14984 7196 14985 7195 14985 7181 14985 7180 14986 7196 14986 7181 14986 7197 14987 7181 14987 7189 14987 7198 14988 7181 14988 7197 14988 7182 14989 7181 14989 7198 14989 7199 14990 7188 14990 7187 14990 7200 14991 7188 14991 7199 14991 7201 14992 7188 14992 7200 14992 7189 14993 7188 14993 7201 14993 7199 14994 7187 14994 7190 14994 7202 14995 7190 14995 7191 14995 7202 14996 7199 14996 7190 14996 7203 14997 7191 14997 7192 14997 7203 14998 7202 14998 7191 14998 7203 14999 7192 14999 7193 14999 7204 15000 7193 15000 7194 15000 7203 15001 7193 15001 7204 15001 7204 15002 7194 15002 7195 15002 7204 15003 7195 15003 7196 15003 7205 15004 7196 15004 7180 15004 7205 15005 7204 15005 7196 15005 7205 15006 7180 15006 7183 15006 7205 15007 7183 15007 7184 15007 7205 15008 7184 15008 7185 15008 7206 15009 7185 15009 7172 15009 7206 15010 7205 15010 7185 15010 7206 15011 7172 15011 7175 15011 7206 15012 7175 15012 7176 15012 7206 15013 7176 15013 7177 15013 7207 15014 7177 15014 7166 15014 7207 15015 7206 15015 7177 15015 7207 15016 7166 15016 7169 15016 7207 15017 7169 15017 7170 15017 7208 15018 7170 15018 7162 15018 7208 15019 7207 15019 7170 15019 7208 15020 7162 15020 7165 15020 7208 15021 7165 15021 7157 15021 7209 15022 7157 15022 7160 15022 7209 15023 7208 15023 7157 15023 7209 15024 7160 15024 7153 15024 7210 15025 7153 15025 7150 15025 7210 15026 7209 15026 7153 15026 7210 15027 7150 15027 7147 15027 7211 15028 7147 15028 7144 15028 7211 15029 7210 15029 7147 15029 7212 15030 7144 15030 7139 15030 7212 15031 7211 15031 7144 15031 7213 15032 7139 15032 7134 15032 7213 15033 7212 15033 7139 15033 7213 15034 7134 15034 7128 15034 7214 15035 7128 15035 7120 15035 7214 15036 7213 15036 7128 15036 7215 15037 7120 15037 7112 15037 7215 15038 7214 15038 7120 15038 7094 15039 7112 15039 7093 15039 7094 15040 7215 15040 7112 15040 7216 15041 7217 15041 7218 15041 7219 15042 7218 15042 7217 15042 7220 15043 7216 15043 7218 15043 7221 15044 7220 15044 7218 15044 7222 15045 7221 15045 7218 15045 7219 15046 7222 15046 7218 15046 7216 15047 7223 15047 7217 15047 7224 15048 7217 15048 7223 15048 7225 15049 7219 15049 7217 15049 7224 15050 7225 15050 7217 15050 7216 15051 7226 15051 7223 15051 7227 15052 7223 15052 7226 15052 7227 15053 7224 15053 7223 15053 7216 15054 7228 15054 7226 15054 7227 15055 7226 15055 7228 15055 7229 15056 7228 15056 7216 15056 7230 15057 7227 15057 7228 15057 7231 15058 7230 15058 7228 15058 7229 15059 7231 15059 7228 15059 7232 15060 7216 15060 7220 15060 7232 15061 7229 15061 7216 15061 7221 15062 7233 15062 7220 15062 7232 15063 7220 15063 7233 15063 7234 15064 7235 15064 7233 15064 7236 15065 7233 15065 7235 15065 7221 15066 7234 15066 7233 15066 7236 15067 7232 15067 7233 15067 7237 15068 7238 15068 7235 15068 7239 15069 7235 15069 7238 15069 7234 15070 7237 15070 7235 15070 7239 15071 7236 15071 7235 15071 7240 15072 7241 15072 7238 15072 7242 15073 7238 15073 7241 15073 7243 15074 7240 15074 7238 15074 7237 15075 7243 15075 7238 15075 7242 15076 7239 15076 7238 15076 7244 15077 7245 15077 7241 15077 7246 15078 7241 15078 7245 15078 7240 15079 7244 15079 7241 15079 7246 15080 7242 15080 7241 15080 7247 15081 7248 15081 7245 15081 7249 15082 7245 15082 7248 15082 7244 15083 7247 15083 7245 15083 7249 15084 7246 15084 7245 15084 7250 15085 7251 15085 7248 15085 7252 15086 7248 15086 7251 15086 7247 15087 7250 15087 7248 15087 7252 15088 7249 15088 7248 15088 7253 15089 7254 15089 7251 15089 7255 15090 7251 15090 7254 15090 7256 15091 7253 15091 7251 15091 7250 15092 7256 15092 7251 15092 7255 15093 7252 15093 7251 15093 7257 15094 7258 15094 7254 15094 7259 15095 7254 15095 7258 15095 7253 15096 7257 15096 7254 15096 7259 15097 7255 15097 7254 15097 7260 15098 7261 15098 7258 15098 7262 15099 7258 15099 7261 15099 7257 15100 7260 15100 7258 15100 7262 15101 7259 15101 7258 15101 7260 15102 7263 15102 7261 15102 7264 15103 7261 15103 7263 15103 7264 15104 7262 15104 7261 15104 7265 15105 7266 15105 7263 15105 7264 15106 7263 15106 7266 15106 7260 15107 7265 15107 7263 15107 7267 15108 7268 15108 7266 15108 7269 15109 7266 15109 7268 15109 7270 15110 7267 15110 7266 15110 7265 15111 7270 15111 7266 15111 7269 15112 7264 15112 7266 15112 7271 15113 7272 15113 7268 15113 7273 15114 7268 15114 7272 15114 7267 15115 7271 15115 7268 15115 7274 15116 7269 15116 7268 15116 7275 15117 7274 15117 7268 15117 7273 15118 7275 15118 7268 15118 7276 15119 7277 15119 7272 15119 7278 15120 7272 15120 7277 15120 7271 15121 7276 15121 7272 15121 7279 15122 7273 15122 7272 15122 7278 15123 7279 15123 7272 15123 7280 15124 7281 15124 7277 15124 7282 15125 7277 15125 7281 15125 7276 15126 7280 15126 7277 15126 7283 15127 7278 15127 7277 15127 7282 15128 7283 15128 7277 15128 7284 15129 7285 15129 7281 15129 7286 15130 7281 15130 7285 15130 7280 15131 7284 15131 7281 15131 7286 15132 7282 15132 7281 15132 7287 15133 7288 15133 7285 15133 7289 15134 7285 15134 7288 15134 7284 15135 7287 15135 7285 15135 7290 15136 7286 15136 7285 15136 7289 15137 7290 15137 7285 15137 7287 15138 7291 15138 7288 15138 7292 15139 7288 15139 7291 15139 7292 15140 7289 15140 7288 15140 7287 15141 7293 15141 7291 15141 7292 15142 7291 15142 7293 15142 7294 15143 7295 15143 7293 15143 7296 15144 7293 15144 7295 15144 7287 15145 7294 15145 7293 15145 7296 15146 7292 15146 7293 15146 7294 15147 7297 15147 7295 15147 7298 15148 7295 15148 7297 15148 7298 15149 7296 15149 7295 15149 7294 15150 7299 15150 7297 15150 7298 15151 7297 15151 7299 15151 7300 15152 7301 15152 7299 15152 7302 15153 7299 15153 7301 15153 7294 15154 7300 15154 7299 15154 7302 15155 7298 15155 7299 15155 7300 15156 7303 15156 7301 15156 7302 15157 7301 15157 7303 15157 7300 15158 7304 15158 7303 15158 7305 15159 7303 15159 7304 15159 7305 15160 7302 15160 7303 15160 7300 15161 7306 15161 7304 15161 7307 15162 7304 15162 7306 15162 7307 15163 7305 15163 7304 15163 7308 15164 7309 15164 7306 15164 7310 15165 7306 15165 7309 15165 7300 15166 7308 15166 7306 15166 7310 15167 7307 15167 7306 15167 7308 15168 7311 15168 7309 15168 7310 15169 7309 15169 7311 15169 7308 15170 7312 15170 7311 15170 7313 15171 7311 15171 7312 15171 7313 15172 7310 15172 7311 15172 7314 15173 7315 15173 7312 15173 7313 15174 7312 15174 7315 15174 7308 15175 7314 15175 7312 15175 7314 15176 7316 15176 7315 15176 7317 15177 7315 15177 7316 15177 7317 15178 7313 15178 7315 15178 7314 15179 7318 15179 7316 15179 7319 15180 7316 15180 7318 15180 7319 15181 7317 15181 7316 15181 6616 15182 7320 15182 7318 15182 7321 15183 7318 15183 7320 15183 7314 15184 6616 15184 7318 15184 7321 15185 7319 15185 7318 15185 6616 15186 6596 15186 7320 15186 7321 15187 7320 15187 6596 15187 7321 15188 6596 15188 6598 15188 7322 15189 6616 15189 7314 15189 7323 15190 7095 15190 6616 15190 7324 15191 7323 15191 6616 15191 7325 15192 7324 15192 6616 15192 7326 15193 7325 15193 6616 15193 7322 15194 7326 15194 6616 15194 7326 15195 7314 15195 7308 15195 7322 15196 7314 15196 7326 15196 7327 15197 7308 15197 7300 15197 7327 15198 7326 15198 7308 15198 7328 15199 7300 15199 7294 15199 7328 15200 7327 15200 7300 15200 7329 15201 7294 15201 7287 15201 7329 15202 7328 15202 7294 15202 7330 15203 7287 15203 7284 15203 7330 15204 7329 15204 7287 15204 7331 15205 7284 15205 7280 15205 7331 15206 7330 15206 7284 15206 7332 15207 7280 15207 7276 15207 7332 15208 7331 15208 7280 15208 7332 15209 7276 15209 7271 15209 7333 15210 7271 15210 7267 15210 7333 15211 7332 15211 7271 15211 7333 15212 7267 15212 7270 15212 7334 15213 7270 15213 7265 15213 7334 15214 7333 15214 7270 15214 7334 15215 7265 15215 7260 15215 7335 15216 7260 15216 7257 15216 7335 15217 7334 15217 7260 15217 7335 15218 7257 15218 7253 15218 7336 15219 7253 15219 7256 15219 7336 15220 7335 15220 7253 15220 7336 15221 7256 15221 7250 15221 7336 15222 7250 15222 7247 15222 7336 15223 7247 15223 7244 15223 7337 15224 7244 15224 7240 15224 7337 15225 7336 15225 7244 15225 7337 15226 7240 15226 7243 15226 7337 15227 7243 15227 7237 15227 7222 15228 7237 15228 7234 15228 7222 15229 7337 15229 7237 15229 7222 15230 7234 15230 7221 15230 6600 15231 6599 15231 6602 15231 6605 15232 6602 15232 6601 15232 7338 15233 6602 15233 6605 15233 6600 15234 6602 15234 7338 15234 6605 15235 6601 15235 6604 15235 7339 15236 7338 15236 6605 15236 7340 15237 7339 15237 6605 15237 7340 15238 6605 15238 6603 15238 7341 15239 7338 15239 7339 15239 6600 15240 7338 15240 7341 15240 7342 15241 7343 15241 7344 15241 7345 15242 7344 15242 7343 15242 7346 15243 7342 15243 7344 15243 7347 15244 7346 15244 7344 15244 7345 15245 7347 15245 7344 15245 7342 15246 7348 15246 7343 15246 7349 15247 7343 15247 7348 15247 7349 15248 7345 15248 7343 15248 7350 15249 7351 15249 7348 15249 7349 15250 7348 15250 7351 15250 7342 15251 7350 15251 7348 15251 7352 15252 7353 15252 7351 15252 7354 15253 7351 15253 7353 15253 7350 15254 7352 15254 7351 15254 7354 15255 7349 15255 7351 15255 7355 15256 7356 15256 7353 15256 7354 15257 7353 15257 7356 15257 7352 15258 7355 15258 7353 15258 7357 15259 7358 15259 7356 15259 7359 15260 7356 15260 7358 15260 7355 15261 7357 15261 7356 15261 7359 15262 7354 15262 7356 15262 7360 15263 7361 15263 7358 15263 7362 15264 7358 15264 7361 15264 7357 15265 7360 15265 7358 15265 7362 15266 7359 15266 7358 15266 7363 15267 7364 15267 7361 15267 7365 15268 7361 15268 7364 15268 7360 15269 7363 15269 7361 15269 7365 15270 7362 15270 7361 15270 7366 15271 7367 15271 7364 15271 7365 15272 7364 15272 7367 15272 7363 15273 7366 15273 7364 15273 7368 15274 7369 15274 7367 15274 7370 15275 7367 15275 7369 15275 7366 15276 7368 15276 7367 15276 7370 15277 7365 15277 7367 15277 7371 15278 7372 15278 7369 15278 7370 15279 7369 15279 7372 15279 7368 15280 7371 15280 7369 15280 7373 15281 7374 15281 7372 15281 7375 15282 7372 15282 7374 15282 7371 15283 7373 15283 7372 15283 7375 15284 7370 15284 7372 15284 7376 15285 7377 15285 7374 15285 7378 15286 7374 15286 7377 15286 7373 15287 7376 15287 7374 15287 7378 15288 7375 15288 7374 15288 7379 15289 7380 15289 7377 15289 7378 15290 7377 15290 7380 15290 7376 15291 7379 15291 7377 15291 7381 15292 7382 15292 7380 15292 7383 15293 7380 15293 7382 15293 7379 15294 7381 15294 7380 15294 7383 15295 7378 15295 7380 15295 7384 15296 7385 15296 7382 15296 7383 15297 7382 15297 7385 15297 7381 15298 7384 15298 7382 15298 7386 15299 7387 15299 7385 15299 7388 15300 7385 15300 7387 15300 7384 15301 7386 15301 7385 15301 7388 15302 7383 15302 7385 15302 7389 15303 7390 15303 7387 15303 7391 15304 7387 15304 7390 15304 7386 15305 7389 15305 7387 15305 7391 15306 7388 15306 7387 15306 7392 15307 7393 15307 7390 15307 7391 15308 7390 15308 7393 15308 7389 15309 7392 15309 7390 15309 7394 15310 7395 15310 7393 15310 7396 15311 7393 15311 7395 15311 7392 15312 7394 15312 7393 15312 7396 15313 7391 15313 7393 15313 7397 15314 7398 15314 7395 15314 7399 15315 7395 15315 7398 15315 7394 15316 7397 15316 7395 15316 7399 15317 7396 15317 7395 15317 7400 15318 7401 15318 7398 15318 7399 15319 7398 15319 7401 15319 7397 15320 7400 15320 7398 15320 7402 15321 7403 15321 7401 15321 7404 15322 7401 15322 7403 15322 7400 15323 7402 15323 7401 15323 7404 15324 7399 15324 7401 15324 7405 15325 7406 15325 7403 15325 7404 15326 7403 15326 7406 15326 7402 15327 7405 15327 7403 15327 7405 15328 7407 15328 7406 15328 7408 15329 7406 15329 7407 15329 7408 15330 7404 15330 7406 15330 7409 15331 7410 15331 7407 15331 7408 15332 7407 15332 7410 15332 7405 15333 7409 15333 7407 15333 7411 15334 7412 15334 7410 15334 7413 15335 7410 15335 7412 15335 7414 15336 7411 15336 7410 15336 7409 15337 7414 15337 7410 15337 7413 15338 7408 15338 7410 15338 7415 15339 7416 15339 7412 15339 7417 15340 7412 15340 7416 15340 7418 15341 7415 15341 7412 15341 7411 15342 7418 15342 7412 15342 7419 15343 7413 15343 7412 15343 7417 15344 7419 15344 7412 15344 7420 15345 7421 15345 7416 15345 7422 15346 7416 15346 7421 15346 7415 15347 7420 15347 7416 15347 7422 15348 7417 15348 7416 15348 7423 15349 7424 15349 7421 15349 7425 15350 7421 15350 7424 15350 7420 15351 7423 15351 7421 15351 7426 15352 7422 15352 7421 15352 7425 15353 7426 15353 7421 15353 7427 15354 7428 15354 7424 15354 7429 15355 7424 15355 7428 15355 7423 15356 7427 15356 7424 15356 7429 15357 7425 15357 7424 15357 7430 15358 7431 15358 7428 15358 7432 15359 7428 15359 7431 15359 7427 15360 7430 15360 7428 15360 7432 15361 7429 15361 7428 15361 7433 15362 7434 15362 7431 15362 7435 15363 7431 15363 7434 15363 7430 15364 7433 15364 7431 15364 7435 15365 7432 15365 7431 15365 7436 15366 7437 15366 7434 15366 7435 15367 7434 15367 7437 15367 7433 15368 7436 15368 7434 15368 7438 15369 7439 15369 7437 15369 7440 15370 7437 15370 7439 15370 7436 15371 7438 15371 7437 15371 7440 15372 7435 15372 7437 15372 7441 15373 7442 15373 7439 15373 7443 15374 7439 15374 7442 15374 7444 15375 7441 15375 7439 15375 7438 15376 7444 15376 7439 15376 7443 15377 7440 15377 7439 15377 7445 15378 7446 15378 7442 15378 7443 15379 7442 15379 7446 15379 7441 15380 7445 15380 7442 15380 7447 15381 7448 15381 7446 15381 7449 15382 7446 15382 7448 15382 7445 15383 7447 15383 7446 15383 7449 15384 7443 15384 7446 15384 7450 15385 7451 15385 7448 15385 7449 15386 7448 15386 7451 15386 7447 15387 7450 15387 7448 15387 7452 15388 7453 15388 7451 15388 7454 15389 7451 15389 7453 15389 7450 15390 7452 15390 7451 15390 7454 15391 7449 15391 7451 15391 7452 15392 7455 15392 7453 15392 7454 15393 7453 15393 7455 15393 7456 15394 7457 15394 7455 15394 7458 15395 7455 15395 7457 15395 7452 15396 7456 15396 7455 15396 7458 15397 7454 15397 7455 15397 7456 15398 7459 15398 7457 15398 7458 15399 7457 15399 7459 15399 7460 15400 7461 15400 7459 15400 7462 15401 7459 15401 7461 15401 7456 15402 7460 15402 7459 15402 7462 15403 7458 15403 7459 15403 7463 15404 7464 15404 7461 15404 7462 15405 7461 15405 7464 15405 7460 15406 7463 15406 7461 15406 7465 15407 7466 15407 7464 15407 7467 15408 7464 15408 7466 15408 7463 15409 7465 15409 7464 15409 7467 15410 7462 15410 7464 15410 7468 15411 7469 15411 7466 15411 7467 15412 7466 15412 7469 15412 7465 15413 7468 15413 7466 15413 7470 15414 7471 15414 7469 15414 7472 15415 7469 15415 7471 15415 7468 15416 7470 15416 7469 15416 7472 15417 7467 15417 7469 15417 7341 15418 7339 15418 7471 15418 7340 15419 7471 15419 7339 15419 7470 15420 7341 15420 7471 15420 7340 15421 7472 15421 7471 15421 7473 15422 7341 15422 7470 15422 7473 15423 6600 15423 7341 15423 7474 15424 7470 15424 7468 15424 7474 15425 7473 15425 7470 15425 7474 15426 7468 15426 7465 15426 7475 15427 7465 15427 7463 15427 7475 15428 7474 15428 7465 15428 7475 15429 7463 15429 7460 15429 7476 15430 7460 15430 7456 15430 7476 15431 7475 15431 7460 15431 7477 15432 7456 15432 7452 15432 7477 15433 7476 15433 7456 15433 7478 15434 7452 15434 7450 15434 7478 15435 7477 15435 7452 15435 7478 15436 7450 15436 7447 15436 7479 15437 7447 15437 7445 15437 7479 15438 7478 15438 7447 15438 7479 15439 7445 15439 7441 15439 7480 15440 7441 15440 7444 15440 7480 15441 7479 15441 7441 15441 7480 15442 7444 15442 7438 15442 7481 15443 7438 15443 7436 15443 7481 15444 7480 15444 7438 15444 7482 15445 7436 15445 7433 15445 7482 15446 7481 15446 7436 15446 7483 15447 7433 15447 7430 15447 7483 15448 7482 15448 7433 15448 7484 15449 7430 15449 7427 15449 7484 15450 7483 15450 7430 15450 7485 15451 7427 15451 7423 15451 7485 15452 7484 15452 7427 15452 7486 15453 7423 15453 7420 15453 7486 15454 7485 15454 7423 15454 7487 15455 7420 15455 7415 15455 7487 15456 7486 15456 7420 15456 7488 15457 7415 15457 7418 15457 7488 15458 7487 15458 7415 15458 7489 15459 7418 15459 7411 15459 7489 15460 7488 15460 7418 15460 7489 15461 7411 15461 7414 15461 7490 15462 7414 15462 7409 15462 7490 15463 7489 15463 7414 15463 7491 15464 7409 15464 7405 15464 7491 15465 7490 15465 7409 15465 7491 15466 7405 15466 7402 15466 7492 15467 7402 15467 7400 15467 7492 15468 7491 15468 7402 15468 7493 15469 7400 15469 7397 15469 7493 15470 7492 15470 7400 15470 7493 15471 7397 15471 7394 15471 7494 15472 7394 15472 7392 15472 7494 15473 7493 15473 7394 15473 7495 15474 7392 15474 7389 15474 7495 15475 7494 15475 7392 15475 7495 15476 7389 15476 7386 15476 7496 15477 7386 15477 7384 15477 7496 15478 7495 15478 7386 15478 7497 15479 7384 15479 7381 15479 7497 15480 7496 15480 7384 15480 7497 15481 7381 15481 7379 15481 7498 15482 7379 15482 7376 15482 7498 15483 7497 15483 7379 15483 7498 15484 7376 15484 7373 15484 7499 15485 7373 15485 7371 15485 7499 15486 7498 15486 7373 15486 7500 15487 7371 15487 7368 15487 7500 15488 7499 15488 7371 15488 7500 15489 7368 15489 7366 15489 7501 15490 7366 15490 7363 15490 7501 15491 7500 15491 7366 15491 7502 15492 7363 15492 7360 15492 7502 15493 7501 15493 7363 15493 7502 15494 7360 15494 7357 15494 7503 15495 7357 15495 7355 15495 7503 15496 7502 15496 7357 15496 7504 15497 7355 15497 7352 15497 7504 15498 7503 15498 7355 15498 7504 15499 7352 15499 7350 15499 7505 15500 7350 15500 7342 15500 7505 15501 7504 15501 7350 15501 7506 15502 7342 15502 7346 15502 7505 15503 7342 15503 7506 15503 7507 15504 7346 15504 7347 15504 7230 15505 7346 15505 7507 15505 7506 15506 7346 15506 7230 15506 7508 15507 7507 15507 7347 15507 7202 15508 7508 15508 7347 15508 7202 15509 7347 15509 7199 15509 7509 15510 7199 15510 7347 15510 7510 15511 7509 15511 7347 15511 7345 15512 7510 15512 7347 15512 7511 15513 7507 15513 7508 15513 7230 15514 7507 15514 7511 15514 7512 15515 7513 15515 7514 15515 7515 15516 7514 15516 7513 15516 7516 15517 7512 15517 7514 15517 7517 15518 7516 15518 7514 15518 7518 15519 7517 15519 7514 15519 7518 15520 7514 15520 7515 15520 7511 15521 7508 15521 7513 15521 7203 15522 7513 15522 7508 15522 7512 15523 7511 15523 7513 15523 7515 15524 7513 15524 7519 15524 7203 15525 7519 15525 7513 15525 7203 15526 7508 15526 7202 15526 7227 15527 7511 15527 7512 15527 7230 15528 7511 15528 7227 15528 7224 15529 7512 15529 7516 15529 7227 15530 7512 15530 7224 15530 7520 15531 7516 15531 7517 15531 7521 15532 7516 15532 7520 15532 7224 15533 7516 15533 7521 15533 7522 15534 7523 15534 7097 15534 7098 15535 7097 15535 7523 15535 7096 15536 7522 15536 7097 15536 7522 15537 7524 15537 7523 15537 7525 15538 7523 15538 7524 15538 7098 15539 7523 15539 7106 15539 7525 15540 7106 15540 7523 15540 7526 15541 7527 15541 7524 15541 7525 15542 7524 15542 7527 15542 7522 15543 7526 15543 7524 15543 7528 15544 7529 15544 7527 15544 7530 15545 7527 15545 7529 15545 7526 15546 7528 15546 7527 15546 7525 15547 7527 15547 7530 15547 7531 15548 7532 15548 7529 15548 7533 15549 7529 15549 7532 15549 7528 15550 7531 15550 7529 15550 7530 15551 7529 15551 7533 15551 7534 15552 7535 15552 7532 15552 7536 15553 7532 15553 7535 15553 7531 15554 7534 15554 7532 15554 7533 15555 7532 15555 7536 15555 7537 15556 7538 15556 7535 15556 7536 15557 7535 15557 7538 15557 7534 15558 7537 15558 7535 15558 7539 15559 7540 15559 7538 15559 7541 15560 7538 15560 7540 15560 7537 15561 7539 15561 7538 15561 7536 15562 7538 15562 7541 15562 7539 15563 7542 15563 7540 15563 7543 15564 7540 15564 7542 15564 7541 15565 7540 15565 7543 15565 7544 15566 7545 15566 7542 15566 7543 15567 7542 15567 7545 15567 7539 15568 7544 15568 7542 15568 7546 15569 7547 15569 7545 15569 7548 15570 7545 15570 7547 15570 7544 15571 7546 15571 7545 15571 7543 15572 7545 15572 7548 15572 7549 15573 7550 15573 7547 15573 7548 15574 7547 15574 7550 15574 7546 15575 7549 15575 7547 15575 7551 15576 7552 15576 7550 15576 7553 15577 7550 15577 7552 15577 7549 15578 7551 15578 7550 15578 7548 15579 7550 15579 7553 15579 7554 15580 7555 15580 7552 15580 7553 15581 7552 15581 7555 15581 7551 15582 7554 15582 7552 15582 7554 15583 7556 15583 7555 15583 7553 15584 7555 15584 7556 15584 7557 15585 7558 15585 7556 15585 7559 15586 7556 15586 7558 15586 7554 15587 7557 15587 7556 15587 7553 15588 7556 15588 7559 15588 7560 15589 7561 15589 7558 15589 7559 15590 7558 15590 7561 15590 7557 15591 7560 15591 7558 15591 7562 15592 7563 15592 7561 15592 7559 15593 7561 15593 7563 15593 7560 15594 7562 15594 7561 15594 7564 15595 7565 15595 7563 15595 7566 15596 7563 15596 7565 15596 7562 15597 7564 15597 7563 15597 7559 15598 7563 15598 7566 15598 7567 15599 7568 15599 7565 15599 7566 15600 7565 15600 7568 15600 7564 15601 7567 15601 7565 15601 7567 15602 7569 15602 7568 15602 7566 15603 7568 15603 7569 15603 7570 15604 7571 15604 7569 15604 7566 15605 7569 15605 7571 15605 7567 15606 7570 15606 7569 15606 7572 15607 7573 15607 7571 15607 7574 15608 7571 15608 7573 15608 7570 15609 7572 15609 7571 15609 7566 15610 7571 15610 7574 15610 7575 15611 7576 15611 7573 15611 7574 15612 7573 15612 7576 15612 7572 15613 7575 15613 7573 15613 7577 15614 7578 15614 7576 15614 7574 15615 7576 15615 7578 15615 7575 15616 7577 15616 7576 15616 7579 15617 7580 15617 7578 15617 7574 15618 7578 15618 7580 15618 7577 15619 7579 15619 7578 15619 7579 15620 7581 15620 7580 15620 7518 15621 7580 15621 7581 15621 7574 15622 7580 15622 7518 15622 7582 15623 7583 15623 7581 15623 7518 15624 7581 15624 7583 15624 7579 15625 7582 15625 7581 15625 7520 15626 7517 15626 7583 15626 7518 15627 7583 15627 7517 15627 7582 15628 7520 15628 7583 15628 7521 15629 7520 15629 7582 15629 7584 15630 7582 15630 7579 15630 7584 15631 7521 15631 7582 15631 7584 15632 7579 15632 7577 15632 7584 15633 7577 15633 7575 15633 7584 15634 7575 15634 7572 15634 7585 15635 7572 15635 7570 15635 7585 15636 7584 15636 7572 15636 7585 15637 7570 15637 7567 15637 7585 15638 7567 15638 7564 15638 7586 15639 7564 15639 7562 15639 7586 15640 7585 15640 7564 15640 7586 15641 7562 15641 7560 15641 7586 15642 7560 15642 7557 15642 7587 15643 7557 15643 7554 15643 7587 15644 7586 15644 7557 15644 7587 15645 7554 15645 7551 15645 7588 15646 7551 15646 7549 15646 7588 15647 7587 15647 7551 15647 7589 15648 7549 15648 7546 15648 7589 15649 7588 15649 7549 15649 7589 15650 7546 15650 7544 15650 7590 15651 7544 15651 7539 15651 7590 15652 7589 15652 7544 15652 7591 15653 7539 15653 7537 15653 7591 15654 7590 15654 7539 15654 7592 15655 7537 15655 7534 15655 7592 15656 7591 15656 7537 15656 7593 15657 7534 15657 7531 15657 7593 15658 7592 15658 7534 15658 7593 15659 7531 15659 7528 15659 7594 15660 7528 15660 7526 15660 7594 15661 7593 15661 7528 15661 7595 15662 7526 15662 7522 15662 7595 15663 7594 15663 7526 15663 7100 15664 7522 15664 7096 15664 7595 15665 7522 15665 7100 15665 7100 15666 7096 15666 7099 15666 7323 15667 7100 15667 7095 15667 7595 15668 7100 15668 7323 15668 7325 15669 7323 15669 7324 15669 7326 15670 7323 15670 7325 15670 7596 15671 7323 15671 7326 15671 7596 15672 7595 15672 7323 15672 7596 15673 7326 15673 7327 15673 7094 15674 7088 15674 7101 15674 7597 15675 7101 15675 7102 15675 7597 15676 7094 15676 7101 15676 7597 15677 7102 15677 7103 15677 7597 15678 7103 15678 7104 15678 7525 15679 7104 15679 7105 15679 7525 15680 7597 15680 7104 15680 7525 15681 7105 15681 7106 15681 7519 15682 7204 15682 7205 15682 7203 15683 7204 15683 7519 15683 7598 15684 7205 15684 7206 15684 7598 15685 7519 15685 7205 15685 7599 15686 7206 15686 7207 15686 7599 15687 7598 15687 7206 15687 7600 15688 7207 15688 7208 15688 7600 15689 7599 15689 7207 15689 7601 15690 7208 15690 7209 15690 7601 15691 7600 15691 7208 15691 7602 15692 7209 15692 7210 15692 7602 15693 7601 15693 7209 15693 7603 15694 7210 15694 7211 15694 7603 15695 7602 15695 7210 15695 7604 15696 7211 15696 7212 15696 7604 15697 7603 15697 7211 15697 7605 15698 7212 15698 7213 15698 7605 15699 7604 15699 7212 15699 7606 15700 7213 15700 7214 15700 7606 15701 7605 15701 7213 15701 7607 15702 7214 15702 7215 15702 7607 15703 7606 15703 7214 15703 7608 15704 7215 15704 7094 15704 7608 15705 7607 15705 7215 15705 7597 15706 7608 15706 7094 15706 7515 15707 7519 15707 7598 15707 7518 15708 7598 15708 7599 15708 7518 15709 7515 15709 7598 15709 7574 15710 7599 15710 7600 15710 7574 15711 7518 15711 7599 15711 7566 15712 7600 15712 7601 15712 7566 15713 7574 15713 7600 15713 7559 15714 7601 15714 7602 15714 7559 15715 7566 15715 7601 15715 7553 15716 7602 15716 7603 15716 7553 15717 7559 15717 7602 15717 7548 15718 7603 15718 7604 15718 7548 15719 7553 15719 7603 15719 7543 15720 7604 15720 7605 15720 7543 15721 7548 15721 7604 15721 7541 15722 7605 15722 7606 15722 7541 15723 7543 15723 7605 15723 7536 15724 7606 15724 7607 15724 7536 15725 7541 15725 7606 15725 7533 15726 7607 15726 7608 15726 7533 15727 7536 15727 7607 15727 7530 15728 7608 15728 7597 15728 7530 15729 7533 15729 7608 15729 7525 15730 7530 15730 7597 15730 7609 15731 7200 15731 7199 15731 7509 15732 7609 15732 7199 15732 7610 15733 7200 15733 7609 15733 7201 15734 7200 15734 7610 15734 7610 15735 7609 15735 7509 15735 7349 15736 7509 15736 7510 15736 7610 15737 7509 15737 7349 15737 7349 15738 7510 15738 7345 15738 7611 15739 6603 15739 6607 15739 7611 15740 7340 15740 6603 15740 7107 15741 6607 15741 6606 15741 7107 15742 7611 15742 6607 15742 7610 15743 7349 15743 7354 15743 7612 15744 7354 15744 7359 15744 7612 15745 7610 15745 7354 15745 7613 15746 7359 15746 7362 15746 7613 15747 7612 15747 7359 15747 7614 15748 7362 15748 7365 15748 7614 15749 7613 15749 7362 15749 7615 15750 7365 15750 7370 15750 7615 15751 7614 15751 7365 15751 7616 15752 7370 15752 7375 15752 7616 15753 7615 15753 7370 15753 7617 15754 7375 15754 7378 15754 7617 15755 7616 15755 7375 15755 7618 15756 7378 15756 7383 15756 7618 15757 7617 15757 7378 15757 7619 15758 7383 15758 7388 15758 7619 15759 7618 15759 7383 15759 7620 15760 7388 15760 7391 15760 7620 15761 7619 15761 7388 15761 7621 15762 7391 15762 7396 15762 7621 15763 7620 15763 7391 15763 7622 15764 7396 15764 7399 15764 7622 15765 7621 15765 7396 15765 7623 15766 7399 15766 7404 15766 7623 15767 7622 15767 7399 15767 7624 15768 7404 15768 7408 15768 7624 15769 7623 15769 7404 15769 7625 15770 7408 15770 7413 15770 7625 15771 7624 15771 7408 15771 7626 15772 7413 15772 7419 15772 7626 15773 7625 15773 7413 15773 7627 15774 7419 15774 7417 15774 7627 15775 7626 15775 7419 15775 7628 15776 7417 15776 7422 15776 7628 15777 7627 15777 7417 15777 7629 15778 7422 15778 7426 15778 7629 15779 7628 15779 7422 15779 7630 15780 7426 15780 7425 15780 7630 15781 7629 15781 7426 15781 7631 15782 7425 15782 7429 15782 7631 15783 7630 15783 7425 15783 7632 15784 7429 15784 7432 15784 7632 15785 7631 15785 7429 15785 7633 15786 7432 15786 7435 15786 7633 15787 7632 15787 7432 15787 7634 15788 7435 15788 7440 15788 7634 15789 7633 15789 7435 15789 7635 15790 7440 15790 7443 15790 7635 15791 7634 15791 7440 15791 7636 15792 7443 15792 7449 15792 7636 15793 7635 15793 7443 15793 7637 15794 7449 15794 7454 15794 7637 15795 7636 15795 7449 15795 7638 15796 7454 15796 7458 15796 7638 15797 7637 15797 7454 15797 7639 15798 7458 15798 7462 15798 7639 15799 7638 15799 7458 15799 7640 15800 7462 15800 7467 15800 7640 15801 7639 15801 7462 15801 7641 15802 7467 15802 7472 15802 7641 15803 7640 15803 7467 15803 7642 15804 7472 15804 7340 15804 7642 15805 7641 15805 7472 15805 7611 15806 7642 15806 7340 15806 7201 15807 7610 15807 7612 15807 7189 15808 7612 15808 7613 15808 7189 15809 7201 15809 7612 15809 7197 15810 7613 15810 7614 15810 7197 15811 7189 15811 7613 15811 7198 15812 7614 15812 7615 15812 7198 15813 7197 15813 7614 15813 7182 15814 7615 15814 7616 15814 7182 15815 7198 15815 7615 15815 7186 15816 7616 15816 7617 15816 7186 15817 7182 15817 7616 15817 7174 15818 7617 15818 7618 15818 7174 15819 7186 15819 7617 15819 7178 15820 7618 15820 7619 15820 7178 15821 7174 15821 7618 15821 7179 15822 7619 15822 7620 15822 7179 15823 7178 15823 7619 15823 7168 15824 7620 15824 7621 15824 7168 15825 7179 15825 7620 15825 7171 15826 7621 15826 7622 15826 7171 15827 7168 15827 7621 15827 7164 15828 7622 15828 7623 15828 7164 15829 7171 15829 7622 15829 7159 15830 7623 15830 7624 15830 7159 15831 7164 15831 7623 15831 7161 15832 7624 15832 7625 15832 7161 15833 7159 15833 7624 15833 7155 15834 7625 15834 7626 15834 7155 15835 7161 15835 7625 15835 7156 15836 7626 15836 7627 15836 7156 15837 7155 15837 7626 15837 7152 15838 7627 15838 7628 15838 7152 15839 7156 15839 7627 15839 7149 15840 7628 15840 7629 15840 7149 15841 7152 15841 7628 15841 7146 15842 7629 15842 7630 15842 7146 15843 7149 15843 7629 15843 7143 15844 7630 15844 7631 15844 7143 15845 7146 15845 7630 15845 7141 15846 7631 15846 7632 15846 7141 15847 7143 15847 7631 15847 7138 15848 7632 15848 7633 15848 7138 15849 7141 15849 7632 15849 7136 15850 7633 15850 7634 15850 7136 15851 7138 15851 7633 15851 7133 15852 7634 15852 7635 15852 7133 15853 7136 15853 7634 15853 7131 15854 7635 15854 7636 15854 7131 15855 7133 15855 7635 15855 7127 15856 7636 15856 7637 15856 7127 15857 7131 15857 7636 15857 7125 15858 7637 15858 7638 15858 7125 15859 7127 15859 7637 15859 7122 15860 7638 15860 7639 15860 7122 15861 7125 15861 7638 15861 7117 15862 7639 15862 7640 15862 7117 15863 7122 15863 7639 15863 7114 15864 7640 15864 7641 15864 7114 15865 7117 15865 7640 15865 7110 15866 7641 15866 7642 15866 7110 15867 7114 15867 7641 15867 7108 15868 7642 15868 7611 15868 7108 15869 7110 15869 7642 15869 7107 15870 7108 15870 7611 15870 7225 15871 7521 15871 7584 15871 7224 15872 7521 15872 7225 15872 7643 15873 7584 15873 7585 15873 7644 15874 7225 15874 7584 15874 7644 15875 7584 15875 7643 15875 7645 15876 7585 15876 7586 15876 7643 15877 7585 15877 7645 15877 7646 15878 7586 15878 7587 15878 7645 15879 7586 15879 7646 15879 7647 15880 7587 15880 7588 15880 7646 15881 7587 15881 7647 15881 7648 15882 7588 15882 7589 15882 7647 15883 7588 15883 7648 15883 7649 15884 7589 15884 7590 15884 7648 15885 7589 15885 7649 15885 7650 15886 7590 15886 7591 15886 7649 15887 7590 15887 7650 15887 7651 15888 7591 15888 7592 15888 7650 15889 7591 15889 7651 15889 7652 15890 7592 15890 7593 15890 7651 15891 7592 15891 7652 15891 7653 15892 7593 15892 7594 15892 7652 15893 7593 15893 7653 15893 7596 15894 7594 15894 7595 15894 7653 15895 7594 15895 7596 15895 7653 15896 7327 15896 7328 15896 7653 15897 7596 15897 7327 15897 7652 15898 7328 15898 7329 15898 7652 15899 7653 15899 7328 15899 7651 15900 7329 15900 7330 15900 7651 15901 7652 15901 7329 15901 7650 15902 7330 15902 7331 15902 7650 15903 7651 15903 7330 15903 7649 15904 7331 15904 7332 15904 7649 15905 7650 15905 7331 15905 7648 15906 7332 15906 7333 15906 7648 15907 7649 15907 7332 15907 7647 15908 7333 15908 7334 15908 7647 15909 7648 15909 7333 15909 7646 15910 7334 15910 7335 15910 7646 15911 7647 15911 7334 15911 7645 15912 7335 15912 7336 15912 7645 15913 7646 15913 7335 15913 7643 15914 7336 15914 7337 15914 7643 15915 7645 15915 7336 15915 7644 15916 7337 15916 7222 15916 7644 15917 7643 15917 7337 15917 7644 15918 7222 15918 7219 15918 7644 15919 7219 15919 7225 15919 7654 15920 7506 15920 7230 15920 7655 15921 7654 15921 7230 15921 7231 15922 7655 15922 7230 15922 7655 15923 7506 15923 7654 15923 7505 15924 7506 15924 7655 15924 7229 15925 7655 15925 7231 15925 7656 15926 7655 15926 7229 15926 7656 15927 7505 15927 7655 15927 7656 15928 7229 15928 7232 15928 7657 15929 6598 15929 6597 15929 7657 15930 7321 15930 6598 15930 7473 15931 6597 15931 6600 15931 7657 15932 6597 15932 7473 15932 7658 15933 7232 15933 7236 15933 7656 15934 7232 15934 7658 15934 7659 15935 7236 15935 7239 15935 7658 15936 7236 15936 7659 15936 7660 15937 7239 15937 7242 15937 7659 15938 7239 15938 7660 15938 7661 15939 7242 15939 7246 15939 7660 15940 7242 15940 7661 15940 7662 15941 7246 15941 7249 15941 7661 15942 7246 15942 7662 15942 7663 15943 7249 15943 7252 15943 7662 15944 7249 15944 7663 15944 7664 15945 7252 15945 7255 15945 7663 15946 7252 15946 7664 15946 7665 15947 7255 15947 7259 15947 7664 15948 7255 15948 7665 15948 7666 15949 7259 15949 7262 15949 7665 15950 7259 15950 7666 15950 7667 15951 7262 15951 7264 15951 7666 15952 7262 15952 7667 15952 7668 15953 7264 15953 7269 15953 7667 15954 7264 15954 7668 15954 7669 15955 7269 15955 7274 15955 7668 15956 7269 15956 7669 15956 7670 15957 7274 15957 7275 15957 7669 15958 7274 15958 7670 15958 7671 15959 7275 15959 7273 15959 7670 15960 7275 15960 7671 15960 7672 15961 7273 15961 7279 15961 7671 15962 7273 15962 7672 15962 7673 15963 7279 15963 7278 15963 7672 15964 7279 15964 7673 15964 7674 15965 7278 15965 7283 15965 7673 15966 7278 15966 7674 15966 7675 15967 7283 15967 7282 15967 7674 15968 7283 15968 7675 15968 7676 15969 7282 15969 7286 15969 7675 15970 7282 15970 7676 15970 7677 15971 7286 15971 7290 15971 7676 15972 7286 15972 7677 15972 7678 15973 7290 15973 7289 15973 7677 15974 7290 15974 7678 15974 7679 15975 7289 15975 7292 15975 7678 15976 7289 15976 7679 15976 7680 15977 7292 15977 7296 15977 7679 15978 7292 15978 7680 15978 7681 15979 7296 15979 7298 15979 7680 15980 7296 15980 7681 15980 7682 15981 7298 15981 7302 15981 7681 15982 7298 15982 7682 15982 7683 15983 7302 15983 7305 15983 7682 15984 7302 15984 7683 15984 7684 15985 7305 15985 7307 15985 7683 15986 7305 15986 7684 15986 7685 15987 7307 15987 7310 15987 7684 15988 7307 15988 7685 15988 7686 15989 7310 15989 7313 15989 7685 15990 7310 15990 7686 15990 7687 15991 7313 15991 7317 15991 7686 15992 7313 15992 7687 15992 7688 15993 7317 15993 7319 15993 7687 15994 7317 15994 7688 15994 7657 15995 7319 15995 7321 15995 7688 15996 7319 15996 7657 15996 7688 15997 7473 15997 7474 15997 7688 15998 7657 15998 7473 15998 7687 15999 7474 15999 7475 15999 7687 16000 7688 16000 7474 16000 7686 16001 7475 16001 7476 16001 7686 16002 7687 16002 7475 16002 7685 16003 7476 16003 7477 16003 7685 16004 7686 16004 7476 16004 7684 16005 7477 16005 7478 16005 7684 16006 7685 16006 7477 16006 7683 16007 7478 16007 7479 16007 7683 16008 7684 16008 7478 16008 7682 16009 7479 16009 7480 16009 7682 16010 7683 16010 7479 16010 7681 16011 7480 16011 7481 16011 7681 16012 7682 16012 7480 16012 7680 16013 7481 16013 7482 16013 7680 16014 7681 16014 7481 16014 7679 16015 7482 16015 7483 16015 7679 16016 7680 16016 7482 16016 7678 16017 7483 16017 7484 16017 7678 16018 7679 16018 7483 16018 7677 16019 7484 16019 7485 16019 7677 16020 7678 16020 7484 16020 7676 16021 7485 16021 7486 16021 7676 16022 7677 16022 7485 16022 7675 16023 7486 16023 7487 16023 7675 16024 7676 16024 7486 16024 7674 16025 7487 16025 7488 16025 7674 16026 7675 16026 7487 16026 7673 16027 7488 16027 7489 16027 7673 16028 7674 16028 7488 16028 7672 16029 7489 16029 7490 16029 7672 16030 7673 16030 7489 16030 7671 16031 7490 16031 7491 16031 7671 16032 7672 16032 7490 16032 7670 16033 7491 16033 7492 16033 7670 16034 7671 16034 7491 16034 7669 16035 7492 16035 7493 16035 7669 16036 7670 16036 7492 16036 7668 16037 7493 16037 7494 16037 7668 16038 7669 16038 7493 16038 7667 16039 7494 16039 7495 16039 7667 16040 7668 16040 7494 16040 7666 16041 7495 16041 7496 16041 7666 16042 7667 16042 7495 16042 7665 16043 7496 16043 7497 16043 7665 16044 7666 16044 7496 16044 7664 16045 7497 16045 7498 16045 7664 16046 7665 16046 7497 16046 7663 16047 7498 16047 7499 16047 7663 16048 7664 16048 7498 16048 7662 16049 7499 16049 7500 16049 7662 16050 7663 16050 7499 16050 7661 16051 7500 16051 7501 16051 7661 16052 7662 16052 7500 16052 7660 16053 7501 16053 7502 16053 7660 16054 7661 16054 7501 16054 7659 16055 7502 16055 7503 16055 7659 16056 7660 16056 7502 16056 7658 16057 7503 16057 7504 16057 7658 16058 7659 16058 7503 16058 7656 16059 7504 16059 7505 16059 7656 16060 7658 16060 7504 16060 7689 16061 6739 16061 6738 16061 7690 16062 7689 16062 6738 16062 7044 16063 7690 16063 6738 16063 7691 16064 6739 16064 7689 16064 6733 16065 6739 16065 7691 16065 7692 16066 7689 16066 7690 16066 7691 16067 7689 16067 7692 16067 7692 16068 7690 16068 7044 16068 7693 16069 7044 16069 7045 16069 7692 16070 7044 16070 7693 16070 7046 16071 7694 16071 7047 16071 7693 16072 7045 16072 6878 16072 6878 16073 7045 16073 6872 16073 7695 16074 6627 16074 6625 16074 7695 16075 6868 16075 6627 16075 7696 16076 6625 16076 6629 16076 7696 16077 7695 16077 6625 16077 7697 16078 6629 16078 6628 16078 7697 16079 7696 16079 6629 16079 6649 16080 6628 16080 6630 16080 6649 16081 7697 16081 6628 16081 7693 16082 6878 16082 6877 16082 7698 16083 6877 16083 6881 16083 7698 16084 7693 16084 6877 16084 7699 16085 6881 16085 6883 16085 7699 16086 7698 16086 6881 16086 7700 16087 6883 16087 6888 16087 7700 16088 7699 16088 6883 16088 7701 16089 6888 16089 6891 16089 7701 16090 7700 16090 6888 16090 7702 16091 6891 16091 6894 16091 7702 16092 7701 16092 6891 16092 7703 16093 6894 16093 6899 16093 7703 16094 7702 16094 6894 16094 7704 16095 6899 16095 6904 16095 7704 16096 7703 16096 6899 16096 7705 16097 6904 16097 6909 16097 7705 16098 7704 16098 6904 16098 7706 16099 6909 16099 6912 16099 7706 16100 7705 16100 6909 16100 7707 16101 6912 16101 6917 16101 7707 16102 7706 16102 6912 16102 7708 16103 6917 16103 6921 16103 7708 16104 7707 16104 6917 16104 7709 16105 6921 16105 6926 16105 7709 16106 7708 16106 6921 16106 7710 16107 6926 16107 6931 16107 7710 16108 7709 16108 6926 16108 7711 16109 6931 16109 6934 16109 7711 16110 7710 16110 6931 16110 7712 16111 6934 16111 6938 16111 7712 16112 7711 16112 6934 16112 7713 16113 6938 16113 6940 16113 7713 16114 7712 16114 6938 16114 7714 16115 6940 16115 6943 16115 7714 16116 7713 16116 6940 16116 7715 16117 6943 16117 6947 16117 7715 16118 7714 16118 6943 16118 7716 16119 6947 16119 6951 16119 7716 16120 7715 16120 6947 16120 7717 16121 6951 16121 6950 16121 7717 16122 7716 16122 6951 16122 7718 16123 6950 16123 6956 16123 7718 16124 7717 16124 6950 16124 7719 16125 6956 16125 6959 16125 7719 16126 7718 16126 6956 16126 7720 16127 6959 16127 6964 16127 7720 16128 7719 16128 6959 16128 7721 16129 6964 16129 6968 16129 7721 16130 7720 16130 6964 16130 7722 16131 6968 16131 6973 16131 7722 16132 7721 16132 6968 16132 7723 16133 6973 16133 6979 16133 7723 16134 7722 16134 6973 16134 7724 16135 6979 16135 6984 16135 7724 16136 7723 16136 6979 16136 7725 16137 6984 16137 6989 16137 7725 16138 7724 16138 6984 16138 7726 16139 6989 16139 6994 16139 7726 16140 7725 16140 6989 16140 7727 16141 6994 16141 6999 16141 7727 16142 7726 16142 6994 16142 7728 16143 6999 16143 7005 16143 7728 16144 7727 16144 6999 16144 7729 16145 7005 16145 6868 16145 7729 16146 7728 16146 7005 16146 7695 16147 7729 16147 6868 16147 7692 16148 7693 16148 7698 16148 7730 16149 7698 16149 7699 16149 7730 16150 7692 16150 7698 16150 7731 16151 7699 16151 7700 16151 7731 16152 7730 16152 7699 16152 7732 16153 7700 16153 7701 16153 7732 16154 7731 16154 7700 16154 7733 16155 7701 16155 7702 16155 7733 16156 7732 16156 7701 16156 7734 16157 7702 16157 7703 16157 7734 16158 7733 16158 7702 16158 7735 16159 7703 16159 7704 16159 7735 16160 7734 16160 7703 16160 7736 16161 7704 16161 7705 16161 7736 16162 7735 16162 7704 16162 7737 16163 7705 16163 7706 16163 7737 16164 7736 16164 7705 16164 7738 16165 7706 16165 7707 16165 7738 16166 7737 16166 7706 16166 7739 16167 7707 16167 7708 16167 7739 16168 7738 16168 7707 16168 7740 16169 7708 16169 7709 16169 7740 16170 7739 16170 7708 16170 7741 16171 7709 16171 7710 16171 7741 16172 7740 16172 7709 16172 7742 16173 7710 16173 7711 16173 7742 16174 7741 16174 7710 16174 7743 16175 7711 16175 7712 16175 7743 16176 7742 16176 7711 16176 7744 16177 7712 16177 7713 16177 7744 16178 7743 16178 7712 16178 7745 16179 7713 16179 7714 16179 7745 16180 7744 16180 7713 16180 7746 16181 7714 16181 7715 16181 7746 16182 7745 16182 7714 16182 7747 16183 7715 16183 7716 16183 7747 16184 7746 16184 7715 16184 7748 16185 7716 16185 7717 16185 7748 16186 7747 16186 7716 16186 7749 16187 7717 16187 7718 16187 7749 16188 7748 16188 7717 16188 7750 16189 7718 16189 7719 16189 7750 16190 7749 16190 7718 16190 7751 16191 7719 16191 7720 16191 7751 16192 7750 16192 7719 16192 7752 16193 7720 16193 7721 16193 7752 16194 7751 16194 7720 16194 7753 16195 7721 16195 7722 16195 7753 16196 7752 16196 7721 16196 7754 16197 7722 16197 7723 16197 7754 16198 7753 16198 7722 16198 7755 16199 7723 16199 7724 16199 7755 16200 7754 16200 7723 16200 7756 16201 7724 16201 7725 16201 7756 16202 7755 16202 7724 16202 7757 16203 7725 16203 7726 16203 7757 16204 7756 16204 7725 16204 7758 16205 7726 16205 7727 16205 7758 16206 7757 16206 7726 16206 7759 16207 7727 16207 7728 16207 7759 16208 7758 16208 7727 16208 7760 16209 7728 16209 7729 16209 7760 16210 7759 16210 7728 16210 7761 16211 7729 16211 7695 16211 7761 16212 7760 16212 7729 16212 7696 16213 7761 16213 7695 16213 7691 16214 7692 16214 7730 16214 7762 16215 7730 16215 7731 16215 7762 16216 7691 16216 7730 16216 7763 16217 7731 16217 7732 16217 7763 16218 7762 16218 7731 16218 7764 16219 7732 16219 7733 16219 7764 16220 7763 16220 7732 16220 7765 16221 7733 16221 7734 16221 7765 16222 7764 16222 7733 16222 7766 16223 7734 16223 7735 16223 7766 16224 7765 16224 7734 16224 7767 16225 7735 16225 7736 16225 7767 16226 7766 16226 7735 16226 7768 16227 7736 16227 7737 16227 7768 16228 7767 16228 7736 16228 7769 16229 7737 16229 7738 16229 7769 16230 7768 16230 7737 16230 7770 16231 7738 16231 7739 16231 7770 16232 7769 16232 7738 16232 7771 16233 7739 16233 7740 16233 7771 16234 7770 16234 7739 16234 7772 16235 7740 16235 7741 16235 7772 16236 7771 16236 7740 16236 7773 16237 7741 16237 7742 16237 7773 16238 7772 16238 7741 16238 7774 16239 7742 16239 7743 16239 7774 16240 7773 16240 7742 16240 7775 16241 7743 16241 7744 16241 7775 16242 7774 16242 7743 16242 7776 16243 7744 16243 7745 16243 7776 16244 7775 16244 7744 16244 7777 16245 7745 16245 7746 16245 7777 16246 7776 16246 7745 16246 7778 16247 7746 16247 7747 16247 7778 16248 7777 16248 7746 16248 7779 16249 7747 16249 7748 16249 7779 16250 7778 16250 7747 16250 7780 16251 7748 16251 7749 16251 7780 16252 7779 16252 7748 16252 7781 16253 7749 16253 7750 16253 7781 16254 7780 16254 7749 16254 7782 16255 7750 16255 7751 16255 7782 16256 7781 16256 7750 16256 7783 16257 7751 16257 7752 16257 7783 16258 7782 16258 7751 16258 7784 16259 7752 16259 7753 16259 7784 16260 7783 16260 7752 16260 7785 16261 7753 16261 7754 16261 7785 16262 7784 16262 7753 16262 7786 16263 7754 16263 7755 16263 7786 16264 7785 16264 7754 16264 7787 16265 7755 16265 7756 16265 7787 16266 7786 16266 7755 16266 7788 16267 7756 16267 7757 16267 7788 16268 7787 16268 7756 16268 7789 16269 7757 16269 7758 16269 7789 16270 7788 16270 7757 16270 7790 16271 7758 16271 7759 16271 7790 16272 7789 16272 7758 16272 7791 16273 7759 16273 7760 16273 7791 16274 7790 16274 7759 16274 7792 16275 7760 16275 7761 16275 7792 16276 7791 16276 7760 16276 7793 16277 7761 16277 7696 16277 7793 16278 7792 16278 7761 16278 7697 16279 7793 16279 7696 16279 6733 16280 7691 16280 7762 16280 6729 16281 7762 16281 7763 16281 6729 16282 6733 16282 7762 16282 6730 16283 7763 16283 7764 16283 6730 16284 6729 16284 7763 16284 6724 16285 7764 16285 7765 16285 6724 16286 6730 16286 7764 16286 6726 16287 7765 16287 7766 16287 6726 16288 6724 16288 7765 16288 6719 16289 7766 16289 7767 16289 6719 16290 6726 16290 7766 16290 6721 16291 7767 16291 7768 16291 6721 16292 6719 16292 7767 16292 6714 16293 7768 16293 7769 16293 6714 16294 6721 16294 7768 16294 6715 16295 7769 16295 7770 16295 6715 16296 6714 16296 7769 16296 6716 16297 7770 16297 7771 16297 6716 16298 6715 16298 7770 16298 6709 16299 7771 16299 7772 16299 6709 16300 6716 16300 7771 16300 6711 16301 7772 16301 7773 16301 6711 16302 6709 16302 7772 16302 6705 16303 7773 16303 7774 16303 6705 16304 6711 16304 7773 16304 6701 16305 7774 16305 7775 16305 6701 16306 6705 16306 7774 16306 6702 16307 7775 16307 7776 16307 6702 16308 6701 16308 7775 16308 6698 16309 7776 16309 7777 16309 6698 16310 6702 16310 7776 16310 6694 16311 7777 16311 7778 16311 6694 16312 6698 16312 7777 16312 6695 16313 7778 16313 7779 16313 6695 16314 6694 16314 7778 16314 6691 16315 7779 16315 7780 16315 6691 16316 6695 16316 7779 16316 6689 16317 7780 16317 7781 16317 6689 16318 6691 16318 7780 16318 6686 16319 7781 16319 7782 16319 6686 16320 6689 16320 7781 16320 6684 16321 7782 16321 7783 16321 6684 16322 6686 16322 7782 16322 6681 16323 7783 16323 7784 16323 6681 16324 6684 16324 7783 16324 6678 16325 7784 16325 7785 16325 6678 16326 6681 16326 7784 16326 6674 16327 7785 16327 7786 16327 6674 16328 6678 16328 7785 16328 6672 16329 7786 16329 7787 16329 6672 16330 6674 16330 7786 16330 6668 16331 7787 16331 7788 16331 6668 16332 6672 16332 7787 16332 6665 16333 7788 16333 7789 16333 6665 16334 6668 16334 7788 16334 6662 16335 7789 16335 7790 16335 6662 16336 6665 16336 7789 16336 6657 16337 7790 16337 7791 16337 6657 16338 6662 16338 7790 16338 6654 16339 7791 16339 7792 16339 6654 16340 6657 16340 7791 16340 6651 16341 7792 16341 7793 16341 6651 16342 6654 16342 7792 16342 6650 16343 7793 16343 7697 16343 6650 16344 6651 16344 7793 16344 6649 16345 6650 16345 7697 16345 7794 16346 7042 16346 6828 16346 7694 16347 7795 16347 7047 16347 7796 16348 7794 16348 6828 16348 6829 16349 7796 16349 6828 16349 7694 16350 7797 16350 7795 16350 7040 16351 7042 16351 7794 16351 7798 16352 7794 16352 7796 16352 7798 16353 7040 16353 7794 16353 6830 16354 7796 16354 6829 16354 7799 16355 7796 16355 6830 16355 7798 16356 7796 16356 7799 16356 7800 16357 6830 16357 6827 16357 7799 16358 6830 16358 7800 16358 7800 16359 6827 16359 6831 16359 7801 16360 6618 16360 6619 16360 7801 16361 6753 16361 6618 16361 7048 16362 6619 16362 6617 16362 7048 16363 7801 16363 6619 16363 7046 16364 6617 16364 6622 16364 7046 16365 7048 16365 6617 16365 7007 16366 6622 16366 6621 16366 7046 16367 6622 16367 7007 16367 7694 16368 7007 16368 7008 16368 7046 16369 7007 16369 7694 16369 7797 16370 7008 16370 7009 16370 7694 16371 7008 16371 7797 16371 7802 16372 7009 16372 7010 16372 7797 16373 7009 16373 7802 16373 7803 16374 7010 16374 7011 16374 7802 16375 7010 16375 7803 16375 7804 16376 7011 16376 7012 16376 7803 16377 7011 16377 7804 16377 7805 16378 7012 16378 7013 16378 7804 16379 7012 16379 7805 16379 7806 16380 7013 16380 7014 16380 7805 16381 7013 16381 7806 16381 7807 16382 7014 16382 7015 16382 7806 16383 7014 16383 7807 16383 7808 16384 7015 16384 7016 16384 7807 16385 7015 16385 7808 16385 7809 16386 7016 16386 7017 16386 7808 16387 7016 16387 7809 16387 7810 16388 7017 16388 7018 16388 7809 16389 7017 16389 7810 16389 7811 16390 7018 16390 7019 16390 7810 16391 7018 16391 7811 16391 7812 16392 7019 16392 7020 16392 7811 16393 7019 16393 7812 16393 7813 16394 7020 16394 7021 16394 7812 16395 7020 16395 7813 16395 7814 16396 7021 16396 7022 16396 7813 16397 7021 16397 7814 16397 7815 16398 7022 16398 7023 16398 7814 16399 7022 16399 7815 16399 7816 16400 7023 16400 7024 16400 7815 16401 7023 16401 7816 16401 7817 16402 7024 16402 7025 16402 7816 16403 7024 16403 7817 16403 7818 16404 7025 16404 7026 16404 7817 16405 7025 16405 7818 16405 7819 16406 7026 16406 7027 16406 7818 16407 7026 16407 7819 16407 7820 16408 7027 16408 7028 16408 7819 16409 7027 16409 7820 16409 7821 16410 7028 16410 7029 16410 7820 16411 7028 16411 7821 16411 7822 16412 7029 16412 7030 16412 7821 16413 7029 16413 7822 16413 7823 16414 7030 16414 7031 16414 7822 16415 7030 16415 7823 16415 7824 16416 7031 16416 7032 16416 7823 16417 7031 16417 7824 16417 7825 16418 7032 16418 7033 16418 7824 16419 7032 16419 7825 16419 7826 16420 7033 16420 7034 16420 7825 16421 7033 16421 7826 16421 7827 16422 7034 16422 7035 16422 7826 16423 7034 16423 7827 16423 7828 16424 7035 16424 7036 16424 7827 16425 7035 16425 7828 16425 7829 16426 7036 16426 7037 16426 7828 16427 7036 16427 7829 16427 7830 16428 7037 16428 7039 16428 7829 16429 7037 16429 7830 16429 7831 16430 7039 16430 7038 16430 7830 16431 7039 16431 7831 16431 7798 16432 7038 16432 7040 16432 7831 16433 7038 16433 7798 16433 7832 16434 6831 16434 6832 16434 7832 16435 7800 16435 6831 16435 7833 16436 6832 16436 6834 16436 7833 16437 7832 16437 6832 16437 7834 16438 6834 16438 6833 16438 7834 16439 7833 16439 6834 16439 7835 16440 6833 16440 6835 16440 7835 16441 7834 16441 6833 16441 7836 16442 6835 16442 6837 16442 7836 16443 7835 16443 6835 16443 7837 16444 6837 16444 6838 16444 7837 16445 7836 16445 6837 16445 7838 16446 6838 16446 6836 16446 7838 16447 7837 16447 6838 16447 7839 16448 6836 16448 6840 16448 7839 16449 7838 16449 6836 16449 7840 16450 6840 16450 6839 16450 7840 16451 7839 16451 6840 16451 7841 16452 6839 16452 6842 16452 7841 16453 7840 16453 6839 16453 7842 16454 6842 16454 6843 16454 7842 16455 7841 16455 6842 16455 7843 16456 6843 16456 6841 16456 7843 16457 7842 16457 6843 16457 7844 16458 6841 16458 6845 16458 7844 16459 7843 16459 6841 16459 7845 16460 6845 16460 6844 16460 7845 16461 7844 16461 6845 16461 7846 16462 6844 16462 6847 16462 7846 16463 7845 16463 6844 16463 7847 16464 6847 16464 6846 16464 7847 16465 7846 16465 6847 16465 7848 16466 6846 16466 6848 16466 7848 16467 7847 16467 6846 16467 7849 16468 6848 16468 6850 16468 7849 16469 7848 16469 6848 16469 7850 16470 6850 16470 6849 16470 7850 16471 7849 16471 6850 16471 7851 16472 6849 16472 6851 16472 7851 16473 7850 16473 6849 16473 7852 16474 6851 16474 6852 16474 7852 16475 7851 16475 6851 16475 7853 16476 6852 16476 6853 16476 7853 16477 7852 16477 6852 16477 7854 16478 6853 16478 6854 16478 7854 16479 7853 16479 6853 16479 7855 16480 6854 16480 6855 16480 7855 16481 7854 16481 6854 16481 7856 16482 6855 16482 6856 16482 7856 16483 7855 16483 6855 16483 7857 16484 6856 16484 6857 16484 7857 16485 7856 16485 6856 16485 7858 16486 6857 16486 6858 16486 7858 16487 7857 16487 6857 16487 7859 16488 6858 16488 6859 16488 7859 16489 7858 16489 6858 16489 7860 16490 6859 16490 6860 16490 7860 16491 7859 16491 6859 16491 7861 16492 6860 16492 6861 16492 7861 16493 7860 16493 6860 16493 7862 16494 6861 16494 6862 16494 7862 16495 7861 16495 6861 16495 7863 16496 6862 16496 6863 16496 7863 16497 7862 16497 6862 16497 7801 16498 6863 16498 6753 16498 7801 16499 7863 16499 6863 16499 7864 16500 7800 16500 7832 16500 7864 16501 7799 16501 7800 16501 7865 16502 7832 16502 7833 16502 7865 16503 7864 16503 7832 16503 7866 16504 7833 16504 7834 16504 7866 16505 7865 16505 7833 16505 7867 16506 7834 16506 7835 16506 7867 16507 7866 16507 7834 16507 7868 16508 7835 16508 7836 16508 7868 16509 7867 16509 7835 16509 7869 16510 7836 16510 7837 16510 7869 16511 7868 16511 7836 16511 7870 16512 7837 16512 7838 16512 7870 16513 7869 16513 7837 16513 7871 16514 7838 16514 7839 16514 7871 16515 7870 16515 7838 16515 7872 16516 7839 16516 7840 16516 7872 16517 7871 16517 7839 16517 7873 16518 7840 16518 7841 16518 7873 16519 7872 16519 7840 16519 7874 16520 7841 16520 7842 16520 7874 16521 7873 16521 7841 16521 7875 16522 7842 16522 7843 16522 7875 16523 7874 16523 7842 16523 7876 16524 7843 16524 7844 16524 7876 16525 7875 16525 7843 16525 7877 16526 7844 16526 7845 16526 7877 16527 7876 16527 7844 16527 7878 16528 7845 16528 7846 16528 7878 16529 7877 16529 7845 16529 7879 16530 7846 16530 7847 16530 7879 16531 7878 16531 7846 16531 7880 16532 7847 16532 7848 16532 7880 16533 7879 16533 7847 16533 7881 16534 7848 16534 7849 16534 7881 16535 7880 16535 7848 16535 7882 16536 7849 16536 7850 16536 7882 16537 7881 16537 7849 16537 7883 16538 7850 16538 7851 16538 7883 16539 7882 16539 7850 16539 7884 16540 7851 16540 7852 16540 7884 16541 7883 16541 7851 16541 7885 16542 7852 16542 7853 16542 7885 16543 7884 16543 7852 16543 7886 16544 7853 16544 7854 16544 7886 16545 7885 16545 7853 16545 7887 16546 7854 16546 7855 16546 7887 16547 7886 16547 7854 16547 7888 16548 7855 16548 7856 16548 7888 16549 7887 16549 7855 16549 7889 16550 7856 16550 7857 16550 7889 16551 7888 16551 7856 16551 7890 16552 7857 16552 7858 16552 7890 16553 7889 16553 7857 16553 7891 16554 7858 16554 7859 16554 7891 16555 7890 16555 7858 16555 7892 16556 7859 16556 7860 16556 7892 16557 7891 16557 7859 16557 7893 16558 7860 16558 7861 16558 7893 16559 7892 16559 7860 16559 7795 16560 7861 16560 7862 16560 7795 16561 7893 16561 7861 16561 7047 16562 7862 16562 7863 16562 7047 16563 7795 16563 7862 16563 7048 16564 7863 16564 7801 16564 7048 16565 7047 16565 7863 16565 7831 16566 7799 16566 7864 16566 7831 16567 7798 16567 7799 16567 7830 16568 7864 16568 7865 16568 7830 16569 7831 16569 7864 16569 7829 16570 7865 16570 7866 16570 7829 16571 7830 16571 7865 16571 7828 16572 7866 16572 7867 16572 7828 16573 7829 16573 7866 16573 7827 16574 7867 16574 7868 16574 7827 16575 7828 16575 7867 16575 7826 16576 7868 16576 7869 16576 7826 16577 7827 16577 7868 16577 7825 16578 7869 16578 7870 16578 7825 16579 7826 16579 7869 16579 7824 16580 7870 16580 7871 16580 7824 16581 7825 16581 7870 16581 7823 16582 7871 16582 7872 16582 7823 16583 7824 16583 7871 16583 7822 16584 7872 16584 7873 16584 7822 16585 7823 16585 7872 16585 7821 16586 7873 16586 7874 16586 7821 16587 7822 16587 7873 16587 7820 16588 7874 16588 7875 16588 7820 16589 7821 16589 7874 16589 7819 16590 7875 16590 7876 16590 7819 16591 7820 16591 7875 16591 7818 16592 7876 16592 7877 16592 7818 16593 7819 16593 7876 16593 7817 16594 7877 16594 7878 16594 7817 16595 7818 16595 7877 16595 7816 16596 7878 16596 7879 16596 7816 16597 7817 16597 7878 16597 7815 16598 7879 16598 7880 16598 7815 16599 7816 16599 7879 16599 7814 16600 7880 16600 7881 16600 7814 16601 7815 16601 7880 16601 7813 16602 7881 16602 7882 16602 7813 16603 7814 16603 7881 16603 7812 16604 7882 16604 7883 16604 7812 16605 7813 16605 7882 16605 7811 16606 7883 16606 7884 16606 7811 16607 7812 16607 7883 16607 7810 16608 7884 16608 7885 16608 7810 16609 7811 16609 7884 16609 7809 16610 7885 16610 7886 16610 7809 16611 7810 16611 7885 16611 7808 16612 7886 16612 7887 16612 7808 16613 7809 16613 7886 16613 7807 16614 7887 16614 7888 16614 7807 16615 7808 16615 7887 16615 7806 16616 7888 16616 7889 16616 7806 16617 7807 16617 7888 16617 7805 16618 7889 16618 7890 16618 7805 16619 7806 16619 7889 16619 7804 16620 7890 16620 7891 16620 7804 16621 7805 16621 7890 16621 7803 16622 7891 16622 7892 16622 7803 16623 7804 16623 7891 16623 7802 16624 7892 16624 7893 16624 7802 16625 7803 16625 7892 16625 7797 16626 7893 16626 7795 16626 7797 16627 7802 16627 7893 16627 7894 16628 7895 16628 7896 16628 7896 16629 7897 16629 7898 16629 7898 16630 7899 16630 7900 16630 7900 16631 7901 16631 7902 16631 7902 16632 7903 16632 7904 16632 7904 16633 7905 16633 7906 16633 7906 16634 7907 16634 7908 16634 7908 16635 7909 16635 7910 16635 7910 16636 7911 16636 7913 16636 7912 16637 7913 16637 7915 16637 7914 16638 7915 16638 7917 16638 7916 16639 7917 16639 7919 16639 7918 16640 7919 16640 7921 16640 7920 16641 7921 16641 7923 16641 7922 16642 7923 16642 7925 16642 7924 16643 7925 16643 7927 16643 7926 16644 7927 16644 7929 16644 7928 16645 7929 16645 7931 16645 7930 16646 7931 16646 7933 16646 7932 16647 7933 16647 7935 16647 7934 16648 7935 16648 7937 16648 7936 16649 7937 16649 7939 16649 7938 16650 7939 16650 7941 16650 7940 16651 7941 16651 7943 16651 7942 16652 7943 16652 7944 16652 7944 16653 7945 16653 7946 16653 7946 16654 7947 16654 7948 16654 7948 16655 7949 16655 7950 16655 7950 16656 7951 16656 7952 16656 7952 16657 7953 16657 7954 16657 7897 16658 7895 16658 7957 16658 7956 16659 7957 16659 7894 16659 7954 16660 7955 16660 7956 16660 7944 16661 7940 16661 7942 16661 7958 16662 7959 16662 7960 16662 7961 16663 7960 16663 7959 16663 7962 16664 7960 16664 7963 16664 7964 16665 7963 16665 7960 16665 7958 16666 7960 16666 7962 16666 7965 16667 7960 16667 7961 16667 7966 16668 7964 16668 7960 16668 7967 16669 7966 16669 7960 16669 7965 16670 7967 16670 7960 16670 7968 16671 7969 16671 7959 16671 7970 16672 7959 16672 7969 16672 7971 16673 7968 16673 7959 16673 7972 16674 7971 16674 7959 16674 7958 16675 7972 16675 7959 16675 7973 16676 7959 16676 7970 16676 7974 16677 7975 16677 7959 16677 7976 16678 7959 16678 7975 16678 7973 16679 7974 16679 7959 16679 7976 16680 7961 16680 7959 16680 7977 16681 7978 16681 7969 16681 7979 16682 7969 16682 7978 16682 7968 16683 7977 16683 7969 16683 7970 16684 7969 16684 7979 16684 7980 16685 7981 16685 7978 16685 7982 16686 7978 16686 7981 16686 7977 16687 7980 16687 7978 16687 7979 16688 7978 16688 7982 16688 7983 16689 7981 16689 7980 16689 7982 16690 7981 16690 7983 16690 7984 16691 7980 16691 7977 16691 7983 16692 7980 16692 7984 16692 7985 16693 7977 16693 7968 16693 7984 16694 7977 16694 7985 16694 7986 16695 7987 16695 7968 16695 7988 16696 7968 16696 7987 16696 7971 16697 7986 16697 7968 16697 7985 16698 7968 16698 7988 16698 7989 16699 7990 16699 7987 16699 7991 16700 7987 16700 7990 16700 7992 16701 7989 16701 7987 16701 7986 16702 7992 16702 7987 16702 7988 16703 7987 16703 7993 16703 7991 16704 7993 16704 7987 16704 7994 16705 7995 16705 7990 16705 7996 16706 7990 16706 7995 16706 7989 16707 7994 16707 7990 16707 7997 16708 7991 16708 7990 16708 7998 16709 7997 16709 7990 16709 7999 16710 7998 16710 7990 16710 7996 16711 7999 16711 7990 16711 8000 16712 8001 16712 7995 16712 8002 16713 7995 16713 8001 16713 8003 16714 8000 16714 7995 16714 8004 16715 8003 16715 7995 16715 7994 16716 8004 16716 7995 16716 8005 16717 7995 16717 8002 16717 8006 16718 7996 16718 7995 16718 8007 16719 8008 16719 7995 16719 8006 16720 7995 16720 8008 16720 8005 16721 8007 16721 7995 16721 8009 16722 8010 16722 8001 16722 8011 16723 8001 16723 8010 16723 8000 16724 8009 16724 8001 16724 8002 16725 8001 16725 8011 16725 8012 16726 8013 16726 8010 16726 8014 16727 8010 16727 8013 16727 8009 16728 8012 16728 8010 16728 8011 16729 8010 16729 8014 16729 8015 16730 8013 16730 8012 16730 8014 16731 8013 16731 8015 16731 8016 16732 8012 16732 8009 16732 8015 16733 8012 16733 8016 16733 8017 16734 8009 16734 8000 16734 8016 16735 8009 16735 8017 16735 8018 16736 7963 16736 8000 16736 8019 16737 8000 16737 7963 16737 8003 16738 8018 16738 8000 16738 8017 16739 8000 16739 8019 16739 8020 16740 7962 16740 7963 16740 8018 16741 8020 16741 7963 16741 8019 16742 7963 16742 8021 16742 7964 16743 8021 16743 7963 16743 8022 16744 7962 16744 8020 16744 8023 16745 7958 16745 7962 16745 8023 16746 7962 16746 8022 16746 8024 16747 8020 16747 8018 16747 8024 16748 8022 16748 8020 16748 8025 16749 8018 16749 8003 16749 8024 16750 8018 16750 8025 16750 8026 16751 8003 16751 8004 16751 8025 16752 8003 16752 8026 16752 8027 16753 8004 16753 7994 16753 8026 16754 8004 16754 8027 16754 8028 16755 7994 16755 7989 16755 8027 16756 7994 16756 8028 16756 8029 16757 7989 16757 7992 16757 8028 16758 7989 16758 8029 16758 8030 16759 7992 16759 7986 16759 8029 16760 7992 16760 8030 16760 8031 16761 7986 16761 7971 16761 8030 16762 7986 16762 8031 16762 8032 16763 7971 16763 7972 16763 8031 16764 7971 16764 8032 16764 7972 16765 7958 16765 8033 16765 8032 16766 7972 16766 8033 16766 8033 16767 7958 16767 8023 16767 8024 16768 8021 16768 8034 16768 8035 16769 8034 16769 8021 16769 8022 16770 8034 16770 7970 16770 7973 16771 7970 16771 8034 16771 8024 16772 8034 16772 8022 16772 8036 16773 7973 16773 8034 16773 8037 16774 8036 16774 8034 16774 8038 16775 8037 16775 8034 16775 8039 16776 8038 16776 8034 16776 8040 16777 8039 16777 8034 16777 8035 16778 8040 16778 8034 16778 8011 16779 8019 16779 8021 16779 8026 16780 8011 16780 8021 16780 8025 16781 8026 16781 8021 16781 8024 16782 8025 16782 8021 16782 8041 16783 8035 16783 8021 16783 7964 16784 8041 16784 8021 16784 8014 16785 8017 16785 8019 16785 8011 16786 8014 16786 8019 16786 8015 16787 8016 16787 8017 16787 8014 16788 8015 16788 8017 16788 8027 16789 8002 16789 8011 16789 8026 16790 8027 16790 8011 16790 8029 16791 8042 16791 8002 16791 8005 16792 8002 16792 8042 16792 8028 16793 8029 16793 8002 16793 8027 16794 8028 16794 8002 16794 8030 16795 7993 16795 8042 16795 8043 16796 8042 16796 7993 16796 8029 16797 8030 16797 8042 16797 8044 16798 8042 16798 8043 16798 8045 16799 8005 16799 8042 16799 8046 16800 8045 16800 8042 16800 8047 16801 8046 16801 8042 16801 8048 16802 8047 16802 8042 16802 8044 16803 8048 16803 8042 16803 7979 16804 7988 16804 7993 16804 8032 16805 7979 16805 7993 16805 8031 16806 8032 16806 7993 16806 8030 16807 8031 16807 7993 16807 8049 16808 8043 16808 7993 16808 7991 16809 8049 16809 7993 16809 7982 16810 7985 16810 7988 16810 7979 16811 7982 16811 7988 16811 7983 16812 7984 16812 7985 16812 7982 16813 7983 16813 7985 16813 8033 16814 7970 16814 7979 16814 8032 16815 8033 16815 7979 16815 8023 16816 8022 16816 7970 16816 8033 16817 8023 16817 7970 16817 8050 16818 7975 16818 7974 16818 8050 16819 7976 16819 7975 16819 8051 16820 7974 16820 7973 16820 8052 16821 8050 16821 7974 16821 8051 16822 8052 16822 7974 16822 8053 16823 7973 16823 8036 16823 8054 16824 7973 16824 8053 16824 8054 16825 8051 16825 7973 16825 8055 16826 8036 16826 8037 16826 8056 16827 8053 16827 8036 16827 8055 16828 8056 16828 8036 16828 8057 16829 8037 16829 8038 16829 8058 16830 8055 16830 8037 16830 8059 16831 8058 16831 8037 16831 8057 16832 8059 16832 8037 16832 8060 16833 8038 16833 8039 16833 8061 16834 8057 16834 8038 16834 8060 16835 8061 16835 8038 16835 8062 16836 8039 16836 8040 16836 8060 16837 8039 16837 8062 16837 8062 16838 8040 16838 8035 16838 8063 16839 8035 16839 8041 16839 8063 16840 8064 16840 8035 16840 8062 16841 8035 16841 8064 16841 8065 16842 8043 16842 8049 16842 8066 16843 8044 16843 8043 16843 8065 16844 8067 16844 8043 16844 8066 16845 8043 16845 8067 16845 8065 16846 8049 16846 7991 16846 8065 16847 7991 16847 7997 16847 8065 16848 7997 16848 7998 16848 8068 16849 7998 16849 7999 16849 8068 16850 8065 16850 7998 16850 8068 16851 7999 16851 7996 16851 8069 16852 7996 16852 8006 16852 8068 16853 7996 16853 8069 16853 8050 16854 7961 16854 7976 16854 8070 16855 7965 16855 7961 16855 8070 16856 7961 16856 8050 16856 8069 16857 8008 16857 8007 16857 8069 16858 8006 16858 8008 16858 8071 16859 8007 16859 8005 16859 8072 16860 8069 16860 8007 16860 8073 16861 8072 16861 8007 16861 8071 16862 8073 16862 8007 16862 8074 16863 8005 16863 8045 16863 8075 16864 8005 16864 8074 16864 8076 16865 8071 16865 8005 16865 8075 16866 8076 16866 8005 16866 8077 16867 8045 16867 8046 16867 8078 16868 8074 16868 8045 16868 8077 16869 8078 16869 8045 16869 8079 16870 8046 16870 8047 16870 8080 16871 8077 16871 8046 16871 8081 16872 8080 16872 8046 16872 8079 16873 8081 16873 8046 16873 8082 16874 8047 16874 8048 16874 8083 16875 8079 16875 8047 16875 8082 16876 8083 16876 8047 16876 8066 16877 8048 16877 8044 16877 8084 16878 8048 16878 8066 16878 8084 16879 8082 16879 8048 16879 8063 16880 8041 16880 7964 16880 8063 16881 7964 16881 7966 16881 8063 16882 7966 16882 7967 16882 8070 16883 7967 16883 7965 16883 8070 16884 8063 16884 7967 16884 8085 16885 8067 16885 8065 16885 8086 16886 8066 16886 8067 16886 8087 16887 8086 16887 8067 16887 8088 16888 8087 16888 8067 16888 8089 16889 8088 16889 8067 16889 8090 16890 8089 16890 8067 16890 8091 16891 8090 16891 8067 16891 8092 16892 8091 16892 8067 16892 8092 16893 8067 16893 8085 16893 8093 16894 8065 16894 8068 16894 8094 16895 8095 16895 8065 16895 8096 16896 8065 16896 8095 16896 8093 16897 8094 16897 8065 16897 8097 16898 8085 16898 8065 16898 8098 16899 8097 16899 8065 16899 8099 16900 8098 16900 8065 16900 8100 16901 8099 16901 8065 16901 8101 16902 8100 16902 8065 16902 8102 16903 8101 16903 8065 16903 8096 16904 8102 16904 8065 16904 8084 16905 8066 16905 8086 16905 8103 16906 8086 16906 8087 16906 8103 16907 8084 16907 8086 16907 8104 16908 8087 16908 8088 16908 8103 16909 8087 16909 8104 16909 8104 16910 8088 16910 8089 16910 8105 16911 8089 16911 8090 16911 8104 16912 8089 16912 8105 16912 8091 16913 8106 16913 8090 16913 8105 16914 8090 16914 8106 16914 8091 16915 8107 16915 8106 16915 8108 16916 8106 16916 8107 16916 8105 16917 8106 16917 8108 16917 8091 16918 8109 16918 8107 16918 8108 16919 8107 16919 8109 16919 8091 16920 8110 16920 8109 16920 8111 16921 8109 16921 8110 16921 8108 16922 8109 16922 8111 16922 8091 16923 8112 16923 8110 16923 8111 16924 8110 16924 8112 16924 8091 16925 8113 16925 8112 16925 8111 16926 8112 16926 8113 16926 8114 16927 8115 16927 8113 16927 8116 16928 8113 16928 8115 16928 8091 16929 8114 16929 8113 16929 8111 16930 8113 16930 8116 16930 8114 16931 8117 16931 8115 16931 8116 16932 8115 16932 8117 16932 8114 16933 8118 16933 8117 16933 8119 16934 8117 16934 8118 16934 8116 16935 8117 16935 8119 16935 8114 16936 8120 16936 8118 16936 8119 16937 8118 16937 8120 16937 8114 16938 8121 16938 8120 16938 8122 16939 8120 16939 8121 16939 8119 16940 8120 16940 8122 16940 8114 16941 8123 16941 8121 16941 8122 16942 8121 16942 8123 16942 8124 16943 8125 16943 8123 16943 8126 16944 8123 16944 8125 16944 8114 16945 8124 16945 8123 16945 8122 16946 8123 16946 8126 16946 8124 16947 8127 16947 8125 16947 8128 16948 8125 16948 8127 16948 8126 16949 8125 16949 8128 16949 8124 16950 8129 16950 8127 16950 8128 16951 8127 16951 8129 16951 8130 16952 8131 16952 8129 16952 8132 16953 8129 16953 8131 16953 8124 16954 8130 16954 8129 16954 8128 16955 8129 16955 8132 16955 8130 16956 8133 16956 8131 16956 8132 16957 8131 16957 8133 16957 8130 16958 8134 16958 8133 16958 8135 16959 8133 16959 8134 16959 8132 16960 8133 16960 8135 16960 8136 16961 8137 16961 8134 16961 8138 16962 8134 16962 8137 16962 8130 16963 8136 16963 8134 16963 8135 16964 8134 16964 8138 16964 8136 16965 8139 16965 8137 16965 8140 16966 8137 16966 8139 16966 8138 16967 8137 16967 8140 16967 8141 16968 8142 16968 8139 16968 8143 16969 8139 16969 8142 16969 8136 16970 8141 16970 8139 16970 8140 16971 8139 16971 8143 16971 8141 16972 8144 16972 8142 16972 8145 16973 8142 16973 8144 16973 8143 16974 8142 16974 8145 16974 8146 16975 8147 16975 8144 16975 8148 16976 8144 16976 8147 16976 8141 16977 8146 16977 8144 16977 8149 16978 8144 16978 8148 16978 8145 16979 8144 16979 8149 16979 8150 16980 8151 16980 8147 16980 8152 16981 8147 16981 8151 16981 8146 16982 8150 16982 8147 16982 8148 16983 8147 16983 8152 16983 8153 16984 8154 16984 8151 16984 8155 16985 8151 16985 8154 16985 8150 16986 8153 16986 8151 16986 8156 16987 8151 16987 8155 16987 8152 16988 8151 16988 8156 16988 8157 16989 8158 16989 8154 16989 8159 16990 8154 16990 8158 16990 8160 16991 8157 16991 8154 16991 8153 16992 8160 16992 8154 16992 8155 16993 8154 16993 8159 16993 8161 16994 8162 16994 8158 16994 8163 16995 8158 16995 8162 16995 8164 16996 8161 16996 8158 16996 8157 16997 8164 16997 8158 16997 8165 16998 8158 16998 8163 16998 8159 16999 8158 16999 8165 16999 8166 17000 8167 17000 8162 17000 8168 17001 8162 17001 8167 17001 8161 17002 8166 17002 8162 17002 8169 17003 8162 17003 8168 17003 8170 17004 8162 17004 8169 17004 8163 17005 8162 17005 8170 17005 8171 17006 8172 17006 8167 17006 8173 17007 8167 17007 8172 17007 8174 17008 8171 17008 8167 17008 8166 17009 8174 17009 8167 17009 8175 17010 8167 17010 8173 17010 8168 17011 8167 17011 8175 17011 8176 17012 8177 17012 8172 17012 8178 17013 8172 17013 8177 17013 8179 17014 8176 17014 8172 17014 8171 17015 8179 17015 8172 17015 8180 17016 8172 17016 8178 17016 8173 17017 8172 17017 8180 17017 8181 17018 8182 17018 8177 17018 8183 17019 8177 17019 8182 17019 8176 17020 8181 17020 8177 17020 8184 17021 8177 17021 8183 17021 8178 17022 8177 17022 8184 17022 8185 17023 8186 17023 8182 17023 8187 17024 8182 17024 8186 17024 8188 17025 8185 17025 8182 17025 8189 17026 8188 17026 8182 17026 8190 17027 8189 17027 8182 17027 8191 17028 8190 17028 8182 17028 8181 17029 8191 17029 8182 17029 8183 17030 8182 17030 8187 17030 8192 17031 8186 17031 8185 17031 8193 17032 8186 17032 8192 17032 8187 17033 8186 17033 8193 17033 8192 17034 8185 17034 8188 17034 8194 17035 8188 17035 8189 17035 8194 17036 8192 17036 8188 17036 8195 17037 8189 17037 8190 17037 8195 17038 8194 17038 8189 17038 8195 17039 8190 17039 8191 17039 8196 17040 8191 17040 8181 17040 8195 17041 8191 17041 8196 17041 8196 17042 8181 17042 8176 17042 8197 17043 8176 17043 8179 17043 8197 17044 8196 17044 8176 17044 8197 17045 8179 17045 8171 17045 8198 17046 8171 17046 8174 17046 8198 17047 8197 17047 8171 17047 8198 17048 8174 17048 8166 17048 8198 17049 8166 17049 8161 17049 8199 17050 8161 17050 8164 17050 8199 17051 8198 17051 8161 17051 8199 17052 8164 17052 8157 17052 8200 17053 8157 17053 8160 17053 8200 17054 8199 17054 8157 17054 8200 17055 8160 17055 8153 17055 8201 17056 8153 17056 8150 17056 8201 17057 8200 17057 8153 17057 8201 17058 8150 17058 8146 17058 8202 17059 8146 17059 8141 17059 8202 17060 8201 17060 8146 17060 8202 17061 8141 17061 8136 17061 8203 17062 8136 17062 8130 17062 8203 17063 8202 17063 8136 17063 8204 17064 8130 17064 8124 17064 8204 17065 8203 17065 8130 17065 8204 17066 8124 17066 8114 17066 8205 17067 8114 17067 8091 17067 8205 17068 8204 17068 8114 17068 8092 17069 8205 17069 8091 17069 8206 17070 8068 17070 8069 17070 8207 17071 8206 17071 8069 17071 8207 17072 8069 17072 8072 17072 8208 17073 8209 17073 8068 17073 8210 17074 8068 17074 8209 17074 8211 17075 8208 17075 8068 17075 8206 17076 8211 17076 8068 17076 8212 17077 8093 17077 8068 17077 8213 17078 8212 17078 8068 17078 8214 17079 8213 17079 8068 17079 8215 17080 8214 17080 8068 17080 8216 17081 8215 17081 8068 17081 8210 17082 8216 17082 8068 17082 8217 17083 8218 17083 8209 17083 8219 17084 8209 17084 8218 17084 8220 17085 8217 17085 8209 17085 8221 17086 8220 17086 8209 17086 8222 17087 8221 17087 8209 17087 8223 17088 8222 17088 8209 17088 8224 17089 8223 17089 8209 17089 8225 17090 8224 17090 8209 17090 8226 17091 8225 17091 8209 17091 8227 17092 8226 17092 8209 17092 8208 17093 8227 17093 8209 17093 8210 17094 8209 17094 8214 17094 8219 17095 8214 17095 8209 17095 8228 17096 8229 17096 8218 17096 8230 17097 8218 17097 8229 17097 8231 17098 8228 17098 8218 17098 8232 17099 8231 17099 8218 17099 8233 17100 8232 17100 8218 17100 8234 17101 8233 17101 8218 17101 8235 17102 8234 17102 8218 17102 8217 17103 8235 17103 8218 17103 8219 17104 8218 17104 8230 17104 8236 17105 8237 17105 8229 17105 8238 17106 8229 17106 8237 17106 8239 17107 8236 17107 8229 17107 8240 17108 8239 17108 8229 17108 8241 17109 8240 17109 8229 17109 8228 17110 8241 17110 8229 17110 8230 17111 8229 17111 8238 17111 8242 17112 8243 17112 8237 17112 8244 17113 8237 17113 8243 17113 8245 17114 8242 17114 8237 17114 8236 17115 8245 17115 8237 17115 8238 17116 8237 17116 8244 17116 8246 17117 8247 17117 8243 17117 8248 17118 8243 17118 8247 17118 8249 17119 8246 17119 8243 17119 8242 17120 8249 17120 8243 17120 8244 17121 8243 17121 8248 17121 8250 17122 8251 17122 8247 17122 8252 17123 8247 17123 8251 17123 8246 17124 8250 17124 8247 17124 8248 17125 8247 17125 8252 17125 8253 17126 8254 17126 8251 17126 8252 17127 8251 17127 8254 17127 8250 17128 8253 17128 8251 17128 8255 17129 8256 17129 8254 17129 8257 17130 8254 17130 8256 17130 8253 17131 8255 17131 8254 17131 8252 17132 8254 17132 8257 17132 8258 17133 8259 17133 8256 17133 8257 17134 8256 17134 8259 17134 8255 17135 8258 17135 8256 17135 8260 17136 8261 17136 8259 17136 8262 17137 8259 17137 8261 17137 8258 17138 8260 17138 8259 17138 8257 17139 8259 17139 8262 17139 8260 17140 8263 17140 8261 17140 8264 17141 8261 17141 8263 17141 8262 17142 8261 17142 8264 17142 8265 17143 8266 17143 8263 17143 8264 17144 8263 17144 8266 17144 8260 17145 8265 17145 8263 17145 8265 17146 8267 17146 8266 17146 8264 17147 8266 17147 8267 17147 8268 17148 8269 17148 8267 17148 8270 17149 8267 17149 8269 17149 8265 17150 8268 17150 8267 17150 8264 17151 8267 17151 8270 17151 8271 17152 8272 17152 8269 17152 8270 17153 8269 17153 8272 17153 8268 17154 8271 17154 8269 17154 8273 17155 8274 17155 8272 17155 8275 17156 8272 17156 8274 17156 8271 17157 8273 17157 8272 17157 8270 17158 8272 17158 8275 17158 8273 17159 8276 17159 8274 17159 8277 17160 8274 17160 8276 17160 8277 17161 8275 17161 8274 17161 8273 17162 8278 17162 8276 17162 8279 17163 8276 17163 8278 17163 8279 17164 8277 17164 8276 17164 8273 17165 8280 17165 8278 17165 8279 17166 8278 17166 8280 17166 8281 17167 8280 17167 8273 17167 8282 17168 8279 17168 8280 17168 8283 17169 8282 17169 8280 17169 8284 17170 8283 17170 8280 17170 8281 17171 8284 17171 8280 17171 8285 17172 8273 17172 8271 17172 8285 17173 8281 17173 8273 17173 8286 17174 8271 17174 8268 17174 8286 17175 8285 17175 8271 17175 8287 17176 8268 17176 8265 17176 8288 17177 8286 17177 8268 17177 8287 17178 8288 17178 8268 17178 8289 17179 8265 17179 8260 17179 8289 17180 8287 17180 8265 17180 8290 17181 8260 17181 8258 17181 8291 17182 8289 17182 8260 17182 8292 17183 8291 17183 8260 17183 8290 17184 8292 17184 8260 17184 8293 17185 8258 17185 8255 17185 8294 17186 8290 17186 8258 17186 8293 17187 8294 17187 8258 17187 8295 17188 8255 17188 8253 17188 8296 17189 8293 17189 8255 17189 8297 17190 8296 17190 8255 17190 8295 17191 8297 17191 8255 17191 8298 17192 8253 17192 8250 17192 8299 17193 8295 17193 8253 17193 8298 17194 8299 17194 8253 17194 8300 17195 8250 17195 8246 17195 8301 17196 8298 17196 8250 17196 8300 17197 8301 17197 8250 17197 8302 17198 8246 17198 8249 17198 8302 17199 8300 17199 8246 17199 8303 17200 8249 17200 8242 17200 8304 17201 8302 17201 8249 17201 8303 17202 8304 17202 8249 17202 8305 17203 8242 17203 8245 17203 8305 17204 8303 17204 8242 17204 8306 17205 8245 17205 8236 17205 8306 17206 8305 17206 8245 17206 8307 17207 8236 17207 8239 17207 8307 17208 8306 17208 8236 17208 8308 17209 8239 17209 8240 17209 8308 17210 8307 17210 8239 17210 8308 17211 8240 17211 8241 17211 8309 17212 8241 17212 8228 17212 8309 17213 8308 17213 8241 17213 8309 17214 8228 17214 8231 17214 8310 17215 8231 17215 8232 17215 8310 17216 8309 17216 8231 17216 8310 17217 8232 17217 8233 17217 8311 17218 8233 17218 8234 17218 8311 17219 8310 17219 8233 17219 8311 17220 8234 17220 8235 17220 8312 17221 8235 17221 8217 17221 8312 17222 8311 17222 8235 17222 8312 17223 8217 17223 8220 17223 8313 17224 8220 17224 8221 17224 8313 17225 8312 17225 8220 17225 8313 17226 8221 17226 8222 17226 8314 17227 8222 17227 8223 17227 8314 17228 8313 17228 8222 17228 8315 17229 8223 17229 8224 17229 8315 17230 8314 17230 8223 17230 8315 17231 8224 17231 8225 17231 8315 17232 8225 17232 8226 17232 8316 17233 8226 17233 8227 17233 8316 17234 8315 17234 8226 17234 8316 17235 8227 17235 8208 17235 8317 17236 8208 17236 8211 17236 8317 17237 8316 17237 8208 17237 8207 17238 8211 17238 8206 17238 8207 17239 8317 17239 8211 17239 8075 17240 8074 17240 8078 17240 8318 17241 8078 17241 8077 17241 8319 17242 8078 17242 8318 17242 8075 17243 8078 17243 8319 17243 8318 17244 8077 17244 8080 17244 8081 17245 8318 17245 8080 17245 8320 17246 8319 17246 8318 17246 8320 17247 8318 17247 8321 17247 8322 17248 8321 17248 8318 17248 8322 17249 8318 17249 8081 17249 8075 17250 8319 17250 8320 17250 8323 17251 8324 17251 8325 17251 8326 17252 8325 17252 8324 17252 8327 17253 8323 17253 8325 17253 8328 17254 8327 17254 8325 17254 8326 17255 8328 17255 8325 17255 8329 17256 8330 17256 8324 17256 8331 17257 8324 17257 8330 17257 8323 17258 8329 17258 8324 17258 8332 17259 8326 17259 8324 17259 8331 17260 8332 17260 8324 17260 8333 17261 8334 17261 8330 17261 8335 17262 8330 17262 8334 17262 8329 17263 8333 17263 8330 17263 8335 17264 8331 17264 8330 17264 8333 17265 8336 17265 8334 17265 8337 17266 8334 17266 8336 17266 8337 17267 8335 17267 8334 17267 8338 17268 8339 17268 8336 17268 8337 17269 8336 17269 8339 17269 8333 17270 8338 17270 8336 17270 8340 17271 8341 17271 8339 17271 8342 17272 8339 17272 8341 17272 8338 17273 8340 17273 8339 17273 8342 17274 8337 17274 8339 17274 8343 17275 8344 17275 8341 17275 8345 17276 8341 17276 8344 17276 8340 17277 8343 17277 8341 17277 8345 17278 8342 17278 8341 17278 8346 17279 8347 17279 8344 17279 8348 17280 8344 17280 8347 17280 8343 17281 8346 17281 8344 17281 8348 17282 8345 17282 8344 17282 8349 17283 8350 17283 8347 17283 8348 17284 8347 17284 8350 17284 8346 17285 8349 17285 8347 17285 8351 17286 8352 17286 8350 17286 8353 17287 8350 17287 8352 17287 8349 17288 8351 17288 8350 17288 8353 17289 8348 17289 8350 17289 8354 17290 8355 17290 8352 17290 8353 17291 8352 17291 8355 17291 8351 17292 8354 17292 8352 17292 8356 17293 8357 17293 8355 17293 8358 17294 8355 17294 8357 17294 8354 17295 8356 17295 8355 17295 8358 17296 8353 17296 8355 17296 8359 17297 8360 17297 8357 17297 8358 17298 8357 17298 8360 17298 8356 17299 8359 17299 8357 17299 8361 17300 8362 17300 8360 17300 8363 17301 8360 17301 8362 17301 8359 17302 8361 17302 8360 17302 8363 17303 8358 17303 8360 17303 8364 17304 8365 17304 8362 17304 8366 17305 8362 17305 8365 17305 8361 17306 8364 17306 8362 17306 8366 17307 8363 17307 8362 17307 8367 17308 8368 17308 8365 17308 8366 17309 8365 17309 8368 17309 8364 17310 8367 17310 8365 17310 8369 17311 8370 17311 8368 17311 8371 17312 8368 17312 8370 17312 8372 17313 8369 17313 8368 17313 8367 17314 8372 17314 8368 17314 8371 17315 8366 17315 8368 17315 8373 17316 8374 17316 8370 17316 8375 17317 8370 17317 8374 17317 8369 17318 8373 17318 8370 17318 8375 17319 8371 17319 8370 17319 8376 17320 8377 17320 8374 17320 8375 17321 8374 17321 8377 17321 8373 17322 8376 17322 8374 17322 8378 17323 8379 17323 8377 17323 8380 17324 8377 17324 8379 17324 8376 17325 8378 17325 8377 17325 8380 17326 8375 17326 8377 17326 8381 17327 8382 17327 8379 17327 8380 17328 8379 17328 8382 17328 8378 17329 8381 17329 8379 17329 8383 17330 8384 17330 8382 17330 8385 17331 8382 17331 8384 17331 8381 17332 8383 17332 8382 17332 8385 17333 8380 17333 8382 17333 8386 17334 8387 17334 8384 17334 8388 17335 8384 17335 8387 17335 8383 17336 8386 17336 8384 17336 8388 17337 8385 17337 8384 17337 8389 17338 8390 17338 8387 17338 8388 17339 8387 17339 8390 17339 8386 17340 8389 17340 8387 17340 8389 17341 8391 17341 8390 17341 8392 17342 8390 17342 8391 17342 8392 17343 8388 17343 8390 17343 8389 17344 8393 17344 8391 17344 8394 17345 8391 17345 8393 17345 8394 17346 8392 17346 8391 17346 8395 17347 8396 17347 8393 17347 8397 17348 8393 17348 8396 17348 8398 17349 8395 17349 8393 17349 8389 17350 8398 17350 8393 17350 8397 17351 8394 17351 8393 17351 8399 17352 8400 17352 8396 17352 8401 17353 8396 17353 8400 17353 8395 17354 8399 17354 8396 17354 8401 17355 8397 17355 8396 17355 8402 17356 8403 17356 8400 17356 8404 17357 8400 17357 8403 17357 8399 17358 8402 17358 8400 17358 8405 17359 8401 17359 8400 17359 8404 17360 8405 17360 8400 17360 8406 17361 8407 17361 8403 17361 8404 17362 8403 17362 8407 17362 8402 17363 8406 17363 8403 17363 8408 17364 8409 17364 8407 17364 8410 17365 8407 17365 8409 17365 8406 17366 8408 17366 8407 17366 8410 17367 8404 17367 8407 17367 8411 17368 8412 17368 8409 17368 8413 17369 8409 17369 8412 17369 8408 17370 8411 17370 8409 17370 8413 17371 8410 17371 8409 17371 8414 17372 8415 17372 8412 17372 8413 17373 8412 17373 8415 17373 8411 17374 8414 17374 8412 17374 8416 17375 8417 17375 8415 17375 8418 17376 8415 17376 8417 17376 8419 17377 8416 17377 8415 17377 8414 17378 8419 17378 8415 17378 8418 17379 8413 17379 8415 17379 8420 17380 8421 17380 8417 17380 8422 17381 8417 17381 8421 17381 8416 17382 8420 17382 8417 17382 8422 17383 8418 17383 8417 17383 8423 17384 8424 17384 8421 17384 8422 17385 8421 17385 8424 17385 8420 17386 8423 17386 8421 17386 8425 17387 8426 17387 8424 17387 8427 17388 8424 17388 8426 17388 8428 17389 8425 17389 8424 17389 8423 17390 8428 17390 8424 17390 8427 17391 8422 17391 8424 17391 8429 17392 8430 17392 8426 17392 8427 17393 8426 17393 8430 17393 8425 17394 8429 17394 8426 17394 8431 17395 8432 17395 8430 17395 8433 17396 8430 17396 8432 17396 8429 17397 8431 17397 8430 17397 8433 17398 8427 17398 8430 17398 8434 17399 8435 17399 8432 17399 8433 17400 8432 17400 8435 17400 8431 17401 8434 17401 8432 17401 8436 17402 8437 17402 8435 17402 8438 17403 8435 17403 8437 17403 8434 17404 8436 17404 8435 17404 8438 17405 8433 17405 8435 17405 8439 17406 8440 17406 8437 17406 8438 17407 8437 17407 8440 17407 8436 17408 8439 17408 8437 17408 8441 17409 8442 17409 8440 17409 8443 17410 8440 17410 8442 17410 8439 17411 8441 17411 8440 17411 8443 17412 8438 17412 8440 17412 8444 17413 8445 17413 8442 17413 8443 17414 8442 17414 8445 17414 8441 17415 8444 17415 8442 17415 8446 17416 8447 17416 8445 17416 8448 17417 8445 17417 8447 17417 8444 17418 8446 17418 8445 17418 8448 17419 8443 17419 8445 17419 8449 17420 8450 17420 8447 17420 8448 17421 8447 17421 8450 17421 8446 17422 8449 17422 8447 17422 8451 17423 8452 17423 8450 17423 8453 17424 8450 17424 8452 17424 8449 17425 8451 17425 8450 17425 8453 17426 8448 17426 8450 17426 8454 17427 8455 17427 8452 17427 8453 17428 8452 17428 8455 17428 8456 17429 8454 17429 8452 17429 8451 17430 8456 17430 8452 17430 8457 17431 8458 17431 8455 17431 8459 17432 8455 17432 8458 17432 8454 17433 8457 17433 8455 17433 8459 17434 8453 17434 8455 17434 8460 17435 8321 17435 8458 17435 8322 17436 8458 17436 8321 17436 8457 17437 8460 17437 8458 17437 8322 17438 8459 17438 8458 17438 8460 17439 8320 17439 8321 17439 8461 17440 8320 17440 8460 17440 8461 17441 8075 17441 8320 17441 8461 17442 8460 17442 8457 17442 8462 17443 8457 17443 8454 17443 8462 17444 8461 17444 8457 17444 8462 17445 8454 17445 8456 17445 8463 17446 8456 17446 8451 17446 8463 17447 8462 17447 8456 17447 8463 17448 8451 17448 8449 17448 8463 17449 8449 17449 8446 17449 8464 17450 8446 17450 8444 17450 8464 17451 8463 17451 8446 17451 8464 17452 8444 17452 8441 17452 8465 17453 8441 17453 8439 17453 8465 17454 8464 17454 8441 17454 8466 17455 8439 17455 8436 17455 8466 17456 8465 17456 8439 17456 8466 17457 8436 17457 8434 17457 8466 17458 8434 17458 8431 17458 8467 17459 8431 17459 8429 17459 8467 17460 8466 17460 8431 17460 8467 17461 8429 17461 8425 17461 8468 17462 8425 17462 8428 17462 8468 17463 8467 17463 8425 17463 8468 17464 8428 17464 8423 17464 8468 17465 8423 17465 8420 17465 8469 17466 8420 17466 8416 17466 8469 17467 8468 17467 8420 17467 8469 17468 8416 17468 8419 17468 8470 17469 8419 17469 8414 17469 8470 17470 8469 17470 8419 17470 8471 17471 8414 17471 8411 17471 8471 17472 8470 17472 8414 17472 8471 17473 8411 17473 8408 17473 8472 17474 8408 17474 8406 17474 8472 17475 8471 17475 8408 17475 8473 17476 8406 17476 8402 17476 8473 17477 8472 17477 8406 17477 8474 17478 8402 17478 8399 17478 8474 17479 8473 17479 8402 17479 8475 17480 8399 17480 8395 17480 8475 17481 8474 17481 8399 17481 8476 17482 8395 17482 8398 17482 8476 17483 8475 17483 8395 17483 8477 17484 8398 17484 8389 17484 8477 17485 8476 17485 8398 17485 8478 17486 8389 17486 8386 17486 8478 17487 8477 17487 8389 17487 8479 17488 8386 17488 8383 17488 8479 17489 8478 17489 8386 17489 8480 17490 8383 17490 8381 17490 8480 17491 8479 17491 8383 17491 8480 17492 8381 17492 8378 17492 8481 17493 8378 17493 8376 17493 8481 17494 8480 17494 8378 17494 8482 17495 8376 17495 8373 17495 8482 17496 8481 17496 8376 17496 8482 17497 8373 17497 8369 17497 8483 17498 8369 17498 8372 17498 8483 17499 8482 17499 8369 17499 8483 17500 8372 17500 8367 17500 8484 17501 8367 17501 8364 17501 8484 17502 8483 17502 8367 17502 8484 17503 8364 17503 8361 17503 8485 17504 8361 17504 8359 17504 8485 17505 8484 17505 8361 17505 8486 17506 8359 17506 8356 17506 8486 17507 8485 17507 8359 17507 8486 17508 8356 17508 8354 17508 8487 17509 8354 17509 8351 17509 8487 17510 8486 17510 8354 17510 8487 17511 8351 17511 8349 17511 8488 17512 8349 17512 8346 17512 8488 17513 8487 17513 8349 17513 8489 17514 8346 17514 8343 17514 8489 17515 8488 17515 8346 17515 8489 17516 8343 17516 8340 17516 8490 17517 8340 17517 8338 17517 8490 17518 8489 17518 8340 17518 8490 17519 8338 17519 8333 17519 8491 17520 8333 17520 8329 17520 8491 17521 8490 17521 8333 17521 8492 17522 8329 17522 8323 17522 8493 17523 8491 17523 8329 17523 8492 17524 8493 17524 8329 17524 8494 17525 8323 17525 8327 17525 8494 17526 8492 17526 8323 17526 8495 17527 8327 17527 8328 17527 8282 17528 8327 17528 8495 17528 8496 17529 8327 17529 8282 17529 8494 17530 8327 17530 8496 17530 8497 17531 8495 17531 8328 17531 8194 17532 8497 17532 8328 17532 8194 17533 8328 17533 8192 17533 8498 17534 8192 17534 8328 17534 8499 17535 8498 17535 8328 17535 8500 17536 8501 17536 8502 17536 8326 17537 8499 17537 8328 17537 8503 17538 8495 17538 8497 17538 8282 17539 8495 17539 8503 17539 8504 17540 8505 17540 8506 17540 8196 17541 8506 17541 8505 17541 8507 17542 8504 17542 8506 17542 8508 17543 8507 17543 8506 17543 8197 17544 8508 17544 8506 17544 8197 17545 8506 17545 8196 17545 8503 17546 8497 17546 8505 17546 8195 17547 8505 17547 8497 17547 8504 17548 8503 17548 8505 17548 8195 17549 8196 17549 8505 17549 8195 17550 8497 17550 8194 17550 8279 17551 8503 17551 8504 17551 8282 17552 8503 17552 8279 17552 8277 17553 8504 17553 8507 17553 8279 17554 8504 17554 8277 17554 8509 17555 8507 17555 8508 17555 8275 17556 8507 17556 8509 17556 8277 17557 8507 17557 8275 17557 8510 17558 8511 17558 8095 17558 8096 17559 8095 17559 8511 17559 8094 17560 8510 17560 8095 17560 8512 17561 8513 17561 8511 17561 8092 17562 8511 17562 8513 17562 8510 17563 8512 17563 8511 17563 8100 17564 8511 17564 8099 17564 8092 17565 8099 17565 8511 17565 8101 17566 8511 17566 8100 17566 8102 17567 8511 17567 8101 17567 8096 17568 8511 17568 8102 17568 8514 17569 8515 17569 8513 17569 8205 17570 8513 17570 8515 17570 8512 17571 8514 17571 8513 17571 8092 17572 8513 17572 8205 17572 8516 17573 8517 17573 8515 17573 8204 17574 8515 17574 8517 17574 8514 17575 8516 17575 8515 17575 8205 17576 8515 17576 8204 17576 8516 17577 8518 17577 8517 17577 8204 17578 8517 17578 8518 17578 8519 17579 8520 17579 8518 17579 8203 17580 8518 17580 8520 17580 8516 17581 8519 17581 8518 17581 8204 17582 8518 17582 8203 17582 8521 17583 8522 17583 8520 17583 8202 17584 8520 17584 8522 17584 8519 17585 8521 17585 8520 17585 8203 17586 8520 17586 8202 17586 8523 17587 8524 17587 8522 17587 8202 17588 8522 17588 8524 17588 8521 17589 8523 17589 8522 17589 8523 17590 8525 17590 8524 17590 8201 17591 8524 17591 8525 17591 8202 17592 8524 17592 8201 17592 8526 17593 8527 17593 8525 17593 8201 17594 8525 17594 8527 17594 8523 17595 8526 17595 8525 17595 8528 17596 8529 17596 8527 17596 8200 17597 8527 17597 8529 17597 8526 17598 8528 17598 8527 17598 8201 17599 8527 17599 8200 17599 8528 17600 8530 17600 8529 17600 8200 17601 8529 17601 8530 17601 8531 17602 8532 17602 8530 17602 8199 17603 8530 17603 8532 17603 8528 17604 8531 17604 8530 17604 8200 17605 8530 17605 8199 17605 8533 17606 8534 17606 8532 17606 8199 17607 8532 17607 8534 17607 8531 17608 8533 17608 8532 17608 8535 17609 8536 17609 8534 17609 8199 17610 8534 17610 8536 17610 8533 17611 8535 17611 8534 17611 8535 17612 8537 17612 8536 17612 8198 17613 8536 17613 8537 17613 8199 17614 8536 17614 8198 17614 8538 17615 8539 17615 8537 17615 8198 17616 8537 17616 8539 17616 8535 17617 8538 17617 8537 17617 8540 17618 8541 17618 8539 17618 8197 17619 8539 17619 8541 17619 8538 17620 8540 17620 8539 17620 8198 17621 8539 17621 8197 17621 8509 17622 8508 17622 8541 17622 8197 17623 8541 17623 8508 17623 8540 17624 8509 17624 8541 17624 8270 17625 8509 17625 8540 17625 8270 17626 8275 17626 8509 17626 8270 17627 8540 17627 8538 17627 8264 17628 8538 17628 8535 17628 8264 17629 8270 17629 8538 17629 8264 17630 8535 17630 8533 17630 8262 17631 8533 17631 8531 17631 8262 17632 8264 17632 8533 17632 8262 17633 8531 17633 8528 17633 8257 17634 8528 17634 8526 17634 8257 17635 8262 17635 8528 17635 8252 17636 8526 17636 8523 17636 8252 17637 8257 17637 8526 17637 8252 17638 8523 17638 8521 17638 8248 17639 8521 17639 8519 17639 8248 17640 8252 17640 8521 17640 8244 17641 8519 17641 8516 17641 8244 17642 8248 17642 8519 17642 8238 17643 8516 17643 8514 17643 8238 17644 8244 17644 8516 17644 8230 17645 8514 17645 8512 17645 8230 17646 8238 17646 8514 17646 8219 17647 8512 17647 8510 17647 8219 17648 8230 17648 8512 17648 8214 17649 8510 17649 8094 17649 8219 17650 8510 17650 8214 17650 8212 17651 8094 17651 8093 17651 8213 17652 8094 17652 8212 17652 8214 17653 8094 17653 8213 17653 8216 17654 8214 17654 8215 17654 8210 17655 8214 17655 8216 17655 8092 17656 8085 17656 8097 17656 8092 17657 8097 17657 8098 17657 8092 17658 8098 17658 8099 17658 8542 17659 8064 17659 8063 17659 8543 17660 8062 17660 8064 17660 8544 17661 8543 17661 8064 17661 8545 17662 8544 17662 8064 17662 8546 17663 8545 17663 8064 17663 8547 17664 8546 17664 8064 17664 8548 17665 8547 17665 8064 17665 8548 17666 8064 17666 8542 17666 8549 17667 8063 17667 8070 17667 8550 17668 8551 17668 8063 17668 8552 17669 8063 17669 8551 17669 8553 17670 8550 17670 8063 17670 8554 17671 8553 17671 8063 17671 8549 17672 8554 17672 8063 17672 8555 17673 8542 17673 8063 17673 8556 17674 8555 17674 8063 17674 8557 17675 8556 17675 8063 17675 8558 17676 8557 17676 8063 17676 8559 17677 8558 17677 8063 17677 8560 17678 8559 17678 8063 17678 8552 17679 8560 17679 8063 17679 8060 17680 8062 17680 8543 17680 8561 17681 8543 17681 8544 17681 8561 17682 8060 17682 8543 17682 8562 17683 8544 17683 8545 17683 8561 17684 8544 17684 8562 17684 8562 17685 8545 17685 8546 17685 8547 17686 8563 17686 8546 17686 8564 17687 8546 17687 8563 17687 8562 17688 8546 17688 8564 17688 8547 17689 8565 17689 8563 17689 8564 17690 8563 17690 8565 17690 8566 17691 8567 17691 8565 17691 8568 17692 8565 17692 8567 17692 8547 17693 8566 17693 8565 17693 8564 17694 8565 17694 8568 17694 8566 17695 8569 17695 8567 17695 8568 17696 8567 17696 8569 17696 8566 17697 8570 17697 8569 17697 8571 17698 8569 17698 8570 17698 8568 17699 8569 17699 8571 17699 8566 17700 8572 17700 8570 17700 8571 17701 8570 17701 8572 17701 8566 17702 8573 17702 8572 17702 8571 17703 8572 17703 8573 17703 8574 17704 8575 17704 8573 17704 8576 17705 8573 17705 8575 17705 8566 17706 8574 17706 8573 17706 8571 17707 8573 17707 8576 17707 8574 17708 8577 17708 8575 17708 8576 17709 8575 17709 8577 17709 8574 17710 8578 17710 8577 17710 8579 17711 8577 17711 8578 17711 8576 17712 8577 17712 8579 17712 8574 17713 8580 17713 8578 17713 8581 17714 8578 17714 8580 17714 8579 17715 8578 17715 8581 17715 8582 17716 8583 17716 8580 17716 8581 17717 8580 17717 8583 17717 8574 17718 8582 17718 8580 17718 8582 17719 8584 17719 8583 17719 8585 17720 8583 17720 8584 17720 8581 17721 8583 17721 8585 17721 8582 17722 8586 17722 8584 17722 8587 17723 8584 17723 8586 17723 8585 17724 8584 17724 8587 17724 8588 17725 8589 17725 8586 17725 8590 17726 8586 17726 8589 17726 8582 17727 8588 17727 8586 17727 8587 17728 8586 17728 8590 17728 8588 17729 8591 17729 8589 17729 8592 17730 8589 17730 8591 17730 8590 17731 8589 17731 8592 17731 8593 17732 8594 17732 8591 17732 8595 17733 8591 17733 8594 17733 8588 17734 8593 17734 8591 17734 8592 17735 8591 17735 8595 17735 8593 17736 8596 17736 8594 17736 8597 17737 8594 17737 8596 17737 8595 17738 8594 17738 8597 17738 8598 17739 8599 17739 8596 17739 8600 17740 8596 17740 8599 17740 8593 17741 8598 17741 8596 17741 8597 17742 8596 17742 8600 17742 8601 17743 8602 17743 8599 17743 8603 17744 8599 17744 8602 17744 8598 17745 8601 17745 8599 17745 8600 17746 8599 17746 8603 17746 8604 17747 8605 17747 8602 17747 8606 17748 8602 17748 8605 17748 8601 17749 8604 17749 8602 17749 8603 17750 8602 17750 8606 17750 8607 17751 8608 17751 8605 17751 8609 17752 8605 17752 8608 17752 8604 17753 8607 17753 8605 17753 8610 17754 8605 17754 8609 17754 8606 17755 8605 17755 8610 17755 8611 17756 8612 17756 8608 17756 8613 17757 8608 17757 8612 17757 8614 17758 8611 17758 8608 17758 8607 17759 8614 17759 8608 17759 8615 17760 8608 17760 8613 17760 8609 17761 8608 17761 8615 17761 8616 17762 8617 17762 8612 17762 8618 17763 8612 17763 8617 17763 8619 17764 8616 17764 8612 17764 8611 17765 8619 17765 8612 17765 8613 17766 8612 17766 8618 17766 8620 17767 8621 17767 8617 17767 8622 17768 8617 17768 8621 17768 8623 17769 8620 17769 8617 17769 8624 17770 8623 17770 8617 17770 8616 17771 8624 17771 8617 17771 8625 17772 8617 17772 8622 17772 8618 17773 8617 17773 8625 17773 8626 17774 8627 17774 8621 17774 8628 17775 8621 17775 8627 17775 8629 17776 8626 17776 8621 17776 8630 17777 8629 17777 8621 17777 8631 17778 8630 17778 8621 17778 8620 17779 8631 17779 8621 17779 8632 17780 8621 17780 8628 17780 8633 17781 8621 17781 8632 17781 8622 17782 8621 17782 8633 17782 8634 17783 8635 17783 8627 17783 8636 17784 8627 17784 8635 17784 8637 17785 8634 17785 8627 17785 8638 17786 8637 17786 8627 17786 8639 17787 8638 17787 8627 17787 8626 17788 8639 17788 8627 17788 8640 17789 8627 17789 8636 17789 8628 17790 8627 17790 8640 17790 8641 17791 8642 17791 8635 17791 8643 17792 8635 17792 8642 17792 8644 17793 8641 17793 8635 17793 8645 17794 8644 17794 8635 17794 8646 17795 8645 17795 8635 17795 8647 17796 8646 17796 8635 17796 8648 17797 8647 17797 8635 17797 8649 17798 8648 17798 8635 17798 8650 17799 8649 17799 8635 17799 8634 17800 8650 17800 8635 17800 8651 17801 8635 17801 8643 17801 8652 17802 8635 17802 8651 17802 8636 17803 8635 17803 8652 17803 8653 17804 8642 17804 8641 17804 8654 17805 8642 17805 8653 17805 8655 17806 8642 17806 8654 17806 8643 17807 8642 17807 8655 17807 8653 17808 8641 17808 8644 17808 8656 17809 8644 17809 8645 17809 8656 17810 8653 17810 8644 17810 8657 17811 8645 17811 8646 17811 8657 17812 8656 17812 8645 17812 8657 17813 8646 17813 8647 17813 8658 17814 8647 17814 8648 17814 8657 17815 8647 17815 8658 17815 8658 17816 8648 17816 8649 17816 8658 17817 8649 17817 8650 17817 8659 17818 8650 17818 8634 17818 8659 17819 8658 17819 8650 17819 8659 17820 8634 17820 8637 17820 8659 17821 8637 17821 8638 17821 8659 17822 8638 17822 8639 17822 8660 17823 8639 17823 8626 17823 8660 17824 8659 17824 8639 17824 8660 17825 8626 17825 8629 17825 8660 17826 8629 17826 8630 17826 8660 17827 8630 17827 8631 17827 8661 17828 8631 17828 8620 17828 8661 17829 8660 17829 8631 17829 8661 17830 8620 17830 8623 17830 8661 17831 8623 17831 8624 17831 8662 17832 8624 17832 8616 17832 8662 17833 8661 17833 8624 17833 8662 17834 8616 17834 8619 17834 8662 17835 8619 17835 8611 17835 8663 17836 8611 17836 8614 17836 8663 17837 8662 17837 8611 17837 8663 17838 8614 17838 8607 17838 8664 17839 8607 17839 8604 17839 8664 17840 8663 17840 8607 17840 8664 17841 8604 17841 8601 17841 8665 17842 8601 17842 8598 17842 8665 17843 8664 17843 8601 17843 8666 17844 8598 17844 8593 17844 8666 17845 8665 17845 8598 17845 8667 17846 8593 17846 8588 17846 8667 17847 8666 17847 8593 17847 8667 17848 8588 17848 8582 17848 8668 17849 8582 17849 8574 17849 8668 17850 8667 17850 8582 17850 8669 17851 8574 17851 8566 17851 8669 17852 8668 17852 8574 17852 8548 17853 8566 17853 8547 17853 8548 17854 8669 17854 8566 17854 8670 17855 8671 17855 8672 17855 8673 17856 8672 17856 8671 17856 8674 17857 8670 17857 8672 17857 8675 17858 8674 17858 8672 17858 8676 17859 8675 17859 8672 17859 8673 17860 8676 17860 8672 17860 8670 17861 8677 17861 8671 17861 8678 17862 8671 17862 8677 17862 8679 17863 8673 17863 8671 17863 8678 17864 8679 17864 8671 17864 8670 17865 8680 17865 8677 17865 8681 17866 8677 17866 8680 17866 8681 17867 8678 17867 8677 17867 8670 17868 8682 17868 8680 17868 8681 17869 8680 17869 8682 17869 8683 17870 8682 17870 8670 17870 8684 17871 8681 17871 8682 17871 8685 17872 8684 17872 8682 17872 8683 17873 8685 17873 8682 17873 8686 17874 8670 17874 8674 17874 8686 17875 8683 17875 8670 17875 8675 17876 8687 17876 8674 17876 8686 17877 8674 17877 8687 17877 8688 17878 8689 17878 8687 17878 8690 17879 8687 17879 8689 17879 8675 17880 8688 17880 8687 17880 8690 17881 8686 17881 8687 17881 8691 17882 8692 17882 8689 17882 8693 17883 8689 17883 8692 17883 8688 17884 8691 17884 8689 17884 8693 17885 8690 17885 8689 17885 8694 17886 8695 17886 8692 17886 8696 17887 8692 17887 8695 17887 8697 17888 8694 17888 8692 17888 8691 17889 8697 17889 8692 17889 8696 17890 8693 17890 8692 17890 8698 17891 8699 17891 8695 17891 8700 17892 8695 17892 8699 17892 8694 17893 8698 17893 8695 17893 8700 17894 8696 17894 8695 17894 8701 17895 8702 17895 8699 17895 8703 17896 8699 17896 8702 17896 8698 17897 8701 17897 8699 17897 8703 17898 8700 17898 8699 17898 8704 17899 8705 17899 8702 17899 8706 17900 8702 17900 8705 17900 8701 17901 8704 17901 8702 17901 8706 17902 8703 17902 8702 17902 8707 17903 8708 17903 8705 17903 8709 17904 8705 17904 8708 17904 8710 17905 8707 17905 8705 17905 8704 17906 8710 17906 8705 17906 8709 17907 8706 17907 8705 17907 8711 17908 8712 17908 8708 17908 8713 17909 8708 17909 8712 17909 8707 17910 8711 17910 8708 17910 8713 17911 8709 17911 8708 17911 8714 17912 8715 17912 8712 17912 8716 17913 8712 17913 8715 17913 8711 17914 8714 17914 8712 17914 8716 17915 8713 17915 8712 17915 8714 17916 8717 17916 8715 17916 8718 17917 8715 17917 8717 17917 8718 17918 8716 17918 8715 17918 8719 17919 8720 17919 8717 17919 8718 17920 8717 17920 8720 17920 8714 17921 8719 17921 8717 17921 8721 17922 8722 17922 8720 17922 8723 17923 8720 17923 8722 17923 8724 17924 8721 17924 8720 17924 8719 17925 8724 17925 8720 17925 8723 17926 8718 17926 8720 17926 8725 17927 8726 17927 8722 17927 8727 17928 8722 17928 8726 17928 8721 17929 8725 17929 8722 17929 8728 17930 8723 17930 8722 17930 8729 17931 8728 17931 8722 17931 8727 17932 8729 17932 8722 17932 8730 17933 8731 17933 8726 17933 8732 17934 8726 17934 8731 17934 8725 17935 8730 17935 8726 17935 8733 17936 8727 17936 8726 17936 8732 17937 8733 17937 8726 17937 8734 17938 8735 17938 8731 17938 8736 17939 8731 17939 8735 17939 8730 17940 8734 17940 8731 17940 8737 17941 8732 17941 8731 17941 8736 17942 8737 17942 8731 17942 8738 17943 8739 17943 8735 17943 8740 17944 8735 17944 8739 17944 8734 17945 8738 17945 8735 17945 8740 17946 8736 17946 8735 17946 8741 17947 8742 17947 8739 17947 8743 17948 8739 17948 8742 17948 8738 17949 8741 17949 8739 17949 8744 17950 8740 17950 8739 17950 8743 17951 8744 17951 8739 17951 8741 17952 8745 17952 8742 17952 8746 17953 8742 17953 8745 17953 8746 17954 8743 17954 8742 17954 8741 17955 8747 17955 8745 17955 8746 17956 8745 17956 8747 17956 8748 17957 8749 17957 8747 17957 8750 17958 8747 17958 8749 17958 8741 17959 8748 17959 8747 17959 8750 17960 8746 17960 8747 17960 8748 17961 8751 17961 8749 17961 8752 17962 8749 17962 8751 17962 8752 17963 8750 17963 8749 17963 8748 17964 8753 17964 8751 17964 8752 17965 8751 17965 8753 17965 8754 17966 8755 17966 8753 17966 8756 17967 8753 17967 8755 17967 8748 17968 8754 17968 8753 17968 8756 17969 8752 17969 8753 17969 8754 17970 8757 17970 8755 17970 8756 17971 8755 17971 8757 17971 8754 17972 8758 17972 8757 17972 8759 17973 8757 17973 8758 17973 8759 17974 8756 17974 8757 17974 8754 17975 8760 17975 8758 17975 8761 17976 8758 17976 8760 17976 8761 17977 8759 17977 8758 17977 8762 17978 8763 17978 8760 17978 8764 17979 8760 17979 8763 17979 8754 17980 8762 17980 8760 17980 8764 17981 8761 17981 8760 17981 8762 17982 8765 17982 8763 17982 8764 17983 8763 17983 8765 17983 8762 17984 8766 17984 8765 17984 8767 17985 8765 17985 8766 17985 8767 17986 8764 17986 8765 17986 8768 17987 8769 17987 8766 17987 8767 17988 8766 17988 8769 17988 8762 17989 8768 17989 8766 17989 8768 17990 8770 17990 8769 17990 8771 17991 8769 17991 8770 17991 8771 17992 8767 17992 8769 17992 8768 17993 8772 17993 8770 17993 8773 17994 8770 17994 8772 17994 8773 17995 8771 17995 8770 17995 8070 17996 8774 17996 8772 17996 8775 17997 8772 17997 8774 17997 8768 17998 8070 17998 8772 17998 8775 17999 8773 17999 8772 17999 8070 18000 8050 18000 8774 18000 8775 18001 8774 18001 8050 18001 8775 18002 8050 18002 8052 18002 8776 18003 8070 18003 8768 18003 8777 18004 8549 18004 8070 18004 8778 18005 8777 18005 8070 18005 8779 18006 8778 18006 8070 18006 8780 18007 8779 18007 8070 18007 8776 18008 8780 18008 8070 18008 8780 18009 8768 18009 8762 18009 8776 18010 8768 18010 8780 18010 8781 18011 8762 18011 8754 18011 8781 18012 8780 18012 8762 18012 8782 18013 8754 18013 8748 18013 8782 18014 8781 18014 8754 18014 8783 18015 8748 18015 8741 18015 8783 18016 8782 18016 8748 18016 8784 18017 8741 18017 8738 18017 8784 18018 8783 18018 8741 18018 8785 18019 8738 18019 8734 18019 8785 18020 8784 18020 8738 18020 8786 18021 8734 18021 8730 18021 8786 18022 8785 18022 8734 18022 8786 18023 8730 18023 8725 18023 8787 18024 8725 18024 8721 18024 8787 18025 8786 18025 8725 18025 8787 18026 8721 18026 8724 18026 8788 18027 8724 18027 8719 18027 8788 18028 8787 18028 8724 18028 8788 18029 8719 18029 8714 18029 8789 18030 8714 18030 8711 18030 8789 18031 8788 18031 8714 18031 8789 18032 8711 18032 8707 18032 8790 18033 8707 18033 8710 18033 8790 18034 8789 18034 8707 18034 8790 18035 8710 18035 8704 18035 8790 18036 8704 18036 8701 18036 8790 18037 8701 18037 8698 18037 8791 18038 8698 18038 8694 18038 8791 18039 8790 18039 8698 18039 8791 18040 8694 18040 8697 18040 8791 18041 8697 18041 8691 18041 8676 18042 8691 18042 8688 18042 8676 18043 8791 18043 8691 18043 8676 18044 8688 18044 8675 18044 8054 18045 8053 18045 8056 18045 8059 18046 8056 18046 8055 18046 8792 18047 8056 18047 8059 18047 8054 18048 8056 18048 8792 18048 8059 18049 8055 18049 8058 18049 8793 18050 8792 18050 8059 18050 8794 18051 8793 18051 8059 18051 8794 18052 8059 18052 8057 18052 8795 18053 8792 18053 8793 18053 8054 18054 8792 18054 8795 18054 8796 18055 8797 18055 8798 18055 8799 18056 8798 18056 8797 18056 8800 18057 8796 18057 8798 18057 8801 18058 8800 18058 8798 18058 8799 18059 8801 18059 8798 18059 8796 18060 8802 18060 8797 18060 8803 18061 8797 18061 8802 18061 8803 18062 8799 18062 8797 18062 8804 18063 8805 18063 8802 18063 8803 18064 8802 18064 8805 18064 8796 18065 8804 18065 8802 18065 8806 18066 8807 18066 8805 18066 8808 18067 8805 18067 8807 18067 8804 18068 8806 18068 8805 18068 8808 18069 8803 18069 8805 18069 8809 18070 8810 18070 8807 18070 8808 18071 8807 18071 8810 18071 8806 18072 8809 18072 8807 18072 8811 18073 8812 18073 8810 18073 8813 18074 8810 18074 8812 18074 8809 18075 8811 18075 8810 18075 8813 18076 8808 18076 8810 18076 8814 18077 8815 18077 8812 18077 8816 18078 8812 18078 8815 18078 8811 18079 8814 18079 8812 18079 8816 18080 8813 18080 8812 18080 8817 18081 8818 18081 8815 18081 8819 18082 8815 18082 8818 18082 8814 18083 8817 18083 8815 18083 8819 18084 8816 18084 8815 18084 8820 18085 8821 18085 8818 18085 8819 18086 8818 18086 8821 18086 8817 18087 8820 18087 8818 18087 8822 18088 8823 18088 8821 18088 8824 18089 8821 18089 8823 18089 8820 18090 8822 18090 8821 18090 8824 18091 8819 18091 8821 18091 8825 18092 8826 18092 8823 18092 8824 18093 8823 18093 8826 18093 8822 18094 8825 18094 8823 18094 8827 18095 8828 18095 8826 18095 8829 18096 8826 18096 8828 18096 8825 18097 8827 18097 8826 18097 8829 18098 8824 18098 8826 18098 8830 18099 8831 18099 8828 18099 8832 18100 8828 18100 8831 18100 8827 18101 8830 18101 8828 18101 8832 18102 8829 18102 8828 18102 8833 18103 8834 18103 8831 18103 8832 18104 8831 18104 8834 18104 8830 18105 8833 18105 8831 18105 8835 18106 8836 18106 8834 18106 8837 18107 8834 18107 8836 18107 8833 18108 8835 18108 8834 18108 8837 18109 8832 18109 8834 18109 8838 18110 8839 18110 8836 18110 8837 18111 8836 18111 8839 18111 8835 18112 8838 18112 8836 18112 8840 18113 8841 18113 8839 18113 8842 18114 8839 18114 8841 18114 8838 18115 8840 18115 8839 18115 8842 18116 8837 18116 8839 18116 8843 18117 8844 18117 8841 18117 8845 18118 8841 18118 8844 18118 8840 18119 8843 18119 8841 18119 8845 18120 8842 18120 8841 18120 8846 18121 8847 18121 8844 18121 8845 18122 8844 18122 8847 18122 8843 18123 8846 18123 8844 18123 8848 18124 8849 18124 8847 18124 8850 18125 8847 18125 8849 18125 8846 18126 8848 18126 8847 18126 8850 18127 8845 18127 8847 18127 8851 18128 8852 18128 8849 18128 8853 18129 8849 18129 8852 18129 8848 18130 8851 18130 8849 18130 8853 18131 8850 18131 8849 18131 8854 18132 8855 18132 8852 18132 8853 18133 8852 18133 8855 18133 8851 18134 8854 18134 8852 18134 8856 18135 8857 18135 8855 18135 8858 18136 8855 18136 8857 18136 8854 18137 8856 18137 8855 18137 8858 18138 8853 18138 8855 18138 8859 18139 8860 18139 8857 18139 8858 18140 8857 18140 8860 18140 8856 18141 8859 18141 8857 18141 8859 18142 8861 18142 8860 18142 8862 18143 8860 18143 8861 18143 8862 18144 8858 18144 8860 18144 8863 18145 8864 18145 8861 18145 8862 18146 8861 18146 8864 18146 8859 18147 8863 18147 8861 18147 8865 18148 8866 18148 8864 18148 8867 18149 8864 18149 8866 18149 8868 18150 8865 18150 8864 18150 8863 18151 8868 18151 8864 18151 8867 18152 8862 18152 8864 18152 8869 18153 8870 18153 8866 18153 8871 18154 8866 18154 8870 18154 8872 18155 8869 18155 8866 18155 8865 18156 8872 18156 8866 18156 8873 18157 8867 18157 8866 18157 8871 18158 8873 18158 8866 18158 8874 18159 8875 18159 8870 18159 8876 18160 8870 18160 8875 18160 8869 18161 8874 18161 8870 18161 8876 18162 8871 18162 8870 18162 8877 18163 8878 18163 8875 18163 8879 18164 8875 18164 8878 18164 8874 18165 8877 18165 8875 18165 8880 18166 8876 18166 8875 18166 8879 18167 8880 18167 8875 18167 8881 18168 8882 18168 8878 18168 8883 18169 8878 18169 8882 18169 8877 18170 8881 18170 8878 18170 8883 18171 8879 18171 8878 18171 8884 18172 8885 18172 8882 18172 8886 18173 8882 18173 8885 18173 8881 18174 8884 18174 8882 18174 8886 18175 8883 18175 8882 18175 8887 18176 8888 18176 8885 18176 8889 18177 8885 18177 8888 18177 8884 18178 8887 18178 8885 18178 8889 18179 8886 18179 8885 18179 8890 18180 8891 18180 8888 18180 8889 18181 8888 18181 8891 18181 8887 18182 8890 18182 8888 18182 8892 18183 8893 18183 8891 18183 8894 18184 8891 18184 8893 18184 8890 18185 8892 18185 8891 18185 8894 18186 8889 18186 8891 18186 8895 18187 8896 18187 8893 18187 8897 18188 8893 18188 8896 18188 8898 18189 8895 18189 8893 18189 8892 18190 8898 18190 8893 18190 8897 18191 8894 18191 8893 18191 8899 18192 8900 18192 8896 18192 8897 18193 8896 18193 8900 18193 8895 18194 8899 18194 8896 18194 8901 18195 8902 18195 8900 18195 8903 18196 8900 18196 8902 18196 8899 18197 8901 18197 8900 18197 8903 18198 8897 18198 8900 18198 8904 18199 8905 18199 8902 18199 8903 18200 8902 18200 8905 18200 8901 18201 8904 18201 8902 18201 8906 18202 8907 18202 8905 18202 8908 18203 8905 18203 8907 18203 8904 18204 8906 18204 8905 18204 8908 18205 8903 18205 8905 18205 8906 18206 8909 18206 8907 18206 8908 18207 8907 18207 8909 18207 8910 18208 8911 18208 8909 18208 8912 18209 8909 18209 8911 18209 8906 18210 8910 18210 8909 18210 8912 18211 8908 18211 8909 18211 8910 18212 8913 18212 8911 18212 8912 18213 8911 18213 8913 18213 8914 18214 8915 18214 8913 18214 8916 18215 8913 18215 8915 18215 8910 18216 8914 18216 8913 18216 8916 18217 8912 18217 8913 18217 8917 18218 8918 18218 8915 18218 8916 18219 8915 18219 8918 18219 8914 18220 8917 18220 8915 18220 8919 18221 8920 18221 8918 18221 8921 18222 8918 18222 8920 18222 8917 18223 8919 18223 8918 18223 8921 18224 8916 18224 8918 18224 8922 18225 8923 18225 8920 18225 8921 18226 8920 18226 8923 18226 8919 18227 8922 18227 8920 18227 8924 18228 8925 18228 8923 18228 8926 18229 8923 18229 8925 18229 8922 18230 8924 18230 8923 18230 8926 18231 8921 18231 8923 18231 8795 18232 8793 18232 8925 18232 8794 18233 8925 18233 8793 18233 8924 18234 8795 18234 8925 18234 8794 18235 8926 18235 8925 18235 8927 18236 8795 18236 8924 18236 8927 18237 8054 18237 8795 18237 8928 18238 8924 18238 8922 18238 8928 18239 8927 18239 8924 18239 8928 18240 8922 18240 8919 18240 8929 18241 8919 18241 8917 18241 8929 18242 8928 18242 8919 18242 8929 18243 8917 18243 8914 18243 8930 18244 8914 18244 8910 18244 8930 18245 8929 18245 8914 18245 8931 18246 8910 18246 8906 18246 8931 18247 8930 18247 8910 18247 8932 18248 8906 18248 8904 18248 8932 18249 8931 18249 8906 18249 8932 18250 8904 18250 8901 18250 8933 18251 8901 18251 8899 18251 8933 18252 8932 18252 8901 18252 8933 18253 8899 18253 8895 18253 8934 18254 8895 18254 8898 18254 8934 18255 8933 18255 8895 18255 8934 18256 8898 18256 8892 18256 8935 18257 8892 18257 8890 18257 8935 18258 8934 18258 8892 18258 8936 18259 8890 18259 8887 18259 8936 18260 8935 18260 8890 18260 8937 18261 8887 18261 8884 18261 8937 18262 8936 18262 8887 18262 8938 18263 8884 18263 8881 18263 8938 18264 8937 18264 8884 18264 8939 18265 8881 18265 8877 18265 8939 18266 8938 18266 8881 18266 8940 18267 8877 18267 8874 18267 8940 18268 8939 18268 8877 18268 8941 18269 8874 18269 8869 18269 8941 18270 8940 18270 8874 18270 8942 18271 8869 18271 8872 18271 8942 18272 8941 18272 8869 18272 8943 18273 8872 18273 8865 18273 8943 18274 8942 18274 8872 18274 8943 18275 8865 18275 8868 18275 8944 18276 8868 18276 8863 18276 8944 18277 8943 18277 8868 18277 8945 18278 8863 18278 8859 18278 8945 18279 8944 18279 8863 18279 8945 18280 8859 18280 8856 18280 8946 18281 8856 18281 8854 18281 8946 18282 8945 18282 8856 18282 8947 18283 8854 18283 8851 18283 8947 18284 8946 18284 8854 18284 8947 18285 8851 18285 8848 18285 8948 18286 8848 18286 8846 18286 8948 18287 8947 18287 8848 18287 8949 18288 8846 18288 8843 18288 8949 18289 8948 18289 8846 18289 8949 18290 8843 18290 8840 18290 8950 18291 8840 18291 8838 18291 8950 18292 8949 18292 8840 18292 8951 18293 8838 18293 8835 18293 8951 18294 8950 18294 8838 18294 8951 18295 8835 18295 8833 18295 8952 18296 8833 18296 8830 18296 8952 18297 8951 18297 8833 18297 8952 18298 8830 18298 8827 18298 8953 18299 8827 18299 8825 18299 8953 18300 8952 18300 8827 18300 8954 18301 8825 18301 8822 18301 8954 18302 8953 18302 8825 18302 8954 18303 8822 18303 8820 18303 8955 18304 8820 18304 8817 18304 8955 18305 8954 18305 8820 18305 8956 18306 8817 18306 8814 18306 8956 18307 8955 18307 8817 18307 8956 18308 8814 18308 8811 18308 8957 18309 8811 18309 8809 18309 8957 18310 8956 18310 8811 18310 8958 18311 8809 18311 8806 18311 8958 18312 8957 18312 8809 18312 8958 18313 8806 18313 8804 18313 8959 18314 8804 18314 8796 18314 8959 18315 8958 18315 8804 18315 8960 18316 8796 18316 8800 18316 8959 18317 8796 18317 8960 18317 8961 18318 8800 18318 8801 18318 8684 18319 8800 18319 8961 18319 8960 18320 8800 18320 8684 18320 8962 18321 8961 18321 8801 18321 8656 18322 8962 18322 8801 18322 8656 18323 8801 18323 8653 18323 8963 18324 8653 18324 8801 18324 8964 18325 8963 18325 8801 18325 8799 18326 8964 18326 8801 18326 8965 18327 8961 18327 8962 18327 8684 18328 8961 18328 8965 18328 8966 18329 8967 18329 8968 18329 8969 18330 8968 18330 8967 18330 8970 18331 8966 18331 8968 18331 8971 18332 8970 18332 8968 18332 8972 18333 8971 18333 8968 18333 8972 18334 8968 18334 8969 18334 8965 18335 8962 18335 8967 18335 8657 18336 8967 18336 8962 18336 8966 18337 8965 18337 8967 18337 8969 18338 8967 18338 8973 18338 8657 18339 8973 18339 8967 18339 8657 18340 8962 18340 8656 18340 8681 18341 8965 18341 8966 18341 8684 18342 8965 18342 8681 18342 8678 18343 8966 18343 8970 18343 8681 18344 8966 18344 8678 18344 8974 18345 8970 18345 8971 18345 8975 18346 8970 18346 8974 18346 8678 18347 8970 18347 8975 18347 8976 18348 8977 18348 8551 18348 8552 18349 8551 18349 8977 18349 8550 18350 8976 18350 8551 18350 8976 18351 8978 18351 8977 18351 8979 18352 8977 18352 8978 18352 8552 18353 8977 18353 8560 18353 8979 18354 8560 18354 8977 18354 8980 18355 8981 18355 8978 18355 8979 18356 8978 18356 8981 18356 8976 18357 8980 18357 8978 18357 8982 18358 8983 18358 8981 18358 8984 18359 8981 18359 8983 18359 8980 18360 8982 18360 8981 18360 8979 18361 8981 18361 8984 18361 8985 18362 8986 18362 8983 18362 8987 18363 8983 18363 8986 18363 8982 18364 8985 18364 8983 18364 8984 18365 8983 18365 8987 18365 8988 18366 8989 18366 8986 18366 8990 18367 8986 18367 8989 18367 8985 18368 8988 18368 8986 18368 8987 18369 8986 18369 8990 18369 8991 18370 8992 18370 8989 18370 8990 18371 8989 18371 8992 18371 8988 18372 8991 18372 8989 18372 8993 18373 8994 18373 8992 18373 8995 18374 8992 18374 8994 18374 8991 18375 8993 18375 8992 18375 8990 18376 8992 18376 8995 18376 8993 18377 8996 18377 8994 18377 8997 18378 8994 18378 8996 18378 8995 18379 8994 18379 8997 18379 8998 18380 8999 18380 8996 18380 8997 18381 8996 18381 8999 18381 8993 18382 8998 18382 8996 18382 9000 18383 9001 18383 8999 18383 9002 18384 8999 18384 9001 18384 8998 18385 9000 18385 8999 18385 8997 18386 8999 18386 9002 18386 9003 18387 9004 18387 9001 18387 9002 18388 9001 18388 9004 18388 9000 18389 9003 18389 9001 18389 9005 18390 9006 18390 9004 18390 9007 18391 9004 18391 9006 18391 9003 18392 9005 18392 9004 18392 9002 18393 9004 18393 9007 18393 9008 18394 9009 18394 9006 18394 9007 18395 9006 18395 9009 18395 9005 18396 9008 18396 9006 18396 9008 18397 9010 18397 9009 18397 9007 18398 9009 18398 9010 18398 9011 18399 9012 18399 9010 18399 9013 18400 9010 18400 9012 18400 9008 18401 9011 18401 9010 18401 9007 18402 9010 18402 9013 18402 9014 18403 9015 18403 9012 18403 9013 18404 9012 18404 9015 18404 9011 18405 9014 18405 9012 18405 9016 18406 9017 18406 9015 18406 9013 18407 9015 18407 9017 18407 9014 18408 9016 18408 9015 18408 9018 18409 9019 18409 9017 18409 9020 18410 9017 18410 9019 18410 9016 18411 9018 18411 9017 18411 9013 18412 9017 18412 9020 18412 9021 18413 9022 18413 9019 18413 9020 18414 9019 18414 9022 18414 9018 18415 9021 18415 9019 18415 9021 18416 9023 18416 9022 18416 9020 18417 9022 18417 9023 18417 9024 18418 9025 18418 9023 18418 9020 18419 9023 18419 9025 18419 9021 18420 9024 18420 9023 18420 9026 18421 9027 18421 9025 18421 9028 18422 9025 18422 9027 18422 9024 18423 9026 18423 9025 18423 9020 18424 9025 18424 9028 18424 9029 18425 9030 18425 9027 18425 9028 18426 9027 18426 9030 18426 9026 18427 9029 18427 9027 18427 9031 18428 9032 18428 9030 18428 9028 18429 9030 18429 9032 18429 9029 18430 9031 18430 9030 18430 9033 18431 9034 18431 9032 18431 9028 18432 9032 18432 9034 18432 9031 18433 9033 18433 9032 18433 9033 18434 9035 18434 9034 18434 8972 18435 9034 18435 9035 18435 9028 18436 9034 18436 8972 18436 9036 18437 9037 18437 9035 18437 8972 18438 9035 18438 9037 18438 9033 18439 9036 18439 9035 18439 8974 18440 8971 18440 9037 18440 8972 18441 9037 18441 8971 18441 9036 18442 8974 18442 9037 18442 8975 18443 8974 18443 9036 18443 9038 18444 9036 18444 9033 18444 9038 18445 8975 18445 9036 18445 9038 18446 9033 18446 9031 18446 9038 18447 9031 18447 9029 18447 9038 18448 9029 18448 9026 18448 9039 18449 9026 18449 9024 18449 9039 18450 9038 18450 9026 18450 9039 18451 9024 18451 9021 18451 9039 18452 9021 18452 9018 18452 9040 18453 9018 18453 9016 18453 9040 18454 9039 18454 9018 18454 9040 18455 9016 18455 9014 18455 9040 18456 9014 18456 9011 18456 9041 18457 9011 18457 9008 18457 9041 18458 9040 18458 9011 18458 9041 18459 9008 18459 9005 18459 9042 18460 9005 18460 9003 18460 9042 18461 9041 18461 9005 18461 9043 18462 9003 18462 9000 18462 9043 18463 9042 18463 9003 18463 9043 18464 9000 18464 8998 18464 9044 18465 8998 18465 8993 18465 9044 18466 9043 18466 8998 18466 9045 18467 8993 18467 8991 18467 9045 18468 9044 18468 8993 18468 9046 18469 8991 18469 8988 18469 9046 18470 9045 18470 8991 18470 9047 18471 8988 18471 8985 18471 9047 18472 9046 18472 8988 18472 9047 18473 8985 18473 8982 18473 9048 18474 8982 18474 8980 18474 9048 18475 9047 18475 8982 18475 9049 18476 8980 18476 8976 18476 9049 18477 9048 18477 8980 18477 8554 18478 8976 18478 8550 18478 9049 18479 8976 18479 8554 18479 8554 18480 8550 18480 8553 18480 8777 18481 8554 18481 8549 18481 9049 18482 8554 18482 8777 18482 8779 18483 8777 18483 8778 18483 8780 18484 8777 18484 8779 18484 9050 18485 8777 18485 8780 18485 9050 18486 9049 18486 8777 18486 9050 18487 8780 18487 8781 18487 8548 18488 8542 18488 8555 18488 9051 18489 8555 18489 8556 18489 9051 18490 8548 18490 8555 18490 9051 18491 8556 18491 8557 18491 9051 18492 8557 18492 8558 18492 8979 18493 8558 18493 8559 18493 8979 18494 9051 18494 8558 18494 8979 18495 8559 18495 8560 18495 8973 18496 8658 18496 8659 18496 8657 18497 8658 18497 8973 18497 9052 18498 8659 18498 8660 18498 9052 18499 8973 18499 8659 18499 9053 18500 8660 18500 8661 18500 9053 18501 9052 18501 8660 18501 9054 18502 8661 18502 8662 18502 9054 18503 9053 18503 8661 18503 9055 18504 8662 18504 8663 18504 9055 18505 9054 18505 8662 18505 9056 18506 8663 18506 8664 18506 9056 18507 9055 18507 8663 18507 9057 18508 8664 18508 8665 18508 9057 18509 9056 18509 8664 18509 9058 18510 8665 18510 8666 18510 9058 18511 9057 18511 8665 18511 9059 18512 8666 18512 8667 18512 9059 18513 9058 18513 8666 18513 9060 18514 8667 18514 8668 18514 9060 18515 9059 18515 8667 18515 9061 18516 8668 18516 8669 18516 9061 18517 9060 18517 8668 18517 9062 18518 8669 18518 8548 18518 9062 18519 9061 18519 8669 18519 9051 18520 9062 18520 8548 18520 8969 18521 8973 18521 9052 18521 8972 18522 9052 18522 9053 18522 8972 18523 8969 18523 9052 18523 9028 18524 9053 18524 9054 18524 9028 18525 8972 18525 9053 18525 9020 18526 9054 18526 9055 18526 9020 18527 9028 18527 9054 18527 9013 18528 9055 18528 9056 18528 9013 18529 9020 18529 9055 18529 9007 18530 9056 18530 9057 18530 9007 18531 9013 18531 9056 18531 9002 18532 9057 18532 9058 18532 9002 18533 9007 18533 9057 18533 8997 18534 9058 18534 9059 18534 8997 18535 9002 18535 9058 18535 8995 18536 9059 18536 9060 18536 8995 18537 8997 18537 9059 18537 8990 18538 9060 18538 9061 18538 8990 18539 8995 18539 9060 18539 8987 18540 9061 18540 9062 18540 8987 18541 8990 18541 9061 18541 8984 18542 9062 18542 9051 18542 8984 18543 8987 18543 9062 18543 8979 18544 8984 18544 9051 18544 9063 18545 8654 18545 8653 18545 8963 18546 9063 18546 8653 18546 9064 18547 8654 18547 9063 18547 8655 18548 8654 18548 9064 18548 9064 18549 9063 18549 8963 18549 8803 18550 8963 18550 8964 18550 9064 18551 8963 18551 8803 18551 8803 18552 8964 18552 8799 18552 9065 18553 8057 18553 8061 18553 9065 18554 8794 18554 8057 18554 8561 18555 8061 18555 8060 18555 8561 18556 9065 18556 8061 18556 9064 18557 8803 18557 8808 18557 9066 18558 8808 18558 8813 18558 9066 18559 9064 18559 8808 18559 9067 18560 8813 18560 8816 18560 9067 18561 9066 18561 8813 18561 9068 18562 8816 18562 8819 18562 9068 18563 9067 18563 8816 18563 9069 18564 8819 18564 8824 18564 9069 18565 9068 18565 8819 18565 9070 18566 8824 18566 8829 18566 9070 18567 9069 18567 8824 18567 9071 18568 8829 18568 8832 18568 9071 18569 9070 18569 8829 18569 9072 18570 8832 18570 8837 18570 9072 18571 9071 18571 8832 18571 9073 18572 8837 18572 8842 18572 9073 18573 9072 18573 8837 18573 9074 18574 8842 18574 8845 18574 9074 18575 9073 18575 8842 18575 9075 18576 8845 18576 8850 18576 9075 18577 9074 18577 8845 18577 9076 18578 8850 18578 8853 18578 9076 18579 9075 18579 8850 18579 9077 18580 8853 18580 8858 18580 9077 18581 9076 18581 8853 18581 9078 18582 8858 18582 8862 18582 9078 18583 9077 18583 8858 18583 9079 18584 8862 18584 8867 18584 9079 18585 9078 18585 8862 18585 9080 18586 8867 18586 8873 18586 9080 18587 9079 18587 8867 18587 9081 18588 8873 18588 8871 18588 9081 18589 9080 18589 8873 18589 9082 18590 8871 18590 8876 18590 9082 18591 9081 18591 8871 18591 9083 18592 8876 18592 8880 18592 9083 18593 9082 18593 8876 18593 9084 18594 8880 18594 8879 18594 9084 18595 9083 18595 8880 18595 9085 18596 8879 18596 8883 18596 9085 18597 9084 18597 8879 18597 9086 18598 8883 18598 8886 18598 9086 18599 9085 18599 8883 18599 9087 18600 8886 18600 8889 18600 9087 18601 9086 18601 8886 18601 9088 18602 8889 18602 8894 18602 9088 18603 9087 18603 8889 18603 9089 18604 8894 18604 8897 18604 9089 18605 9088 18605 8894 18605 9090 18606 8897 18606 8903 18606 9090 18607 9089 18607 8897 18607 9091 18608 8903 18608 8908 18608 9091 18609 9090 18609 8903 18609 9092 18610 8908 18610 8912 18610 9092 18611 9091 18611 8908 18611 9093 18612 8912 18612 8916 18612 9093 18613 9092 18613 8912 18613 9094 18614 8916 18614 8921 18614 9094 18615 9093 18615 8916 18615 9095 18616 8921 18616 8926 18616 9095 18617 9094 18617 8921 18617 9096 18618 8926 18618 8794 18618 9096 18619 9095 18619 8926 18619 9065 18620 9096 18620 8794 18620 8655 18621 9064 18621 9066 18621 8643 18622 9066 18622 9067 18622 8643 18623 8655 18623 9066 18623 8651 18624 9067 18624 9068 18624 8651 18625 8643 18625 9067 18625 8652 18626 9068 18626 9069 18626 8652 18627 8651 18627 9068 18627 8636 18628 9069 18628 9070 18628 8636 18629 8652 18629 9069 18629 8640 18630 9070 18630 9071 18630 8640 18631 8636 18631 9070 18631 8628 18632 9071 18632 9072 18632 8628 18633 8640 18633 9071 18633 8632 18634 9072 18634 9073 18634 8632 18635 8628 18635 9072 18635 8633 18636 9073 18636 9074 18636 8633 18637 8632 18637 9073 18637 8622 18638 9074 18638 9075 18638 8622 18639 8633 18639 9074 18639 8625 18640 9075 18640 9076 18640 8625 18641 8622 18641 9075 18641 8618 18642 9076 18642 9077 18642 8618 18643 8625 18643 9076 18643 8613 18644 9077 18644 9078 18644 8613 18645 8618 18645 9077 18645 8615 18646 9078 18646 9079 18646 8615 18647 8613 18647 9078 18647 8609 18648 9079 18648 9080 18648 8609 18649 8615 18649 9079 18649 8610 18650 9080 18650 9081 18650 8610 18651 8609 18651 9080 18651 8606 18652 9081 18652 9082 18652 8606 18653 8610 18653 9081 18653 8603 18654 9082 18654 9083 18654 8603 18655 8606 18655 9082 18655 8600 18656 9083 18656 9084 18656 8600 18657 8603 18657 9083 18657 8597 18658 9084 18658 9085 18658 8597 18659 8600 18659 9084 18659 8595 18660 9085 18660 9086 18660 8595 18661 8597 18661 9085 18661 8592 18662 9086 18662 9087 18662 8592 18663 8595 18663 9086 18663 8590 18664 9087 18664 9088 18664 8590 18665 8592 18665 9087 18665 8587 18666 9088 18666 9089 18666 8587 18667 8590 18667 9088 18667 8585 18668 9089 18668 9090 18668 8585 18669 8587 18669 9089 18669 8581 18670 9090 18670 9091 18670 8581 18671 8585 18671 9090 18671 8579 18672 9091 18672 9092 18672 8579 18673 8581 18673 9091 18673 8576 18674 9092 18674 9093 18674 8576 18675 8579 18675 9092 18675 8571 18676 9093 18676 9094 18676 8571 18677 8576 18677 9093 18677 8568 18678 9094 18678 9095 18678 8568 18679 8571 18679 9094 18679 8564 18680 9095 18680 9096 18680 8564 18681 8568 18681 9095 18681 8562 18682 9096 18682 9065 18682 8562 18683 8564 18683 9096 18683 8561 18684 8562 18684 9065 18684 8679 18685 8975 18685 9038 18685 8678 18686 8975 18686 8679 18686 9097 18687 9038 18687 9039 18687 9098 18688 8679 18688 9038 18688 9098 18689 9038 18689 9097 18689 9099 18690 9039 18690 9040 18690 9097 18691 9039 18691 9099 18691 9100 18692 9040 18692 9041 18692 9099 18693 9040 18693 9100 18693 9101 18694 9041 18694 9042 18694 9100 18695 9041 18695 9101 18695 9102 18696 9042 18696 9043 18696 9101 18697 9042 18697 9102 18697 9103 18698 9043 18698 9044 18698 9102 18699 9043 18699 9103 18699 9104 18700 9044 18700 9045 18700 9103 18701 9044 18701 9104 18701 9105 18702 9045 18702 9046 18702 9104 18703 9045 18703 9105 18703 9106 18704 9046 18704 9047 18704 9105 18705 9046 18705 9106 18705 9107 18706 9047 18706 9048 18706 9106 18707 9047 18707 9107 18707 9050 18708 9048 18708 9049 18708 9107 18709 9048 18709 9050 18709 9107 18710 8781 18710 8782 18710 9107 18711 9050 18711 8781 18711 9106 18712 8782 18712 8783 18712 9106 18713 9107 18713 8782 18713 9105 18714 8783 18714 8784 18714 9105 18715 9106 18715 8783 18715 9104 18716 8784 18716 8785 18716 9104 18717 9105 18717 8784 18717 9103 18718 8785 18718 8786 18718 9103 18719 9104 18719 8785 18719 9102 18720 8786 18720 8787 18720 9102 18721 9103 18721 8786 18721 9101 18722 8787 18722 8788 18722 9101 18723 9102 18723 8787 18723 9100 18724 8788 18724 8789 18724 9100 18725 9101 18725 8788 18725 9099 18726 8789 18726 8790 18726 9099 18727 9100 18727 8789 18727 9097 18728 8790 18728 8791 18728 9097 18729 9099 18729 8790 18729 9098 18730 8791 18730 8676 18730 9098 18731 9097 18731 8791 18731 9098 18732 8676 18732 8673 18732 9098 18733 8673 18733 8679 18733 9108 18734 8960 18734 8684 18734 9109 18735 9108 18735 8684 18735 8685 18736 9109 18736 8684 18736 9109 18737 8960 18737 9108 18737 8959 18738 8960 18738 9109 18738 8683 18739 9109 18739 8685 18739 9110 18740 9109 18740 8683 18740 9110 18741 8959 18741 9109 18741 9110 18742 8683 18742 8686 18742 9111 18743 8052 18743 8051 18743 9111 18744 8775 18744 8052 18744 8927 18745 8051 18745 8054 18745 9111 18746 8051 18746 8927 18746 9112 18747 8686 18747 8690 18747 9110 18748 8686 18748 9112 18748 9113 18749 8690 18749 8693 18749 9112 18750 8690 18750 9113 18750 9114 18751 8693 18751 8696 18751 9113 18752 8693 18752 9114 18752 9115 18753 8696 18753 8700 18753 9114 18754 8696 18754 9115 18754 9116 18755 8700 18755 8703 18755 9115 18756 8700 18756 9116 18756 9117 18757 8703 18757 8706 18757 9116 18758 8703 18758 9117 18758 9118 18759 8706 18759 8709 18759 9117 18760 8706 18760 9118 18760 9119 18761 8709 18761 8713 18761 9118 18762 8709 18762 9119 18762 9120 18763 8713 18763 8716 18763 9119 18764 8713 18764 9120 18764 9121 18765 8716 18765 8718 18765 9120 18766 8716 18766 9121 18766 9122 18767 8718 18767 8723 18767 9121 18768 8718 18768 9122 18768 9123 18769 8723 18769 8728 18769 9122 18770 8723 18770 9123 18770 9124 18771 8728 18771 8729 18771 9123 18772 8728 18772 9124 18772 9125 18773 8729 18773 8727 18773 9124 18774 8729 18774 9125 18774 9126 18775 8727 18775 8733 18775 9125 18776 8727 18776 9126 18776 9127 18777 8733 18777 8732 18777 9126 18778 8733 18778 9127 18778 9128 18779 8732 18779 8737 18779 9127 18780 8732 18780 9128 18780 9129 18781 8737 18781 8736 18781 9128 18782 8737 18782 9129 18782 9130 18783 8736 18783 8740 18783 9129 18784 8736 18784 9130 18784 9131 18785 8740 18785 8744 18785 9130 18786 8740 18786 9131 18786 9132 18787 8744 18787 8743 18787 9131 18788 8744 18788 9132 18788 9133 18789 8743 18789 8746 18789 9132 18790 8743 18790 9133 18790 9134 18791 8746 18791 8750 18791 9133 18792 8746 18792 9134 18792 9135 18793 8750 18793 8752 18793 9134 18794 8750 18794 9135 18794 9136 18795 8752 18795 8756 18795 9135 18796 8752 18796 9136 18796 9137 18797 8756 18797 8759 18797 9136 18798 8756 18798 9137 18798 9138 18799 8759 18799 8761 18799 9137 18800 8759 18800 9138 18800 9139 18801 8761 18801 8764 18801 9138 18802 8761 18802 9139 18802 9140 18803 8764 18803 8767 18803 9139 18804 8764 18804 9140 18804 9141 18805 8767 18805 8771 18805 9140 18806 8767 18806 9141 18806 9142 18807 8771 18807 8773 18807 9141 18808 8771 18808 9142 18808 9111 18809 8773 18809 8775 18809 9142 18810 8773 18810 9111 18810 9142 18811 8927 18811 8928 18811 9142 18812 9111 18812 8927 18812 9141 18813 8928 18813 8929 18813 9141 18814 9142 18814 8928 18814 9140 18815 8929 18815 8930 18815 9140 18816 9141 18816 8929 18816 9139 18817 8930 18817 8931 18817 9139 18818 9140 18818 8930 18818 9138 18819 8931 18819 8932 18819 9138 18820 9139 18820 8931 18820 9137 18821 8932 18821 8933 18821 9137 18822 9138 18822 8932 18822 9136 18823 8933 18823 8934 18823 9136 18824 9137 18824 8933 18824 9135 18825 8934 18825 8935 18825 9135 18826 9136 18826 8934 18826 9134 18827 8935 18827 8936 18827 9134 18828 9135 18828 8935 18828 9133 18829 8936 18829 8937 18829 9133 18830 9134 18830 8936 18830 9132 18831 8937 18831 8938 18831 9132 18832 9133 18832 8937 18832 9131 18833 8938 18833 8939 18833 9131 18834 9132 18834 8938 18834 9130 18835 8939 18835 8940 18835 9130 18836 9131 18836 8939 18836 9129 18837 8940 18837 8941 18837 9129 18838 9130 18838 8940 18838 9128 18839 8941 18839 8942 18839 9128 18840 9129 18840 8941 18840 9127 18841 8942 18841 8943 18841 9127 18842 9128 18842 8942 18842 9126 18843 8943 18843 8944 18843 9126 18844 9127 18844 8943 18844 9125 18845 8944 18845 8945 18845 9125 18846 9126 18846 8944 18846 9124 18847 8945 18847 8946 18847 9124 18848 9125 18848 8945 18848 9123 18849 8946 18849 8947 18849 9123 18850 9124 18850 8946 18850 9122 18851 8947 18851 8948 18851 9122 18852 9123 18852 8947 18852 9121 18853 8948 18853 8949 18853 9121 18854 9122 18854 8948 18854 9120 18855 8949 18855 8950 18855 9120 18856 9121 18856 8949 18856 9119 18857 8950 18857 8951 18857 9119 18858 9120 18858 8950 18858 9118 18859 8951 18859 8952 18859 9118 18860 9119 18860 8951 18860 9117 18861 8952 18861 8953 18861 9117 18862 9118 18862 8952 18862 9116 18863 8953 18863 8954 18863 9116 18864 9117 18864 8953 18864 9115 18865 8954 18865 8955 18865 9115 18866 9116 18866 8954 18866 9114 18867 8955 18867 8956 18867 9114 18868 9115 18868 8955 18868 9113 18869 8956 18869 8957 18869 9113 18870 9114 18870 8956 18870 9112 18871 8957 18871 8958 18871 9112 18872 9113 18872 8957 18872 9110 18873 8958 18873 8959 18873 9110 18874 9112 18874 8958 18874 9143 18875 8193 18875 8192 18875 9144 18876 9143 18876 8192 18876 8498 18877 9144 18877 8192 18877 9145 18878 8193 18878 9143 18878 8187 18879 8193 18879 9145 18879 9146 18880 9143 18880 9144 18880 9145 18881 9143 18881 9146 18881 9146 18882 9144 18882 8498 18882 9147 18883 8498 18883 8499 18883 9146 18884 8498 18884 9147 18884 8500 18885 9148 18885 8501 18885 9147 18886 8499 18886 8332 18886 8332 18887 8499 18887 8326 18887 9149 18888 8081 18888 8079 18888 9149 18889 8322 18889 8081 18889 9150 18890 8079 18890 8083 18890 9150 18891 9149 18891 8079 18891 9151 18892 8083 18892 8082 18892 9151 18893 9150 18893 8083 18893 8103 18894 8082 18894 8084 18894 8103 18895 9151 18895 8082 18895 9147 18896 8332 18896 8331 18896 9152 18897 8331 18897 8335 18897 9152 18898 9147 18898 8331 18898 9153 18899 8335 18899 8337 18899 9153 18900 9152 18900 8335 18900 9154 18901 8337 18901 8342 18901 9154 18902 9153 18902 8337 18902 9155 18903 8342 18903 8345 18903 9155 18904 9154 18904 8342 18904 9156 18905 8345 18905 8348 18905 9156 18906 9155 18906 8345 18906 9157 18907 8348 18907 8353 18907 9157 18908 9156 18908 8348 18908 9158 18909 8353 18909 8358 18909 9158 18910 9157 18910 8353 18910 9159 18911 8358 18911 8363 18911 9159 18912 9158 18912 8358 18912 9160 18913 8363 18913 8366 18913 9160 18914 9159 18914 8363 18914 9161 18915 8366 18915 8371 18915 9161 18916 9160 18916 8366 18916 9162 18917 8371 18917 8375 18917 9162 18918 9161 18918 8371 18918 9163 18919 8375 18919 8380 18919 9163 18920 9162 18920 8375 18920 9164 18921 8380 18921 8385 18921 9164 18922 9163 18922 8380 18922 9165 18923 8385 18923 8388 18923 9165 18924 9164 18924 8385 18924 9166 18925 8388 18925 8392 18925 9166 18926 9165 18926 8388 18926 9167 18927 8392 18927 8394 18927 9167 18928 9166 18928 8392 18928 9168 18929 8394 18929 8397 18929 9168 18930 9167 18930 8394 18930 9169 18931 8397 18931 8401 18931 9169 18932 9168 18932 8397 18932 9170 18933 8401 18933 8405 18933 9170 18934 9169 18934 8401 18934 9171 18935 8405 18935 8404 18935 9171 18936 9170 18936 8405 18936 9172 18937 8404 18937 8410 18937 9172 18938 9171 18938 8404 18938 9173 18939 8410 18939 8413 18939 9173 18940 9172 18940 8410 18940 9174 18941 8413 18941 8418 18941 9174 18942 9173 18942 8413 18942 9175 18943 8418 18943 8422 18943 9175 18944 9174 18944 8418 18944 9176 18945 8422 18945 8427 18945 9176 18946 9175 18946 8422 18946 9177 18947 8427 18947 8433 18947 9177 18948 9176 18948 8427 18948 9178 18949 8433 18949 8438 18949 9178 18950 9177 18950 8433 18950 9179 18951 8438 18951 8443 18951 9179 18952 9178 18952 8438 18952 9180 18953 8443 18953 8448 18953 9180 18954 9179 18954 8443 18954 9181 18955 8448 18955 8453 18955 9181 18956 9180 18956 8448 18956 9182 18957 8453 18957 8459 18957 9182 18958 9181 18958 8453 18958 9183 18959 8459 18959 8322 18959 9183 18960 9182 18960 8459 18960 9149 18961 9183 18961 8322 18961 9146 18962 9147 18962 9152 18962 9184 18963 9152 18963 9153 18963 9184 18964 9146 18964 9152 18964 9185 18965 9153 18965 9154 18965 9185 18966 9184 18966 9153 18966 9186 18967 9154 18967 9155 18967 9186 18968 9185 18968 9154 18968 9187 18969 9155 18969 9156 18969 9187 18970 9186 18970 9155 18970 9188 18971 9156 18971 9157 18971 9188 18972 9187 18972 9156 18972 9189 18973 9157 18973 9158 18973 9189 18974 9188 18974 9157 18974 9190 18975 9158 18975 9159 18975 9190 18976 9189 18976 9158 18976 9191 18977 9159 18977 9160 18977 9191 18978 9190 18978 9159 18978 9192 18979 9160 18979 9161 18979 9192 18980 9191 18980 9160 18980 9193 18981 9161 18981 9162 18981 9193 18982 9192 18982 9161 18982 9194 18983 9162 18983 9163 18983 9194 18984 9193 18984 9162 18984 9195 18985 9163 18985 9164 18985 9195 18986 9194 18986 9163 18986 9196 18987 9164 18987 9165 18987 9196 18988 9195 18988 9164 18988 9197 18989 9165 18989 9166 18989 9197 18990 9196 18990 9165 18990 9198 18991 9166 18991 9167 18991 9198 18992 9197 18992 9166 18992 9199 18993 9167 18993 9168 18993 9199 18994 9198 18994 9167 18994 9200 18995 9168 18995 9169 18995 9200 18996 9199 18996 9168 18996 9201 18997 9169 18997 9170 18997 9201 18998 9200 18998 9169 18998 9202 18999 9170 18999 9171 18999 9202 19000 9201 19000 9170 19000 9203 19001 9171 19001 9172 19001 9203 19002 9202 19002 9171 19002 9204 19003 9172 19003 9173 19003 9204 19004 9203 19004 9172 19004 9205 19005 9173 19005 9174 19005 9205 19006 9204 19006 9173 19006 9206 19007 9174 19007 9175 19007 9206 19008 9205 19008 9174 19008 9207 19009 9175 19009 9176 19009 9207 19010 9206 19010 9175 19010 9208 19011 9176 19011 9177 19011 9208 19012 9207 19012 9176 19012 9209 19013 9177 19013 9178 19013 9209 19014 9208 19014 9177 19014 9210 19015 9178 19015 9179 19015 9210 19016 9209 19016 9178 19016 9211 19017 9179 19017 9180 19017 9211 19018 9210 19018 9179 19018 9212 19019 9180 19019 9181 19019 9212 19020 9211 19020 9180 19020 9213 19021 9181 19021 9182 19021 9213 19022 9212 19022 9181 19022 9214 19023 9182 19023 9183 19023 9214 19024 9213 19024 9182 19024 9215 19025 9183 19025 9149 19025 9215 19026 9214 19026 9183 19026 9150 19027 9215 19027 9149 19027 9145 19028 9146 19028 9184 19028 9216 19029 9184 19029 9185 19029 9216 19030 9145 19030 9184 19030 9217 19031 9185 19031 9186 19031 9217 19032 9216 19032 9185 19032 9218 19033 9186 19033 9187 19033 9218 19034 9217 19034 9186 19034 9219 19035 9187 19035 9188 19035 9219 19036 9218 19036 9187 19036 9220 19037 9188 19037 9189 19037 9220 19038 9219 19038 9188 19038 9221 19039 9189 19039 9190 19039 9221 19040 9220 19040 9189 19040 9222 19041 9190 19041 9191 19041 9222 19042 9221 19042 9190 19042 9223 19043 9191 19043 9192 19043 9223 19044 9222 19044 9191 19044 9224 19045 9192 19045 9193 19045 9224 19046 9223 19046 9192 19046 9225 19047 9193 19047 9194 19047 9225 19048 9224 19048 9193 19048 9226 19049 9194 19049 9195 19049 9226 19050 9225 19050 9194 19050 9227 19051 9195 19051 9196 19051 9227 19052 9226 19052 9195 19052 9228 19053 9196 19053 9197 19053 9228 19054 9227 19054 9196 19054 9229 19055 9197 19055 9198 19055 9229 19056 9228 19056 9197 19056 9230 19057 9198 19057 9199 19057 9230 19058 9229 19058 9198 19058 9231 19059 9199 19059 9200 19059 9231 19060 9230 19060 9199 19060 9232 19061 9200 19061 9201 19061 9232 19062 9231 19062 9200 19062 9233 19063 9201 19063 9202 19063 9233 19064 9232 19064 9201 19064 9234 19065 9202 19065 9203 19065 9234 19066 9233 19066 9202 19066 9235 19067 9203 19067 9204 19067 9235 19068 9234 19068 9203 19068 9236 19069 9204 19069 9205 19069 9236 19070 9235 19070 9204 19070 9237 19071 9205 19071 9206 19071 9237 19072 9236 19072 9205 19072 9238 19073 9206 19073 9207 19073 9238 19074 9237 19074 9206 19074 9239 19075 9207 19075 9208 19075 9239 19076 9238 19076 9207 19076 9240 19077 9208 19077 9209 19077 9240 19078 9239 19078 9208 19078 9241 19079 9209 19079 9210 19079 9241 19080 9240 19080 9209 19080 9242 19081 9210 19081 9211 19081 9242 19082 9241 19082 9210 19082 9243 19083 9211 19083 9212 19083 9243 19084 9242 19084 9211 19084 9244 19085 9212 19085 9213 19085 9244 19086 9243 19086 9212 19086 9245 19087 9213 19087 9214 19087 9245 19088 9244 19088 9213 19088 9246 19089 9214 19089 9215 19089 9246 19090 9245 19090 9214 19090 9247 19091 9215 19091 9150 19091 9247 19092 9246 19092 9215 19092 9151 19093 9247 19093 9150 19093 8187 19094 9145 19094 9216 19094 8183 19095 9216 19095 9217 19095 8183 19096 8187 19096 9216 19096 8184 19097 9217 19097 9218 19097 8184 19098 8183 19098 9217 19098 8178 19099 9218 19099 9219 19099 8178 19100 8184 19100 9218 19100 8180 19101 9219 19101 9220 19101 8180 19102 8178 19102 9219 19102 8173 19103 9220 19103 9221 19103 8173 19104 8180 19104 9220 19104 8175 19105 9221 19105 9222 19105 8175 19106 8173 19106 9221 19106 8168 19107 9222 19107 9223 19107 8168 19108 8175 19108 9222 19108 8169 19109 9223 19109 9224 19109 8169 19110 8168 19110 9223 19110 8170 19111 9224 19111 9225 19111 8170 19112 8169 19112 9224 19112 8163 19113 9225 19113 9226 19113 8163 19114 8170 19114 9225 19114 8165 19115 9226 19115 9227 19115 8165 19116 8163 19116 9226 19116 8159 19117 9227 19117 9228 19117 8159 19118 8165 19118 9227 19118 8155 19119 9228 19119 9229 19119 8155 19120 8159 19120 9228 19120 8156 19121 9229 19121 9230 19121 8156 19122 8155 19122 9229 19122 8152 19123 9230 19123 9231 19123 8152 19124 8156 19124 9230 19124 8148 19125 9231 19125 9232 19125 8148 19126 8152 19126 9231 19126 8149 19127 9232 19127 9233 19127 8149 19128 8148 19128 9232 19128 8145 19129 9233 19129 9234 19129 8145 19130 8149 19130 9233 19130 8143 19131 9234 19131 9235 19131 8143 19132 8145 19132 9234 19132 8140 19133 9235 19133 9236 19133 8140 19134 8143 19134 9235 19134 8138 19135 9236 19135 9237 19135 8138 19136 8140 19136 9236 19136 8135 19137 9237 19137 9238 19137 8135 19138 8138 19138 9237 19138 8132 19139 9238 19139 9239 19139 8132 19140 8135 19140 9238 19140 8128 19141 9239 19141 9240 19141 8128 19142 8132 19142 9239 19142 8126 19143 9240 19143 9241 19143 8126 19144 8128 19144 9240 19144 8122 19145 9241 19145 9242 19145 8122 19146 8126 19146 9241 19146 8119 19147 9242 19147 9243 19147 8119 19148 8122 19148 9242 19148 8116 19149 9243 19149 9244 19149 8116 19150 8119 19150 9243 19150 8111 19151 9244 19151 9245 19151 8111 19152 8116 19152 9244 19152 8108 19153 9245 19153 9246 19153 8108 19154 8111 19154 9245 19154 8105 19155 9246 19155 9247 19155 8105 19156 8108 19156 9246 19156 8104 19157 9247 19157 9151 19157 8104 19158 8105 19158 9247 19158 8103 19159 8104 19159 9151 19159 9248 19160 8496 19160 8282 19160 9148 19161 9249 19161 8501 19161 9250 19162 9248 19162 8282 19162 8283 19163 9250 19163 8282 19163 9148 19164 9251 19164 9249 19164 8494 19165 8496 19165 9248 19165 9252 19166 9248 19166 9250 19166 9252 19167 8494 19167 9248 19167 8284 19168 9250 19168 8283 19168 9253 19169 9250 19169 8284 19169 9252 19170 9250 19170 9253 19170 9254 19171 8284 19171 8281 19171 9253 19172 8284 19172 9254 19172 9254 19173 8281 19173 8285 19173 9255 19174 8072 19174 8073 19174 9255 19175 8207 19175 8072 19175 8502 19176 8073 19176 8071 19176 8502 19177 9255 19177 8073 19177 8500 19178 8071 19178 8076 19178 8500 19179 8502 19179 8071 19179 8461 19180 8076 19180 8075 19180 8500 19181 8076 19181 8461 19181 9148 19182 8461 19182 8462 19182 8500 19183 8461 19183 9148 19183 9251 19184 8462 19184 8463 19184 9148 19185 8462 19185 9251 19185 9256 19186 8463 19186 8464 19186 9251 19187 8463 19187 9256 19187 9257 19188 8464 19188 8465 19188 9256 19189 8464 19189 9257 19189 9258 19190 8465 19190 8466 19190 9257 19191 8465 19191 9258 19191 9259 19192 8466 19192 8467 19192 9258 19193 8466 19193 9259 19193 9260 19194 8467 19194 8468 19194 9259 19195 8467 19195 9260 19195 9261 19196 8468 19196 8469 19196 9260 19197 8468 19197 9261 19197 9262 19198 8469 19198 8470 19198 9261 19199 8469 19199 9262 19199 9263 19200 8470 19200 8471 19200 9262 19201 8470 19201 9263 19201 9264 19202 8471 19202 8472 19202 9263 19203 8471 19203 9264 19203 9265 19204 8472 19204 8473 19204 9264 19205 8472 19205 9265 19205 9266 19206 8473 19206 8474 19206 9265 19207 8473 19207 9266 19207 9267 19208 8474 19208 8475 19208 9266 19209 8474 19209 9267 19209 9268 19210 8475 19210 8476 19210 9267 19211 8475 19211 9268 19211 9269 19212 8476 19212 8477 19212 9268 19213 8476 19213 9269 19213 9270 19214 8477 19214 8478 19214 9269 19215 8477 19215 9270 19215 9271 19216 8478 19216 8479 19216 9270 19217 8478 19217 9271 19217 9272 19218 8479 19218 8480 19218 9271 19219 8479 19219 9272 19219 9273 19220 8480 19220 8481 19220 9272 19221 8480 19221 9273 19221 9274 19222 8481 19222 8482 19222 9273 19223 8481 19223 9274 19223 9275 19224 8482 19224 8483 19224 9274 19225 8482 19225 9275 19225 9276 19226 8483 19226 8484 19226 9275 19227 8483 19227 9276 19227 9277 19228 8484 19228 8485 19228 9276 19229 8484 19229 9277 19229 9278 19230 8485 19230 8486 19230 9277 19231 8485 19231 9278 19231 9279 19232 8486 19232 8487 19232 9278 19233 8486 19233 9279 19233 9280 19234 8487 19234 8488 19234 9279 19235 8487 19235 9280 19235 9281 19236 8488 19236 8489 19236 9280 19237 8488 19237 9281 19237 9282 19238 8489 19238 8490 19238 9281 19239 8489 19239 9282 19239 9283 19240 8490 19240 8491 19240 9282 19241 8490 19241 9283 19241 9284 19242 8491 19242 8493 19242 9283 19243 8491 19243 9284 19243 9285 19244 8493 19244 8492 19244 9284 19245 8493 19245 9285 19245 9252 19246 8492 19246 8494 19246 9285 19247 8492 19247 9252 19247 9286 19248 8285 19248 8286 19248 9286 19249 9254 19249 8285 19249 9287 19250 8286 19250 8288 19250 9287 19251 9286 19251 8286 19251 9288 19252 8288 19252 8287 19252 9288 19253 9287 19253 8288 19253 9289 19254 8287 19254 8289 19254 9289 19255 9288 19255 8287 19255 9290 19256 8289 19256 8291 19256 9290 19257 9289 19257 8289 19257 9291 19258 8291 19258 8292 19258 9291 19259 9290 19259 8291 19259 9292 19260 8292 19260 8290 19260 9292 19261 9291 19261 8292 19261 9293 19262 8290 19262 8294 19262 9293 19263 9292 19263 8290 19263 9294 19264 8294 19264 8293 19264 9294 19265 9293 19265 8294 19265 9295 19266 8293 19266 8296 19266 9295 19267 9294 19267 8293 19267 9296 19268 8296 19268 8297 19268 9296 19269 9295 19269 8296 19269 9297 19270 8297 19270 8295 19270 9297 19271 9296 19271 8297 19271 9298 19272 8295 19272 8299 19272 9298 19273 9297 19273 8295 19273 9299 19274 8299 19274 8298 19274 9299 19275 9298 19275 8299 19275 9300 19276 8298 19276 8301 19276 9300 19277 9299 19277 8298 19277 9301 19278 8301 19278 8300 19278 9301 19279 9300 19279 8301 19279 9302 19280 8300 19280 8302 19280 9302 19281 9301 19281 8300 19281 9303 19282 8302 19282 8304 19282 9303 19283 9302 19283 8302 19283 9304 19284 8304 19284 8303 19284 9304 19285 9303 19285 8304 19285 9305 19286 8303 19286 8305 19286 9305 19287 9304 19287 8303 19287 9306 19288 8305 19288 8306 19288 9306 19289 9305 19289 8305 19289 9307 19290 8306 19290 8307 19290 9307 19291 9306 19291 8306 19291 9308 19292 8307 19292 8308 19292 9308 19293 9307 19293 8307 19293 9309 19294 8308 19294 8309 19294 9309 19295 9308 19295 8308 19295 9310 19296 8309 19296 8310 19296 9310 19297 9309 19297 8309 19297 9311 19298 8310 19298 8311 19298 9311 19299 9310 19299 8310 19299 9312 19300 8311 19300 8312 19300 9312 19301 9311 19301 8311 19301 9313 19302 8312 19302 8313 19302 9313 19303 9312 19303 8312 19303 9314 19304 8313 19304 8314 19304 9314 19305 9313 19305 8313 19305 9315 19306 8314 19306 8315 19306 9315 19307 9314 19307 8314 19307 9316 19308 8315 19308 8316 19308 9316 19309 9315 19309 8315 19309 9317 19310 8316 19310 8317 19310 9317 19311 9316 19311 8316 19311 9255 19312 8317 19312 8207 19312 9255 19313 9317 19313 8317 19313 9318 19314 9254 19314 9286 19314 9318 19315 9253 19315 9254 19315 9319 19316 9286 19316 9287 19316 9319 19317 9318 19317 9286 19317 9320 19318 9287 19318 9288 19318 9320 19319 9319 19319 9287 19319 9321 19320 9288 19320 9289 19320 9321 19321 9320 19321 9288 19321 9322 19322 9289 19322 9290 19322 9322 19323 9321 19323 9289 19323 9323 19324 9290 19324 9291 19324 9323 19325 9322 19325 9290 19325 9324 19326 9291 19326 9292 19326 9324 19327 9323 19327 9291 19327 9325 19328 9292 19328 9293 19328 9325 19329 9324 19329 9292 19329 9326 19330 9293 19330 9294 19330 9326 19331 9325 19331 9293 19331 9327 19332 9294 19332 9295 19332 9327 19333 9326 19333 9294 19333 9328 19334 9295 19334 9296 19334 9328 19335 9327 19335 9295 19335 9329 19336 9296 19336 9297 19336 9329 19337 9328 19337 9296 19337 9330 19338 9297 19338 9298 19338 9330 19339 9329 19339 9297 19339 9331 19340 9298 19340 9299 19340 9331 19341 9330 19341 9298 19341 9332 19342 9299 19342 9300 19342 9332 19343 9331 19343 9299 19343 9333 19344 9300 19344 9301 19344 9333 19345 9332 19345 9300 19345 9334 19346 9301 19346 9302 19346 9334 19347 9333 19347 9301 19347 9335 19348 9302 19348 9303 19348 9335 19349 9334 19349 9302 19349 9336 19350 9303 19350 9304 19350 9336 19351 9335 19351 9303 19351 9337 19352 9304 19352 9305 19352 9337 19353 9336 19353 9304 19353 9338 19354 9305 19354 9306 19354 9338 19355 9337 19355 9305 19355 9339 19356 9306 19356 9307 19356 9339 19357 9338 19357 9306 19357 9340 19358 9307 19358 9308 19358 9340 19359 9339 19359 9307 19359 9341 19360 9308 19360 9309 19360 9341 19361 9340 19361 9308 19361 9342 19362 9309 19362 9310 19362 9342 19363 9341 19363 9309 19363 9343 19364 9310 19364 9311 19364 9343 19365 9342 19365 9310 19365 9344 19366 9311 19366 9312 19366 9344 19367 9343 19367 9311 19367 9345 19368 9312 19368 9313 19368 9345 19369 9344 19369 9312 19369 9346 19370 9313 19370 9314 19370 9346 19371 9345 19371 9313 19371 9347 19372 9314 19372 9315 19372 9347 19373 9346 19373 9314 19373 9249 19374 9315 19374 9316 19374 9249 19375 9347 19375 9315 19375 8501 19376 9316 19376 9317 19376 8501 19377 9249 19377 9316 19377 8502 19378 9317 19378 9255 19378 8502 19379 8501 19379 9317 19379 9285 19380 9253 19380 9318 19380 9285 19381 9252 19381 9253 19381 9284 19382 9318 19382 9319 19382 9284 19383 9285 19383 9318 19383 9283 19384 9319 19384 9320 19384 9283 19385 9284 19385 9319 19385 9282 19386 9320 19386 9321 19386 9282 19387 9283 19387 9320 19387 9281 19388 9321 19388 9322 19388 9281 19389 9282 19389 9321 19389 9280 19390 9322 19390 9323 19390 9280 19391 9281 19391 9322 19391 9279 19392 9323 19392 9324 19392 9279 19393 9280 19393 9323 19393 9278 19394 9324 19394 9325 19394 9278 19395 9279 19395 9324 19395 9277 19396 9325 19396 9326 19396 9277 19397 9278 19397 9325 19397 9276 19398 9326 19398 9327 19398 9276 19399 9277 19399 9326 19399 9275 19400 9327 19400 9328 19400 9275 19401 9276 19401 9327 19401 9274 19402 9328 19402 9329 19402 9274 19403 9275 19403 9328 19403 9273 19404 9329 19404 9330 19404 9273 19405 9274 19405 9329 19405 9272 19406 9330 19406 9331 19406 9272 19407 9273 19407 9330 19407 9271 19408 9331 19408 9332 19408 9271 19409 9272 19409 9331 19409 9270 19410 9332 19410 9333 19410 9270 19411 9271 19411 9332 19411 9269 19412 9333 19412 9334 19412 9269 19413 9270 19413 9333 19413 9268 19414 9334 19414 9335 19414 9268 19415 9269 19415 9334 19415 9267 19416 9335 19416 9336 19416 9267 19417 9268 19417 9335 19417 9266 19418 9336 19418 9337 19418 9266 19419 9267 19419 9336 19419 9265 19420 9337 19420 9338 19420 9265 19421 9266 19421 9337 19421 9264 19422 9338 19422 9339 19422 9264 19423 9265 19423 9338 19423 9263 19424 9339 19424 9340 19424 9263 19425 9264 19425 9339 19425 9262 19426 9340 19426 9341 19426 9262 19427 9263 19427 9340 19427 9261 19428 9341 19428 9342 19428 9261 19429 9262 19429 9341 19429 9260 19430 9342 19430 9343 19430 9260 19431 9261 19431 9342 19431 9259 19432 9343 19432 9344 19432 9259 19433 9260 19433 9343 19433 9258 19434 9344 19434 9345 19434 9258 19435 9259 19435 9344 19435 9257 19436 9345 19436 9346 19436 9257 19437 9258 19437 9345 19437 9256 19438 9346 19438 9347 19438 9256 19439 9257 19439 9346 19439 9251 19440 9347 19440 9249 19440 9251 19441 9256 19441 9347 19441 9348 19442 9349 19442 9350 19442 9350 19443 9351 19443 9352 19443 9352 19444 9353 19444 9354 19444 9354 19445 9355 19445 9356 19445 9356 19446 9357 19446 9358 19446 9358 19447 9359 19447 9360 19447 9360 19448 9361 19448 9362 19448 9362 19449 9363 19449 9364 19449 9364 19450 9365 19450 9367 19450 9366 19451 9367 19451 9369 19451 9368 19452 9369 19452 9371 19452 9370 19453 9371 19453 9373 19453 9372 19454 9373 19454 9375 19454 9374 19455 9375 19455 9377 19455 9376 19456 9377 19456 9379 19456 9378 19457 9379 19457 9381 19457 9380 19458 9381 19458 9383 19458 9382 19459 9383 19459 9385 19459 9384 19460 9385 19460 9387 19460 9386 19461 9387 19461 9389 19461 9388 19462 9389 19462 9391 19462 9390 19463 9391 19463 9393 19463 9392 19464 9393 19464 9395 19464 9394 19465 9395 19465 9397 19465 9396 19466 9397 19466 9398 19466 9398 19467 9399 19467 9400 19467 9400 19468 9401 19468 9402 19468 9402 19469 9403 19469 9404 19469 9404 19470 9405 19470 9406 19470 9406 19471 9407 19471 9408 19471 9351 19472 9349 19472 9411 19472 9410 19473 9411 19473 9348 19473 9408 19474 9409 19474 9410 19474 9398 19475 9394 19475 9396 19475 7895 19476 7897 19476 7896 19476 7897 19477 7899 19477 7898 19477 7899 19478 7901 19478 7900 19478 7901 19479 7903 19479 7902 19479 7903 19480 7905 19480 7904 19480 7905 19481 7907 19481 7906 19481 7907 19482 7909 19482 7908 19482 7909 19483 7911 19483 7910 19483 7912 19484 7910 19484 7913 19484 7914 19485 7912 19485 7915 19485 7916 19486 7914 19486 7917 19486 7918 19487 7916 19487 7919 19487 7920 19488 7918 19488 7921 19488 7922 19489 7920 19489 7923 19489 7924 19490 7922 19490 7925 19490 7926 19491 7924 19491 7927 19491 7928 19492 7926 19492 7929 19492 7930 19493 7928 19493 7931 19493 7932 19494 7930 19494 7933 19494 7934 19495 7932 19495 7935 19495 7936 19496 7934 19496 7937 19496 7938 19497 7936 19497 7939 19497 7940 19498 7938 19498 7941 19498 7942 19499 7940 19499 7943 19499 7943 19500 7945 19500 7944 19500 7945 19501 7947 19501 7946 19501 7947 19502 7949 19502 7948 19502 7949 19503 7951 19503 7950 19503 7951 19504 7953 19504 7952 19504 7953 19505 7955 19505 7954 19505 7899 19506 7897 19506 7901 19506 7897 19507 7957 19507 7901 19507 7957 19508 7955 19508 7953 19508 7901 19509 7957 19509 7903 19509 7957 19510 7953 19510 7951 19510 7957 19511 7951 19511 7949 19511 7957 19512 7949 19512 7947 19512 7939 19513 7943 19513 7941 19513 7937 19514 7943 19514 7939 19514 7935 19515 7943 19515 7937 19515 7931 19516 7935 19516 7933 19516 7931 19517 7943 19517 7935 19517 7927 19518 7931 19518 7929 19518 7923 19519 7927 19519 7925 19519 7919 19520 7923 19520 7921 19520 7905 19521 7903 19521 7907 19521 7917 19522 7923 19522 7919 19522 7915 19523 7923 19523 7917 19523 7911 19524 7915 19524 7913 19524 7911 19525 7923 19525 7915 19525 7911 19526 7927 19526 7923 19526 7911 19527 7931 19527 7927 19527 7907 19528 7903 19528 7909 19528 7903 19529 7957 19529 7909 19529 7957 19530 7947 19530 7909 19530 7947 19531 7945 19531 7909 19531 7945 19532 7943 19532 7909 19532 7943 19533 7931 19533 7909 19533 7931 19534 7911 19534 7909 19534 7957 19535 7895 19535 7894 19535 7955 19536 7957 19536 7956 19536 7944 19537 7938 19537 7940 19537 7946 19538 7938 19538 7944 19538 7946 19539 7936 19539 7938 19539 7948 19540 7936 19540 7946 19540 7948 19541 7934 19541 7936 19541 7950 19542 7934 19542 7948 19542 7950 19543 7932 19543 7934 19543 7952 19544 7932 19544 7950 19544 7952 19545 7930 19545 7932 19545 7954 19546 7930 19546 7952 19546 7954 19547 7928 19547 7930 19547 7956 19548 7928 19548 7954 19548 7956 19549 7926 19549 7928 19549 7956 19550 7894 19550 7926 19550 7894 19551 7896 19551 7926 19551 7926 19552 7896 19552 7924 19552 7896 19553 7898 19553 7924 19553 7924 19554 7898 19554 7922 19554 7898 19555 7900 19555 7922 19555 7922 19556 7900 19556 7920 19556 7900 19557 7902 19557 7920 19557 7920 19558 7902 19558 7918 19558 7902 19559 7904 19559 7918 19559 7918 19560 7904 19560 7916 19560 7904 19561 7906 19561 7916 19561 7916 19562 7906 19562 7914 19562 7906 19563 7908 19563 7914 19563 7908 19564 7910 19564 7912 19564 7914 19565 7908 19565 7912 19565 9349 19566 9351 19566 9350 19566 9351 19567 9353 19567 9352 19567 9353 19568 9355 19568 9354 19568 9355 19569 9357 19569 9356 19569 9357 19570 9359 19570 9358 19570 9359 19571 9361 19571 9360 19571 9361 19572 9363 19572 9362 19572 9363 19573 9365 19573 9364 19573 9366 19574 9364 19574 9367 19574 9368 19575 9366 19575 9369 19575 9370 19576 9368 19576 9371 19576 9372 19577 9370 19577 9373 19577 9374 19578 9372 19578 9375 19578 9376 19579 9374 19579 9377 19579 9378 19580 9376 19580 9379 19580 9380 19581 9378 19581 9381 19581 9382 19582 9380 19582 9383 19582 9384 19583 9382 19583 9385 19583 9386 19584 9384 19584 9387 19584 9388 19585 9386 19585 9389 19585 9390 19586 9388 19586 9391 19586 9392 19587 9390 19587 9393 19587 9394 19588 9392 19588 9395 19588 9396 19589 9394 19589 9397 19589 9397 19590 9399 19590 9398 19590 9399 19591 9401 19591 9400 19591 9401 19592 9403 19592 9402 19592 9403 19593 9405 19593 9404 19593 9405 19594 9407 19594 9406 19594 9407 19595 9409 19595 9408 19595 9353 19596 9351 19596 9355 19596 9351 19597 9411 19597 9355 19597 9411 19598 9409 19598 9407 19598 9355 19599 9411 19599 9357 19599 9411 19600 9407 19600 9405 19600 9411 19601 9405 19601 9403 19601 9411 19602 9403 19602 9401 19602 9393 19603 9397 19603 9395 19603 9391 19604 9397 19604 9393 19604 9389 19605 9397 19605 9391 19605 9385 19606 9389 19606 9387 19606 9385 19607 9397 19607 9389 19607 9381 19608 9385 19608 9383 19608 9377 19609 9381 19609 9379 19609 9373 19610 9377 19610 9375 19610 9365 19611 9369 19611 9367 19611 9359 19612 9357 19612 9361 19612 9361 19613 9357 19613 9363 19613 9371 19614 9377 19614 9373 19614 9369 19615 9377 19615 9371 19615 9365 19616 9377 19616 9369 19616 9365 19617 9381 19617 9377 19617 9365 19618 9385 19618 9381 19618 9357 19619 9411 19619 9363 19619 9411 19620 9401 19620 9363 19620 9401 19621 9399 19621 9363 19621 9399 19622 9397 19622 9363 19622 9397 19623 9385 19623 9363 19623 9385 19624 9365 19624 9363 19624 9411 19625 9349 19625 9348 19625 9409 19626 9411 19626 9410 19626 9398 19627 9392 19627 9394 19627 9400 19628 9392 19628 9398 19628 9400 19629 9390 19629 9392 19629 9402 19630 9390 19630 9400 19630 9402 19631 9388 19631 9390 19631 9404 19632 9388 19632 9402 19632 9404 19633 9386 19633 9388 19633 9406 19634 9386 19634 9404 19634 9406 19635 9384 19635 9386 19635 9408 19636 9384 19636 9406 19636 9408 19637 9382 19637 9384 19637 9410 19638 9382 19638 9408 19638 9410 19639 9380 19639 9382 19639 9410 19640 9348 19640 9380 19640 9348 19641 9350 19641 9380 19641 9380 19642 9350 19642 9378 19642 9378 19643 9350 19643 9376 19643 9350 19644 9352 19644 9376 19644 9352 19645 9354 19645 9376 19645 9376 19646 9354 19646 9374 19646 9354 19647 9356 19647 9374 19647 9374 19648 9356 19648 9372 19648 9356 19649 9358 19649 9372 19649 9372 19650 9358 19650 9370 19650 9358 19651 9360 19651 9370 19651 9370 19652 9360 19652 9368 19652 9360 19653 9362 19653 9368 19653 9362 19654 9364 19654 9366 19654 9368 19655 9362 19655 9366 19655</p> + </polylist> + <polylist material="mat_helix_back-material" count="5808"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>9412 19656 9413 19656 9414 19656 9415 19657 9414 19657 9413 19657 9416 19658 9414 19658 9417 19658 9418 19659 9417 19659 9414 19659 9412 19660 9414 19660 9416 19660 9419 19661 9414 19661 9415 19661 9420 19662 9418 19662 9414 19662 9421 19663 9420 19663 9414 19663 9419 19664 9421 19664 9414 19664 9422 19665 9423 19665 9413 19665 9424 19666 9413 19666 9423 19666 9425 19667 9422 19667 9413 19667 9426 19668 9425 19668 9413 19668 9412 19669 9426 19669 9413 19669 9427 19670 9413 19670 9424 19670 9428 19671 9429 19671 9413 19671 9430 19672 9413 19672 9429 19672 9427 19673 9428 19673 9413 19673 9430 19674 9415 19674 9413 19674 9431 19675 9432 19675 9423 19675 9433 19676 9423 19676 9432 19676 9422 19677 9431 19677 9423 19677 9424 19678 9423 19678 9433 19678 9434 19679 9435 19679 9432 19679 9436 19680 9432 19680 9435 19680 9431 19681 9434 19681 9432 19681 9433 19682 9432 19682 9436 19682 9437 19683 9435 19683 9434 19683 9436 19684 9435 19684 9437 19684 9438 19685 9434 19685 9431 19685 9437 19686 9434 19686 9438 19686 9439 19687 9431 19687 9422 19687 9438 19688 9431 19688 9439 19688 9440 19689 9441 19689 9422 19689 9442 19690 9422 19690 9441 19690 9425 19691 9440 19691 9422 19691 9439 19692 9422 19692 9442 19692 9443 19693 9444 19693 9441 19693 9445 19694 9441 19694 9444 19694 9446 19695 9443 19695 9441 19695 9440 19696 9446 19696 9441 19696 9442 19697 9441 19697 9447 19697 9445 19698 9447 19698 9441 19698 9448 19699 9449 19699 9444 19699 9450 19700 9444 19700 9449 19700 9443 19701 9448 19701 9444 19701 9451 19702 9445 19702 9444 19702 9452 19703 9451 19703 9444 19703 9453 19704 9452 19704 9444 19704 9450 19705 9453 19705 9444 19705 9454 19706 9455 19706 9449 19706 9456 19707 9449 19707 9455 19707 9457 19708 9454 19708 9449 19708 9458 19709 9457 19709 9449 19709 9448 19710 9458 19710 9449 19710 9459 19711 9449 19711 9456 19711 9460 19712 9450 19712 9449 19712 9461 19713 9462 19713 9449 19713 9460 19714 9449 19714 9462 19714 9459 19715 9461 19715 9449 19715 9463 19716 9464 19716 9455 19716 9465 19717 9455 19717 9464 19717 9454 19718 9463 19718 9455 19718 9456 19719 9455 19719 9465 19719 9466 19720 9467 19720 9464 19720 9468 19721 9464 19721 9467 19721 9463 19722 9466 19722 9464 19722 9465 19723 9464 19723 9468 19723 9469 19724 9467 19724 9466 19724 9468 19725 9467 19725 9469 19725 9470 19726 9466 19726 9463 19726 9469 19727 9466 19727 9470 19727 9471 19728 9463 19728 9454 19728 9470 19729 9463 19729 9471 19729 9472 19730 9417 19730 9454 19730 9473 19731 9454 19731 9417 19731 9457 19732 9472 19732 9454 19732 9471 19733 9454 19733 9473 19733 9474 19734 9416 19734 9417 19734 9472 19735 9474 19735 9417 19735 9473 19736 9417 19736 9475 19736 9418 19737 9475 19737 9417 19737 9476 19738 9416 19738 9474 19738 9477 19739 9412 19739 9416 19739 9477 19740 9416 19740 9476 19740 9478 19741 9474 19741 9472 19741 9478 19742 9476 19742 9474 19742 9479 19743 9472 19743 9457 19743 9478 19744 9472 19744 9479 19744 9480 19745 9457 19745 9458 19745 9479 19746 9457 19746 9480 19746 9481 19747 9458 19747 9448 19747 9480 19748 9458 19748 9481 19748 9482 19749 9448 19749 9443 19749 9481 19750 9448 19750 9482 19750 9483 19751 9443 19751 9446 19751 9482 19752 9443 19752 9483 19752 9484 19753 9446 19753 9440 19753 9483 19754 9446 19754 9484 19754 9485 19755 9440 19755 9425 19755 9484 19756 9440 19756 9485 19756 9486 19757 9425 19757 9426 19757 9485 19758 9425 19758 9486 19758 9426 19759 9412 19759 9487 19759 9486 19760 9426 19760 9487 19760 9487 19761 9412 19761 9477 19761 9478 19762 9475 19762 9488 19762 9489 19763 9488 19763 9475 19763 9476 19764 9488 19764 9424 19764 9427 19765 9424 19765 9488 19765 9478 19766 9488 19766 9476 19766 9490 19767 9427 19767 9488 19767 9491 19768 9490 19768 9488 19768 9492 19769 9491 19769 9488 19769 9493 19770 9492 19770 9488 19770 9494 19771 9493 19771 9488 19771 9489 19772 9494 19772 9488 19772 9465 19773 9473 19773 9475 19773 9480 19774 9465 19774 9475 19774 9479 19775 9480 19775 9475 19775 9478 19776 9479 19776 9475 19776 9495 19777 9489 19777 9475 19777 9418 19778 9495 19778 9475 19778 9468 19779 9471 19779 9473 19779 9465 19780 9468 19780 9473 19780 9469 19781 9470 19781 9471 19781 9468 19782 9469 19782 9471 19782 9481 19783 9456 19783 9465 19783 9480 19784 9481 19784 9465 19784 9483 19785 9496 19785 9456 19785 9459 19786 9456 19786 9496 19786 9482 19787 9483 19787 9456 19787 9481 19788 9482 19788 9456 19788 9484 19789 9447 19789 9496 19789 9497 19790 9496 19790 9447 19790 9483 19791 9484 19791 9496 19791 9498 19792 9496 19792 9497 19792 9499 19793 9459 19793 9496 19793 9500 19794 9499 19794 9496 19794 9501 19795 9500 19795 9496 19795 9502 19796 9501 19796 9496 19796 9498 19797 9502 19797 9496 19797 9433 19798 9442 19798 9447 19798 9486 19799 9433 19799 9447 19799 9485 19800 9486 19800 9447 19800 9484 19801 9485 19801 9447 19801 9503 19802 9497 19802 9447 19802 9445 19803 9503 19803 9447 19803 9436 19804 9439 19804 9442 19804 9433 19805 9436 19805 9442 19805 9437 19806 9438 19806 9439 19806 9436 19807 9437 19807 9439 19807 9487 19808 9424 19808 9433 19808 9486 19809 9487 19809 9433 19809 9477 19810 9476 19810 9424 19810 9487 19811 9477 19811 9424 19811 9504 19812 9429 19812 9428 19812 9504 19813 9430 19813 9429 19813 9505 19814 9428 19814 9427 19814 9506 19815 9504 19815 9428 19815 9505 19816 9506 19816 9428 19816 9507 19817 9427 19817 9490 19817 9508 19818 9427 19818 9507 19818 9508 19819 9505 19819 9427 19819 9509 19820 9490 19820 9491 19820 9510 19821 9507 19821 9490 19821 9509 19822 9510 19822 9490 19822 9511 19823 9491 19823 9492 19823 9512 19824 9509 19824 9491 19824 9513 19825 9512 19825 9491 19825 9511 19826 9513 19826 9491 19826 9514 19827 9492 19827 9493 19827 9515 19828 9511 19828 9492 19828 9514 19829 9515 19829 9492 19829 9516 19830 9493 19830 9494 19830 9514 19831 9493 19831 9516 19831 9516 19832 9494 19832 9489 19832 9517 19833 9489 19833 9495 19833 9517 19834 9518 19834 9489 19834 9516 19835 9489 19835 9518 19835 9519 19836 9497 19836 9503 19836 9520 19837 9498 19837 9497 19837 9519 19838 9521 19838 9497 19838 9520 19839 9497 19839 9521 19839 9519 19840 9503 19840 9445 19840 9519 19841 9445 19841 9451 19841 9519 19842 9451 19842 9452 19842 9522 19843 9452 19843 9453 19843 9522 19844 9519 19844 9452 19844 9522 19845 9453 19845 9450 19845 9523 19846 9450 19846 9460 19846 9522 19847 9450 19847 9523 19847 9504 19848 9415 19848 9430 19848 9524 19849 9419 19849 9415 19849 9524 19850 9415 19850 9504 19850 9523 19851 9462 19851 9461 19851 9523 19852 9460 19852 9462 19852 9525 19853 9461 19853 9459 19853 9526 19854 9523 19854 9461 19854 9527 19855 9526 19855 9461 19855 9525 19856 9527 19856 9461 19856 9528 19857 9459 19857 9499 19857 9529 19858 9459 19858 9528 19858 9530 19859 9525 19859 9459 19859 9529 19860 9530 19860 9459 19860 9531 19861 9499 19861 9500 19861 9532 19862 9528 19862 9499 19862 9531 19863 9532 19863 9499 19863 9533 19864 9500 19864 9501 19864 9534 19865 9531 19865 9500 19865 9535 19866 9534 19866 9500 19866 9533 19867 9535 19867 9500 19867 9536 19868 9501 19868 9502 19868 9537 19869 9533 19869 9501 19869 9536 19870 9537 19870 9501 19870 9520 19871 9502 19871 9498 19871 9538 19872 9502 19872 9520 19872 9538 19873 9536 19873 9502 19873 9517 19874 9495 19874 9418 19874 9517 19875 9418 19875 9420 19875 9517 19876 9420 19876 9421 19876 9524 19877 9421 19877 9419 19877 9524 19878 9517 19878 9421 19878 9539 19879 9521 19879 9519 19879 9540 19880 9520 19880 9521 19880 9541 19881 9540 19881 9521 19881 9542 19882 9541 19882 9521 19882 9543 19883 9542 19883 9521 19883 9544 19884 9543 19884 9521 19884 9545 19885 9544 19885 9521 19885 9546 19886 9545 19886 9521 19886 9546 19887 9521 19887 9539 19887 9547 19888 9519 19888 9522 19888 9548 19889 9549 19889 9519 19889 9550 19890 9519 19890 9549 19890 9547 19891 9548 19891 9519 19891 9551 19892 9539 19892 9519 19892 9552 19893 9551 19893 9519 19893 9553 19894 9552 19894 9519 19894 9554 19895 9553 19895 9519 19895 9555 19896 9554 19896 9519 19896 9556 19897 9555 19897 9519 19897 9550 19898 9556 19898 9519 19898 9538 19899 9520 19899 9540 19899 9557 19900 9540 19900 9541 19900 9557 19901 9538 19901 9540 19901 9558 19902 9541 19902 9542 19902 9557 19903 9541 19903 9558 19903 9558 19904 9542 19904 9543 19904 9559 19905 9543 19905 9544 19905 9558 19906 9543 19906 9559 19906 9545 19907 9560 19907 9544 19907 9559 19908 9544 19908 9560 19908 9545 19909 9561 19909 9560 19909 9562 19910 9560 19910 9561 19910 9559 19911 9560 19911 9562 19911 9545 19912 9563 19912 9561 19912 9562 19913 9561 19913 9563 19913 9545 19914 9564 19914 9563 19914 9565 19915 9563 19915 9564 19915 9562 19916 9563 19916 9565 19916 9545 19917 9566 19917 9564 19917 9565 19918 9564 19918 9566 19918 9545 19919 9567 19919 9566 19919 9565 19920 9566 19920 9567 19920 9568 19921 9569 19921 9567 19921 9570 19922 9567 19922 9569 19922 9545 19923 9568 19923 9567 19923 9565 19924 9567 19924 9570 19924 9568 19925 9571 19925 9569 19925 9570 19926 9569 19926 9571 19926 9568 19927 9572 19927 9571 19927 9573 19928 9571 19928 9572 19928 9570 19929 9571 19929 9573 19929 9568 19930 9574 19930 9572 19930 9573 19931 9572 19931 9574 19931 9568 19932 9575 19932 9574 19932 9576 19933 9574 19933 9575 19933 9573 19934 9574 19934 9576 19934 9568 19935 9577 19935 9575 19935 9576 19936 9575 19936 9577 19936 9578 19937 9579 19937 9577 19937 9580 19938 9577 19938 9579 19938 9568 19939 9578 19939 9577 19939 9576 19940 9577 19940 9580 19940 9578 19941 9581 19941 9579 19941 9582 19942 9579 19942 9581 19942 9580 19943 9579 19943 9582 19943 9578 19944 9583 19944 9581 19944 9582 19945 9581 19945 9583 19945 9584 19946 9585 19946 9583 19946 9586 19947 9583 19947 9585 19947 9578 19948 9584 19948 9583 19948 9582 19949 9583 19949 9586 19949 9584 19950 9587 19950 9585 19950 9586 19951 9585 19951 9587 19951 9584 19952 9588 19952 9587 19952 9589 19953 9587 19953 9588 19953 9586 19954 9587 19954 9589 19954 9590 19955 9591 19955 9588 19955 9592 19956 9588 19956 9591 19956 9584 19957 9590 19957 9588 19957 9589 19958 9588 19958 9592 19958 9590 19959 9593 19959 9591 19959 9594 19960 9591 19960 9593 19960 9592 19961 9591 19961 9594 19961 9595 19962 9596 19962 9593 19962 9597 19963 9593 19963 9596 19963 9590 19964 9595 19964 9593 19964 9594 19965 9593 19965 9597 19965 9595 19966 9598 19966 9596 19966 9599 19967 9596 19967 9598 19967 9597 19968 9596 19968 9599 19968 9600 19969 9601 19969 9598 19969 9602 19970 9598 19970 9601 19970 9595 19971 9600 19971 9598 19971 9603 19972 9598 19972 9602 19972 9599 19973 9598 19973 9603 19973 9604 19974 9605 19974 9601 19974 9606 19975 9601 19975 9605 19975 9600 19976 9604 19976 9601 19976 9602 19977 9601 19977 9606 19977 9607 19978 9608 19978 9605 19978 9609 19979 9605 19979 9608 19979 9604 19980 9607 19980 9605 19980 9610 19981 9605 19981 9609 19981 9606 19982 9605 19982 9610 19982 9611 19983 9612 19983 9608 19983 9613 19984 9608 19984 9612 19984 9614 19985 9611 19985 9608 19985 9607 19986 9614 19986 9608 19986 9609 19987 9608 19987 9613 19987 9615 19988 9616 19988 9612 19988 9617 19989 9612 19989 9616 19989 9618 19990 9615 19990 9612 19990 9611 19991 9618 19991 9612 19991 9619 19992 9612 19992 9617 19992 9613 19993 9612 19993 9619 19993 9620 19994 9621 19994 9616 19994 9622 19995 9616 19995 9621 19995 9615 19996 9620 19996 9616 19996 9623 19997 9616 19997 9622 19997 9624 19998 9616 19998 9623 19998 9617 19999 9616 19999 9624 19999 9625 20000 9626 20000 9621 20000 9627 20001 9621 20001 9626 20001 9628 20002 9625 20002 9621 20002 9620 20003 9628 20003 9621 20003 9629 20004 9621 20004 9627 20004 9622 20005 9621 20005 9629 20005 9630 20006 9631 20006 9626 20006 9632 20007 9626 20007 9631 20007 9633 20008 9630 20008 9626 20008 9625 20009 9633 20009 9626 20009 9634 20010 9626 20010 9632 20010 9627 20011 9626 20011 9634 20011 9635 20012 9636 20012 9631 20012 9637 20013 9631 20013 9636 20013 9630 20014 9635 20014 9631 20014 9638 20015 9631 20015 9637 20015 9632 20016 9631 20016 9638 20016 9639 20017 9640 20017 9636 20017 9641 20018 9636 20018 9640 20018 9642 20019 9639 20019 9636 20019 9643 20020 9642 20020 9636 20020 9644 20021 9643 20021 9636 20021 9645 20022 9644 20022 9636 20022 9635 20023 9645 20023 9636 20023 9637 20024 9636 20024 9641 20024 9646 20025 9640 20025 9639 20025 9647 20026 9640 20026 9646 20026 9641 20027 9640 20027 9647 20027 9646 20028 9639 20028 9642 20028 9648 20029 9642 20029 9643 20029 9648 20030 9646 20030 9642 20030 9649 20031 9643 20031 9644 20031 9649 20032 9648 20032 9643 20032 9649 20033 9644 20033 9645 20033 9650 20034 9645 20034 9635 20034 9649 20035 9645 20035 9650 20035 9650 20036 9635 20036 9630 20036 9651 20037 9630 20037 9633 20037 9651 20038 9650 20038 9630 20038 9651 20039 9633 20039 9625 20039 9652 20040 9625 20040 9628 20040 9652 20041 9651 20041 9625 20041 9652 20042 9628 20042 9620 20042 9652 20043 9620 20043 9615 20043 9653 20044 9615 20044 9618 20044 9653 20045 9652 20045 9615 20045 9653 20046 9618 20046 9611 20046 9654 20047 9611 20047 9614 20047 9654 20048 9653 20048 9611 20048 9654 20049 9614 20049 9607 20049 9655 20050 9607 20050 9604 20050 9655 20051 9654 20051 9607 20051 9655 20052 9604 20052 9600 20052 9656 20053 9600 20053 9595 20053 9656 20054 9655 20054 9600 20054 9656 20055 9595 20055 9590 20055 9657 20056 9590 20056 9584 20056 9657 20057 9656 20057 9590 20057 9658 20058 9584 20058 9578 20058 9658 20059 9657 20059 9584 20059 9658 20060 9578 20060 9568 20060 9659 20061 9568 20061 9545 20061 9659 20062 9658 20062 9568 20062 9546 20063 9659 20063 9545 20063 9660 20064 9522 20064 9523 20064 9661 20065 9660 20065 9523 20065 9661 20066 9523 20066 9526 20066 9662 20067 9663 20067 9522 20067 9664 20068 9522 20068 9663 20068 9665 20069 9662 20069 9522 20069 9660 20070 9665 20070 9522 20070 9666 20071 9547 20071 9522 20071 9667 20072 9666 20072 9522 20072 9668 20073 9667 20073 9522 20073 9669 20074 9668 20074 9522 20074 9670 20075 9669 20075 9522 20075 9664 20076 9670 20076 9522 20076 9671 20077 9672 20077 9663 20077 9673 20078 9663 20078 9672 20078 9674 20079 9671 20079 9663 20079 9675 20080 9674 20080 9663 20080 9676 20081 9675 20081 9663 20081 9677 20082 9676 20082 9663 20082 9678 20083 9677 20083 9663 20083 9679 20084 9678 20084 9663 20084 9680 20085 9679 20085 9663 20085 9681 20086 9680 20086 9663 20086 9662 20087 9681 20087 9663 20087 9664 20088 9663 20088 9668 20088 9673 20089 9668 20089 9663 20089 9682 20090 9683 20090 9672 20090 9684 20091 9672 20091 9683 20091 9685 20092 9682 20092 9672 20092 9686 20093 9685 20093 9672 20093 9687 20094 9686 20094 9672 20094 9688 20095 9687 20095 9672 20095 9689 20096 9688 20096 9672 20096 9671 20097 9689 20097 9672 20097 9673 20098 9672 20098 9684 20098 9690 20099 9691 20099 9683 20099 9692 20100 9683 20100 9691 20100 9693 20101 9690 20101 9683 20101 9694 20102 9693 20102 9683 20102 9695 20103 9694 20103 9683 20103 9682 20104 9695 20104 9683 20104 9684 20105 9683 20105 9692 20105 9696 20106 9697 20106 9691 20106 9698 20107 9691 20107 9697 20107 9699 20108 9696 20108 9691 20108 9690 20109 9699 20109 9691 20109 9692 20110 9691 20110 9698 20110 9700 20111 9701 20111 9697 20111 9702 20112 9697 20112 9701 20112 9703 20113 9700 20113 9697 20113 9696 20114 9703 20114 9697 20114 9698 20115 9697 20115 9702 20115 9704 20116 9705 20116 9701 20116 9706 20117 9701 20117 9705 20117 9700 20118 9704 20118 9701 20118 9702 20119 9701 20119 9706 20119 9707 20120 9708 20120 9705 20120 9706 20121 9705 20121 9708 20121 9704 20122 9707 20122 9705 20122 9709 20123 9710 20123 9708 20123 9711 20124 9708 20124 9710 20124 9707 20125 9709 20125 9708 20125 9706 20126 9708 20126 9711 20126 9712 20127 9713 20127 9710 20127 9711 20128 9710 20128 9713 20128 9709 20129 9712 20129 9710 20129 9714 20130 9715 20130 9713 20130 9716 20131 9713 20131 9715 20131 9712 20132 9714 20132 9713 20132 9711 20133 9713 20133 9716 20133 9714 20134 9717 20134 9715 20134 9718 20135 9715 20135 9717 20135 9716 20136 9715 20136 9718 20136 9719 20137 9720 20137 9717 20137 9718 20138 9717 20138 9720 20138 9714 20139 9719 20139 9717 20139 9719 20140 9721 20140 9720 20140 9718 20141 9720 20141 9721 20141 9722 20142 9723 20142 9721 20142 9724 20143 9721 20143 9723 20143 9719 20144 9722 20144 9721 20144 9718 20145 9721 20145 9724 20145 9725 20146 9726 20146 9723 20146 9724 20147 9723 20147 9726 20147 9722 20148 9725 20148 9723 20148 9727 20149 9728 20149 9726 20149 9729 20150 9726 20150 9728 20150 9725 20151 9727 20151 9726 20151 9724 20152 9726 20152 9729 20152 9727 20153 9730 20153 9728 20153 9731 20154 9728 20154 9730 20154 9731 20155 9729 20155 9728 20155 9727 20156 9732 20156 9730 20156 9733 20157 9730 20157 9732 20157 9733 20158 9731 20158 9730 20158 9727 20159 9734 20159 9732 20159 9733 20160 9732 20160 9734 20160 9735 20161 9734 20161 9727 20161 9736 20162 9733 20162 9734 20162 9737 20163 9736 20163 9734 20163 9738 20164 9737 20164 9734 20164 9735 20165 9738 20165 9734 20165 9739 20166 9727 20166 9725 20166 9739 20167 9735 20167 9727 20167 9740 20168 9725 20168 9722 20168 9740 20169 9739 20169 9725 20169 9741 20170 9722 20170 9719 20170 9742 20171 9740 20171 9722 20171 9741 20172 9742 20172 9722 20172 9743 20173 9719 20173 9714 20173 9743 20174 9741 20174 9719 20174 9744 20175 9714 20175 9712 20175 9745 20176 9743 20176 9714 20176 9746 20177 9745 20177 9714 20177 9744 20178 9746 20178 9714 20178 9747 20179 9712 20179 9709 20179 9748 20180 9744 20180 9712 20180 9747 20181 9748 20181 9712 20181 9749 20182 9709 20182 9707 20182 9750 20183 9747 20183 9709 20183 9751 20184 9750 20184 9709 20184 9749 20185 9751 20185 9709 20185 9752 20186 9707 20186 9704 20186 9753 20187 9749 20187 9707 20187 9752 20188 9753 20188 9707 20188 9754 20189 9704 20189 9700 20189 9755 20190 9752 20190 9704 20190 9754 20191 9755 20191 9704 20191 9756 20192 9700 20192 9703 20192 9756 20193 9754 20193 9700 20193 9757 20194 9703 20194 9696 20194 9758 20195 9756 20195 9703 20195 9757 20196 9758 20196 9703 20196 9759 20197 9696 20197 9699 20197 9759 20198 9757 20198 9696 20198 9760 20199 9699 20199 9690 20199 9760 20200 9759 20200 9699 20200 9761 20201 9690 20201 9693 20201 9761 20202 9760 20202 9690 20202 9762 20203 9693 20203 9694 20203 9762 20204 9761 20204 9693 20204 9762 20205 9694 20205 9695 20205 9763 20206 9695 20206 9682 20206 9763 20207 9762 20207 9695 20207 9763 20208 9682 20208 9685 20208 9764 20209 9685 20209 9686 20209 9764 20210 9763 20210 9685 20210 9764 20211 9686 20211 9687 20211 9765 20212 9687 20212 9688 20212 9765 20213 9764 20213 9687 20213 9765 20214 9688 20214 9689 20214 9766 20215 9689 20215 9671 20215 9766 20216 9765 20216 9689 20216 9766 20217 9671 20217 9674 20217 9767 20218 9674 20218 9675 20218 9767 20219 9766 20219 9674 20219 9767 20220 9675 20220 9676 20220 9768 20221 9676 20221 9677 20221 9768 20222 9767 20222 9676 20222 9769 20223 9677 20223 9678 20223 9769 20224 9768 20224 9677 20224 9769 20225 9678 20225 9679 20225 9769 20226 9679 20226 9680 20226 9770 20227 9680 20227 9681 20227 9770 20228 9769 20228 9680 20228 9770 20229 9681 20229 9662 20229 9771 20230 9662 20230 9665 20230 9771 20231 9770 20231 9662 20231 9661 20232 9665 20232 9660 20232 9661 20233 9771 20233 9665 20233 9529 20234 9528 20234 9532 20234 9772 20235 9532 20235 9531 20235 9773 20236 9532 20236 9772 20236 9529 20237 9532 20237 9773 20237 9772 20238 9531 20238 9534 20238 9535 20239 9772 20239 9534 20239 9774 20240 9773 20240 9772 20240 9774 20241 9772 20241 9775 20241 9776 20242 9775 20242 9772 20242 9776 20243 9772 20243 9535 20243 9529 20244 9773 20244 9774 20244 9777 20245 9778 20245 9779 20245 9780 20246 9779 20246 9778 20246 9781 20247 9777 20247 9779 20247 9782 20248 9781 20248 9779 20248 9780 20249 9782 20249 9779 20249 9783 20250 9784 20250 9778 20250 9785 20251 9778 20251 9784 20251 9777 20252 9783 20252 9778 20252 9786 20253 9780 20253 9778 20253 9785 20254 9786 20254 9778 20254 9787 20255 9788 20255 9784 20255 9789 20256 9784 20256 9788 20256 9783 20257 9787 20257 9784 20257 9789 20258 9785 20258 9784 20258 9787 20259 9790 20259 9788 20259 9791 20260 9788 20260 9790 20260 9791 20261 9789 20261 9788 20261 9792 20262 9793 20262 9790 20262 9791 20263 9790 20263 9793 20263 9787 20264 9792 20264 9790 20264 9794 20265 9795 20265 9793 20265 9796 20266 9793 20266 9795 20266 9792 20267 9794 20267 9793 20267 9796 20268 9791 20268 9793 20268 9797 20269 9798 20269 9795 20269 9799 20270 9795 20270 9798 20270 9794 20271 9797 20271 9795 20271 9799 20272 9796 20272 9795 20272 9800 20273 9801 20273 9798 20273 9802 20274 9798 20274 9801 20274 9797 20275 9800 20275 9798 20275 9802 20276 9799 20276 9798 20276 9803 20277 9804 20277 9801 20277 9802 20278 9801 20278 9804 20278 9800 20279 9803 20279 9801 20279 9805 20280 9806 20280 9804 20280 9807 20281 9804 20281 9806 20281 9803 20282 9805 20282 9804 20282 9807 20283 9802 20283 9804 20283 9808 20284 9809 20284 9806 20284 9807 20285 9806 20285 9809 20285 9805 20286 9808 20286 9806 20286 9810 20287 9811 20287 9809 20287 9812 20288 9809 20288 9811 20288 9808 20289 9810 20289 9809 20289 9812 20290 9807 20290 9809 20290 9813 20291 9814 20291 9811 20291 9812 20292 9811 20292 9814 20292 9810 20293 9813 20293 9811 20293 9815 20294 9816 20294 9814 20294 9817 20295 9814 20295 9816 20295 9813 20296 9815 20296 9814 20296 9817 20297 9812 20297 9814 20297 9818 20298 9819 20298 9816 20298 9820 20299 9816 20299 9819 20299 9815 20300 9818 20300 9816 20300 9820 20301 9817 20301 9816 20301 9821 20302 9822 20302 9819 20302 9820 20303 9819 20303 9822 20303 9818 20304 9821 20304 9819 20304 9823 20305 9824 20305 9822 20305 9825 20306 9822 20306 9824 20306 9826 20307 9823 20307 9822 20307 9821 20308 9826 20308 9822 20308 9825 20309 9820 20309 9822 20309 9827 20310 9828 20310 9824 20310 9829 20311 9824 20311 9828 20311 9823 20312 9827 20312 9824 20312 9829 20313 9825 20313 9824 20313 9830 20314 9831 20314 9828 20314 9829 20315 9828 20315 9831 20315 9827 20316 9830 20316 9828 20316 9832 20317 9833 20317 9831 20317 9834 20318 9831 20318 9833 20318 9830 20319 9832 20319 9831 20319 9834 20320 9829 20320 9831 20320 9835 20321 9836 20321 9833 20321 9834 20322 9833 20322 9836 20322 9832 20323 9835 20323 9833 20323 9837 20324 9838 20324 9836 20324 9839 20325 9836 20325 9838 20325 9835 20326 9837 20326 9836 20326 9839 20327 9834 20327 9836 20327 9840 20328 9841 20328 9838 20328 9842 20329 9838 20329 9841 20329 9837 20330 9840 20330 9838 20330 9842 20331 9839 20331 9838 20331 9843 20332 9844 20332 9841 20332 9842 20333 9841 20333 9844 20333 9840 20334 9843 20334 9841 20334 9843 20335 9845 20335 9844 20335 9846 20336 9844 20336 9845 20336 9846 20337 9842 20337 9844 20337 9843 20338 9847 20338 9845 20338 9848 20339 9845 20339 9847 20339 9848 20340 9846 20340 9845 20340 9849 20341 9850 20341 9847 20341 9851 20342 9847 20342 9850 20342 9852 20343 9849 20343 9847 20343 9843 20344 9852 20344 9847 20344 9851 20345 9848 20345 9847 20345 9853 20346 9854 20346 9850 20346 9855 20347 9850 20347 9854 20347 9849 20348 9853 20348 9850 20348 9855 20349 9851 20349 9850 20349 9856 20350 9857 20350 9854 20350 9858 20351 9854 20351 9857 20351 9853 20352 9856 20352 9854 20352 9859 20353 9855 20353 9854 20353 9858 20354 9859 20354 9854 20354 9860 20355 9861 20355 9857 20355 9858 20356 9857 20356 9861 20356 9856 20357 9860 20357 9857 20357 9862 20358 9863 20358 9861 20358 9864 20359 9861 20359 9863 20359 9860 20360 9862 20360 9861 20360 9864 20361 9858 20361 9861 20361 9865 20362 9866 20362 9863 20362 9867 20363 9863 20363 9866 20363 9862 20364 9865 20364 9863 20364 9867 20365 9864 20365 9863 20365 9868 20366 9869 20366 9866 20366 9867 20367 9866 20367 9869 20367 9865 20368 9868 20368 9866 20368 9870 20369 9871 20369 9869 20369 9872 20370 9869 20370 9871 20370 9873 20371 9870 20371 9869 20371 9868 20372 9873 20372 9869 20372 9872 20373 9867 20373 9869 20373 9874 20374 9875 20374 9871 20374 9876 20375 9871 20375 9875 20375 9870 20376 9874 20376 9871 20376 9876 20377 9872 20377 9871 20377 9877 20378 9878 20378 9875 20378 9876 20379 9875 20379 9878 20379 9874 20380 9877 20380 9875 20380 9879 20381 9880 20381 9878 20381 9881 20382 9878 20382 9880 20382 9882 20383 9879 20383 9878 20383 9877 20384 9882 20384 9878 20384 9881 20385 9876 20385 9878 20385 9883 20386 9884 20386 9880 20386 9881 20387 9880 20387 9884 20387 9879 20388 9883 20388 9880 20388 9885 20389 9886 20389 9884 20389 9887 20390 9884 20390 9886 20390 9883 20391 9885 20391 9884 20391 9887 20392 9881 20392 9884 20392 9888 20393 9889 20393 9886 20393 9887 20394 9886 20394 9889 20394 9885 20395 9888 20395 9886 20395 9890 20396 9891 20396 9889 20396 9892 20397 9889 20397 9891 20397 9888 20398 9890 20398 9889 20398 9892 20399 9887 20399 9889 20399 9893 20400 9894 20400 9891 20400 9892 20401 9891 20401 9894 20401 9890 20402 9893 20402 9891 20402 9895 20403 9896 20403 9894 20403 9897 20404 9894 20404 9896 20404 9893 20405 9895 20405 9894 20405 9897 20406 9892 20406 9894 20406 9898 20407 9899 20407 9896 20407 9897 20408 9896 20408 9899 20408 9895 20409 9898 20409 9896 20409 9900 20410 9901 20410 9899 20410 9902 20411 9899 20411 9901 20411 9898 20412 9900 20412 9899 20412 9902 20413 9897 20413 9899 20413 9903 20414 9904 20414 9901 20414 9902 20415 9901 20415 9904 20415 9900 20416 9903 20416 9901 20416 9905 20417 9906 20417 9904 20417 9907 20418 9904 20418 9906 20418 9903 20419 9905 20419 9904 20419 9907 20420 9902 20420 9904 20420 9908 20421 9909 20421 9906 20421 9907 20422 9906 20422 9909 20422 9910 20423 9908 20423 9906 20423 9905 20424 9910 20424 9906 20424 9911 20425 9912 20425 9909 20425 9913 20426 9909 20426 9912 20426 9908 20427 9911 20427 9909 20427 9913 20428 9907 20428 9909 20428 9914 20429 9775 20429 9912 20429 9776 20430 9912 20430 9775 20430 9911 20431 9914 20431 9912 20431 9776 20432 9913 20432 9912 20432 9914 20433 9774 20433 9775 20433 9915 20434 9774 20434 9914 20434 9915 20435 9529 20435 9774 20435 9915 20436 9914 20436 9911 20436 9916 20437 9911 20437 9908 20437 9916 20438 9915 20438 9911 20438 9916 20439 9908 20439 9910 20439 9917 20440 9910 20440 9905 20440 9917 20441 9916 20441 9910 20441 9917 20442 9905 20442 9903 20442 9917 20443 9903 20443 9900 20443 9918 20444 9900 20444 9898 20444 9918 20445 9917 20445 9900 20445 9918 20446 9898 20446 9895 20446 9919 20447 9895 20447 9893 20447 9919 20448 9918 20448 9895 20448 9920 20449 9893 20449 9890 20449 9920 20450 9919 20450 9893 20450 9920 20451 9890 20451 9888 20451 9920 20452 9888 20452 9885 20452 9921 20453 9885 20453 9883 20453 9921 20454 9920 20454 9885 20454 9921 20455 9883 20455 9879 20455 9922 20456 9879 20456 9882 20456 9922 20457 9921 20457 9879 20457 9922 20458 9882 20458 9877 20458 9922 20459 9877 20459 9874 20459 9923 20460 9874 20460 9870 20460 9923 20461 9922 20461 9874 20461 9923 20462 9870 20462 9873 20462 9924 20463 9873 20463 9868 20463 9924 20464 9923 20464 9873 20464 9925 20465 9868 20465 9865 20465 9925 20466 9924 20466 9868 20466 9925 20467 9865 20467 9862 20467 9926 20468 9862 20468 9860 20468 9926 20469 9925 20469 9862 20469 9927 20470 9860 20470 9856 20470 9927 20471 9926 20471 9860 20471 9928 20472 9856 20472 9853 20472 9928 20473 9927 20473 9856 20473 9929 20474 9853 20474 9849 20474 9929 20475 9928 20475 9853 20475 9930 20476 9849 20476 9852 20476 9930 20477 9929 20477 9849 20477 9931 20478 9852 20478 9843 20478 9931 20479 9930 20479 9852 20479 9932 20480 9843 20480 9840 20480 9932 20481 9931 20481 9843 20481 9933 20482 9840 20482 9837 20482 9933 20483 9932 20483 9840 20483 9934 20484 9837 20484 9835 20484 9934 20485 9933 20485 9837 20485 9934 20486 9835 20486 9832 20486 9935 20487 9832 20487 9830 20487 9935 20488 9934 20488 9832 20488 9936 20489 9830 20489 9827 20489 9936 20490 9935 20490 9830 20490 9936 20491 9827 20491 9823 20491 9937 20492 9823 20492 9826 20492 9937 20493 9936 20493 9823 20493 9937 20494 9826 20494 9821 20494 9938 20495 9821 20495 9818 20495 9938 20496 9937 20496 9821 20496 9938 20497 9818 20497 9815 20497 9939 20498 9815 20498 9813 20498 9939 20499 9938 20499 9815 20499 9940 20500 9813 20500 9810 20500 9940 20501 9939 20501 9813 20501 9940 20502 9810 20502 9808 20502 9941 20503 9808 20503 9805 20503 9941 20504 9940 20504 9808 20504 9941 20505 9805 20505 9803 20505 9942 20506 9803 20506 9800 20506 9942 20507 9941 20507 9803 20507 9943 20508 9800 20508 9797 20508 9943 20509 9942 20509 9800 20509 9943 20510 9797 20510 9794 20510 9944 20511 9794 20511 9792 20511 9944 20512 9943 20512 9794 20512 9944 20513 9792 20513 9787 20513 9945 20514 9787 20514 9783 20514 9945 20515 9944 20515 9787 20515 9946 20516 9783 20516 9777 20516 9947 20517 9945 20517 9783 20517 9946 20518 9947 20518 9783 20518 9948 20519 9777 20519 9781 20519 9948 20520 9946 20520 9777 20520 9949 20521 9781 20521 9782 20521 9736 20522 9781 20522 9949 20522 9950 20523 9781 20523 9736 20523 9948 20524 9781 20524 9950 20524 9951 20525 9949 20525 9782 20525 9648 20526 9951 20526 9782 20526 9648 20527 9782 20527 9646 20527 9952 20528 9646 20528 9782 20528 9953 20529 9952 20529 9782 20529 9954 20530 9955 20530 9956 20530 9780 20531 9953 20531 9782 20531 9957 20532 9949 20532 9951 20532 9736 20533 9949 20533 9957 20533 9958 20534 9959 20534 9960 20534 9650 20535 9960 20535 9959 20535 9961 20536 9958 20536 9960 20536 9962 20537 9961 20537 9960 20537 9651 20538 9962 20538 9960 20538 9651 20539 9960 20539 9650 20539 9957 20540 9951 20540 9959 20540 9649 20541 9959 20541 9951 20541 9958 20542 9957 20542 9959 20542 9649 20543 9650 20543 9959 20543 9649 20544 9951 20544 9648 20544 9733 20545 9957 20545 9958 20545 9736 20546 9957 20546 9733 20546 9731 20547 9958 20547 9961 20547 9733 20548 9958 20548 9731 20548 9963 20549 9961 20549 9962 20549 9729 20550 9961 20550 9963 20550 9731 20551 9961 20551 9729 20551 9964 20552 9965 20552 9549 20552 9550 20553 9549 20553 9965 20553 9548 20554 9964 20554 9549 20554 9966 20555 9967 20555 9965 20555 9546 20556 9965 20556 9967 20556 9964 20557 9966 20557 9965 20557 9554 20558 9965 20558 9553 20558 9546 20559 9553 20559 9965 20559 9555 20560 9965 20560 9554 20560 9556 20561 9965 20561 9555 20561 9550 20562 9965 20562 9556 20562 9968 20563 9969 20563 9967 20563 9659 20564 9967 20564 9969 20564 9966 20565 9968 20565 9967 20565 9546 20566 9967 20566 9659 20566 9970 20567 9971 20567 9969 20567 9658 20568 9969 20568 9971 20568 9968 20569 9970 20569 9969 20569 9659 20570 9969 20570 9658 20570 9970 20571 9972 20571 9971 20571 9658 20572 9971 20572 9972 20572 9973 20573 9974 20573 9972 20573 9657 20574 9972 20574 9974 20574 9970 20575 9973 20575 9972 20575 9658 20576 9972 20576 9657 20576 9975 20577 9976 20577 9974 20577 9656 20578 9974 20578 9976 20578 9973 20579 9975 20579 9974 20579 9657 20580 9974 20580 9656 20580 9977 20581 9978 20581 9976 20581 9656 20582 9976 20582 9978 20582 9975 20583 9977 20583 9976 20583 9977 20584 9979 20584 9978 20584 9655 20585 9978 20585 9979 20585 9656 20586 9978 20586 9655 20586 9980 20587 9981 20587 9979 20587 9655 20588 9979 20588 9981 20588 9977 20589 9980 20589 9979 20589 9982 20590 9983 20590 9981 20590 9654 20591 9981 20591 9983 20591 9980 20592 9982 20592 9981 20592 9655 20593 9981 20593 9654 20593 9982 20594 9984 20594 9983 20594 9654 20595 9983 20595 9984 20595 9985 20596 9986 20596 9984 20596 9653 20597 9984 20597 9986 20597 9982 20598 9985 20598 9984 20598 9654 20599 9984 20599 9653 20599 9987 20600 9988 20600 9986 20600 9653 20601 9986 20601 9988 20601 9985 20602 9987 20602 9986 20602 9989 20603 9990 20603 9988 20603 9653 20604 9988 20604 9990 20604 9987 20605 9989 20605 9988 20605 9989 20606 9991 20606 9990 20606 9652 20607 9990 20607 9991 20607 9653 20608 9990 20608 9652 20608 9992 20609 9993 20609 9991 20609 9652 20610 9991 20610 9993 20610 9989 20611 9992 20611 9991 20611 9994 20612 9995 20612 9993 20612 9651 20613 9993 20613 9995 20613 9992 20614 9994 20614 9993 20614 9652 20615 9993 20615 9651 20615 9963 20616 9962 20616 9995 20616 9651 20617 9995 20617 9962 20617 9994 20618 9963 20618 9995 20618 9724 20619 9963 20619 9994 20619 9724 20620 9729 20620 9963 20620 9724 20621 9994 20621 9992 20621 9718 20622 9992 20622 9989 20622 9718 20623 9724 20623 9992 20623 9718 20624 9989 20624 9987 20624 9716 20625 9987 20625 9985 20625 9716 20626 9718 20626 9987 20626 9716 20627 9985 20627 9982 20627 9711 20628 9982 20628 9980 20628 9711 20629 9716 20629 9982 20629 9706 20630 9980 20630 9977 20630 9706 20631 9711 20631 9980 20631 9706 20632 9977 20632 9975 20632 9702 20633 9975 20633 9973 20633 9702 20634 9706 20634 9975 20634 9698 20635 9973 20635 9970 20635 9698 20636 9702 20636 9973 20636 9692 20637 9970 20637 9968 20637 9692 20638 9698 20638 9970 20638 9684 20639 9968 20639 9966 20639 9684 20640 9692 20640 9968 20640 9673 20641 9966 20641 9964 20641 9673 20642 9684 20642 9966 20642 9668 20643 9964 20643 9548 20643 9673 20644 9964 20644 9668 20644 9666 20645 9548 20645 9547 20645 9667 20646 9548 20646 9666 20646 9668 20647 9548 20647 9667 20647 9670 20648 9668 20648 9669 20648 9664 20649 9668 20649 9670 20649 9546 20650 9539 20650 9551 20650 9546 20651 9551 20651 9552 20651 9546 20652 9552 20652 9553 20652 9996 20653 9518 20653 9517 20653 9997 20654 9516 20654 9518 20654 9998 20655 9997 20655 9518 20655 9999 20656 9998 20656 9518 20656 10000 20657 9999 20657 9518 20657 10001 20658 10000 20658 9518 20658 10002 20659 10001 20659 9518 20659 10002 20660 9518 20660 9996 20660 10003 20661 9517 20661 9524 20661 10004 20662 10005 20662 9517 20662 10006 20663 9517 20663 10005 20663 10007 20664 10004 20664 9517 20664 10008 20665 10007 20665 9517 20665 10003 20666 10008 20666 9517 20666 10009 20667 9996 20667 9517 20667 10010 20668 10009 20668 9517 20668 10011 20669 10010 20669 9517 20669 10012 20670 10011 20670 9517 20670 10013 20671 10012 20671 9517 20671 10014 20672 10013 20672 9517 20672 10006 20673 10014 20673 9517 20673 9514 20674 9516 20674 9997 20674 10015 20675 9997 20675 9998 20675 10015 20676 9514 20676 9997 20676 10016 20677 9998 20677 9999 20677 10015 20678 9998 20678 10016 20678 10016 20679 9999 20679 10000 20679 10001 20680 10017 20680 10000 20680 10018 20681 10000 20681 10017 20681 10016 20682 10000 20682 10018 20682 10001 20683 10019 20683 10017 20683 10018 20684 10017 20684 10019 20684 10020 20685 10021 20685 10019 20685 10022 20686 10019 20686 10021 20686 10001 20687 10020 20687 10019 20687 10018 20688 10019 20688 10022 20688 10020 20689 10023 20689 10021 20689 10022 20690 10021 20690 10023 20690 10020 20691 10024 20691 10023 20691 10025 20692 10023 20692 10024 20692 10022 20693 10023 20693 10025 20693 10020 20694 10026 20694 10024 20694 10025 20695 10024 20695 10026 20695 10020 20696 10027 20696 10026 20696 10025 20697 10026 20697 10027 20697 10028 20698 10029 20698 10027 20698 10030 20699 10027 20699 10029 20699 10020 20700 10028 20700 10027 20700 10025 20701 10027 20701 10030 20701 10028 20702 10031 20702 10029 20702 10030 20703 10029 20703 10031 20703 10028 20704 10032 20704 10031 20704 10033 20705 10031 20705 10032 20705 10030 20706 10031 20706 10033 20706 10028 20707 10034 20707 10032 20707 10035 20708 10032 20708 10034 20708 10033 20709 10032 20709 10035 20709 10036 20710 10037 20710 10034 20710 10035 20711 10034 20711 10037 20711 10028 20712 10036 20712 10034 20712 10036 20713 10038 20713 10037 20713 10039 20714 10037 20714 10038 20714 10035 20715 10037 20715 10039 20715 10036 20716 10040 20716 10038 20716 10041 20717 10038 20717 10040 20717 10039 20718 10038 20718 10041 20718 10042 20719 10043 20719 10040 20719 10044 20720 10040 20720 10043 20720 10036 20721 10042 20721 10040 20721 10041 20722 10040 20722 10044 20722 10042 20723 10045 20723 10043 20723 10046 20724 10043 20724 10045 20724 10044 20725 10043 20725 10046 20725 10047 20726 10048 20726 10045 20726 10049 20727 10045 20727 10048 20727 10042 20728 10047 20728 10045 20728 10046 20729 10045 20729 10049 20729 10047 20730 10050 20730 10048 20730 10051 20731 10048 20731 10050 20731 10049 20732 10048 20732 10051 20732 10052 20733 10053 20733 10050 20733 10054 20734 10050 20734 10053 20734 10047 20735 10052 20735 10050 20735 10051 20736 10050 20736 10054 20736 10055 20737 10056 20737 10053 20737 10057 20738 10053 20738 10056 20738 10052 20739 10055 20739 10053 20739 10054 20740 10053 20740 10057 20740 10058 20741 10059 20741 10056 20741 10060 20742 10056 20742 10059 20742 10055 20743 10058 20743 10056 20743 10057 20744 10056 20744 10060 20744 10061 20745 10062 20745 10059 20745 10063 20746 10059 20746 10062 20746 10058 20747 10061 20747 10059 20747 10064 20748 10059 20748 10063 20748 10060 20749 10059 20749 10064 20749 10065 20750 10066 20750 10062 20750 10067 20751 10062 20751 10066 20751 10068 20752 10065 20752 10062 20752 10061 20753 10068 20753 10062 20753 10069 20754 10062 20754 10067 20754 10063 20755 10062 20755 10069 20755 10070 20756 10071 20756 10066 20756 10072 20757 10066 20757 10071 20757 10073 20758 10070 20758 10066 20758 10065 20759 10073 20759 10066 20759 10067 20760 10066 20760 10072 20760 10074 20761 10075 20761 10071 20761 10076 20762 10071 20762 10075 20762 10077 20763 10074 20763 10071 20763 10078 20764 10077 20764 10071 20764 10070 20765 10078 20765 10071 20765 10079 20766 10071 20766 10076 20766 10072 20767 10071 20767 10079 20767 10080 20768 10081 20768 10075 20768 10082 20769 10075 20769 10081 20769 10083 20770 10080 20770 10075 20770 10084 20771 10083 20771 10075 20771 10085 20772 10084 20772 10075 20772 10074 20773 10085 20773 10075 20773 10086 20774 10075 20774 10082 20774 10087 20775 10075 20775 10086 20775 10076 20776 10075 20776 10087 20776 10088 20777 10089 20777 10081 20777 10090 20778 10081 20778 10089 20778 10091 20779 10088 20779 10081 20779 10092 20780 10091 20780 10081 20780 10093 20781 10092 20781 10081 20781 10080 20782 10093 20782 10081 20782 10094 20783 10081 20783 10090 20783 10082 20784 10081 20784 10094 20784 10095 20785 10096 20785 10089 20785 10097 20786 10089 20786 10096 20786 10098 20787 10095 20787 10089 20787 10099 20788 10098 20788 10089 20788 10100 20789 10099 20789 10089 20789 10101 20790 10100 20790 10089 20790 10102 20791 10101 20791 10089 20791 10103 20792 10102 20792 10089 20792 10104 20793 10103 20793 10089 20793 10088 20794 10104 20794 10089 20794 10105 20795 10089 20795 10097 20795 10106 20796 10089 20796 10105 20796 10090 20797 10089 20797 10106 20797 10107 20798 10096 20798 10095 20798 10108 20799 10096 20799 10107 20799 10109 20800 10096 20800 10108 20800 10097 20801 10096 20801 10109 20801 10107 20802 10095 20802 10098 20802 10110 20803 10098 20803 10099 20803 10110 20804 10107 20804 10098 20804 10111 20805 10099 20805 10100 20805 10111 20806 10110 20806 10099 20806 10111 20807 10100 20807 10101 20807 10112 20808 10101 20808 10102 20808 10111 20809 10101 20809 10112 20809 10112 20810 10102 20810 10103 20810 10112 20811 10103 20811 10104 20811 10113 20812 10104 20812 10088 20812 10113 20813 10112 20813 10104 20813 10113 20814 10088 20814 10091 20814 10113 20815 10091 20815 10092 20815 10113 20816 10092 20816 10093 20816 10114 20817 10093 20817 10080 20817 10114 20818 10113 20818 10093 20818 10114 20819 10080 20819 10083 20819 10114 20820 10083 20820 10084 20820 10114 20821 10084 20821 10085 20821 10115 20822 10085 20822 10074 20822 10115 20823 10114 20823 10085 20823 10115 20824 10074 20824 10077 20824 10115 20825 10077 20825 10078 20825 10116 20826 10078 20826 10070 20826 10116 20827 10115 20827 10078 20827 10116 20828 10070 20828 10073 20828 10116 20829 10073 20829 10065 20829 10117 20830 10065 20830 10068 20830 10117 20831 10116 20831 10065 20831 10117 20832 10068 20832 10061 20832 10118 20833 10061 20833 10058 20833 10118 20834 10117 20834 10061 20834 10118 20835 10058 20835 10055 20835 10119 20836 10055 20836 10052 20836 10119 20837 10118 20837 10055 20837 10120 20838 10052 20838 10047 20838 10120 20839 10119 20839 10052 20839 10121 20840 10047 20840 10042 20840 10121 20841 10120 20841 10047 20841 10121 20842 10042 20842 10036 20842 10122 20843 10036 20843 10028 20843 10122 20844 10121 20844 10036 20844 10123 20845 10028 20845 10020 20845 10123 20846 10122 20846 10028 20846 10002 20847 10020 20847 10001 20847 10002 20848 10123 20848 10020 20848 10124 20849 10125 20849 10126 20849 10127 20850 10126 20850 10125 20850 10128 20851 10124 20851 10126 20851 10129 20852 10128 20852 10126 20852 10130 20853 10129 20853 10126 20853 10127 20854 10130 20854 10126 20854 10124 20855 10131 20855 10125 20855 10132 20856 10125 20856 10131 20856 10133 20857 10127 20857 10125 20857 10132 20858 10133 20858 10125 20858 10124 20859 10134 20859 10131 20859 10135 20860 10131 20860 10134 20860 10135 20861 10132 20861 10131 20861 10124 20862 10136 20862 10134 20862 10135 20863 10134 20863 10136 20863 10137 20864 10136 20864 10124 20864 10138 20865 10135 20865 10136 20865 10139 20866 10138 20866 10136 20866 10137 20867 10139 20867 10136 20867 10140 20868 10124 20868 10128 20868 10140 20869 10137 20869 10124 20869 10129 20870 10141 20870 10128 20870 10140 20871 10128 20871 10141 20871 10142 20872 10143 20872 10141 20872 10144 20873 10141 20873 10143 20873 10129 20874 10142 20874 10141 20874 10144 20875 10140 20875 10141 20875 10145 20876 10146 20876 10143 20876 10147 20877 10143 20877 10146 20877 10142 20878 10145 20878 10143 20878 10147 20879 10144 20879 10143 20879 10148 20880 10149 20880 10146 20880 10150 20881 10146 20881 10149 20881 10151 20882 10148 20882 10146 20882 10145 20883 10151 20883 10146 20883 10150 20884 10147 20884 10146 20884 10152 20885 10153 20885 10149 20885 10154 20886 10149 20886 10153 20886 10148 20887 10152 20887 10149 20887 10154 20888 10150 20888 10149 20888 10155 20889 10156 20889 10153 20889 10157 20890 10153 20890 10156 20890 10152 20891 10155 20891 10153 20891 10157 20892 10154 20892 10153 20892 10158 20893 10159 20893 10156 20893 10160 20894 10156 20894 10159 20894 10155 20895 10158 20895 10156 20895 10160 20896 10157 20896 10156 20896 10161 20897 10162 20897 10159 20897 10163 20898 10159 20898 10162 20898 10164 20899 10161 20899 10159 20899 10158 20900 10164 20900 10159 20900 10163 20901 10160 20901 10159 20901 10165 20902 10166 20902 10162 20902 10167 20903 10162 20903 10166 20903 10161 20904 10165 20904 10162 20904 10167 20905 10163 20905 10162 20905 10168 20906 10169 20906 10166 20906 10170 20907 10166 20907 10169 20907 10165 20908 10168 20908 10166 20908 10170 20909 10167 20909 10166 20909 10168 20910 10171 20910 10169 20910 10172 20911 10169 20911 10171 20911 10172 20912 10170 20912 10169 20912 10173 20913 10174 20913 10171 20913 10172 20914 10171 20914 10174 20914 10168 20915 10173 20915 10171 20915 10175 20916 10176 20916 10174 20916 10177 20917 10174 20917 10176 20917 10178 20918 10175 20918 10174 20918 10173 20919 10178 20919 10174 20919 10177 20920 10172 20920 10174 20920 10179 20921 10180 20921 10176 20921 10181 20922 10176 20922 10180 20922 10175 20923 10179 20923 10176 20923 10182 20924 10177 20924 10176 20924 10183 20925 10182 20925 10176 20925 10181 20926 10183 20926 10176 20926 10184 20927 10185 20927 10180 20927 10186 20928 10180 20928 10185 20928 10179 20929 10184 20929 10180 20929 10187 20930 10181 20930 10180 20930 10186 20931 10187 20931 10180 20931 10188 20932 10189 20932 10185 20932 10190 20933 10185 20933 10189 20933 10184 20934 10188 20934 10185 20934 10191 20935 10186 20935 10185 20935 10190 20936 10191 20936 10185 20936 10192 20937 10193 20937 10189 20937 10194 20938 10189 20938 10193 20938 10188 20939 10192 20939 10189 20939 10194 20940 10190 20940 10189 20940 10195 20941 10196 20941 10193 20941 10197 20942 10193 20942 10196 20942 10192 20943 10195 20943 10193 20943 10198 20944 10194 20944 10193 20944 10197 20945 10198 20945 10193 20945 10195 20946 10199 20946 10196 20946 10200 20947 10196 20947 10199 20947 10200 20948 10197 20948 10196 20948 10195 20949 10201 20949 10199 20949 10200 20950 10199 20950 10201 20950 10202 20951 10203 20951 10201 20951 10204 20952 10201 20952 10203 20952 10195 20953 10202 20953 10201 20953 10204 20954 10200 20954 10201 20954 10202 20955 10205 20955 10203 20955 10206 20956 10203 20956 10205 20956 10206 20957 10204 20957 10203 20957 10202 20958 10207 20958 10205 20958 10206 20959 10205 20959 10207 20959 10208 20960 10209 20960 10207 20960 10210 20961 10207 20961 10209 20961 10202 20962 10208 20962 10207 20962 10210 20963 10206 20963 10207 20963 10208 20964 10211 20964 10209 20964 10210 20965 10209 20965 10211 20965 10208 20966 10212 20966 10211 20966 10213 20967 10211 20967 10212 20967 10213 20968 10210 20968 10211 20968 10208 20969 10214 20969 10212 20969 10215 20970 10212 20970 10214 20970 10215 20971 10213 20971 10212 20971 10216 20972 10217 20972 10214 20972 10218 20973 10214 20973 10217 20973 10208 20974 10216 20974 10214 20974 10218 20975 10215 20975 10214 20975 10216 20976 10219 20976 10217 20976 10218 20977 10217 20977 10219 20977 10216 20978 10220 20978 10219 20978 10221 20979 10219 20979 10220 20979 10221 20980 10218 20980 10219 20980 10222 20981 10223 20981 10220 20981 10221 20982 10220 20982 10223 20982 10216 20983 10222 20983 10220 20983 10222 20984 10224 20984 10223 20984 10225 20985 10223 20985 10224 20985 10225 20986 10221 20986 10223 20986 10222 20987 10226 20987 10224 20987 10227 20988 10224 20988 10226 20988 10227 20989 10225 20989 10224 20989 9524 20990 10228 20990 10226 20990 10229 20991 10226 20991 10228 20991 10222 20992 9524 20992 10226 20992 10229 20993 10227 20993 10226 20993 9524 20994 9504 20994 10228 20994 10229 20995 10228 20995 9504 20995 10229 20996 9504 20996 9506 20996 10230 20997 9524 20997 10222 20997 10231 20998 10003 20998 9524 20998 10232 20999 10231 20999 9524 20999 10233 21000 10232 21000 9524 21000 10234 21001 10233 21001 9524 21001 10230 21002 10234 21002 9524 21002 10234 21003 10222 21003 10216 21003 10230 21004 10222 21004 10234 21004 10235 21005 10216 21005 10208 21005 10235 21006 10234 21006 10216 21006 10236 21007 10208 21007 10202 21007 10236 21008 10235 21008 10208 21008 10237 21009 10202 21009 10195 21009 10237 21010 10236 21010 10202 21010 10238 21011 10195 21011 10192 21011 10238 21012 10237 21012 10195 21012 10239 21013 10192 21013 10188 21013 10239 21014 10238 21014 10192 21014 10240 21015 10188 21015 10184 21015 10240 21016 10239 21016 10188 21016 10240 21017 10184 21017 10179 21017 10241 21018 10179 21018 10175 21018 10241 21019 10240 21019 10179 21019 10241 21020 10175 21020 10178 21020 10242 21021 10178 21021 10173 21021 10242 21022 10241 21022 10178 21022 10242 21023 10173 21023 10168 21023 10243 21024 10168 21024 10165 21024 10243 21025 10242 21025 10168 21025 10243 21026 10165 21026 10161 21026 10244 21027 10161 21027 10164 21027 10244 21028 10243 21028 10161 21028 10244 21029 10164 21029 10158 21029 10244 21030 10158 21030 10155 21030 10244 21031 10155 21031 10152 21031 10245 21032 10152 21032 10148 21032 10245 21033 10244 21033 10152 21033 10245 21034 10148 21034 10151 21034 10245 21035 10151 21035 10145 21035 10130 21036 10145 21036 10142 21036 10130 21037 10245 21037 10145 21037 10130 21038 10142 21038 10129 21038 9508 21039 9507 21039 9510 21039 9513 21040 9510 21040 9509 21040 10246 21041 9510 21041 9513 21041 9508 21042 9510 21042 10246 21042 9513 21043 9509 21043 9512 21043 10247 21044 10246 21044 9513 21044 10248 21045 10247 21045 9513 21045 10248 21046 9513 21046 9511 21046 10249 21047 10246 21047 10247 21047 9508 21048 10246 21048 10249 21048 10250 21049 10251 21049 10252 21049 10253 21050 10252 21050 10251 21050 10254 21051 10250 21051 10252 21051 10255 21052 10254 21052 10252 21052 10253 21053 10255 21053 10252 21053 10250 21054 10256 21054 10251 21054 10257 21055 10251 21055 10256 21055 10257 21056 10253 21056 10251 21056 10258 21057 10259 21057 10256 21057 10257 21058 10256 21058 10259 21058 10250 21059 10258 21059 10256 21059 10260 21060 10261 21060 10259 21060 10262 21061 10259 21061 10261 21061 10258 21062 10260 21062 10259 21062 10262 21063 10257 21063 10259 21063 10263 21064 10264 21064 10261 21064 10262 21065 10261 21065 10264 21065 10260 21066 10263 21066 10261 21066 10265 21067 10266 21067 10264 21067 10267 21068 10264 21068 10266 21068 10263 21069 10265 21069 10264 21069 10267 21070 10262 21070 10264 21070 10268 21071 10269 21071 10266 21071 10270 21072 10266 21072 10269 21072 10265 21073 10268 21073 10266 21073 10270 21074 10267 21074 10266 21074 10271 21075 10272 21075 10269 21075 10273 21076 10269 21076 10272 21076 10268 21077 10271 21077 10269 21077 10273 21078 10270 21078 10269 21078 10274 21079 10275 21079 10272 21079 10273 21080 10272 21080 10275 21080 10271 21081 10274 21081 10272 21081 10276 21082 10277 21082 10275 21082 10278 21083 10275 21083 10277 21083 10274 21084 10276 21084 10275 21084 10278 21085 10273 21085 10275 21085 10279 21086 10280 21086 10277 21086 10278 21087 10277 21087 10280 21087 10276 21088 10279 21088 10277 21088 10281 21089 10282 21089 10280 21089 10283 21090 10280 21090 10282 21090 10279 21091 10281 21091 10280 21091 10283 21092 10278 21092 10280 21092 10284 21093 10285 21093 10282 21093 10286 21094 10282 21094 10285 21094 10281 21095 10284 21095 10282 21095 10286 21096 10283 21096 10282 21096 10287 21097 10288 21097 10285 21097 10286 21098 10285 21098 10288 21098 10284 21099 10287 21099 10285 21099 10289 21100 10290 21100 10288 21100 10291 21101 10288 21101 10290 21101 10287 21102 10289 21102 10288 21102 10291 21103 10286 21103 10288 21103 10292 21104 10293 21104 10290 21104 10291 21105 10290 21105 10293 21105 10289 21106 10292 21106 10290 21106 10294 21107 10295 21107 10293 21107 10296 21108 10293 21108 10295 21108 10292 21109 10294 21109 10293 21109 10296 21110 10291 21110 10293 21110 10297 21111 10298 21111 10295 21111 10299 21112 10295 21112 10298 21112 10294 21113 10297 21113 10295 21113 10299 21114 10296 21114 10295 21114 10300 21115 10301 21115 10298 21115 10299 21116 10298 21116 10301 21116 10297 21117 10300 21117 10298 21117 10302 21118 10303 21118 10301 21118 10304 21119 10301 21119 10303 21119 10300 21120 10302 21120 10301 21120 10304 21121 10299 21121 10301 21121 10305 21122 10306 21122 10303 21122 10307 21123 10303 21123 10306 21123 10302 21124 10305 21124 10303 21124 10307 21125 10304 21125 10303 21125 10308 21126 10309 21126 10306 21126 10307 21127 10306 21127 10309 21127 10305 21128 10308 21128 10306 21128 10310 21129 10311 21129 10309 21129 10312 21130 10309 21130 10311 21130 10308 21131 10310 21131 10309 21131 10312 21132 10307 21132 10309 21132 10313 21133 10314 21133 10311 21133 10312 21134 10311 21134 10314 21134 10310 21135 10313 21135 10311 21135 10313 21136 10315 21136 10314 21136 10316 21137 10314 21137 10315 21137 10316 21138 10312 21138 10314 21138 10317 21139 10318 21139 10315 21139 10316 21140 10315 21140 10318 21140 10313 21141 10317 21141 10315 21141 10319 21142 10320 21142 10318 21142 10321 21143 10318 21143 10320 21143 10322 21144 10319 21144 10318 21144 10317 21145 10322 21145 10318 21145 10321 21146 10316 21146 10318 21146 10323 21147 10324 21147 10320 21147 10325 21148 10320 21148 10324 21148 10326 21149 10323 21149 10320 21149 10319 21150 10326 21150 10320 21150 10327 21151 10321 21151 10320 21151 10325 21152 10327 21152 10320 21152 10328 21153 10329 21153 10324 21153 10330 21154 10324 21154 10329 21154 10323 21155 10328 21155 10324 21155 10330 21156 10325 21156 10324 21156 10331 21157 10332 21157 10329 21157 10333 21158 10329 21158 10332 21158 10328 21159 10331 21159 10329 21159 10334 21160 10330 21160 10329 21160 10333 21161 10334 21161 10329 21161 10335 21162 10336 21162 10332 21162 10337 21163 10332 21163 10336 21163 10331 21164 10335 21164 10332 21164 10337 21165 10333 21165 10332 21165 10338 21166 10339 21166 10336 21166 10340 21167 10336 21167 10339 21167 10335 21168 10338 21168 10336 21168 10340 21169 10337 21169 10336 21169 10341 21170 10342 21170 10339 21170 10343 21171 10339 21171 10342 21171 10338 21172 10341 21172 10339 21172 10343 21173 10340 21173 10339 21173 10344 21174 10345 21174 10342 21174 10343 21175 10342 21175 10345 21175 10341 21176 10344 21176 10342 21176 10346 21177 10347 21177 10345 21177 10348 21178 10345 21178 10347 21178 10344 21179 10346 21179 10345 21179 10348 21180 10343 21180 10345 21180 10349 21181 10350 21181 10347 21181 10351 21182 10347 21182 10350 21182 10352 21183 10349 21183 10347 21183 10346 21184 10352 21184 10347 21184 10351 21185 10348 21185 10347 21185 10353 21186 10354 21186 10350 21186 10351 21187 10350 21187 10354 21187 10349 21188 10353 21188 10350 21188 10355 21189 10356 21189 10354 21189 10357 21190 10354 21190 10356 21190 10353 21191 10355 21191 10354 21191 10357 21192 10351 21192 10354 21192 10358 21193 10359 21193 10356 21193 10357 21194 10356 21194 10359 21194 10355 21195 10358 21195 10356 21195 10360 21196 10361 21196 10359 21196 10362 21197 10359 21197 10361 21197 10358 21198 10360 21198 10359 21198 10362 21199 10357 21199 10359 21199 10360 21200 10363 21200 10361 21200 10362 21201 10361 21201 10363 21201 10364 21202 10365 21202 10363 21202 10366 21203 10363 21203 10365 21203 10360 21204 10364 21204 10363 21204 10366 21205 10362 21205 10363 21205 10364 21206 10367 21206 10365 21206 10366 21207 10365 21207 10367 21207 10368 21208 10369 21208 10367 21208 10370 21209 10367 21209 10369 21209 10364 21210 10368 21210 10367 21210 10370 21211 10366 21211 10367 21211 10371 21212 10372 21212 10369 21212 10370 21213 10369 21213 10372 21213 10368 21214 10371 21214 10369 21214 10373 21215 10374 21215 10372 21215 10375 21216 10372 21216 10374 21216 10371 21217 10373 21217 10372 21217 10375 21218 10370 21218 10372 21218 10376 21219 10377 21219 10374 21219 10375 21220 10374 21220 10377 21220 10373 21221 10376 21221 10374 21221 10378 21222 10379 21222 10377 21222 10380 21223 10377 21223 10379 21223 10376 21224 10378 21224 10377 21224 10380 21225 10375 21225 10377 21225 10249 21226 10247 21226 10379 21226 10248 21227 10379 21227 10247 21227 10378 21228 10249 21228 10379 21228 10248 21229 10380 21229 10379 21229 10381 21230 10249 21230 10378 21230 10381 21231 9508 21231 10249 21231 10382 21232 10378 21232 10376 21232 10382 21233 10381 21233 10378 21233 10382 21234 10376 21234 10373 21234 10383 21235 10373 21235 10371 21235 10383 21236 10382 21236 10373 21236 10383 21237 10371 21237 10368 21237 10384 21238 10368 21238 10364 21238 10384 21239 10383 21239 10368 21239 10385 21240 10364 21240 10360 21240 10385 21241 10384 21241 10364 21241 10386 21242 10360 21242 10358 21242 10386 21243 10385 21243 10360 21243 10386 21244 10358 21244 10355 21244 10387 21245 10355 21245 10353 21245 10387 21246 10386 21246 10355 21246 10387 21247 10353 21247 10349 21247 10388 21248 10349 21248 10352 21248 10388 21249 10387 21249 10349 21249 10388 21250 10352 21250 10346 21250 10389 21251 10346 21251 10344 21251 10389 21252 10388 21252 10346 21252 10390 21253 10344 21253 10341 21253 10390 21254 10389 21254 10344 21254 10391 21255 10341 21255 10338 21255 10391 21256 10390 21256 10341 21256 10392 21257 10338 21257 10335 21257 10392 21258 10391 21258 10338 21258 10393 21259 10335 21259 10331 21259 10393 21260 10392 21260 10335 21260 10394 21261 10331 21261 10328 21261 10394 21262 10393 21262 10331 21262 10395 21263 10328 21263 10323 21263 10395 21264 10394 21264 10328 21264 10396 21265 10323 21265 10326 21265 10396 21266 10395 21266 10323 21266 10397 21267 10326 21267 10319 21267 10397 21268 10396 21268 10326 21268 10397 21269 10319 21269 10322 21269 10398 21270 10322 21270 10317 21270 10398 21271 10397 21271 10322 21271 10399 21272 10317 21272 10313 21272 10399 21273 10398 21273 10317 21273 10399 21274 10313 21274 10310 21274 10400 21275 10310 21275 10308 21275 10400 21276 10399 21276 10310 21276 10401 21277 10308 21277 10305 21277 10401 21278 10400 21278 10308 21278 10401 21279 10305 21279 10302 21279 10402 21280 10302 21280 10300 21280 10402 21281 10401 21281 10302 21281 10403 21282 10300 21282 10297 21282 10403 21283 10402 21283 10300 21283 10403 21284 10297 21284 10294 21284 10404 21285 10294 21285 10292 21285 10404 21286 10403 21286 10294 21286 10405 21287 10292 21287 10289 21287 10405 21288 10404 21288 10292 21288 10405 21289 10289 21289 10287 21289 10406 21290 10287 21290 10284 21290 10406 21291 10405 21291 10287 21291 10406 21292 10284 21292 10281 21292 10407 21293 10281 21293 10279 21293 10407 21294 10406 21294 10281 21294 10408 21295 10279 21295 10276 21295 10408 21296 10407 21296 10279 21296 10408 21297 10276 21297 10274 21297 10409 21298 10274 21298 10271 21298 10409 21299 10408 21299 10274 21299 10410 21300 10271 21300 10268 21300 10410 21301 10409 21301 10271 21301 10410 21302 10268 21302 10265 21302 10411 21303 10265 21303 10263 21303 10411 21304 10410 21304 10265 21304 10412 21305 10263 21305 10260 21305 10412 21306 10411 21306 10263 21306 10412 21307 10260 21307 10258 21307 10413 21308 10258 21308 10250 21308 10413 21309 10412 21309 10258 21309 10414 21310 10250 21310 10254 21310 10413 21311 10250 21311 10414 21311 10415 21312 10254 21312 10255 21312 10138 21313 10254 21313 10415 21313 10414 21314 10254 21314 10138 21314 10416 21315 10415 21315 10255 21315 10110 21316 10416 21316 10255 21316 10110 21317 10255 21317 10107 21317 10417 21318 10107 21318 10255 21318 10418 21319 10417 21319 10255 21319 10253 21320 10418 21320 10255 21320 10419 21321 10415 21321 10416 21321 10138 21322 10415 21322 10419 21322 10420 21323 10421 21323 10422 21323 10423 21324 10422 21324 10421 21324 10424 21325 10420 21325 10422 21325 10425 21326 10424 21326 10422 21326 10426 21327 10425 21327 10422 21327 10426 21328 10422 21328 10423 21328 10419 21329 10416 21329 10421 21329 10111 21330 10421 21330 10416 21330 10420 21331 10419 21331 10421 21331 10423 21332 10421 21332 10427 21332 10111 21333 10427 21333 10421 21333 10111 21334 10416 21334 10110 21334 10135 21335 10419 21335 10420 21335 10138 21336 10419 21336 10135 21336 10132 21337 10420 21337 10424 21337 10135 21338 10420 21338 10132 21338 10428 21339 10424 21339 10425 21339 10429 21340 10424 21340 10428 21340 10132 21341 10424 21341 10429 21341 10430 21342 10431 21342 10005 21342 10006 21343 10005 21343 10431 21343 10004 21344 10430 21344 10005 21344 10430 21345 10432 21345 10431 21345 10433 21346 10431 21346 10432 21346 10006 21347 10431 21347 10014 21347 10433 21348 10014 21348 10431 21348 10434 21349 10435 21349 10432 21349 10433 21350 10432 21350 10435 21350 10430 21351 10434 21351 10432 21351 10436 21352 10437 21352 10435 21352 10438 21353 10435 21353 10437 21353 10434 21354 10436 21354 10435 21354 10433 21355 10435 21355 10438 21355 10439 21356 10440 21356 10437 21356 10441 21357 10437 21357 10440 21357 10436 21358 10439 21358 10437 21358 10438 21359 10437 21359 10441 21359 10442 21360 10443 21360 10440 21360 10444 21361 10440 21361 10443 21361 10439 21362 10442 21362 10440 21362 10441 21363 10440 21363 10444 21363 10445 21364 10446 21364 10443 21364 10444 21365 10443 21365 10446 21365 10442 21366 10445 21366 10443 21366 10447 21367 10448 21367 10446 21367 10449 21368 10446 21368 10448 21368 10445 21369 10447 21369 10446 21369 10444 21370 10446 21370 10449 21370 10447 21371 10450 21371 10448 21371 10451 21372 10448 21372 10450 21372 10449 21373 10448 21373 10451 21373 10452 21374 10453 21374 10450 21374 10451 21375 10450 21375 10453 21375 10447 21376 10452 21376 10450 21376 10454 21377 10455 21377 10453 21377 10456 21378 10453 21378 10455 21378 10452 21379 10454 21379 10453 21379 10451 21380 10453 21380 10456 21380 10457 21381 10458 21381 10455 21381 10456 21382 10455 21382 10458 21382 10454 21383 10457 21383 10455 21383 10459 21384 10460 21384 10458 21384 10461 21385 10458 21385 10460 21385 10457 21386 10459 21386 10458 21386 10456 21387 10458 21387 10461 21387 10462 21388 10463 21388 10460 21388 10461 21389 10460 21389 10463 21389 10459 21390 10462 21390 10460 21390 10462 21391 10464 21391 10463 21391 10461 21392 10463 21392 10464 21392 10465 21393 10466 21393 10464 21393 10467 21394 10464 21394 10466 21394 10462 21395 10465 21395 10464 21395 10461 21396 10464 21396 10467 21396 10468 21397 10469 21397 10466 21397 10467 21398 10466 21398 10469 21398 10465 21399 10468 21399 10466 21399 10470 21400 10471 21400 10469 21400 10467 21401 10469 21401 10471 21401 10468 21402 10470 21402 10469 21402 10472 21403 10473 21403 10471 21403 10474 21404 10471 21404 10473 21404 10470 21405 10472 21405 10471 21405 10467 21406 10471 21406 10474 21406 10475 21407 10476 21407 10473 21407 10474 21408 10473 21408 10476 21408 10472 21409 10475 21409 10473 21409 10475 21410 10477 21410 10476 21410 10474 21411 10476 21411 10477 21411 10478 21412 10479 21412 10477 21412 10474 21413 10477 21413 10479 21413 10475 21414 10478 21414 10477 21414 10480 21415 10481 21415 10479 21415 10482 21416 10479 21416 10481 21416 10478 21417 10480 21417 10479 21417 10474 21418 10479 21418 10482 21418 10483 21419 10484 21419 10481 21419 10482 21420 10481 21420 10484 21420 10480 21421 10483 21421 10481 21421 10485 21422 10486 21422 10484 21422 10482 21423 10484 21423 10486 21423 10483 21424 10485 21424 10484 21424 10487 21425 10488 21425 10486 21425 10482 21426 10486 21426 10488 21426 10485 21427 10487 21427 10486 21427 10487 21428 10489 21428 10488 21428 10426 21429 10488 21429 10489 21429 10482 21430 10488 21430 10426 21430 10490 21431 10491 21431 10489 21431 10426 21432 10489 21432 10491 21432 10487 21433 10490 21433 10489 21433 10428 21434 10425 21434 10491 21434 10426 21435 10491 21435 10425 21435 10490 21436 10428 21436 10491 21436 10429 21437 10428 21437 10490 21437 10492 21438 10490 21438 10487 21438 10492 21439 10429 21439 10490 21439 10492 21440 10487 21440 10485 21440 10492 21441 10485 21441 10483 21441 10492 21442 10483 21442 10480 21442 10493 21443 10480 21443 10478 21443 10493 21444 10492 21444 10480 21444 10493 21445 10478 21445 10475 21445 10493 21446 10475 21446 10472 21446 10494 21447 10472 21447 10470 21447 10494 21448 10493 21448 10472 21448 10494 21449 10470 21449 10468 21449 10494 21450 10468 21450 10465 21450 10495 21451 10465 21451 10462 21451 10495 21452 10494 21452 10465 21452 10495 21453 10462 21453 10459 21453 10496 21454 10459 21454 10457 21454 10496 21455 10495 21455 10459 21455 10497 21456 10457 21456 10454 21456 10497 21457 10496 21457 10457 21457 10497 21458 10454 21458 10452 21458 10498 21459 10452 21459 10447 21459 10498 21460 10497 21460 10452 21460 10499 21461 10447 21461 10445 21461 10499 21462 10498 21462 10447 21462 10500 21463 10445 21463 10442 21463 10500 21464 10499 21464 10445 21464 10501 21465 10442 21465 10439 21465 10501 21466 10500 21466 10442 21466 10501 21467 10439 21467 10436 21467 10502 21468 10436 21468 10434 21468 10502 21469 10501 21469 10436 21469 10503 21470 10434 21470 10430 21470 10503 21471 10502 21471 10434 21471 10008 21472 10430 21472 10004 21472 10503 21473 10430 21473 10008 21473 10008 21474 10004 21474 10007 21474 10231 21475 10008 21475 10003 21475 10503 21476 10008 21476 10231 21476 10233 21477 10231 21477 10232 21477 10234 21478 10231 21478 10233 21478 10504 21479 10231 21479 10234 21479 10504 21480 10503 21480 10231 21480 10504 21481 10234 21481 10235 21481 10002 21482 9996 21482 10009 21482 10505 21483 10009 21483 10010 21483 10505 21484 10002 21484 10009 21484 10505 21485 10010 21485 10011 21485 10505 21486 10011 21486 10012 21486 10433 21487 10012 21487 10013 21487 10433 21488 10505 21488 10012 21488 10433 21489 10013 21489 10014 21489 10427 21490 10112 21490 10113 21490 10111 21491 10112 21491 10427 21491 10506 21492 10113 21492 10114 21492 10506 21493 10427 21493 10113 21493 10507 21494 10114 21494 10115 21494 10507 21495 10506 21495 10114 21495 10508 21496 10115 21496 10116 21496 10508 21497 10507 21497 10115 21497 10509 21498 10116 21498 10117 21498 10509 21499 10508 21499 10116 21499 10510 21500 10117 21500 10118 21500 10510 21501 10509 21501 10117 21501 10511 21502 10118 21502 10119 21502 10511 21503 10510 21503 10118 21503 10512 21504 10119 21504 10120 21504 10512 21505 10511 21505 10119 21505 10513 21506 10120 21506 10121 21506 10513 21507 10512 21507 10120 21507 10514 21508 10121 21508 10122 21508 10514 21509 10513 21509 10121 21509 10515 21510 10122 21510 10123 21510 10515 21511 10514 21511 10122 21511 10516 21512 10123 21512 10002 21512 10516 21513 10515 21513 10123 21513 10505 21514 10516 21514 10002 21514 10423 21515 10427 21515 10506 21515 10426 21516 10506 21516 10507 21516 10426 21517 10423 21517 10506 21517 10482 21518 10507 21518 10508 21518 10482 21519 10426 21519 10507 21519 10474 21520 10508 21520 10509 21520 10474 21521 10482 21521 10508 21521 10467 21522 10509 21522 10510 21522 10467 21523 10474 21523 10509 21523 10461 21524 10510 21524 10511 21524 10461 21525 10467 21525 10510 21525 10456 21526 10511 21526 10512 21526 10456 21527 10461 21527 10511 21527 10451 21528 10512 21528 10513 21528 10451 21529 10456 21529 10512 21529 10449 21530 10513 21530 10514 21530 10449 21531 10451 21531 10513 21531 10444 21532 10514 21532 10515 21532 10444 21533 10449 21533 10514 21533 10441 21534 10515 21534 10516 21534 10441 21535 10444 21535 10515 21535 10438 21536 10516 21536 10505 21536 10438 21537 10441 21537 10516 21537 10433 21538 10438 21538 10505 21538 10517 21539 10108 21539 10107 21539 10417 21540 10517 21540 10107 21540 10518 21541 10108 21541 10517 21541 10109 21542 10108 21542 10518 21542 10518 21543 10517 21543 10417 21543 10257 21544 10417 21544 10418 21544 10518 21545 10417 21545 10257 21545 10257 21546 10418 21546 10253 21546 10519 21547 9511 21547 9515 21547 10519 21548 10248 21548 9511 21548 10015 21549 9515 21549 9514 21549 10015 21550 10519 21550 9515 21550 10518 21551 10257 21551 10262 21551 10520 21552 10262 21552 10267 21552 10520 21553 10518 21553 10262 21553 10521 21554 10267 21554 10270 21554 10521 21555 10520 21555 10267 21555 10522 21556 10270 21556 10273 21556 10522 21557 10521 21557 10270 21557 10523 21558 10273 21558 10278 21558 10523 21559 10522 21559 10273 21559 10524 21560 10278 21560 10283 21560 10524 21561 10523 21561 10278 21561 10525 21562 10283 21562 10286 21562 10525 21563 10524 21563 10283 21563 10526 21564 10286 21564 10291 21564 10526 21565 10525 21565 10286 21565 10527 21566 10291 21566 10296 21566 10527 21567 10526 21567 10291 21567 10528 21568 10296 21568 10299 21568 10528 21569 10527 21569 10296 21569 10529 21570 10299 21570 10304 21570 10529 21571 10528 21571 10299 21571 10530 21572 10304 21572 10307 21572 10530 21573 10529 21573 10304 21573 10531 21574 10307 21574 10312 21574 10531 21575 10530 21575 10307 21575 10532 21576 10312 21576 10316 21576 10532 21577 10531 21577 10312 21577 10533 21578 10316 21578 10321 21578 10533 21579 10532 21579 10316 21579 10534 21580 10321 21580 10327 21580 10534 21581 10533 21581 10321 21581 10535 21582 10327 21582 10325 21582 10535 21583 10534 21583 10327 21583 10536 21584 10325 21584 10330 21584 10536 21585 10535 21585 10325 21585 10537 21586 10330 21586 10334 21586 10537 21587 10536 21587 10330 21587 10538 21588 10334 21588 10333 21588 10538 21589 10537 21589 10334 21589 10539 21590 10333 21590 10337 21590 10539 21591 10538 21591 10333 21591 10540 21592 10337 21592 10340 21592 10540 21593 10539 21593 10337 21593 10541 21594 10340 21594 10343 21594 10541 21595 10540 21595 10340 21595 10542 21596 10343 21596 10348 21596 10542 21597 10541 21597 10343 21597 10543 21598 10348 21598 10351 21598 10543 21599 10542 21599 10348 21599 10544 21600 10351 21600 10357 21600 10544 21601 10543 21601 10351 21601 10545 21602 10357 21602 10362 21602 10545 21603 10544 21603 10357 21603 10546 21604 10362 21604 10366 21604 10546 21605 10545 21605 10362 21605 10547 21606 10366 21606 10370 21606 10547 21607 10546 21607 10366 21607 10548 21608 10370 21608 10375 21608 10548 21609 10547 21609 10370 21609 10549 21610 10375 21610 10380 21610 10549 21611 10548 21611 10375 21611 10550 21612 10380 21612 10248 21612 10550 21613 10549 21613 10380 21613 10519 21614 10550 21614 10248 21614 10109 21615 10518 21615 10520 21615 10097 21616 10520 21616 10521 21616 10097 21617 10109 21617 10520 21617 10105 21618 10521 21618 10522 21618 10105 21619 10097 21619 10521 21619 10106 21620 10522 21620 10523 21620 10106 21621 10105 21621 10522 21621 10090 21622 10523 21622 10524 21622 10090 21623 10106 21623 10523 21623 10094 21624 10524 21624 10525 21624 10094 21625 10090 21625 10524 21625 10082 21626 10525 21626 10526 21626 10082 21627 10094 21627 10525 21627 10086 21628 10526 21628 10527 21628 10086 21629 10082 21629 10526 21629 10087 21630 10527 21630 10528 21630 10087 21631 10086 21631 10527 21631 10076 21632 10528 21632 10529 21632 10076 21633 10087 21633 10528 21633 10079 21634 10529 21634 10530 21634 10079 21635 10076 21635 10529 21635 10072 21636 10530 21636 10531 21636 10072 21637 10079 21637 10530 21637 10067 21638 10531 21638 10532 21638 10067 21639 10072 21639 10531 21639 10069 21640 10532 21640 10533 21640 10069 21641 10067 21641 10532 21641 10063 21642 10533 21642 10534 21642 10063 21643 10069 21643 10533 21643 10064 21644 10534 21644 10535 21644 10064 21645 10063 21645 10534 21645 10060 21646 10535 21646 10536 21646 10060 21647 10064 21647 10535 21647 10057 21648 10536 21648 10537 21648 10057 21649 10060 21649 10536 21649 10054 21650 10537 21650 10538 21650 10054 21651 10057 21651 10537 21651 10051 21652 10538 21652 10539 21652 10051 21653 10054 21653 10538 21653 10049 21654 10539 21654 10540 21654 10049 21655 10051 21655 10539 21655 10046 21656 10540 21656 10541 21656 10046 21657 10049 21657 10540 21657 10044 21658 10541 21658 10542 21658 10044 21659 10046 21659 10541 21659 10041 21660 10542 21660 10543 21660 10041 21661 10044 21661 10542 21661 10039 21662 10543 21662 10544 21662 10039 21663 10041 21663 10543 21663 10035 21664 10544 21664 10545 21664 10035 21665 10039 21665 10544 21665 10033 21666 10545 21666 10546 21666 10033 21667 10035 21667 10545 21667 10030 21668 10546 21668 10547 21668 10030 21669 10033 21669 10546 21669 10025 21670 10547 21670 10548 21670 10025 21671 10030 21671 10547 21671 10022 21672 10548 21672 10549 21672 10022 21673 10025 21673 10548 21673 10018 21674 10549 21674 10550 21674 10018 21675 10022 21675 10549 21675 10016 21676 10550 21676 10519 21676 10016 21677 10018 21677 10550 21677 10015 21678 10016 21678 10519 21678 10133 21679 10429 21679 10492 21679 10132 21680 10429 21680 10133 21680 10551 21681 10492 21681 10493 21681 10552 21682 10133 21682 10492 21682 10552 21683 10492 21683 10551 21683 10553 21684 10493 21684 10494 21684 10551 21685 10493 21685 10553 21685 10554 21686 10494 21686 10495 21686 10553 21687 10494 21687 10554 21687 10555 21688 10495 21688 10496 21688 10554 21689 10495 21689 10555 21689 10556 21690 10496 21690 10497 21690 10555 21691 10496 21691 10556 21691 10557 21692 10497 21692 10498 21692 10556 21693 10497 21693 10557 21693 10558 21694 10498 21694 10499 21694 10557 21695 10498 21695 10558 21695 10559 21696 10499 21696 10500 21696 10558 21697 10499 21697 10559 21697 10560 21698 10500 21698 10501 21698 10559 21699 10500 21699 10560 21699 10561 21700 10501 21700 10502 21700 10560 21701 10501 21701 10561 21701 10504 21702 10502 21702 10503 21702 10561 21703 10502 21703 10504 21703 10561 21704 10235 21704 10236 21704 10561 21705 10504 21705 10235 21705 10560 21706 10236 21706 10237 21706 10560 21707 10561 21707 10236 21707 10559 21708 10237 21708 10238 21708 10559 21709 10560 21709 10237 21709 10558 21710 10238 21710 10239 21710 10558 21711 10559 21711 10238 21711 10557 21712 10239 21712 10240 21712 10557 21713 10558 21713 10239 21713 10556 21714 10240 21714 10241 21714 10556 21715 10557 21715 10240 21715 10555 21716 10241 21716 10242 21716 10555 21717 10556 21717 10241 21717 10554 21718 10242 21718 10243 21718 10554 21719 10555 21719 10242 21719 10553 21720 10243 21720 10244 21720 10553 21721 10554 21721 10243 21721 10551 21722 10244 21722 10245 21722 10551 21723 10553 21723 10244 21723 10552 21724 10245 21724 10130 21724 10552 21725 10551 21725 10245 21725 10552 21726 10130 21726 10127 21726 10552 21727 10127 21727 10133 21727 10562 21728 10414 21728 10138 21728 10563 21729 10562 21729 10138 21729 10139 21730 10563 21730 10138 21730 10563 21731 10414 21731 10562 21731 10413 21732 10414 21732 10563 21732 10137 21733 10563 21733 10139 21733 10564 21734 10563 21734 10137 21734 10564 21735 10413 21735 10563 21735 10564 21736 10137 21736 10140 21736 10565 21737 9506 21737 9505 21737 10565 21738 10229 21738 9506 21738 10381 21739 9505 21739 9508 21739 10565 21740 9505 21740 10381 21740 10566 21741 10140 21741 10144 21741 10564 21742 10140 21742 10566 21742 10567 21743 10144 21743 10147 21743 10566 21744 10144 21744 10567 21744 10568 21745 10147 21745 10150 21745 10567 21746 10147 21746 10568 21746 10569 21747 10150 21747 10154 21747 10568 21748 10150 21748 10569 21748 10570 21749 10154 21749 10157 21749 10569 21750 10154 21750 10570 21750 10571 21751 10157 21751 10160 21751 10570 21752 10157 21752 10571 21752 10572 21753 10160 21753 10163 21753 10571 21754 10160 21754 10572 21754 10573 21755 10163 21755 10167 21755 10572 21756 10163 21756 10573 21756 10574 21757 10167 21757 10170 21757 10573 21758 10167 21758 10574 21758 10575 21759 10170 21759 10172 21759 10574 21760 10170 21760 10575 21760 10576 21761 10172 21761 10177 21761 10575 21762 10172 21762 10576 21762 10577 21763 10177 21763 10182 21763 10576 21764 10177 21764 10577 21764 10578 21765 10182 21765 10183 21765 10577 21766 10182 21766 10578 21766 10579 21767 10183 21767 10181 21767 10578 21768 10183 21768 10579 21768 10580 21769 10181 21769 10187 21769 10579 21770 10181 21770 10580 21770 10581 21771 10187 21771 10186 21771 10580 21772 10187 21772 10581 21772 10582 21773 10186 21773 10191 21773 10581 21774 10186 21774 10582 21774 10583 21775 10191 21775 10190 21775 10582 21776 10191 21776 10583 21776 10584 21777 10190 21777 10194 21777 10583 21778 10190 21778 10584 21778 10585 21779 10194 21779 10198 21779 10584 21780 10194 21780 10585 21780 10586 21781 10198 21781 10197 21781 10585 21782 10198 21782 10586 21782 10587 21783 10197 21783 10200 21783 10586 21784 10197 21784 10587 21784 10588 21785 10200 21785 10204 21785 10587 21786 10200 21786 10588 21786 10589 21787 10204 21787 10206 21787 10588 21788 10204 21788 10589 21788 10590 21789 10206 21789 10210 21789 10589 21790 10206 21790 10590 21790 10591 21791 10210 21791 10213 21791 10590 21792 10210 21792 10591 21792 10592 21793 10213 21793 10215 21793 10591 21794 10213 21794 10592 21794 10593 21795 10215 21795 10218 21795 10592 21796 10215 21796 10593 21796 10594 21797 10218 21797 10221 21797 10593 21798 10218 21798 10594 21798 10595 21799 10221 21799 10225 21799 10594 21800 10221 21800 10595 21800 10596 21801 10225 21801 10227 21801 10595 21802 10225 21802 10596 21802 10565 21803 10227 21803 10229 21803 10596 21804 10227 21804 10565 21804 10596 21805 10381 21805 10382 21805 10596 21806 10565 21806 10381 21806 10595 21807 10382 21807 10383 21807 10595 21808 10596 21808 10382 21808 10594 21809 10383 21809 10384 21809 10594 21810 10595 21810 10383 21810 10593 21811 10384 21811 10385 21811 10593 21812 10594 21812 10384 21812 10592 21813 10385 21813 10386 21813 10592 21814 10593 21814 10385 21814 10591 21815 10386 21815 10387 21815 10591 21816 10592 21816 10386 21816 10590 21817 10387 21817 10388 21817 10590 21818 10591 21818 10387 21818 10589 21819 10388 21819 10389 21819 10589 21820 10590 21820 10388 21820 10588 21821 10389 21821 10390 21821 10588 21822 10589 21822 10389 21822 10587 21823 10390 21823 10391 21823 10587 21824 10588 21824 10390 21824 10586 21825 10391 21825 10392 21825 10586 21826 10587 21826 10391 21826 10585 21827 10392 21827 10393 21827 10585 21828 10586 21828 10392 21828 10584 21829 10393 21829 10394 21829 10584 21830 10585 21830 10393 21830 10583 21831 10394 21831 10395 21831 10583 21832 10584 21832 10394 21832 10582 21833 10395 21833 10396 21833 10582 21834 10583 21834 10395 21834 10581 21835 10396 21835 10397 21835 10581 21836 10582 21836 10396 21836 10580 21837 10397 21837 10398 21837 10580 21838 10581 21838 10397 21838 10579 21839 10398 21839 10399 21839 10579 21840 10580 21840 10398 21840 10578 21841 10399 21841 10400 21841 10578 21842 10579 21842 10399 21842 10577 21843 10400 21843 10401 21843 10577 21844 10578 21844 10400 21844 10576 21845 10401 21845 10402 21845 10576 21846 10577 21846 10401 21846 10575 21847 10402 21847 10403 21847 10575 21848 10576 21848 10402 21848 10574 21849 10403 21849 10404 21849 10574 21850 10575 21850 10403 21850 10573 21851 10404 21851 10405 21851 10573 21852 10574 21852 10404 21852 10572 21853 10405 21853 10406 21853 10572 21854 10573 21854 10405 21854 10571 21855 10406 21855 10407 21855 10571 21856 10572 21856 10406 21856 10570 21857 10407 21857 10408 21857 10570 21858 10571 21858 10407 21858 10569 21859 10408 21859 10409 21859 10569 21860 10570 21860 10408 21860 10568 21861 10409 21861 10410 21861 10568 21862 10569 21862 10409 21862 10567 21863 10410 21863 10411 21863 10567 21864 10568 21864 10410 21864 10566 21865 10411 21865 10412 21865 10566 21866 10567 21866 10411 21866 10564 21867 10412 21867 10413 21867 10564 21868 10566 21868 10412 21868 10597 21869 9647 21869 9646 21869 10598 21870 10597 21870 9646 21870 9952 21871 10598 21871 9646 21871 10599 21872 9647 21872 10597 21872 9641 21873 9647 21873 10599 21873 10600 21874 10597 21874 10598 21874 10599 21875 10597 21875 10600 21875 10600 21876 10598 21876 9952 21876 10601 21877 9952 21877 9953 21877 10600 21878 9952 21878 10601 21878 9954 21879 10602 21879 9955 21879 10601 21880 9953 21880 9786 21880 9786 21881 9953 21881 9780 21881 10603 21882 9535 21882 9533 21882 10603 21883 9776 21883 9535 21883 10604 21884 9533 21884 9537 21884 10604 21885 10603 21885 9533 21885 10605 21886 9537 21886 9536 21886 10605 21887 10604 21887 9537 21887 9557 21888 9536 21888 9538 21888 9557 21889 10605 21889 9536 21889 10601 21890 9786 21890 9785 21890 10606 21891 9785 21891 9789 21891 10606 21892 10601 21892 9785 21892 10607 21893 9789 21893 9791 21893 10607 21894 10606 21894 9789 21894 10608 21895 9791 21895 9796 21895 10608 21896 10607 21896 9791 21896 10609 21897 9796 21897 9799 21897 10609 21898 10608 21898 9796 21898 10610 21899 9799 21899 9802 21899 10610 21900 10609 21900 9799 21900 10611 21901 9802 21901 9807 21901 10611 21902 10610 21902 9802 21902 10612 21903 9807 21903 9812 21903 10612 21904 10611 21904 9807 21904 10613 21905 9812 21905 9817 21905 10613 21906 10612 21906 9812 21906 10614 21907 9817 21907 9820 21907 10614 21908 10613 21908 9817 21908 10615 21909 9820 21909 9825 21909 10615 21910 10614 21910 9820 21910 10616 21911 9825 21911 9829 21911 10616 21912 10615 21912 9825 21912 10617 21913 9829 21913 9834 21913 10617 21914 10616 21914 9829 21914 10618 21915 9834 21915 9839 21915 10618 21916 10617 21916 9834 21916 10619 21917 9839 21917 9842 21917 10619 21918 10618 21918 9839 21918 10620 21919 9842 21919 9846 21919 10620 21920 10619 21920 9842 21920 10621 21921 9846 21921 9848 21921 10621 21922 10620 21922 9846 21922 10622 21923 9848 21923 9851 21923 10622 21924 10621 21924 9848 21924 10623 21925 9851 21925 9855 21925 10623 21926 10622 21926 9851 21926 10624 21927 9855 21927 9859 21927 10624 21928 10623 21928 9855 21928 10625 21929 9859 21929 9858 21929 10625 21930 10624 21930 9859 21930 10626 21931 9858 21931 9864 21931 10626 21932 10625 21932 9858 21932 10627 21933 9864 21933 9867 21933 10627 21934 10626 21934 9864 21934 10628 21935 9867 21935 9872 21935 10628 21936 10627 21936 9867 21936 10629 21937 9872 21937 9876 21937 10629 21938 10628 21938 9872 21938 10630 21939 9876 21939 9881 21939 10630 21940 10629 21940 9876 21940 10631 21941 9881 21941 9887 21941 10631 21942 10630 21942 9881 21942 10632 21943 9887 21943 9892 21943 10632 21944 10631 21944 9887 21944 10633 21945 9892 21945 9897 21945 10633 21946 10632 21946 9892 21946 10634 21947 9897 21947 9902 21947 10634 21948 10633 21948 9897 21948 10635 21949 9902 21949 9907 21949 10635 21950 10634 21950 9902 21950 10636 21951 9907 21951 9913 21951 10636 21952 10635 21952 9907 21952 10637 21953 9913 21953 9776 21953 10637 21954 10636 21954 9913 21954 10603 21955 10637 21955 9776 21955 10600 21956 10601 21956 10606 21956 10638 21957 10606 21957 10607 21957 10638 21958 10600 21958 10606 21958 10639 21959 10607 21959 10608 21959 10639 21960 10638 21960 10607 21960 10640 21961 10608 21961 10609 21961 10640 21962 10639 21962 10608 21962 10641 21963 10609 21963 10610 21963 10641 21964 10640 21964 10609 21964 10642 21965 10610 21965 10611 21965 10642 21966 10641 21966 10610 21966 10643 21967 10611 21967 10612 21967 10643 21968 10642 21968 10611 21968 10644 21969 10612 21969 10613 21969 10644 21970 10643 21970 10612 21970 10645 21971 10613 21971 10614 21971 10645 21972 10644 21972 10613 21972 10646 21973 10614 21973 10615 21973 10646 21974 10645 21974 10614 21974 10647 21975 10615 21975 10616 21975 10647 21976 10646 21976 10615 21976 10648 21977 10616 21977 10617 21977 10648 21978 10647 21978 10616 21978 10649 21979 10617 21979 10618 21979 10649 21980 10648 21980 10617 21980 10650 21981 10618 21981 10619 21981 10650 21982 10649 21982 10618 21982 10651 21983 10619 21983 10620 21983 10651 21984 10650 21984 10619 21984 10652 21985 10620 21985 10621 21985 10652 21986 10651 21986 10620 21986 10653 21987 10621 21987 10622 21987 10653 21988 10652 21988 10621 21988 10654 21989 10622 21989 10623 21989 10654 21990 10653 21990 10622 21990 10655 21991 10623 21991 10624 21991 10655 21992 10654 21992 10623 21992 10656 21993 10624 21993 10625 21993 10656 21994 10655 21994 10624 21994 10657 21995 10625 21995 10626 21995 10657 21996 10656 21996 10625 21996 10658 21997 10626 21997 10627 21997 10658 21998 10657 21998 10626 21998 10659 21999 10627 21999 10628 21999 10659 22000 10658 22000 10627 22000 10660 22001 10628 22001 10629 22001 10660 22002 10659 22002 10628 22002 10661 22003 10629 22003 10630 22003 10661 22004 10660 22004 10629 22004 10662 22005 10630 22005 10631 22005 10662 22006 10661 22006 10630 22006 10663 22007 10631 22007 10632 22007 10663 22008 10662 22008 10631 22008 10664 22009 10632 22009 10633 22009 10664 22010 10663 22010 10632 22010 10665 22011 10633 22011 10634 22011 10665 22012 10664 22012 10633 22012 10666 22013 10634 22013 10635 22013 10666 22014 10665 22014 10634 22014 10667 22015 10635 22015 10636 22015 10667 22016 10666 22016 10635 22016 10668 22017 10636 22017 10637 22017 10668 22018 10667 22018 10636 22018 10669 22019 10637 22019 10603 22019 10669 22020 10668 22020 10637 22020 10604 22021 10669 22021 10603 22021 10599 22022 10600 22022 10638 22022 10670 22023 10638 22023 10639 22023 10670 22024 10599 22024 10638 22024 10671 22025 10639 22025 10640 22025 10671 22026 10670 22026 10639 22026 10672 22027 10640 22027 10641 22027 10672 22028 10671 22028 10640 22028 10673 22029 10641 22029 10642 22029 10673 22030 10672 22030 10641 22030 10674 22031 10642 22031 10643 22031 10674 22032 10673 22032 10642 22032 10675 22033 10643 22033 10644 22033 10675 22034 10674 22034 10643 22034 10676 22035 10644 22035 10645 22035 10676 22036 10675 22036 10644 22036 10677 22037 10645 22037 10646 22037 10677 22038 10676 22038 10645 22038 10678 22039 10646 22039 10647 22039 10678 22040 10677 22040 10646 22040 10679 22041 10647 22041 10648 22041 10679 22042 10678 22042 10647 22042 10680 22043 10648 22043 10649 22043 10680 22044 10679 22044 10648 22044 10681 22045 10649 22045 10650 22045 10681 22046 10680 22046 10649 22046 10682 22047 10650 22047 10651 22047 10682 22048 10681 22048 10650 22048 10683 22049 10651 22049 10652 22049 10683 22050 10682 22050 10651 22050 10684 22051 10652 22051 10653 22051 10684 22052 10683 22052 10652 22052 10685 22053 10653 22053 10654 22053 10685 22054 10684 22054 10653 22054 10686 22055 10654 22055 10655 22055 10686 22056 10685 22056 10654 22056 10687 22057 10655 22057 10656 22057 10687 22058 10686 22058 10655 22058 10688 22059 10656 22059 10657 22059 10688 22060 10687 22060 10656 22060 10689 22061 10657 22061 10658 22061 10689 22062 10688 22062 10657 22062 10690 22063 10658 22063 10659 22063 10690 22064 10689 22064 10658 22064 10691 22065 10659 22065 10660 22065 10691 22066 10690 22066 10659 22066 10692 22067 10660 22067 10661 22067 10692 22068 10691 22068 10660 22068 10693 22069 10661 22069 10662 22069 10693 22070 10692 22070 10661 22070 10694 22071 10662 22071 10663 22071 10694 22072 10693 22072 10662 22072 10695 22073 10663 22073 10664 22073 10695 22074 10694 22074 10663 22074 10696 22075 10664 22075 10665 22075 10696 22076 10695 22076 10664 22076 10697 22077 10665 22077 10666 22077 10697 22078 10696 22078 10665 22078 10698 22079 10666 22079 10667 22079 10698 22080 10697 22080 10666 22080 10699 22081 10667 22081 10668 22081 10699 22082 10698 22082 10667 22082 10700 22083 10668 22083 10669 22083 10700 22084 10699 22084 10668 22084 10701 22085 10669 22085 10604 22085 10701 22086 10700 22086 10669 22086 10605 22087 10701 22087 10604 22087 9641 22088 10599 22088 10670 22088 9637 22089 10670 22089 10671 22089 9637 22090 9641 22090 10670 22090 9638 22091 10671 22091 10672 22091 9638 22092 9637 22092 10671 22092 9632 22093 10672 22093 10673 22093 9632 22094 9638 22094 10672 22094 9634 22095 10673 22095 10674 22095 9634 22096 9632 22096 10673 22096 9627 22097 10674 22097 10675 22097 9627 22098 9634 22098 10674 22098 9629 22099 10675 22099 10676 22099 9629 22100 9627 22100 10675 22100 9622 22101 10676 22101 10677 22101 9622 22102 9629 22102 10676 22102 9623 22103 10677 22103 10678 22103 9623 22104 9622 22104 10677 22104 9624 22105 10678 22105 10679 22105 9624 22106 9623 22106 10678 22106 9617 22107 10679 22107 10680 22107 9617 22108 9624 22108 10679 22108 9619 22109 10680 22109 10681 22109 9619 22110 9617 22110 10680 22110 9613 22111 10681 22111 10682 22111 9613 22112 9619 22112 10681 22112 9609 22113 10682 22113 10683 22113 9609 22114 9613 22114 10682 22114 9610 22115 10683 22115 10684 22115 9610 22116 9609 22116 10683 22116 9606 22117 10684 22117 10685 22117 9606 22118 9610 22118 10684 22118 9602 22119 10685 22119 10686 22119 9602 22120 9606 22120 10685 22120 9603 22121 10686 22121 10687 22121 9603 22122 9602 22122 10686 22122 9599 22123 10687 22123 10688 22123 9599 22124 9603 22124 10687 22124 9597 22125 10688 22125 10689 22125 9597 22126 9599 22126 10688 22126 9594 22127 10689 22127 10690 22127 9594 22128 9597 22128 10689 22128 9592 22129 10690 22129 10691 22129 9592 22130 9594 22130 10690 22130 9589 22131 10691 22131 10692 22131 9589 22132 9592 22132 10691 22132 9586 22133 10692 22133 10693 22133 9586 22134 9589 22134 10692 22134 9582 22135 10693 22135 10694 22135 9582 22136 9586 22136 10693 22136 9580 22137 10694 22137 10695 22137 9580 22138 9582 22138 10694 22138 9576 22139 10695 22139 10696 22139 9576 22140 9580 22140 10695 22140 9573 22141 10696 22141 10697 22141 9573 22142 9576 22142 10696 22142 9570 22143 10697 22143 10698 22143 9570 22144 9573 22144 10697 22144 9565 22145 10698 22145 10699 22145 9565 22146 9570 22146 10698 22146 9562 22147 10699 22147 10700 22147 9562 22148 9565 22148 10699 22148 9559 22149 10700 22149 10701 22149 9559 22150 9562 22150 10700 22150 9558 22151 10701 22151 10605 22151 9558 22152 9559 22152 10701 22152 9557 22153 9558 22153 10605 22153 10702 22154 9950 22154 9736 22154 10602 22155 10703 22155 9955 22155 10704 22156 10702 22156 9736 22156 9737 22157 10704 22157 9736 22157 10602 22158 10705 22158 10703 22158 9948 22159 9950 22159 10702 22159 10706 22160 10702 22160 10704 22160 10706 22161 9948 22161 10702 22161 9738 22162 10704 22162 9737 22162 10707 22163 10704 22163 9738 22163 10706 22164 10704 22164 10707 22164 10708 22165 9738 22165 9735 22165 10707 22166 9738 22166 10708 22166 10708 22167 9735 22167 9739 22167 10709 22168 9526 22168 9527 22168 10709 22169 9661 22169 9526 22169 9956 22170 9527 22170 9525 22170 9956 22171 10709 22171 9527 22171 9954 22172 9525 22172 9530 22172 9954 22173 9956 22173 9525 22173 9915 22174 9530 22174 9529 22174 9954 22175 9530 22175 9915 22175 10602 22176 9915 22176 9916 22176 9954 22177 9915 22177 10602 22177 10705 22178 9916 22178 9917 22178 10602 22179 9916 22179 10705 22179 10710 22180 9917 22180 9918 22180 10705 22181 9917 22181 10710 22181 10711 22182 9918 22182 9919 22182 10710 22183 9918 22183 10711 22183 10712 22184 9919 22184 9920 22184 10711 22185 9919 22185 10712 22185 10713 22186 9920 22186 9921 22186 10712 22187 9920 22187 10713 22187 10714 22188 9921 22188 9922 22188 10713 22189 9921 22189 10714 22189 10715 22190 9922 22190 9923 22190 10714 22191 9922 22191 10715 22191 10716 22192 9923 22192 9924 22192 10715 22193 9923 22193 10716 22193 10717 22194 9924 22194 9925 22194 10716 22195 9924 22195 10717 22195 10718 22196 9925 22196 9926 22196 10717 22197 9925 22197 10718 22197 10719 22198 9926 22198 9927 22198 10718 22199 9926 22199 10719 22199 10720 22200 9927 22200 9928 22200 10719 22201 9927 22201 10720 22201 10721 22202 9928 22202 9929 22202 10720 22203 9928 22203 10721 22203 10722 22204 9929 22204 9930 22204 10721 22205 9929 22205 10722 22205 10723 22206 9930 22206 9931 22206 10722 22207 9930 22207 10723 22207 10724 22208 9931 22208 9932 22208 10723 22209 9931 22209 10724 22209 10725 22210 9932 22210 9933 22210 10724 22211 9932 22211 10725 22211 10726 22212 9933 22212 9934 22212 10725 22213 9933 22213 10726 22213 10727 22214 9934 22214 9935 22214 10726 22215 9934 22215 10727 22215 10728 22216 9935 22216 9936 22216 10727 22217 9935 22217 10728 22217 10729 22218 9936 22218 9937 22218 10728 22219 9936 22219 10729 22219 10730 22220 9937 22220 9938 22220 10729 22221 9937 22221 10730 22221 10731 22222 9938 22222 9939 22222 10730 22223 9938 22223 10731 22223 10732 22224 9939 22224 9940 22224 10731 22225 9939 22225 10732 22225 10733 22226 9940 22226 9941 22226 10732 22227 9940 22227 10733 22227 10734 22228 9941 22228 9942 22228 10733 22229 9941 22229 10734 22229 10735 22230 9942 22230 9943 22230 10734 22231 9942 22231 10735 22231 10736 22232 9943 22232 9944 22232 10735 22233 9943 22233 10736 22233 10737 22234 9944 22234 9945 22234 10736 22235 9944 22235 10737 22235 10738 22236 9945 22236 9947 22236 10737 22237 9945 22237 10738 22237 10739 22238 9947 22238 9946 22238 10738 22239 9947 22239 10739 22239 10706 22240 9946 22240 9948 22240 10739 22241 9946 22241 10706 22241 10740 22242 9739 22242 9740 22242 10740 22243 10708 22243 9739 22243 10741 22244 9740 22244 9742 22244 10741 22245 10740 22245 9740 22245 10742 22246 9742 22246 9741 22246 10742 22247 10741 22247 9742 22247 10743 22248 9741 22248 9743 22248 10743 22249 10742 22249 9741 22249 10744 22250 9743 22250 9745 22250 10744 22251 10743 22251 9743 22251 10745 22252 9745 22252 9746 22252 10745 22253 10744 22253 9745 22253 10746 22254 9746 22254 9744 22254 10746 22255 10745 22255 9746 22255 10747 22256 9744 22256 9748 22256 10747 22257 10746 22257 9744 22257 10748 22258 9748 22258 9747 22258 10748 22259 10747 22259 9748 22259 10749 22260 9747 22260 9750 22260 10749 22261 10748 22261 9747 22261 10750 22262 9750 22262 9751 22262 10750 22263 10749 22263 9750 22263 10751 22264 9751 22264 9749 22264 10751 22265 10750 22265 9751 22265 10752 22266 9749 22266 9753 22266 10752 22267 10751 22267 9749 22267 10753 22268 9753 22268 9752 22268 10753 22269 10752 22269 9753 22269 10754 22270 9752 22270 9755 22270 10754 22271 10753 22271 9752 22271 10755 22272 9755 22272 9754 22272 10755 22273 10754 22273 9755 22273 10756 22274 9754 22274 9756 22274 10756 22275 10755 22275 9754 22275 10757 22276 9756 22276 9758 22276 10757 22277 10756 22277 9756 22277 10758 22278 9758 22278 9757 22278 10758 22279 10757 22279 9758 22279 10759 22280 9757 22280 9759 22280 10759 22281 10758 22281 9757 22281 10760 22282 9759 22282 9760 22282 10760 22283 10759 22283 9759 22283 10761 22284 9760 22284 9761 22284 10761 22285 10760 22285 9760 22285 10762 22286 9761 22286 9762 22286 10762 22287 10761 22287 9761 22287 10763 22288 9762 22288 9763 22288 10763 22289 10762 22289 9762 22289 10764 22290 9763 22290 9764 22290 10764 22291 10763 22291 9763 22291 10765 22292 9764 22292 9765 22292 10765 22293 10764 22293 9764 22293 10766 22294 9765 22294 9766 22294 10766 22295 10765 22295 9765 22295 10767 22296 9766 22296 9767 22296 10767 22297 10766 22297 9766 22297 10768 22298 9767 22298 9768 22298 10768 22299 10767 22299 9767 22299 10769 22300 9768 22300 9769 22300 10769 22301 10768 22301 9768 22301 10770 22302 9769 22302 9770 22302 10770 22303 10769 22303 9769 22303 10771 22304 9770 22304 9771 22304 10771 22305 10770 22305 9770 22305 10709 22306 9771 22306 9661 22306 10709 22307 10771 22307 9771 22307 10772 22308 10708 22308 10740 22308 10772 22309 10707 22309 10708 22309 10773 22310 10740 22310 10741 22310 10773 22311 10772 22311 10740 22311 10774 22312 10741 22312 10742 22312 10774 22313 10773 22313 10741 22313 10775 22314 10742 22314 10743 22314 10775 22315 10774 22315 10742 22315 10776 22316 10743 22316 10744 22316 10776 22317 10775 22317 10743 22317 10777 22318 10744 22318 10745 22318 10777 22319 10776 22319 10744 22319 10778 22320 10745 22320 10746 22320 10778 22321 10777 22321 10745 22321 10779 22322 10746 22322 10747 22322 10779 22323 10778 22323 10746 22323 10780 22324 10747 22324 10748 22324 10780 22325 10779 22325 10747 22325 10781 22326 10748 22326 10749 22326 10781 22327 10780 22327 10748 22327 10782 22328 10749 22328 10750 22328 10782 22329 10781 22329 10749 22329 10783 22330 10750 22330 10751 22330 10783 22331 10782 22331 10750 22331 10784 22332 10751 22332 10752 22332 10784 22333 10783 22333 10751 22333 10785 22334 10752 22334 10753 22334 10785 22335 10784 22335 10752 22335 10786 22336 10753 22336 10754 22336 10786 22337 10785 22337 10753 22337 10787 22338 10754 22338 10755 22338 10787 22339 10786 22339 10754 22339 10788 22340 10755 22340 10756 22340 10788 22341 10787 22341 10755 22341 10789 22342 10756 22342 10757 22342 10789 22343 10788 22343 10756 22343 10790 22344 10757 22344 10758 22344 10790 22345 10789 22345 10757 22345 10791 22346 10758 22346 10759 22346 10791 22347 10790 22347 10758 22347 10792 22348 10759 22348 10760 22348 10792 22349 10791 22349 10759 22349 10793 22350 10760 22350 10761 22350 10793 22351 10792 22351 10760 22351 10794 22352 10761 22352 10762 22352 10794 22353 10793 22353 10761 22353 10795 22354 10762 22354 10763 22354 10795 22355 10794 22355 10762 22355 10796 22356 10763 22356 10764 22356 10796 22357 10795 22357 10763 22357 10797 22358 10764 22358 10765 22358 10797 22359 10796 22359 10764 22359 10798 22360 10765 22360 10766 22360 10798 22361 10797 22361 10765 22361 10799 22362 10766 22362 10767 22362 10799 22363 10798 22363 10766 22363 10800 22364 10767 22364 10768 22364 10800 22365 10799 22365 10767 22365 10801 22366 10768 22366 10769 22366 10801 22367 10800 22367 10768 22367 10703 22368 10769 22368 10770 22368 10703 22369 10801 22369 10769 22369 9955 22370 10770 22370 10771 22370 9955 22371 10703 22371 10770 22371 9956 22372 10771 22372 10709 22372 9956 22373 9955 22373 10771 22373 10739 22374 10707 22374 10772 22374 10739 22375 10706 22375 10707 22375 10738 22376 10772 22376 10773 22376 10738 22377 10739 22377 10772 22377 10737 22378 10773 22378 10774 22378 10737 22379 10738 22379 10773 22379 10736 22380 10774 22380 10775 22380 10736 22381 10737 22381 10774 22381 10735 22382 10775 22382 10776 22382 10735 22383 10736 22383 10775 22383 10734 22384 10776 22384 10777 22384 10734 22385 10735 22385 10776 22385 10733 22386 10777 22386 10778 22386 10733 22387 10734 22387 10777 22387 10732 22388 10778 22388 10779 22388 10732 22389 10733 22389 10778 22389 10731 22390 10779 22390 10780 22390 10731 22391 10732 22391 10779 22391 10730 22392 10780 22392 10781 22392 10730 22393 10731 22393 10780 22393 10729 22394 10781 22394 10782 22394 10729 22395 10730 22395 10781 22395 10728 22396 10782 22396 10783 22396 10728 22397 10729 22397 10782 22397 10727 22398 10783 22398 10784 22398 10727 22399 10728 22399 10783 22399 10726 22400 10784 22400 10785 22400 10726 22401 10727 22401 10784 22401 10725 22402 10785 22402 10786 22402 10725 22403 10726 22403 10785 22403 10724 22404 10786 22404 10787 22404 10724 22405 10725 22405 10786 22405 10723 22406 10787 22406 10788 22406 10723 22407 10724 22407 10787 22407 10722 22408 10788 22408 10789 22408 10722 22409 10723 22409 10788 22409 10721 22410 10789 22410 10790 22410 10721 22411 10722 22411 10789 22411 10720 22412 10790 22412 10791 22412 10720 22413 10721 22413 10790 22413 10719 22414 10791 22414 10792 22414 10719 22415 10720 22415 10791 22415 10718 22416 10792 22416 10793 22416 10718 22417 10719 22417 10792 22417 10717 22418 10793 22418 10794 22418 10717 22419 10718 22419 10793 22419 10716 22420 10794 22420 10795 22420 10716 22421 10717 22421 10794 22421 10715 22422 10795 22422 10796 22422 10715 22423 10716 22423 10795 22423 10714 22424 10796 22424 10797 22424 10714 22425 10715 22425 10796 22425 10713 22426 10797 22426 10798 22426 10713 22427 10714 22427 10797 22427 10712 22428 10798 22428 10799 22428 10712 22429 10713 22429 10798 22429 10711 22430 10799 22430 10800 22430 10711 22431 10712 22431 10799 22431 10710 22432 10800 22432 10801 22432 10710 22433 10711 22433 10800 22433 10705 22434 10801 22434 10703 22434 10705 22435 10710 22435 10801 22435 10802 22436 10803 22436 10804 22436 10804 22437 10805 22437 10806 22437 10806 22438 10807 22438 10808 22438 10808 22439 10809 22439 10810 22439 10810 22440 10811 22440 10812 22440 10812 22441 10813 22441 10814 22441 10814 22442 10815 22442 10816 22442 10816 22443 10817 22443 10818 22443 10818 22444 10819 22444 10821 22444 10820 22445 10821 22445 10823 22445 10822 22446 10823 22446 10825 22446 10824 22447 10825 22447 10827 22447 10826 22448 10827 22448 10829 22448 10828 22449 10829 22449 10831 22449 10830 22450 10831 22450 10833 22450 10832 22451 10833 22451 10835 22451 10834 22452 10835 22452 10837 22452 10836 22453 10837 22453 10839 22453 10838 22454 10839 22454 10841 22454 10840 22455 10841 22455 10843 22455 10842 22456 10843 22456 10845 22456 10844 22457 10845 22457 10847 22457 10846 22458 10847 22458 10849 22458 10848 22459 10849 22459 10851 22459 10850 22460 10851 22460 10852 22460 10852 22461 10853 22461 10854 22461 10854 22462 10855 22462 10856 22462 10856 22463 10857 22463 10858 22463 10858 22464 10859 22464 10860 22464 10860 22465 10861 22465 10862 22465 10805 22466 10803 22466 10865 22466 10864 22467 10865 22467 10802 22467 10862 22468 10863 22468 10864 22468 10852 22469 10848 22469 10850 22469 10866 22470 10867 22470 10868 22470 10869 22471 10868 22471 10867 22471 10870 22472 10868 22472 10871 22472 10872 22473 10871 22473 10868 22473 10866 22474 10868 22474 10870 22474 10873 22475 10868 22475 10869 22475 10874 22476 10872 22476 10868 22476 10875 22477 10874 22477 10868 22477 10873 22478 10875 22478 10868 22478 10876 22479 10877 22479 10867 22479 10878 22480 10867 22480 10877 22480 10879 22481 10876 22481 10867 22481 10880 22482 10879 22482 10867 22482 10866 22483 10880 22483 10867 22483 10881 22484 10867 22484 10878 22484 10882 22485 10883 22485 10867 22485 10884 22486 10867 22486 10883 22486 10881 22487 10882 22487 10867 22487 10884 22488 10869 22488 10867 22488 10885 22489 10886 22489 10877 22489 10887 22490 10877 22490 10886 22490 10876 22491 10885 22491 10877 22491 10878 22492 10877 22492 10887 22492 10888 22493 10889 22493 10886 22493 10890 22494 10886 22494 10889 22494 10885 22495 10888 22495 10886 22495 10887 22496 10886 22496 10890 22496 10891 22497 10889 22497 10888 22497 10890 22498 10889 22498 10891 22498 10892 22499 10888 22499 10885 22499 10891 22500 10888 22500 10892 22500 10893 22501 10885 22501 10876 22501 10892 22502 10885 22502 10893 22502 10894 22503 10895 22503 10876 22503 10896 22504 10876 22504 10895 22504 10879 22505 10894 22505 10876 22505 10893 22506 10876 22506 10896 22506 10897 22507 10898 22507 10895 22507 10899 22508 10895 22508 10898 22508 10900 22509 10897 22509 10895 22509 10894 22510 10900 22510 10895 22510 10896 22511 10895 22511 10901 22511 10899 22512 10901 22512 10895 22512 10902 22513 10903 22513 10898 22513 10904 22514 10898 22514 10903 22514 10897 22515 10902 22515 10898 22515 10905 22516 10899 22516 10898 22516 10906 22517 10905 22517 10898 22517 10907 22518 10906 22518 10898 22518 10904 22519 10907 22519 10898 22519 10908 22520 10909 22520 10903 22520 10910 22521 10903 22521 10909 22521 10911 22522 10908 22522 10903 22522 10912 22523 10911 22523 10903 22523 10902 22524 10912 22524 10903 22524 10913 22525 10903 22525 10910 22525 10914 22526 10904 22526 10903 22526 10915 22527 10916 22527 10903 22527 10914 22528 10903 22528 10916 22528 10913 22529 10915 22529 10903 22529 10917 22530 10918 22530 10909 22530 10919 22531 10909 22531 10918 22531 10908 22532 10917 22532 10909 22532 10910 22533 10909 22533 10919 22533 10920 22534 10921 22534 10918 22534 10922 22535 10918 22535 10921 22535 10917 22536 10920 22536 10918 22536 10919 22537 10918 22537 10922 22537 10923 22538 10921 22538 10920 22538 10922 22539 10921 22539 10923 22539 10924 22540 10920 22540 10917 22540 10923 22541 10920 22541 10924 22541 10925 22542 10917 22542 10908 22542 10924 22543 10917 22543 10925 22543 10926 22544 10871 22544 10908 22544 10927 22545 10908 22545 10871 22545 10911 22546 10926 22546 10908 22546 10925 22547 10908 22547 10927 22547 10928 22548 10870 22548 10871 22548 10926 22549 10928 22549 10871 22549 10927 22550 10871 22550 10929 22550 10872 22551 10929 22551 10871 22551 10930 22552 10870 22552 10928 22552 10931 22553 10866 22553 10870 22553 10931 22554 10870 22554 10930 22554 10932 22555 10928 22555 10926 22555 10932 22556 10930 22556 10928 22556 10933 22557 10926 22557 10911 22557 10932 22558 10926 22558 10933 22558 10934 22559 10911 22559 10912 22559 10933 22560 10911 22560 10934 22560 10935 22561 10912 22561 10902 22561 10934 22562 10912 22562 10935 22562 10936 22563 10902 22563 10897 22563 10935 22564 10902 22564 10936 22564 10937 22565 10897 22565 10900 22565 10936 22566 10897 22566 10937 22566 10938 22567 10900 22567 10894 22567 10937 22568 10900 22568 10938 22568 10939 22569 10894 22569 10879 22569 10938 22570 10894 22570 10939 22570 10940 22571 10879 22571 10880 22571 10939 22572 10879 22572 10940 22572 10880 22573 10866 22573 10941 22573 10940 22574 10880 22574 10941 22574 10941 22575 10866 22575 10931 22575 10932 22576 10929 22576 10942 22576 10943 22577 10942 22577 10929 22577 10930 22578 10942 22578 10878 22578 10881 22579 10878 22579 10942 22579 10932 22580 10942 22580 10930 22580 10944 22581 10881 22581 10942 22581 10945 22582 10944 22582 10942 22582 10946 22583 10945 22583 10942 22583 10947 22584 10946 22584 10942 22584 10948 22585 10947 22585 10942 22585 10943 22586 10948 22586 10942 22586 10919 22587 10927 22587 10929 22587 10934 22588 10919 22588 10929 22588 10933 22589 10934 22589 10929 22589 10932 22590 10933 22590 10929 22590 10949 22591 10943 22591 10929 22591 10872 22592 10949 22592 10929 22592 10922 22593 10925 22593 10927 22593 10919 22594 10922 22594 10927 22594 10923 22595 10924 22595 10925 22595 10922 22596 10923 22596 10925 22596 10935 22597 10910 22597 10919 22597 10934 22598 10935 22598 10919 22598 10937 22599 10950 22599 10910 22599 10913 22600 10910 22600 10950 22600 10936 22601 10937 22601 10910 22601 10935 22602 10936 22602 10910 22602 10938 22603 10901 22603 10950 22603 10951 22604 10950 22604 10901 22604 10937 22605 10938 22605 10950 22605 10952 22606 10950 22606 10951 22606 10953 22607 10913 22607 10950 22607 10954 22608 10953 22608 10950 22608 10955 22609 10954 22609 10950 22609 10956 22610 10955 22610 10950 22610 10952 22611 10956 22611 10950 22611 10887 22612 10896 22612 10901 22612 10940 22613 10887 22613 10901 22613 10939 22614 10940 22614 10901 22614 10938 22615 10939 22615 10901 22615 10957 22616 10951 22616 10901 22616 10899 22617 10957 22617 10901 22617 10890 22618 10893 22618 10896 22618 10887 22619 10890 22619 10896 22619 10891 22620 10892 22620 10893 22620 10890 22621 10891 22621 10893 22621 10941 22622 10878 22622 10887 22622 10940 22623 10941 22623 10887 22623 10931 22624 10930 22624 10878 22624 10941 22625 10931 22625 10878 22625 10958 22626 10883 22626 10882 22626 10958 22627 10884 22627 10883 22627 10959 22628 10882 22628 10881 22628 10960 22629 10958 22629 10882 22629 10959 22630 10960 22630 10882 22630 10961 22631 10881 22631 10944 22631 10962 22632 10881 22632 10961 22632 10962 22633 10959 22633 10881 22633 10963 22634 10944 22634 10945 22634 10964 22635 10961 22635 10944 22635 10963 22636 10964 22636 10944 22636 10965 22637 10945 22637 10946 22637 10966 22638 10963 22638 10945 22638 10967 22639 10966 22639 10945 22639 10965 22640 10967 22640 10945 22640 10968 22641 10946 22641 10947 22641 10969 22642 10965 22642 10946 22642 10968 22643 10969 22643 10946 22643 10970 22644 10947 22644 10948 22644 10968 22645 10947 22645 10970 22645 10970 22646 10948 22646 10943 22646 10971 22647 10943 22647 10949 22647 10971 22648 10972 22648 10943 22648 10970 22649 10943 22649 10972 22649 10973 22650 10951 22650 10957 22650 10974 22651 10952 22651 10951 22651 10973 22652 10975 22652 10951 22652 10974 22653 10951 22653 10975 22653 10973 22654 10957 22654 10899 22654 10973 22655 10899 22655 10905 22655 10973 22656 10905 22656 10906 22656 10976 22657 10906 22657 10907 22657 10976 22658 10973 22658 10906 22658 10976 22659 10907 22659 10904 22659 10977 22660 10904 22660 10914 22660 10976 22661 10904 22661 10977 22661 10958 22662 10869 22662 10884 22662 10978 22663 10873 22663 10869 22663 10978 22664 10869 22664 10958 22664 10977 22665 10916 22665 10915 22665 10977 22666 10914 22666 10916 22666 10979 22667 10915 22667 10913 22667 10980 22668 10977 22668 10915 22668 10981 22669 10980 22669 10915 22669 10979 22670 10981 22670 10915 22670 10982 22671 10913 22671 10953 22671 10983 22672 10913 22672 10982 22672 10984 22673 10979 22673 10913 22673 10983 22674 10984 22674 10913 22674 10985 22675 10953 22675 10954 22675 10986 22676 10982 22676 10953 22676 10985 22677 10986 22677 10953 22677 10987 22678 10954 22678 10955 22678 10988 22679 10985 22679 10954 22679 10989 22680 10988 22680 10954 22680 10987 22681 10989 22681 10954 22681 10990 22682 10955 22682 10956 22682 10991 22683 10987 22683 10955 22683 10990 22684 10991 22684 10955 22684 10974 22685 10956 22685 10952 22685 10992 22686 10956 22686 10974 22686 10992 22687 10990 22687 10956 22687 10971 22688 10949 22688 10872 22688 10971 22689 10872 22689 10874 22689 10971 22690 10874 22690 10875 22690 10978 22691 10875 22691 10873 22691 10978 22692 10971 22692 10875 22692 10993 22693 10975 22693 10973 22693 10994 22694 10974 22694 10975 22694 10995 22695 10994 22695 10975 22695 10996 22696 10995 22696 10975 22696 10997 22697 10996 22697 10975 22697 10998 22698 10997 22698 10975 22698 10999 22699 10998 22699 10975 22699 11000 22700 10999 22700 10975 22700 11000 22701 10975 22701 10993 22701 11001 22702 10973 22702 10976 22702 11002 22703 11003 22703 10973 22703 11004 22704 10973 22704 11003 22704 11001 22705 11002 22705 10973 22705 11005 22706 10993 22706 10973 22706 11006 22707 11005 22707 10973 22707 11007 22708 11006 22708 10973 22708 11008 22709 11007 22709 10973 22709 11009 22710 11008 22710 10973 22710 11010 22711 11009 22711 10973 22711 11004 22712 11010 22712 10973 22712 10992 22713 10974 22713 10994 22713 11011 22714 10994 22714 10995 22714 11011 22715 10992 22715 10994 22715 11012 22716 10995 22716 10996 22716 11011 22717 10995 22717 11012 22717 11012 22718 10996 22718 10997 22718 11013 22719 10997 22719 10998 22719 11012 22720 10997 22720 11013 22720 10999 22721 11014 22721 10998 22721 11013 22722 10998 22722 11014 22722 10999 22723 11015 22723 11014 22723 11016 22724 11014 22724 11015 22724 11013 22725 11014 22725 11016 22725 10999 22726 11017 22726 11015 22726 11016 22727 11015 22727 11017 22727 10999 22728 11018 22728 11017 22728 11019 22729 11017 22729 11018 22729 11016 22730 11017 22730 11019 22730 10999 22731 11020 22731 11018 22731 11019 22732 11018 22732 11020 22732 10999 22733 11021 22733 11020 22733 11019 22734 11020 22734 11021 22734 11022 22735 11023 22735 11021 22735 11024 22736 11021 22736 11023 22736 10999 22737 11022 22737 11021 22737 11019 22738 11021 22738 11024 22738 11022 22739 11025 22739 11023 22739 11024 22740 11023 22740 11025 22740 11022 22741 11026 22741 11025 22741 11027 22742 11025 22742 11026 22742 11024 22743 11025 22743 11027 22743 11022 22744 11028 22744 11026 22744 11027 22745 11026 22745 11028 22745 11022 22746 11029 22746 11028 22746 11030 22747 11028 22747 11029 22747 11027 22748 11028 22748 11030 22748 11022 22749 11031 22749 11029 22749 11030 22750 11029 22750 11031 22750 11032 22751 11033 22751 11031 22751 11034 22752 11031 22752 11033 22752 11022 22753 11032 22753 11031 22753 11030 22754 11031 22754 11034 22754 11032 22755 11035 22755 11033 22755 11036 22756 11033 22756 11035 22756 11034 22757 11033 22757 11036 22757 11032 22758 11037 22758 11035 22758 11036 22759 11035 22759 11037 22759 11038 22760 11039 22760 11037 22760 11040 22761 11037 22761 11039 22761 11032 22762 11038 22762 11037 22762 11036 22763 11037 22763 11040 22763 11038 22764 11041 22764 11039 22764 11040 22765 11039 22765 11041 22765 11038 22766 11042 22766 11041 22766 11043 22767 11041 22767 11042 22767 11040 22768 11041 22768 11043 22768 11044 22769 11045 22769 11042 22769 11046 22770 11042 22770 11045 22770 11038 22771 11044 22771 11042 22771 11043 22772 11042 22772 11046 22772 11044 22773 11047 22773 11045 22773 11048 22774 11045 22774 11047 22774 11046 22775 11045 22775 11048 22775 11049 22776 11050 22776 11047 22776 11051 22777 11047 22777 11050 22777 11044 22778 11049 22778 11047 22778 11048 22779 11047 22779 11051 22779 11049 22780 11052 22780 11050 22780 11053 22781 11050 22781 11052 22781 11051 22782 11050 22782 11053 22782 11054 22783 11055 22783 11052 22783 11056 22784 11052 22784 11055 22784 11049 22785 11054 22785 11052 22785 11057 22786 11052 22786 11056 22786 11053 22787 11052 22787 11057 22787 11058 22788 11059 22788 11055 22788 11060 22789 11055 22789 11059 22789 11054 22790 11058 22790 11055 22790 11056 22791 11055 22791 11060 22791 11061 22792 11062 22792 11059 22792 11063 22793 11059 22793 11062 22793 11058 22794 11061 22794 11059 22794 11064 22795 11059 22795 11063 22795 11060 22796 11059 22796 11064 22796 11065 22797 11066 22797 11062 22797 11067 22798 11062 22798 11066 22798 11068 22799 11065 22799 11062 22799 11061 22800 11068 22800 11062 22800 11063 22801 11062 22801 11067 22801 11069 22802 11070 22802 11066 22802 11071 22803 11066 22803 11070 22803 11072 22804 11069 22804 11066 22804 11065 22805 11072 22805 11066 22805 11073 22806 11066 22806 11071 22806 11067 22807 11066 22807 11073 22807 11074 22808 11075 22808 11070 22808 11076 22809 11070 22809 11075 22809 11069 22810 11074 22810 11070 22810 11077 22811 11070 22811 11076 22811 11078 22812 11070 22812 11077 22812 11071 22813 11070 22813 11078 22813 11079 22814 11080 22814 11075 22814 11081 22815 11075 22815 11080 22815 11082 22816 11079 22816 11075 22816 11074 22817 11082 22817 11075 22817 11083 22818 11075 22818 11081 22818 11076 22819 11075 22819 11083 22819 11084 22820 11085 22820 11080 22820 11086 22821 11080 22821 11085 22821 11087 22822 11084 22822 11080 22822 11079 22823 11087 22823 11080 22823 11088 22824 11080 22824 11086 22824 11081 22825 11080 22825 11088 22825 11089 22826 11090 22826 11085 22826 11091 22827 11085 22827 11090 22827 11084 22828 11089 22828 11085 22828 11092 22829 11085 22829 11091 22829 11086 22830 11085 22830 11092 22830 11093 22831 11094 22831 11090 22831 11095 22832 11090 22832 11094 22832 11096 22833 11093 22833 11090 22833 11097 22834 11096 22834 11090 22834 11098 22835 11097 22835 11090 22835 11099 22836 11098 22836 11090 22836 11089 22837 11099 22837 11090 22837 11091 22838 11090 22838 11095 22838 11100 22839 11094 22839 11093 22839 11101 22840 11094 22840 11100 22840 11095 22841 11094 22841 11101 22841 11100 22842 11093 22842 11096 22842 11102 22843 11096 22843 11097 22843 11102 22844 11100 22844 11096 22844 11103 22845 11097 22845 11098 22845 11103 22846 11102 22846 11097 22846 11103 22847 11098 22847 11099 22847 11104 22848 11099 22848 11089 22848 11103 22849 11099 22849 11104 22849 11104 22850 11089 22850 11084 22850 11105 22851 11084 22851 11087 22851 11105 22852 11104 22852 11084 22852 11105 22853 11087 22853 11079 22853 11106 22854 11079 22854 11082 22854 11106 22855 11105 22855 11079 22855 11106 22856 11082 22856 11074 22856 11106 22857 11074 22857 11069 22857 11107 22858 11069 22858 11072 22858 11107 22859 11106 22859 11069 22859 11107 22860 11072 22860 11065 22860 11108 22861 11065 22861 11068 22861 11108 22862 11107 22862 11065 22862 11108 22863 11068 22863 11061 22863 11109 22864 11061 22864 11058 22864 11109 22865 11108 22865 11061 22865 11109 22866 11058 22866 11054 22866 11110 22867 11054 22867 11049 22867 11110 22868 11109 22868 11054 22868 11110 22869 11049 22869 11044 22869 11111 22870 11044 22870 11038 22870 11111 22871 11110 22871 11044 22871 11112 22872 11038 22872 11032 22872 11112 22873 11111 22873 11038 22873 11112 22874 11032 22874 11022 22874 11113 22875 11022 22875 10999 22875 11113 22876 11112 22876 11022 22876 11000 22877 11113 22877 10999 22877 11114 22878 10976 22878 10977 22878 11115 22879 11114 22879 10977 22879 11115 22880 10977 22880 10980 22880 11116 22881 11117 22881 10976 22881 11118 22882 10976 22882 11117 22882 11119 22883 11116 22883 10976 22883 11114 22884 11119 22884 10976 22884 11120 22885 11001 22885 10976 22885 11121 22886 11120 22886 10976 22886 11122 22887 11121 22887 10976 22887 11123 22888 11122 22888 10976 22888 11124 22889 11123 22889 10976 22889 11118 22890 11124 22890 10976 22890 11125 22891 11126 22891 11117 22891 11127 22892 11117 22892 11126 22892 11128 22893 11125 22893 11117 22893 11129 22894 11128 22894 11117 22894 11130 22895 11129 22895 11117 22895 11131 22896 11130 22896 11117 22896 11132 22897 11131 22897 11117 22897 11133 22898 11132 22898 11117 22898 11134 22899 11133 22899 11117 22899 11135 22900 11134 22900 11117 22900 11116 22901 11135 22901 11117 22901 11118 22902 11117 22902 11122 22902 11127 22903 11122 22903 11117 22903 11136 22904 11137 22904 11126 22904 11138 22905 11126 22905 11137 22905 11139 22906 11136 22906 11126 22906 11140 22907 11139 22907 11126 22907 11141 22908 11140 22908 11126 22908 11142 22909 11141 22909 11126 22909 11143 22910 11142 22910 11126 22910 11125 22911 11143 22911 11126 22911 11127 22912 11126 22912 11138 22912 11144 22913 11145 22913 11137 22913 11146 22914 11137 22914 11145 22914 11147 22915 11144 22915 11137 22915 11148 22916 11147 22916 11137 22916 11149 22917 11148 22917 11137 22917 11136 22918 11149 22918 11137 22918 11138 22919 11137 22919 11146 22919 11150 22920 11151 22920 11145 22920 11152 22921 11145 22921 11151 22921 11153 22922 11150 22922 11145 22922 11144 22923 11153 22923 11145 22923 11146 22924 11145 22924 11152 22924 11154 22925 11155 22925 11151 22925 11156 22926 11151 22926 11155 22926 11157 22927 11154 22927 11151 22927 11150 22928 11157 22928 11151 22928 11152 22929 11151 22929 11156 22929 11158 22930 11159 22930 11155 22930 11160 22931 11155 22931 11159 22931 11154 22932 11158 22932 11155 22932 11156 22933 11155 22933 11160 22933 11161 22934 11162 22934 11159 22934 11160 22935 11159 22935 11162 22935 11158 22936 11161 22936 11159 22936 11163 22937 11164 22937 11162 22937 11165 22938 11162 22938 11164 22938 11161 22939 11163 22939 11162 22939 11160 22940 11162 22940 11165 22940 11166 22941 11167 22941 11164 22941 11165 22942 11164 22942 11167 22942 11163 22943 11166 22943 11164 22943 11168 22944 11169 22944 11167 22944 11170 22945 11167 22945 11169 22945 11166 22946 11168 22946 11167 22946 11165 22947 11167 22947 11170 22947 11168 22948 11171 22948 11169 22948 11172 22949 11169 22949 11171 22949 11170 22950 11169 22950 11172 22950 11173 22951 11174 22951 11171 22951 11172 22952 11171 22952 11174 22952 11168 22953 11173 22953 11171 22953 11173 22954 11175 22954 11174 22954 11172 22955 11174 22955 11175 22955 11176 22956 11177 22956 11175 22956 11178 22957 11175 22957 11177 22957 11173 22958 11176 22958 11175 22958 11172 22959 11175 22959 11178 22959 11179 22960 11180 22960 11177 22960 11178 22961 11177 22961 11180 22961 11176 22962 11179 22962 11177 22962 11181 22963 11182 22963 11180 22963 11183 22964 11180 22964 11182 22964 11179 22965 11181 22965 11180 22965 11178 22966 11180 22966 11183 22966 11181 22967 11184 22967 11182 22967 11185 22968 11182 22968 11184 22968 11185 22969 11183 22969 11182 22969 11181 22970 11186 22970 11184 22970 11187 22971 11184 22971 11186 22971 11187 22972 11185 22972 11184 22972 11181 22973 11188 22973 11186 22973 11187 22974 11186 22974 11188 22974 11189 22975 11188 22975 11181 22975 11190 22976 11187 22976 11188 22976 11191 22977 11190 22977 11188 22977 11192 22978 11191 22978 11188 22978 11189 22979 11192 22979 11188 22979 11193 22980 11181 22980 11179 22980 11193 22981 11189 22981 11181 22981 11194 22982 11179 22982 11176 22982 11194 22983 11193 22983 11179 22983 11195 22984 11176 22984 11173 22984 11196 22985 11194 22985 11176 22985 11195 22986 11196 22986 11176 22986 11197 22987 11173 22987 11168 22987 11197 22988 11195 22988 11173 22988 11198 22989 11168 22989 11166 22989 11199 22990 11197 22990 11168 22990 11200 22991 11199 22991 11168 22991 11198 22992 11200 22992 11168 22992 11201 22993 11166 22993 11163 22993 11202 22994 11198 22994 11166 22994 11201 22995 11202 22995 11166 22995 11203 22996 11163 22996 11161 22996 11204 22997 11201 22997 11163 22997 11205 22998 11204 22998 11163 22998 11203 22999 11205 22999 11163 22999 11206 23000 11161 23000 11158 23000 11207 23001 11203 23001 11161 23001 11206 23002 11207 23002 11161 23002 11208 23003 11158 23003 11154 23003 11209 23004 11206 23004 11158 23004 11208 23005 11209 23005 11158 23005 11210 23006 11154 23006 11157 23006 11210 23007 11208 23007 11154 23007 11211 23008 11157 23008 11150 23008 11212 23009 11210 23009 11157 23009 11211 23010 11212 23010 11157 23010 11213 23011 11150 23011 11153 23011 11213 23012 11211 23012 11150 23012 11214 23013 11153 23013 11144 23013 11214 23014 11213 23014 11153 23014 11215 23015 11144 23015 11147 23015 11215 23016 11214 23016 11144 23016 11216 23017 11147 23017 11148 23017 11216 23018 11215 23018 11147 23018 11216 23019 11148 23019 11149 23019 11217 23020 11149 23020 11136 23020 11217 23021 11216 23021 11149 23021 11217 23022 11136 23022 11139 23022 11218 23023 11139 23023 11140 23023 11218 23024 11217 23024 11139 23024 11218 23025 11140 23025 11141 23025 11219 23026 11141 23026 11142 23026 11219 23027 11218 23027 11141 23027 11219 23028 11142 23028 11143 23028 11220 23029 11143 23029 11125 23029 11220 23030 11219 23030 11143 23030 11220 23031 11125 23031 11128 23031 11221 23032 11128 23032 11129 23032 11221 23033 11220 23033 11128 23033 11221 23034 11129 23034 11130 23034 11222 23035 11130 23035 11131 23035 11222 23036 11221 23036 11130 23036 11223 23037 11131 23037 11132 23037 11223 23038 11222 23038 11131 23038 11223 23039 11132 23039 11133 23039 11223 23040 11133 23040 11134 23040 11224 23041 11134 23041 11135 23041 11224 23042 11223 23042 11134 23042 11224 23043 11135 23043 11116 23043 11225 23044 11116 23044 11119 23044 11225 23045 11224 23045 11116 23045 11115 23046 11119 23046 11114 23046 11115 23047 11225 23047 11119 23047 10983 23048 10982 23048 10986 23048 11226 23049 10986 23049 10985 23049 11227 23050 10986 23050 11226 23050 10983 23051 10986 23051 11227 23051 11226 23052 10985 23052 10988 23052 10989 23053 11226 23053 10988 23053 11228 23054 11227 23054 11226 23054 11228 23055 11226 23055 11229 23055 11230 23056 11229 23056 11226 23056 11230 23057 11226 23057 10989 23057 10983 23058 11227 23058 11228 23058 11231 23059 11232 23059 11233 23059 11234 23060 11233 23060 11232 23060 11235 23061 11231 23061 11233 23061 11236 23062 11235 23062 11233 23062 11234 23063 11236 23063 11233 23063 11237 23064 11238 23064 11232 23064 11239 23065 11232 23065 11238 23065 11231 23066 11237 23066 11232 23066 11240 23067 11234 23067 11232 23067 11239 23068 11240 23068 11232 23068 11241 23069 11242 23069 11238 23069 11243 23070 11238 23070 11242 23070 11237 23071 11241 23071 11238 23071 11243 23072 11239 23072 11238 23072 11241 23073 11244 23073 11242 23073 11245 23074 11242 23074 11244 23074 11245 23075 11243 23075 11242 23075 11246 23076 11247 23076 11244 23076 11245 23077 11244 23077 11247 23077 11241 23078 11246 23078 11244 23078 11248 23079 11249 23079 11247 23079 11250 23080 11247 23080 11249 23080 11246 23081 11248 23081 11247 23081 11250 23082 11245 23082 11247 23082 11251 23083 11252 23083 11249 23083 11253 23084 11249 23084 11252 23084 11248 23085 11251 23085 11249 23085 11253 23086 11250 23086 11249 23086 11254 23087 11255 23087 11252 23087 11256 23088 11252 23088 11255 23088 11251 23089 11254 23089 11252 23089 11256 23090 11253 23090 11252 23090 11257 23091 11258 23091 11255 23091 11256 23092 11255 23092 11258 23092 11254 23093 11257 23093 11255 23093 11259 23094 11260 23094 11258 23094 11261 23095 11258 23095 11260 23095 11257 23096 11259 23096 11258 23096 11261 23097 11256 23097 11258 23097 11262 23098 11263 23098 11260 23098 11261 23099 11260 23099 11263 23099 11259 23100 11262 23100 11260 23100 11264 23101 11265 23101 11263 23101 11266 23102 11263 23102 11265 23102 11262 23103 11264 23103 11263 23103 11266 23104 11261 23104 11263 23104 11267 23105 11268 23105 11265 23105 11266 23106 11265 23106 11268 23106 11264 23107 11267 23107 11265 23107 11269 23108 11270 23108 11268 23108 11271 23109 11268 23109 11270 23109 11267 23110 11269 23110 11268 23110 11271 23111 11266 23111 11268 23111 11272 23112 11273 23112 11270 23112 11274 23113 11270 23113 11273 23113 11269 23114 11272 23114 11270 23114 11274 23115 11271 23115 11270 23115 11275 23116 11276 23116 11273 23116 11274 23117 11273 23117 11276 23117 11272 23118 11275 23118 11273 23118 11277 23119 11278 23119 11276 23119 11279 23120 11276 23120 11278 23120 11280 23121 11277 23121 11276 23121 11275 23122 11280 23122 11276 23122 11279 23123 11274 23123 11276 23123 11281 23124 11282 23124 11278 23124 11283 23125 11278 23125 11282 23125 11277 23126 11281 23126 11278 23126 11283 23127 11279 23127 11278 23127 11284 23128 11285 23128 11282 23128 11283 23129 11282 23129 11285 23129 11281 23130 11284 23130 11282 23130 11286 23131 11287 23131 11285 23131 11288 23132 11285 23132 11287 23132 11284 23133 11286 23133 11285 23133 11288 23134 11283 23134 11285 23134 11289 23135 11290 23135 11287 23135 11288 23136 11287 23136 11290 23136 11286 23137 11289 23137 11287 23137 11291 23138 11292 23138 11290 23138 11293 23139 11290 23139 11292 23139 11289 23140 11291 23140 11290 23140 11293 23141 11288 23141 11290 23141 11294 23142 11295 23142 11292 23142 11296 23143 11292 23143 11295 23143 11291 23144 11294 23144 11292 23144 11296 23145 11293 23145 11292 23145 11297 23146 11298 23146 11295 23146 11296 23147 11295 23147 11298 23147 11294 23148 11297 23148 11295 23148 11297 23149 11299 23149 11298 23149 11300 23150 11298 23150 11299 23150 11300 23151 11296 23151 11298 23151 11297 23152 11301 23152 11299 23152 11302 23153 11299 23153 11301 23153 11302 23154 11300 23154 11299 23154 11303 23155 11304 23155 11301 23155 11305 23156 11301 23156 11304 23156 11306 23157 11303 23157 11301 23157 11297 23158 11306 23158 11301 23158 11305 23159 11302 23159 11301 23159 11307 23160 11308 23160 11304 23160 11309 23161 11304 23161 11308 23161 11303 23162 11307 23162 11304 23162 11309 23163 11305 23163 11304 23163 11310 23164 11311 23164 11308 23164 11312 23165 11308 23165 11311 23165 11307 23166 11310 23166 11308 23166 11313 23167 11309 23167 11308 23167 11312 23168 11313 23168 11308 23168 11314 23169 11315 23169 11311 23169 11312 23170 11311 23170 11315 23170 11310 23171 11314 23171 11311 23171 11316 23172 11317 23172 11315 23172 11318 23173 11315 23173 11317 23173 11314 23174 11316 23174 11315 23174 11318 23175 11312 23175 11315 23175 11319 23176 11320 23176 11317 23176 11321 23177 11317 23177 11320 23177 11316 23178 11319 23178 11317 23178 11321 23179 11318 23179 11317 23179 11322 23180 11323 23180 11320 23180 11321 23181 11320 23181 11323 23181 11319 23182 11322 23182 11320 23182 11324 23183 11325 23183 11323 23183 11326 23184 11323 23184 11325 23184 11327 23185 11324 23185 11323 23185 11322 23186 11327 23186 11323 23186 11326 23187 11321 23187 11323 23187 11328 23188 11329 23188 11325 23188 11330 23189 11325 23189 11329 23189 11324 23190 11328 23190 11325 23190 11330 23191 11326 23191 11325 23191 11331 23192 11332 23192 11329 23192 11330 23193 11329 23193 11332 23193 11328 23194 11331 23194 11329 23194 11333 23195 11334 23195 11332 23195 11335 23196 11332 23196 11334 23196 11336 23197 11333 23197 11332 23197 11331 23198 11336 23198 11332 23198 11335 23199 11330 23199 11332 23199 11337 23200 11338 23200 11334 23200 11335 23201 11334 23201 11338 23201 11333 23202 11337 23202 11334 23202 11339 23203 11340 23203 11338 23203 11341 23204 11338 23204 11340 23204 11337 23205 11339 23205 11338 23205 11341 23206 11335 23206 11338 23206 11342 23207 11343 23207 11340 23207 11341 23208 11340 23208 11343 23208 11339 23209 11342 23209 11340 23209 11344 23210 11345 23210 11343 23210 11346 23211 11343 23211 11345 23211 11342 23212 11344 23212 11343 23212 11346 23213 11341 23213 11343 23213 11347 23214 11348 23214 11345 23214 11346 23215 11345 23215 11348 23215 11344 23216 11347 23216 11345 23216 11349 23217 11350 23217 11348 23217 11351 23218 11348 23218 11350 23218 11347 23219 11349 23219 11348 23219 11351 23220 11346 23220 11348 23220 11352 23221 11353 23221 11350 23221 11351 23222 11350 23222 11353 23222 11349 23223 11352 23223 11350 23223 11354 23224 11355 23224 11353 23224 11356 23225 11353 23225 11355 23225 11352 23226 11354 23226 11353 23226 11356 23227 11351 23227 11353 23227 11357 23228 11358 23228 11355 23228 11356 23229 11355 23229 11358 23229 11354 23230 11357 23230 11355 23230 11359 23231 11360 23231 11358 23231 11361 23232 11358 23232 11360 23232 11357 23233 11359 23233 11358 23233 11361 23234 11356 23234 11358 23234 11362 23235 11363 23235 11360 23235 11361 23236 11360 23236 11363 23236 11364 23237 11362 23237 11360 23237 11359 23238 11364 23238 11360 23238 11365 23239 11366 23239 11363 23239 11367 23240 11363 23240 11366 23240 11362 23241 11365 23241 11363 23241 11367 23242 11361 23242 11363 23242 11368 23243 11229 23243 11366 23243 11230 23244 11366 23244 11229 23244 11365 23245 11368 23245 11366 23245 11230 23246 11367 23246 11366 23246 11368 23247 11228 23247 11229 23247 11369 23248 11228 23248 11368 23248 11369 23249 10983 23249 11228 23249 11369 23250 11368 23250 11365 23250 11370 23251 11365 23251 11362 23251 11370 23252 11369 23252 11365 23252 11370 23253 11362 23253 11364 23253 11371 23254 11364 23254 11359 23254 11371 23255 11370 23255 11364 23255 11371 23256 11359 23256 11357 23256 11371 23257 11357 23257 11354 23257 11372 23258 11354 23258 11352 23258 11372 23259 11371 23259 11354 23259 11372 23260 11352 23260 11349 23260 11373 23261 11349 23261 11347 23261 11373 23262 11372 23262 11349 23262 11374 23263 11347 23263 11344 23263 11374 23264 11373 23264 11347 23264 11374 23265 11344 23265 11342 23265 11374 23266 11342 23266 11339 23266 11375 23267 11339 23267 11337 23267 11375 23268 11374 23268 11339 23268 11375 23269 11337 23269 11333 23269 11376 23270 11333 23270 11336 23270 11376 23271 11375 23271 11333 23271 11376 23272 11336 23272 11331 23272 11376 23273 11331 23273 11328 23273 11377 23274 11328 23274 11324 23274 11377 23275 11376 23275 11328 23275 11377 23276 11324 23276 11327 23276 11378 23277 11327 23277 11322 23277 11378 23278 11377 23278 11327 23278 11379 23279 11322 23279 11319 23279 11379 23280 11378 23280 11322 23280 11379 23281 11319 23281 11316 23281 11380 23282 11316 23282 11314 23282 11380 23283 11379 23283 11316 23283 11381 23284 11314 23284 11310 23284 11381 23285 11380 23285 11314 23285 11382 23286 11310 23286 11307 23286 11382 23287 11381 23287 11310 23287 11383 23288 11307 23288 11303 23288 11383 23289 11382 23289 11307 23289 11384 23290 11303 23290 11306 23290 11384 23291 11383 23291 11303 23291 11385 23292 11306 23292 11297 23292 11385 23293 11384 23293 11306 23293 11386 23294 11297 23294 11294 23294 11386 23295 11385 23295 11297 23295 11387 23296 11294 23296 11291 23296 11387 23297 11386 23297 11294 23297 11388 23298 11291 23298 11289 23298 11388 23299 11387 23299 11291 23299 11388 23300 11289 23300 11286 23300 11389 23301 11286 23301 11284 23301 11389 23302 11388 23302 11286 23302 11390 23303 11284 23303 11281 23303 11390 23304 11389 23304 11284 23304 11390 23305 11281 23305 11277 23305 11391 23306 11277 23306 11280 23306 11391 23307 11390 23307 11277 23307 11391 23308 11280 23308 11275 23308 11392 23309 11275 23309 11272 23309 11392 23310 11391 23310 11275 23310 11392 23311 11272 23311 11269 23311 11393 23312 11269 23312 11267 23312 11393 23313 11392 23313 11269 23313 11394 23314 11267 23314 11264 23314 11394 23315 11393 23315 11267 23315 11394 23316 11264 23316 11262 23316 11395 23317 11262 23317 11259 23317 11395 23318 11394 23318 11262 23318 11395 23319 11259 23319 11257 23319 11396 23320 11257 23320 11254 23320 11396 23321 11395 23321 11257 23321 11397 23322 11254 23322 11251 23322 11397 23323 11396 23323 11254 23323 11397 23324 11251 23324 11248 23324 11398 23325 11248 23325 11246 23325 11398 23326 11397 23326 11248 23326 11398 23327 11246 23327 11241 23327 11399 23328 11241 23328 11237 23328 11399 23329 11398 23329 11241 23329 11400 23330 11237 23330 11231 23330 11401 23331 11399 23331 11237 23331 11400 23332 11401 23332 11237 23332 11402 23333 11231 23333 11235 23333 11402 23334 11400 23334 11231 23334 11403 23335 11235 23335 11236 23335 11190 23336 11235 23336 11403 23336 11404 23337 11235 23337 11190 23337 11402 23338 11235 23338 11404 23338 11405 23339 11403 23339 11236 23339 11102 23340 11405 23340 11236 23340 11102 23341 11236 23341 11100 23341 11406 23342 11100 23342 11236 23342 11407 23343 11406 23343 11236 23343 11408 23344 11409 23344 11410 23344 11234 23345 11407 23345 11236 23345 11411 23346 11403 23346 11405 23346 11190 23347 11403 23347 11411 23347 11412 23348 11413 23348 11414 23348 11104 23349 11414 23349 11413 23349 11415 23350 11412 23350 11414 23350 11416 23351 11415 23351 11414 23351 11105 23352 11416 23352 11414 23352 11105 23353 11414 23353 11104 23353 11411 23354 11405 23354 11413 23354 11103 23355 11413 23355 11405 23355 11412 23356 11411 23356 11413 23356 11103 23357 11104 23357 11413 23357 11103 23358 11405 23358 11102 23358 11187 23359 11411 23359 11412 23359 11190 23360 11411 23360 11187 23360 11185 23361 11412 23361 11415 23361 11187 23362 11412 23362 11185 23362 11417 23363 11415 23363 11416 23363 11183 23364 11415 23364 11417 23364 11185 23365 11415 23365 11183 23365 11418 23366 11419 23366 11003 23366 11004 23367 11003 23367 11419 23367 11002 23368 11418 23368 11003 23368 11420 23369 11421 23369 11419 23369 11000 23370 11419 23370 11421 23370 11418 23371 11420 23371 11419 23371 11008 23372 11419 23372 11007 23372 11000 23373 11007 23373 11419 23373 11009 23374 11419 23374 11008 23374 11010 23375 11419 23375 11009 23375 11004 23376 11419 23376 11010 23376 11422 23377 11423 23377 11421 23377 11113 23378 11421 23378 11423 23378 11420 23379 11422 23379 11421 23379 11000 23380 11421 23380 11113 23380 11424 23381 11425 23381 11423 23381 11112 23382 11423 23382 11425 23382 11422 23383 11424 23383 11423 23383 11113 23384 11423 23384 11112 23384 11424 23385 11426 23385 11425 23385 11112 23386 11425 23386 11426 23386 11427 23387 11428 23387 11426 23387 11111 23388 11426 23388 11428 23388 11424 23389 11427 23389 11426 23389 11112 23390 11426 23390 11111 23390 11429 23391 11430 23391 11428 23391 11110 23392 11428 23392 11430 23392 11427 23393 11429 23393 11428 23393 11111 23394 11428 23394 11110 23394 11431 23395 11432 23395 11430 23395 11110 23396 11430 23396 11432 23396 11429 23397 11431 23397 11430 23397 11431 23398 11433 23398 11432 23398 11109 23399 11432 23399 11433 23399 11110 23400 11432 23400 11109 23400 11434 23401 11435 23401 11433 23401 11109 23402 11433 23402 11435 23402 11431 23403 11434 23403 11433 23403 11436 23404 11437 23404 11435 23404 11108 23405 11435 23405 11437 23405 11434 23406 11436 23406 11435 23406 11109 23407 11435 23407 11108 23407 11436 23408 11438 23408 11437 23408 11108 23409 11437 23409 11438 23409 11439 23410 11440 23410 11438 23410 11107 23411 11438 23411 11440 23411 11436 23412 11439 23412 11438 23412 11108 23413 11438 23413 11107 23413 11441 23414 11442 23414 11440 23414 11107 23415 11440 23415 11442 23415 11439 23416 11441 23416 11440 23416 11443 23417 11444 23417 11442 23417 11107 23418 11442 23418 11444 23418 11441 23419 11443 23419 11442 23419 11443 23420 11445 23420 11444 23420 11106 23421 11444 23421 11445 23421 11107 23422 11444 23422 11106 23422 11446 23423 11447 23423 11445 23423 11106 23424 11445 23424 11447 23424 11443 23425 11446 23425 11445 23425 11448 23426 11449 23426 11447 23426 11105 23427 11447 23427 11449 23427 11446 23428 11448 23428 11447 23428 11106 23429 11447 23429 11105 23429 11417 23430 11416 23430 11449 23430 11105 23431 11449 23431 11416 23431 11448 23432 11417 23432 11449 23432 11178 23433 11417 23433 11448 23433 11178 23434 11183 23434 11417 23434 11178 23435 11448 23435 11446 23435 11172 23436 11446 23436 11443 23436 11172 23437 11178 23437 11446 23437 11172 23438 11443 23438 11441 23438 11170 23439 11441 23439 11439 23439 11170 23440 11172 23440 11441 23440 11170 23441 11439 23441 11436 23441 11165 23442 11436 23442 11434 23442 11165 23443 11170 23443 11436 23443 11160 23444 11434 23444 11431 23444 11160 23445 11165 23445 11434 23445 11160 23446 11431 23446 11429 23446 11156 23447 11429 23447 11427 23447 11156 23448 11160 23448 11429 23448 11152 23449 11427 23449 11424 23449 11152 23450 11156 23450 11427 23450 11146 23451 11424 23451 11422 23451 11146 23452 11152 23452 11424 23452 11138 23453 11422 23453 11420 23453 11138 23454 11146 23454 11422 23454 11127 23455 11420 23455 11418 23455 11127 23456 11138 23456 11420 23456 11122 23457 11418 23457 11002 23457 11127 23458 11418 23458 11122 23458 11120 23459 11002 23459 11001 23459 11121 23460 11002 23460 11120 23460 11122 23461 11002 23461 11121 23461 11124 23462 11122 23462 11123 23462 11118 23463 11122 23463 11124 23463 11000 23464 10993 23464 11005 23464 11000 23465 11005 23465 11006 23465 11000 23466 11006 23466 11007 23466 11450 23467 10972 23467 10971 23467 11451 23468 10970 23468 10972 23468 11452 23469 11451 23469 10972 23469 11453 23470 11452 23470 10972 23470 11454 23471 11453 23471 10972 23471 11455 23472 11454 23472 10972 23472 11456 23473 11455 23473 10972 23473 11456 23474 10972 23474 11450 23474 11457 23475 10971 23475 10978 23475 11458 23476 11459 23476 10971 23476 11460 23477 10971 23477 11459 23477 11461 23478 11458 23478 10971 23478 11462 23479 11461 23479 10971 23479 11457 23480 11462 23480 10971 23480 11463 23481 11450 23481 10971 23481 11464 23482 11463 23482 10971 23482 11465 23483 11464 23483 10971 23483 11466 23484 11465 23484 10971 23484 11467 23485 11466 23485 10971 23485 11468 23486 11467 23486 10971 23486 11460 23487 11468 23487 10971 23487 10968 23488 10970 23488 11451 23488 11469 23489 11451 23489 11452 23489 11469 23490 10968 23490 11451 23490 11470 23491 11452 23491 11453 23491 11469 23492 11452 23492 11470 23492 11470 23493 11453 23493 11454 23493 11455 23494 11471 23494 11454 23494 11472 23495 11454 23495 11471 23495 11470 23496 11454 23496 11472 23496 11455 23497 11473 23497 11471 23497 11472 23498 11471 23498 11473 23498 11474 23499 11475 23499 11473 23499 11476 23500 11473 23500 11475 23500 11455 23501 11474 23501 11473 23501 11472 23502 11473 23502 11476 23502 11474 23503 11477 23503 11475 23503 11476 23504 11475 23504 11477 23504 11474 23505 11478 23505 11477 23505 11479 23506 11477 23506 11478 23506 11476 23507 11477 23507 11479 23507 11474 23508 11480 23508 11478 23508 11479 23509 11478 23509 11480 23509 11474 23510 11481 23510 11480 23510 11479 23511 11480 23511 11481 23511 11482 23512 11483 23512 11481 23512 11484 23513 11481 23513 11483 23513 11474 23514 11482 23514 11481 23514 11479 23515 11481 23515 11484 23515 11482 23516 11485 23516 11483 23516 11484 23517 11483 23517 11485 23517 11482 23518 11486 23518 11485 23518 11487 23519 11485 23519 11486 23519 11484 23520 11485 23520 11487 23520 11482 23521 11488 23521 11486 23521 11489 23522 11486 23522 11488 23522 11487 23523 11486 23523 11489 23523 11490 23524 11491 23524 11488 23524 11489 23525 11488 23525 11491 23525 11482 23526 11490 23526 11488 23526 11490 23527 11492 23527 11491 23527 11493 23528 11491 23528 11492 23528 11489 23529 11491 23529 11493 23529 11490 23530 11494 23530 11492 23530 11495 23531 11492 23531 11494 23531 11493 23532 11492 23532 11495 23532 11496 23533 11497 23533 11494 23533 11498 23534 11494 23534 11497 23534 11490 23535 11496 23535 11494 23535 11495 23536 11494 23536 11498 23536 11496 23537 11499 23537 11497 23537 11500 23538 11497 23538 11499 23538 11498 23539 11497 23539 11500 23539 11501 23540 11502 23540 11499 23540 11503 23541 11499 23541 11502 23541 11496 23542 11501 23542 11499 23542 11500 23543 11499 23543 11503 23543 11501 23544 11504 23544 11502 23544 11505 23545 11502 23545 11504 23545 11503 23546 11502 23546 11505 23546 11506 23547 11507 23547 11504 23547 11508 23548 11504 23548 11507 23548 11501 23549 11506 23549 11504 23549 11505 23550 11504 23550 11508 23550 11509 23551 11510 23551 11507 23551 11511 23552 11507 23552 11510 23552 11506 23553 11509 23553 11507 23553 11508 23554 11507 23554 11511 23554 11512 23555 11513 23555 11510 23555 11514 23556 11510 23556 11513 23556 11509 23557 11512 23557 11510 23557 11511 23558 11510 23558 11514 23558 11515 23559 11516 23559 11513 23559 11517 23560 11513 23560 11516 23560 11512 23561 11515 23561 11513 23561 11518 23562 11513 23562 11517 23562 11514 23563 11513 23563 11518 23563 11519 23564 11520 23564 11516 23564 11521 23565 11516 23565 11520 23565 11522 23566 11519 23566 11516 23566 11515 23567 11522 23567 11516 23567 11523 23568 11516 23568 11521 23568 11517 23569 11516 23569 11523 23569 11524 23570 11525 23570 11520 23570 11526 23571 11520 23571 11525 23571 11527 23572 11524 23572 11520 23572 11519 23573 11527 23573 11520 23573 11521 23574 11520 23574 11526 23574 11528 23575 11529 23575 11525 23575 11530 23576 11525 23576 11529 23576 11531 23577 11528 23577 11525 23577 11532 23578 11531 23578 11525 23578 11524 23579 11532 23579 11525 23579 11533 23580 11525 23580 11530 23580 11526 23581 11525 23581 11533 23581 11534 23582 11535 23582 11529 23582 11536 23583 11529 23583 11535 23583 11537 23584 11534 23584 11529 23584 11538 23585 11537 23585 11529 23585 11539 23586 11538 23586 11529 23586 11528 23587 11539 23587 11529 23587 11540 23588 11529 23588 11536 23588 11541 23589 11529 23589 11540 23589 11530 23590 11529 23590 11541 23590 11542 23591 11543 23591 11535 23591 11544 23592 11535 23592 11543 23592 11545 23593 11542 23593 11535 23593 11546 23594 11545 23594 11535 23594 11547 23595 11546 23595 11535 23595 11534 23596 11547 23596 11535 23596 11548 23597 11535 23597 11544 23597 11536 23598 11535 23598 11548 23598 11549 23599 11550 23599 11543 23599 11551 23600 11543 23600 11550 23600 11552 23601 11549 23601 11543 23601 11553 23602 11552 23602 11543 23602 11554 23603 11553 23603 11543 23603 11555 23604 11554 23604 11543 23604 11556 23605 11555 23605 11543 23605 11557 23606 11556 23606 11543 23606 11558 23607 11557 23607 11543 23607 11542 23608 11558 23608 11543 23608 11559 23609 11543 23609 11551 23609 11560 23610 11543 23610 11559 23610 11544 23611 11543 23611 11560 23611 11561 23612 11550 23612 11549 23612 11562 23613 11550 23613 11561 23613 11563 23614 11550 23614 11562 23614 11551 23615 11550 23615 11563 23615 11561 23616 11549 23616 11552 23616 11564 23617 11552 23617 11553 23617 11564 23618 11561 23618 11552 23618 11565 23619 11553 23619 11554 23619 11565 23620 11564 23620 11553 23620 11565 23621 11554 23621 11555 23621 11566 23622 11555 23622 11556 23622 11565 23623 11555 23623 11566 23623 11566 23624 11556 23624 11557 23624 11566 23625 11557 23625 11558 23625 11567 23626 11558 23626 11542 23626 11567 23627 11566 23627 11558 23627 11567 23628 11542 23628 11545 23628 11567 23629 11545 23629 11546 23629 11567 23630 11546 23630 11547 23630 11568 23631 11547 23631 11534 23631 11568 23632 11567 23632 11547 23632 11568 23633 11534 23633 11537 23633 11568 23634 11537 23634 11538 23634 11568 23635 11538 23635 11539 23635 11569 23636 11539 23636 11528 23636 11569 23637 11568 23637 11539 23637 11569 23638 11528 23638 11531 23638 11569 23639 11531 23639 11532 23639 11570 23640 11532 23640 11524 23640 11570 23641 11569 23641 11532 23641 11570 23642 11524 23642 11527 23642 11570 23643 11527 23643 11519 23643 11571 23644 11519 23644 11522 23644 11571 23645 11570 23645 11519 23645 11571 23646 11522 23646 11515 23646 11572 23647 11515 23647 11512 23647 11572 23648 11571 23648 11515 23648 11572 23649 11512 23649 11509 23649 11573 23650 11509 23650 11506 23650 11573 23651 11572 23651 11509 23651 11574 23652 11506 23652 11501 23652 11574 23653 11573 23653 11506 23653 11575 23654 11501 23654 11496 23654 11575 23655 11574 23655 11501 23655 11575 23656 11496 23656 11490 23656 11576 23657 11490 23657 11482 23657 11576 23658 11575 23658 11490 23658 11577 23659 11482 23659 11474 23659 11577 23660 11576 23660 11482 23660 11456 23661 11474 23661 11455 23661 11456 23662 11577 23662 11474 23662 11578 23663 11579 23663 11580 23663 11581 23664 11580 23664 11579 23664 11582 23665 11578 23665 11580 23665 11583 23666 11582 23666 11580 23666 11584 23667 11583 23667 11580 23667 11581 23668 11584 23668 11580 23668 11578 23669 11585 23669 11579 23669 11586 23670 11579 23670 11585 23670 11587 23671 11581 23671 11579 23671 11586 23672 11587 23672 11579 23672 11578 23673 11588 23673 11585 23673 11589 23674 11585 23674 11588 23674 11589 23675 11586 23675 11585 23675 11578 23676 11590 23676 11588 23676 11589 23677 11588 23677 11590 23677 11591 23678 11590 23678 11578 23678 11592 23679 11589 23679 11590 23679 11593 23680 11592 23680 11590 23680 11591 23681 11593 23681 11590 23681 11594 23682 11578 23682 11582 23682 11594 23683 11591 23683 11578 23683 11583 23684 11595 23684 11582 23684 11594 23685 11582 23685 11595 23685 11596 23686 11597 23686 11595 23686 11598 23687 11595 23687 11597 23687 11583 23688 11596 23688 11595 23688 11598 23689 11594 23689 11595 23689 11599 23690 11600 23690 11597 23690 11601 23691 11597 23691 11600 23691 11596 23692 11599 23692 11597 23692 11601 23693 11598 23693 11597 23693 11602 23694 11603 23694 11600 23694 11604 23695 11600 23695 11603 23695 11605 23696 11602 23696 11600 23696 11599 23697 11605 23697 11600 23697 11604 23698 11601 23698 11600 23698 11606 23699 11607 23699 11603 23699 11608 23700 11603 23700 11607 23700 11602 23701 11606 23701 11603 23701 11608 23702 11604 23702 11603 23702 11609 23703 11610 23703 11607 23703 11611 23704 11607 23704 11610 23704 11606 23705 11609 23705 11607 23705 11611 23706 11608 23706 11607 23706 11612 23707 11613 23707 11610 23707 11614 23708 11610 23708 11613 23708 11609 23709 11612 23709 11610 23709 11614 23710 11611 23710 11610 23710 11615 23711 11616 23711 11613 23711 11617 23712 11613 23712 11616 23712 11618 23713 11615 23713 11613 23713 11612 23714 11618 23714 11613 23714 11617 23715 11614 23715 11613 23715 11619 23716 11620 23716 11616 23716 11621 23717 11616 23717 11620 23717 11615 23718 11619 23718 11616 23718 11621 23719 11617 23719 11616 23719 11622 23720 11623 23720 11620 23720 11624 23721 11620 23721 11623 23721 11619 23722 11622 23722 11620 23722 11624 23723 11621 23723 11620 23723 11622 23724 11625 23724 11623 23724 11626 23725 11623 23725 11625 23725 11626 23726 11624 23726 11623 23726 11627 23727 11628 23727 11625 23727 11626 23728 11625 23728 11628 23728 11622 23729 11627 23729 11625 23729 11629 23730 11630 23730 11628 23730 11631 23731 11628 23731 11630 23731 11632 23732 11629 23732 11628 23732 11627 23733 11632 23733 11628 23733 11631 23734 11626 23734 11628 23734 11633 23735 11634 23735 11630 23735 11635 23736 11630 23736 11634 23736 11629 23737 11633 23737 11630 23737 11636 23738 11631 23738 11630 23738 11637 23739 11636 23739 11630 23739 11635 23740 11637 23740 11630 23740 11638 23741 11639 23741 11634 23741 11640 23742 11634 23742 11639 23742 11633 23743 11638 23743 11634 23743 11641 23744 11635 23744 11634 23744 11640 23745 11641 23745 11634 23745 11642 23746 11643 23746 11639 23746 11644 23747 11639 23747 11643 23747 11638 23748 11642 23748 11639 23748 11645 23749 11640 23749 11639 23749 11644 23750 11645 23750 11639 23750 11646 23751 11647 23751 11643 23751 11648 23752 11643 23752 11647 23752 11642 23753 11646 23753 11643 23753 11648 23754 11644 23754 11643 23754 11649 23755 11650 23755 11647 23755 11651 23756 11647 23756 11650 23756 11646 23757 11649 23757 11647 23757 11652 23758 11648 23758 11647 23758 11651 23759 11652 23759 11647 23759 11649 23760 11653 23760 11650 23760 11654 23761 11650 23761 11653 23761 11654 23762 11651 23762 11650 23762 11649 23763 11655 23763 11653 23763 11654 23764 11653 23764 11655 23764 11656 23765 11657 23765 11655 23765 11658 23766 11655 23766 11657 23766 11649 23767 11656 23767 11655 23767 11658 23768 11654 23768 11655 23768 11656 23769 11659 23769 11657 23769 11660 23770 11657 23770 11659 23770 11660 23771 11658 23771 11657 23771 11656 23772 11661 23772 11659 23772 11660 23773 11659 23773 11661 23773 11662 23774 11663 23774 11661 23774 11664 23775 11661 23775 11663 23775 11656 23776 11662 23776 11661 23776 11664 23777 11660 23777 11661 23777 11662 23778 11665 23778 11663 23778 11664 23779 11663 23779 11665 23779 11662 23780 11666 23780 11665 23780 11667 23781 11665 23781 11666 23781 11667 23782 11664 23782 11665 23782 11662 23783 11668 23783 11666 23783 11669 23784 11666 23784 11668 23784 11669 23785 11667 23785 11666 23785 11670 23786 11671 23786 11668 23786 11672 23787 11668 23787 11671 23787 11662 23788 11670 23788 11668 23788 11672 23789 11669 23789 11668 23789 11670 23790 11673 23790 11671 23790 11672 23791 11671 23791 11673 23791 11670 23792 11674 23792 11673 23792 11675 23793 11673 23793 11674 23793 11675 23794 11672 23794 11673 23794 11676 23795 11677 23795 11674 23795 11675 23796 11674 23796 11677 23796 11670 23797 11676 23797 11674 23797 11676 23798 11678 23798 11677 23798 11679 23799 11677 23799 11678 23799 11679 23800 11675 23800 11677 23800 11676 23801 11680 23801 11678 23801 11681 23802 11678 23802 11680 23802 11681 23803 11679 23803 11678 23803 10978 23804 11682 23804 11680 23804 11683 23805 11680 23805 11682 23805 11676 23806 10978 23806 11680 23806 11683 23807 11681 23807 11680 23807 10978 23808 10958 23808 11682 23808 11683 23809 11682 23809 10958 23809 11683 23810 10958 23810 10960 23810 11684 23811 10978 23811 11676 23811 11685 23812 11457 23812 10978 23812 11686 23813 11685 23813 10978 23813 11687 23814 11686 23814 10978 23814 11688 23815 11687 23815 10978 23815 11684 23816 11688 23816 10978 23816 11688 23817 11676 23817 11670 23817 11684 23818 11676 23818 11688 23818 11689 23819 11670 23819 11662 23819 11689 23820 11688 23820 11670 23820 11690 23821 11662 23821 11656 23821 11690 23822 11689 23822 11662 23822 11691 23823 11656 23823 11649 23823 11691 23824 11690 23824 11656 23824 11692 23825 11649 23825 11646 23825 11692 23826 11691 23826 11649 23826 11693 23827 11646 23827 11642 23827 11693 23828 11692 23828 11646 23828 11694 23829 11642 23829 11638 23829 11694 23830 11693 23830 11642 23830 11694 23831 11638 23831 11633 23831 11695 23832 11633 23832 11629 23832 11695 23833 11694 23833 11633 23833 11695 23834 11629 23834 11632 23834 11696 23835 11632 23835 11627 23835 11696 23836 11695 23836 11632 23836 11696 23837 11627 23837 11622 23837 11697 23838 11622 23838 11619 23838 11697 23839 11696 23839 11622 23839 11697 23840 11619 23840 11615 23840 11698 23841 11615 23841 11618 23841 11698 23842 11697 23842 11615 23842 11698 23843 11618 23843 11612 23843 11698 23844 11612 23844 11609 23844 11698 23845 11609 23845 11606 23845 11699 23846 11606 23846 11602 23846 11699 23847 11698 23847 11606 23847 11699 23848 11602 23848 11605 23848 11699 23849 11605 23849 11599 23849 11584 23850 11599 23850 11596 23850 11584 23851 11699 23851 11599 23851 11584 23852 11596 23852 11583 23852 10962 23853 10961 23853 10964 23853 10967 23854 10964 23854 10963 23854 11700 23855 10964 23855 10967 23855 10962 23856 10964 23856 11700 23856 10967 23857 10963 23857 10966 23857 11701 23858 11700 23858 10967 23858 11702 23859 11701 23859 10967 23859 11702 23860 10967 23860 10965 23860 11703 23861 11700 23861 11701 23861 10962 23862 11700 23862 11703 23862 11704 23863 11705 23863 11706 23863 11707 23864 11706 23864 11705 23864 11708 23865 11704 23865 11706 23865 11709 23866 11708 23866 11706 23866 11707 23867 11709 23867 11706 23867 11704 23868 11710 23868 11705 23868 11711 23869 11705 23869 11710 23869 11711 23870 11707 23870 11705 23870 11712 23871 11713 23871 11710 23871 11711 23872 11710 23872 11713 23872 11704 23873 11712 23873 11710 23873 11714 23874 11715 23874 11713 23874 11716 23875 11713 23875 11715 23875 11712 23876 11714 23876 11713 23876 11716 23877 11711 23877 11713 23877 11717 23878 11718 23878 11715 23878 11716 23879 11715 23879 11718 23879 11714 23880 11717 23880 11715 23880 11719 23881 11720 23881 11718 23881 11721 23882 11718 23882 11720 23882 11717 23883 11719 23883 11718 23883 11721 23884 11716 23884 11718 23884 11722 23885 11723 23885 11720 23885 11724 23886 11720 23886 11723 23886 11719 23887 11722 23887 11720 23887 11724 23888 11721 23888 11720 23888 11725 23889 11726 23889 11723 23889 11727 23890 11723 23890 11726 23890 11722 23891 11725 23891 11723 23891 11727 23892 11724 23892 11723 23892 11728 23893 11729 23893 11726 23893 11727 23894 11726 23894 11729 23894 11725 23895 11728 23895 11726 23895 11730 23896 11731 23896 11729 23896 11732 23897 11729 23897 11731 23897 11728 23898 11730 23898 11729 23898 11732 23899 11727 23899 11729 23899 11733 23900 11734 23900 11731 23900 11732 23901 11731 23901 11734 23901 11730 23902 11733 23902 11731 23902 11735 23903 11736 23903 11734 23903 11737 23904 11734 23904 11736 23904 11733 23905 11735 23905 11734 23905 11737 23906 11732 23906 11734 23906 11738 23907 11739 23907 11736 23907 11740 23908 11736 23908 11739 23908 11735 23909 11738 23909 11736 23909 11740 23910 11737 23910 11736 23910 11741 23911 11742 23911 11739 23911 11740 23912 11739 23912 11742 23912 11738 23913 11741 23913 11739 23913 11743 23914 11744 23914 11742 23914 11745 23915 11742 23915 11744 23915 11741 23916 11743 23916 11742 23916 11745 23917 11740 23917 11742 23917 11746 23918 11747 23918 11744 23918 11745 23919 11744 23919 11747 23919 11743 23920 11746 23920 11744 23920 11748 23921 11749 23921 11747 23921 11750 23922 11747 23922 11749 23922 11746 23923 11748 23923 11747 23923 11750 23924 11745 23924 11747 23924 11751 23925 11752 23925 11749 23925 11753 23926 11749 23926 11752 23926 11748 23927 11751 23927 11749 23927 11753 23928 11750 23928 11749 23928 11754 23929 11755 23929 11752 23929 11753 23930 11752 23930 11755 23930 11751 23931 11754 23931 11752 23931 11756 23932 11757 23932 11755 23932 11758 23933 11755 23933 11757 23933 11754 23934 11756 23934 11755 23934 11758 23935 11753 23935 11755 23935 11759 23936 11760 23936 11757 23936 11761 23937 11757 23937 11760 23937 11756 23938 11759 23938 11757 23938 11761 23939 11758 23939 11757 23939 11762 23940 11763 23940 11760 23940 11761 23941 11760 23941 11763 23941 11759 23942 11762 23942 11760 23942 11764 23943 11765 23943 11763 23943 11766 23944 11763 23944 11765 23944 11762 23945 11764 23945 11763 23945 11766 23946 11761 23946 11763 23946 11767 23947 11768 23947 11765 23947 11766 23948 11765 23948 11768 23948 11764 23949 11767 23949 11765 23949 11767 23950 11769 23950 11768 23950 11770 23951 11768 23951 11769 23951 11770 23952 11766 23952 11768 23952 11771 23953 11772 23953 11769 23953 11770 23954 11769 23954 11772 23954 11767 23955 11771 23955 11769 23955 11773 23956 11774 23956 11772 23956 11775 23957 11772 23957 11774 23957 11776 23958 11773 23958 11772 23958 11771 23959 11776 23959 11772 23959 11775 23960 11770 23960 11772 23960 11777 23961 11778 23961 11774 23961 11779 23962 11774 23962 11778 23962 11780 23963 11777 23963 11774 23963 11773 23964 11780 23964 11774 23964 11781 23965 11775 23965 11774 23965 11779 23966 11781 23966 11774 23966 11782 23967 11783 23967 11778 23967 11784 23968 11778 23968 11783 23968 11777 23969 11782 23969 11778 23969 11784 23970 11779 23970 11778 23970 11785 23971 11786 23971 11783 23971 11787 23972 11783 23972 11786 23972 11782 23973 11785 23973 11783 23973 11788 23974 11784 23974 11783 23974 11787 23975 11788 23975 11783 23975 11789 23976 11790 23976 11786 23976 11791 23977 11786 23977 11790 23977 11785 23978 11789 23978 11786 23978 11791 23979 11787 23979 11786 23979 11792 23980 11793 23980 11790 23980 11794 23981 11790 23981 11793 23981 11789 23982 11792 23982 11790 23982 11794 23983 11791 23983 11790 23983 11795 23984 11796 23984 11793 23984 11797 23985 11793 23985 11796 23985 11792 23986 11795 23986 11793 23986 11797 23987 11794 23987 11793 23987 11798 23988 11799 23988 11796 23988 11797 23989 11796 23989 11799 23989 11795 23990 11798 23990 11796 23990 11800 23991 11801 23991 11799 23991 11802 23992 11799 23992 11801 23992 11798 23993 11800 23993 11799 23993 11802 23994 11797 23994 11799 23994 11803 23995 11804 23995 11801 23995 11805 23996 11801 23996 11804 23996 11806 23997 11803 23997 11801 23997 11800 23998 11806 23998 11801 23998 11805 23999 11802 23999 11801 23999 11807 24000 11808 24000 11804 24000 11805 24001 11804 24001 11808 24001 11803 24002 11807 24002 11804 24002 11809 24003 11810 24003 11808 24003 11811 24004 11808 24004 11810 24004 11807 24005 11809 24005 11808 24005 11811 24006 11805 24006 11808 24006 11812 24007 11813 24007 11810 24007 11811 24008 11810 24008 11813 24008 11809 24009 11812 24009 11810 24009 11814 24010 11815 24010 11813 24010 11816 24011 11813 24011 11815 24011 11812 24012 11814 24012 11813 24012 11816 24013 11811 24013 11813 24013 11814 24014 11817 24014 11815 24014 11816 24015 11815 24015 11817 24015 11818 24016 11819 24016 11817 24016 11820 24017 11817 24017 11819 24017 11814 24018 11818 24018 11817 24018 11820 24019 11816 24019 11817 24019 11818 24020 11821 24020 11819 24020 11820 24021 11819 24021 11821 24021 11822 24022 11823 24022 11821 24022 11824 24023 11821 24023 11823 24023 11818 24024 11822 24024 11821 24024 11824 24025 11820 24025 11821 24025 11825 24026 11826 24026 11823 24026 11824 24027 11823 24027 11826 24027 11822 24028 11825 24028 11823 24028 11827 24029 11828 24029 11826 24029 11829 24030 11826 24030 11828 24030 11825 24031 11827 24031 11826 24031 11829 24032 11824 24032 11826 24032 11830 24033 11831 24033 11828 24033 11829 24034 11828 24034 11831 24034 11827 24035 11830 24035 11828 24035 11832 24036 11833 24036 11831 24036 11834 24037 11831 24037 11833 24037 11830 24038 11832 24038 11831 24038 11834 24039 11829 24039 11831 24039 11703 24040 11701 24040 11833 24040 11702 24041 11833 24041 11701 24041 11832 24042 11703 24042 11833 24042 11702 24043 11834 24043 11833 24043 11835 24044 11703 24044 11832 24044 11835 24045 10962 24045 11703 24045 11836 24046 11832 24046 11830 24046 11836 24047 11835 24047 11832 24047 11836 24048 11830 24048 11827 24048 11837 24049 11827 24049 11825 24049 11837 24050 11836 24050 11827 24050 11837 24051 11825 24051 11822 24051 11838 24052 11822 24052 11818 24052 11838 24053 11837 24053 11822 24053 11839 24054 11818 24054 11814 24054 11839 24055 11838 24055 11818 24055 11840 24056 11814 24056 11812 24056 11840 24057 11839 24057 11814 24057 11840 24058 11812 24058 11809 24058 11841 24059 11809 24059 11807 24059 11841 24060 11840 24060 11809 24060 11841 24061 11807 24061 11803 24061 11842 24062 11803 24062 11806 24062 11842 24063 11841 24063 11803 24063 11842 24064 11806 24064 11800 24064 11843 24065 11800 24065 11798 24065 11843 24066 11842 24066 11800 24066 11844 24067 11798 24067 11795 24067 11844 24068 11843 24068 11798 24068 11845 24069 11795 24069 11792 24069 11845 24070 11844 24070 11795 24070 11846 24071 11792 24071 11789 24071 11846 24072 11845 24072 11792 24072 11847 24073 11789 24073 11785 24073 11847 24074 11846 24074 11789 24074 11848 24075 11785 24075 11782 24075 11848 24076 11847 24076 11785 24076 11849 24077 11782 24077 11777 24077 11849 24078 11848 24078 11782 24078 11850 24079 11777 24079 11780 24079 11850 24080 11849 24080 11777 24080 11851 24081 11780 24081 11773 24081 11851 24082 11850 24082 11780 24082 11851 24083 11773 24083 11776 24083 11852 24084 11776 24084 11771 24084 11852 24085 11851 24085 11776 24085 11853 24086 11771 24086 11767 24086 11853 24087 11852 24087 11771 24087 11853 24088 11767 24088 11764 24088 11854 24089 11764 24089 11762 24089 11854 24090 11853 24090 11764 24090 11855 24091 11762 24091 11759 24091 11855 24092 11854 24092 11762 24092 11855 24093 11759 24093 11756 24093 11856 24094 11756 24094 11754 24094 11856 24095 11855 24095 11756 24095 11857 24096 11754 24096 11751 24096 11857 24097 11856 24097 11754 24097 11857 24098 11751 24098 11748 24098 11858 24099 11748 24099 11746 24099 11858 24100 11857 24100 11748 24100 11859 24101 11746 24101 11743 24101 11859 24102 11858 24102 11746 24102 11859 24103 11743 24103 11741 24103 11860 24104 11741 24104 11738 24104 11860 24105 11859 24105 11741 24105 11860 24106 11738 24106 11735 24106 11861 24107 11735 24107 11733 24107 11861 24108 11860 24108 11735 24108 11862 24109 11733 24109 11730 24109 11862 24110 11861 24110 11733 24110 11862 24111 11730 24111 11728 24111 11863 24112 11728 24112 11725 24112 11863 24113 11862 24113 11728 24113 11864 24114 11725 24114 11722 24114 11864 24115 11863 24115 11725 24115 11864 24116 11722 24116 11719 24116 11865 24117 11719 24117 11717 24117 11865 24118 11864 24118 11719 24118 11866 24119 11717 24119 11714 24119 11866 24120 11865 24120 11717 24120 11866 24121 11714 24121 11712 24121 11867 24122 11712 24122 11704 24122 11867 24123 11866 24123 11712 24123 11868 24124 11704 24124 11708 24124 11867 24125 11704 24125 11868 24125 11869 24126 11708 24126 11709 24126 11592 24127 11708 24127 11869 24127 11868 24128 11708 24128 11592 24128 11870 24129 11869 24129 11709 24129 11564 24130 11870 24130 11709 24130 11564 24131 11709 24131 11561 24131 11871 24132 11561 24132 11709 24132 11872 24133 11871 24133 11709 24133 11707 24134 11872 24134 11709 24134 11873 24135 11869 24135 11870 24135 11592 24136 11869 24136 11873 24136 11874 24137 11875 24137 11876 24137 11877 24138 11876 24138 11875 24138 11878 24139 11874 24139 11876 24139 11879 24140 11878 24140 11876 24140 11880 24141 11879 24141 11876 24141 11880 24142 11876 24142 11877 24142 11873 24143 11870 24143 11875 24143 11565 24144 11875 24144 11870 24144 11874 24145 11873 24145 11875 24145 11877 24146 11875 24146 11881 24146 11565 24147 11881 24147 11875 24147 11565 24148 11870 24148 11564 24148 11589 24149 11873 24149 11874 24149 11592 24150 11873 24150 11589 24150 11586 24151 11874 24151 11878 24151 11589 24152 11874 24152 11586 24152 11882 24153 11878 24153 11879 24153 11883 24154 11878 24154 11882 24154 11586 24155 11878 24155 11883 24155 11884 24156 11885 24156 11459 24156 11460 24157 11459 24157 11885 24157 11458 24158 11884 24158 11459 24158 11884 24159 11886 24159 11885 24159 11887 24160 11885 24160 11886 24160 11460 24161 11885 24161 11468 24161 11887 24162 11468 24162 11885 24162 11888 24163 11889 24163 11886 24163 11887 24164 11886 24164 11889 24164 11884 24165 11888 24165 11886 24165 11890 24166 11891 24166 11889 24166 11892 24167 11889 24167 11891 24167 11888 24168 11890 24168 11889 24168 11887 24169 11889 24169 11892 24169 11893 24170 11894 24170 11891 24170 11895 24171 11891 24171 11894 24171 11890 24172 11893 24172 11891 24172 11892 24173 11891 24173 11895 24173 11896 24174 11897 24174 11894 24174 11898 24175 11894 24175 11897 24175 11893 24176 11896 24176 11894 24176 11895 24177 11894 24177 11898 24177 11899 24178 11900 24178 11897 24178 11898 24179 11897 24179 11900 24179 11896 24180 11899 24180 11897 24180 11901 24181 11902 24181 11900 24181 11903 24182 11900 24182 11902 24182 11899 24183 11901 24183 11900 24183 11898 24184 11900 24184 11903 24184 11901 24185 11904 24185 11902 24185 11905 24186 11902 24186 11904 24186 11903 24187 11902 24187 11905 24187 11906 24188 11907 24188 11904 24188 11905 24189 11904 24189 11907 24189 11901 24190 11906 24190 11904 24190 11908 24191 11909 24191 11907 24191 11910 24192 11907 24192 11909 24192 11906 24193 11908 24193 11907 24193 11905 24194 11907 24194 11910 24194 11911 24195 11912 24195 11909 24195 11910 24196 11909 24196 11912 24196 11908 24197 11911 24197 11909 24197 11913 24198 11914 24198 11912 24198 11915 24199 11912 24199 11914 24199 11911 24200 11913 24200 11912 24200 11910 24201 11912 24201 11915 24201 11916 24202 11917 24202 11914 24202 11915 24203 11914 24203 11917 24203 11913 24204 11916 24204 11914 24204 11916 24205 11918 24205 11917 24205 11915 24206 11917 24206 11918 24206 11919 24207 11920 24207 11918 24207 11921 24208 11918 24208 11920 24208 11916 24209 11919 24209 11918 24209 11915 24210 11918 24210 11921 24210 11922 24211 11923 24211 11920 24211 11921 24212 11920 24212 11923 24212 11919 24213 11922 24213 11920 24213 11924 24214 11925 24214 11923 24214 11921 24215 11923 24215 11925 24215 11922 24216 11924 24216 11923 24216 11926 24217 11927 24217 11925 24217 11928 24218 11925 24218 11927 24218 11924 24219 11926 24219 11925 24219 11921 24220 11925 24220 11928 24220 11929 24221 11930 24221 11927 24221 11928 24222 11927 24222 11930 24222 11926 24223 11929 24223 11927 24223 11929 24224 11931 24224 11930 24224 11928 24225 11930 24225 11931 24225 11932 24226 11933 24226 11931 24226 11928 24227 11931 24227 11933 24227 11929 24228 11932 24228 11931 24228 11934 24229 11935 24229 11933 24229 11936 24230 11933 24230 11935 24230 11932 24231 11934 24231 11933 24231 11928 24232 11933 24232 11936 24232 11937 24233 11938 24233 11935 24233 11936 24234 11935 24234 11938 24234 11934 24235 11937 24235 11935 24235 11939 24236 11940 24236 11938 24236 11936 24237 11938 24237 11940 24237 11937 24238 11939 24238 11938 24238 11941 24239 11942 24239 11940 24239 11936 24240 11940 24240 11942 24240 11939 24241 11941 24241 11940 24241 11941 24242 11943 24242 11942 24242 11880 24243 11942 24243 11943 24243 11936 24244 11942 24244 11880 24244 11944 24245 11945 24245 11943 24245 11880 24246 11943 24246 11945 24246 11941 24247 11944 24247 11943 24247 11882 24248 11879 24248 11945 24248 11880 24249 11945 24249 11879 24249 11944 24250 11882 24250 11945 24250 11883 24251 11882 24251 11944 24251 11946 24252 11944 24252 11941 24252 11946 24253 11883 24253 11944 24253 11946 24254 11941 24254 11939 24254 11946 24255 11939 24255 11937 24255 11946 24256 11937 24256 11934 24256 11947 24257 11934 24257 11932 24257 11947 24258 11946 24258 11934 24258 11947 24259 11932 24259 11929 24259 11947 24260 11929 24260 11926 24260 11948 24261 11926 24261 11924 24261 11948 24262 11947 24262 11926 24262 11948 24263 11924 24263 11922 24263 11948 24264 11922 24264 11919 24264 11949 24265 11919 24265 11916 24265 11949 24266 11948 24266 11919 24266 11949 24267 11916 24267 11913 24267 11950 24268 11913 24268 11911 24268 11950 24269 11949 24269 11913 24269 11951 24270 11911 24270 11908 24270 11951 24271 11950 24271 11911 24271 11951 24272 11908 24272 11906 24272 11952 24273 11906 24273 11901 24273 11952 24274 11951 24274 11906 24274 11953 24275 11901 24275 11899 24275 11953 24276 11952 24276 11901 24276 11954 24277 11899 24277 11896 24277 11954 24278 11953 24278 11899 24278 11955 24279 11896 24279 11893 24279 11955 24280 11954 24280 11896 24280 11955 24281 11893 24281 11890 24281 11956 24282 11890 24282 11888 24282 11956 24283 11955 24283 11890 24283 11957 24284 11888 24284 11884 24284 11957 24285 11956 24285 11888 24285 11462 24286 11884 24286 11458 24286 11957 24287 11884 24287 11462 24287 11462 24288 11458 24288 11461 24288 11685 24289 11462 24289 11457 24289 11957 24290 11462 24290 11685 24290 11687 24291 11685 24291 11686 24291 11688 24292 11685 24292 11687 24292 11958 24293 11685 24293 11688 24293 11958 24294 11957 24294 11685 24294 11958 24295 11688 24295 11689 24295 11456 24296 11450 24296 11463 24296 11959 24297 11463 24297 11464 24297 11959 24298 11456 24298 11463 24298 11959 24299 11464 24299 11465 24299 11959 24300 11465 24300 11466 24300 11887 24301 11466 24301 11467 24301 11887 24302 11959 24302 11466 24302 11887 24303 11467 24303 11468 24303 11881 24304 11566 24304 11567 24304 11565 24305 11566 24305 11881 24305 11960 24306 11567 24306 11568 24306 11960 24307 11881 24307 11567 24307 11961 24308 11568 24308 11569 24308 11961 24309 11960 24309 11568 24309 11962 24310 11569 24310 11570 24310 11962 24311 11961 24311 11569 24311 11963 24312 11570 24312 11571 24312 11963 24313 11962 24313 11570 24313 11964 24314 11571 24314 11572 24314 11964 24315 11963 24315 11571 24315 11965 24316 11572 24316 11573 24316 11965 24317 11964 24317 11572 24317 11966 24318 11573 24318 11574 24318 11966 24319 11965 24319 11573 24319 11967 24320 11574 24320 11575 24320 11967 24321 11966 24321 11574 24321 11968 24322 11575 24322 11576 24322 11968 24323 11967 24323 11575 24323 11969 24324 11576 24324 11577 24324 11969 24325 11968 24325 11576 24325 11970 24326 11577 24326 11456 24326 11970 24327 11969 24327 11577 24327 11959 24328 11970 24328 11456 24328 11877 24329 11881 24329 11960 24329 11880 24330 11960 24330 11961 24330 11880 24331 11877 24331 11960 24331 11936 24332 11961 24332 11962 24332 11936 24333 11880 24333 11961 24333 11928 24334 11962 24334 11963 24334 11928 24335 11936 24335 11962 24335 11921 24336 11963 24336 11964 24336 11921 24337 11928 24337 11963 24337 11915 24338 11964 24338 11965 24338 11915 24339 11921 24339 11964 24339 11910 24340 11965 24340 11966 24340 11910 24341 11915 24341 11965 24341 11905 24342 11966 24342 11967 24342 11905 24343 11910 24343 11966 24343 11903 24344 11967 24344 11968 24344 11903 24345 11905 24345 11967 24345 11898 24346 11968 24346 11969 24346 11898 24347 11903 24347 11968 24347 11895 24348 11969 24348 11970 24348 11895 24349 11898 24349 11969 24349 11892 24350 11970 24350 11959 24350 11892 24351 11895 24351 11970 24351 11887 24352 11892 24352 11959 24352 11971 24353 11562 24353 11561 24353 11871 24354 11971 24354 11561 24354 11972 24355 11562 24355 11971 24355 11563 24356 11562 24356 11972 24356 11972 24357 11971 24357 11871 24357 11711 24358 11871 24358 11872 24358 11972 24359 11871 24359 11711 24359 11711 24360 11872 24360 11707 24360 11973 24361 10965 24361 10969 24361 11973 24362 11702 24362 10965 24362 11469 24363 10969 24363 10968 24363 11469 24364 11973 24364 10969 24364 11972 24365 11711 24365 11716 24365 11974 24366 11716 24366 11721 24366 11974 24367 11972 24367 11716 24367 11975 24368 11721 24368 11724 24368 11975 24369 11974 24369 11721 24369 11976 24370 11724 24370 11727 24370 11976 24371 11975 24371 11724 24371 11977 24372 11727 24372 11732 24372 11977 24373 11976 24373 11727 24373 11978 24374 11732 24374 11737 24374 11978 24375 11977 24375 11732 24375 11979 24376 11737 24376 11740 24376 11979 24377 11978 24377 11737 24377 11980 24378 11740 24378 11745 24378 11980 24379 11979 24379 11740 24379 11981 24380 11745 24380 11750 24380 11981 24381 11980 24381 11745 24381 11982 24382 11750 24382 11753 24382 11982 24383 11981 24383 11750 24383 11983 24384 11753 24384 11758 24384 11983 24385 11982 24385 11753 24385 11984 24386 11758 24386 11761 24386 11984 24387 11983 24387 11758 24387 11985 24388 11761 24388 11766 24388 11985 24389 11984 24389 11761 24389 11986 24390 11766 24390 11770 24390 11986 24391 11985 24391 11766 24391 11987 24392 11770 24392 11775 24392 11987 24393 11986 24393 11770 24393 11988 24394 11775 24394 11781 24394 11988 24395 11987 24395 11775 24395 11989 24396 11781 24396 11779 24396 11989 24397 11988 24397 11781 24397 11990 24398 11779 24398 11784 24398 11990 24399 11989 24399 11779 24399 11991 24400 11784 24400 11788 24400 11991 24401 11990 24401 11784 24401 11992 24402 11788 24402 11787 24402 11992 24403 11991 24403 11788 24403 11993 24404 11787 24404 11791 24404 11993 24405 11992 24405 11787 24405 11994 24406 11791 24406 11794 24406 11994 24407 11993 24407 11791 24407 11995 24408 11794 24408 11797 24408 11995 24409 11994 24409 11794 24409 11996 24410 11797 24410 11802 24410 11996 24411 11995 24411 11797 24411 11997 24412 11802 24412 11805 24412 11997 24413 11996 24413 11802 24413 11998 24414 11805 24414 11811 24414 11998 24415 11997 24415 11805 24415 11999 24416 11811 24416 11816 24416 11999 24417 11998 24417 11811 24417 12000 24418 11816 24418 11820 24418 12000 24419 11999 24419 11816 24419 12001 24420 11820 24420 11824 24420 12001 24421 12000 24421 11820 24421 12002 24422 11824 24422 11829 24422 12002 24423 12001 24423 11824 24423 12003 24424 11829 24424 11834 24424 12003 24425 12002 24425 11829 24425 12004 24426 11834 24426 11702 24426 12004 24427 12003 24427 11834 24427 11973 24428 12004 24428 11702 24428 11563 24429 11972 24429 11974 24429 11551 24430 11974 24430 11975 24430 11551 24431 11563 24431 11974 24431 11559 24432 11975 24432 11976 24432 11559 24433 11551 24433 11975 24433 11560 24434 11976 24434 11977 24434 11560 24435 11559 24435 11976 24435 11544 24436 11977 24436 11978 24436 11544 24437 11560 24437 11977 24437 11548 24438 11978 24438 11979 24438 11548 24439 11544 24439 11978 24439 11536 24440 11979 24440 11980 24440 11536 24441 11548 24441 11979 24441 11540 24442 11980 24442 11981 24442 11540 24443 11536 24443 11980 24443 11541 24444 11981 24444 11982 24444 11541 24445 11540 24445 11981 24445 11530 24446 11982 24446 11983 24446 11530 24447 11541 24447 11982 24447 11533 24448 11983 24448 11984 24448 11533 24449 11530 24449 11983 24449 11526 24450 11984 24450 11985 24450 11526 24451 11533 24451 11984 24451 11521 24452 11985 24452 11986 24452 11521 24453 11526 24453 11985 24453 11523 24454 11986 24454 11987 24454 11523 24455 11521 24455 11986 24455 11517 24456 11987 24456 11988 24456 11517 24457 11523 24457 11987 24457 11518 24458 11988 24458 11989 24458 11518 24459 11517 24459 11988 24459 11514 24460 11989 24460 11990 24460 11514 24461 11518 24461 11989 24461 11511 24462 11990 24462 11991 24462 11511 24463 11514 24463 11990 24463 11508 24464 11991 24464 11992 24464 11508 24465 11511 24465 11991 24465 11505 24466 11992 24466 11993 24466 11505 24467 11508 24467 11992 24467 11503 24468 11993 24468 11994 24468 11503 24469 11505 24469 11993 24469 11500 24470 11994 24470 11995 24470 11500 24471 11503 24471 11994 24471 11498 24472 11995 24472 11996 24472 11498 24473 11500 24473 11995 24473 11495 24474 11996 24474 11997 24474 11495 24475 11498 24475 11996 24475 11493 24476 11997 24476 11998 24476 11493 24477 11495 24477 11997 24477 11489 24478 11998 24478 11999 24478 11489 24479 11493 24479 11998 24479 11487 24480 11999 24480 12000 24480 11487 24481 11489 24481 11999 24481 11484 24482 12000 24482 12001 24482 11484 24483 11487 24483 12000 24483 11479 24484 12001 24484 12002 24484 11479 24485 11484 24485 12001 24485 11476 24486 12002 24486 12003 24486 11476 24487 11479 24487 12002 24487 11472 24488 12003 24488 12004 24488 11472 24489 11476 24489 12003 24489 11470 24490 12004 24490 11973 24490 11470 24491 11472 24491 12004 24491 11469 24492 11470 24492 11973 24492 11587 24493 11883 24493 11946 24493 11586 24494 11883 24494 11587 24494 12005 24495 11946 24495 11947 24495 12006 24496 11587 24496 11946 24496 12006 24497 11946 24497 12005 24497 12007 24498 11947 24498 11948 24498 12005 24499 11947 24499 12007 24499 12008 24500 11948 24500 11949 24500 12007 24501 11948 24501 12008 24501 12009 24502 11949 24502 11950 24502 12008 24503 11949 24503 12009 24503 12010 24504 11950 24504 11951 24504 12009 24505 11950 24505 12010 24505 12011 24506 11951 24506 11952 24506 12010 24507 11951 24507 12011 24507 12012 24508 11952 24508 11953 24508 12011 24509 11952 24509 12012 24509 12013 24510 11953 24510 11954 24510 12012 24511 11953 24511 12013 24511 12014 24512 11954 24512 11955 24512 12013 24513 11954 24513 12014 24513 12015 24514 11955 24514 11956 24514 12014 24515 11955 24515 12015 24515 11958 24516 11956 24516 11957 24516 12015 24517 11956 24517 11958 24517 12015 24518 11689 24518 11690 24518 12015 24519 11958 24519 11689 24519 12014 24520 11690 24520 11691 24520 12014 24521 12015 24521 11690 24521 12013 24522 11691 24522 11692 24522 12013 24523 12014 24523 11691 24523 12012 24524 11692 24524 11693 24524 12012 24525 12013 24525 11692 24525 12011 24526 11693 24526 11694 24526 12011 24527 12012 24527 11693 24527 12010 24528 11694 24528 11695 24528 12010 24529 12011 24529 11694 24529 12009 24530 11695 24530 11696 24530 12009 24531 12010 24531 11695 24531 12008 24532 11696 24532 11697 24532 12008 24533 12009 24533 11696 24533 12007 24534 11697 24534 11698 24534 12007 24535 12008 24535 11697 24535 12005 24536 11698 24536 11699 24536 12005 24537 12007 24537 11698 24537 12006 24538 11699 24538 11584 24538 12006 24539 12005 24539 11699 24539 12006 24540 11584 24540 11581 24540 12006 24541 11581 24541 11587 24541 12016 24542 11868 24542 11592 24542 12017 24543 12016 24543 11592 24543 11593 24544 12017 24544 11592 24544 12017 24545 11868 24545 12016 24545 11867 24546 11868 24546 12017 24546 11591 24547 12017 24547 11593 24547 12018 24548 12017 24548 11591 24548 12018 24549 11867 24549 12017 24549 12018 24550 11591 24550 11594 24550 12019 24551 10960 24551 10959 24551 12019 24552 11683 24552 10960 24552 11835 24553 10959 24553 10962 24553 12019 24554 10959 24554 11835 24554 12020 24555 11594 24555 11598 24555 12018 24556 11594 24556 12020 24556 12021 24557 11598 24557 11601 24557 12020 24558 11598 24558 12021 24558 12022 24559 11601 24559 11604 24559 12021 24560 11601 24560 12022 24560 12023 24561 11604 24561 11608 24561 12022 24562 11604 24562 12023 24562 12024 24563 11608 24563 11611 24563 12023 24564 11608 24564 12024 24564 12025 24565 11611 24565 11614 24565 12024 24566 11611 24566 12025 24566 12026 24567 11614 24567 11617 24567 12025 24568 11614 24568 12026 24568 12027 24569 11617 24569 11621 24569 12026 24570 11617 24570 12027 24570 12028 24571 11621 24571 11624 24571 12027 24572 11621 24572 12028 24572 12029 24573 11624 24573 11626 24573 12028 24574 11624 24574 12029 24574 12030 24575 11626 24575 11631 24575 12029 24576 11626 24576 12030 24576 12031 24577 11631 24577 11636 24577 12030 24578 11631 24578 12031 24578 12032 24579 11636 24579 11637 24579 12031 24580 11636 24580 12032 24580 12033 24581 11637 24581 11635 24581 12032 24582 11637 24582 12033 24582 12034 24583 11635 24583 11641 24583 12033 24584 11635 24584 12034 24584 12035 24585 11641 24585 11640 24585 12034 24586 11641 24586 12035 24586 12036 24587 11640 24587 11645 24587 12035 24588 11640 24588 12036 24588 12037 24589 11645 24589 11644 24589 12036 24590 11645 24590 12037 24590 12038 24591 11644 24591 11648 24591 12037 24592 11644 24592 12038 24592 12039 24593 11648 24593 11652 24593 12038 24594 11648 24594 12039 24594 12040 24595 11652 24595 11651 24595 12039 24596 11652 24596 12040 24596 12041 24597 11651 24597 11654 24597 12040 24598 11651 24598 12041 24598 12042 24599 11654 24599 11658 24599 12041 24600 11654 24600 12042 24600 12043 24601 11658 24601 11660 24601 12042 24602 11658 24602 12043 24602 12044 24603 11660 24603 11664 24603 12043 24604 11660 24604 12044 24604 12045 24605 11664 24605 11667 24605 12044 24606 11664 24606 12045 24606 12046 24607 11667 24607 11669 24607 12045 24608 11667 24608 12046 24608 12047 24609 11669 24609 11672 24609 12046 24610 11669 24610 12047 24610 12048 24611 11672 24611 11675 24611 12047 24612 11672 24612 12048 24612 12049 24613 11675 24613 11679 24613 12048 24614 11675 24614 12049 24614 12050 24615 11679 24615 11681 24615 12049 24616 11679 24616 12050 24616 12019 24617 11681 24617 11683 24617 12050 24618 11681 24618 12019 24618 12050 24619 11835 24619 11836 24619 12050 24620 12019 24620 11835 24620 12049 24621 11836 24621 11837 24621 12049 24622 12050 24622 11836 24622 12048 24623 11837 24623 11838 24623 12048 24624 12049 24624 11837 24624 12047 24625 11838 24625 11839 24625 12047 24626 12048 24626 11838 24626 12046 24627 11839 24627 11840 24627 12046 24628 12047 24628 11839 24628 12045 24629 11840 24629 11841 24629 12045 24630 12046 24630 11840 24630 12044 24631 11841 24631 11842 24631 12044 24632 12045 24632 11841 24632 12043 24633 11842 24633 11843 24633 12043 24634 12044 24634 11842 24634 12042 24635 11843 24635 11844 24635 12042 24636 12043 24636 11843 24636 12041 24637 11844 24637 11845 24637 12041 24638 12042 24638 11844 24638 12040 24639 11845 24639 11846 24639 12040 24640 12041 24640 11845 24640 12039 24641 11846 24641 11847 24641 12039 24642 12040 24642 11846 24642 12038 24643 11847 24643 11848 24643 12038 24644 12039 24644 11847 24644 12037 24645 11848 24645 11849 24645 12037 24646 12038 24646 11848 24646 12036 24647 11849 24647 11850 24647 12036 24648 12037 24648 11849 24648 12035 24649 11850 24649 11851 24649 12035 24650 12036 24650 11850 24650 12034 24651 11851 24651 11852 24651 12034 24652 12035 24652 11851 24652 12033 24653 11852 24653 11853 24653 12033 24654 12034 24654 11852 24654 12032 24655 11853 24655 11854 24655 12032 24656 12033 24656 11853 24656 12031 24657 11854 24657 11855 24657 12031 24658 12032 24658 11854 24658 12030 24659 11855 24659 11856 24659 12030 24660 12031 24660 11855 24660 12029 24661 11856 24661 11857 24661 12029 24662 12030 24662 11856 24662 12028 24663 11857 24663 11858 24663 12028 24664 12029 24664 11857 24664 12027 24665 11858 24665 11859 24665 12027 24666 12028 24666 11858 24666 12026 24667 11859 24667 11860 24667 12026 24668 12027 24668 11859 24668 12025 24669 11860 24669 11861 24669 12025 24670 12026 24670 11860 24670 12024 24671 11861 24671 11862 24671 12024 24672 12025 24672 11861 24672 12023 24673 11862 24673 11863 24673 12023 24674 12024 24674 11862 24674 12022 24675 11863 24675 11864 24675 12022 24676 12023 24676 11863 24676 12021 24677 11864 24677 11865 24677 12021 24678 12022 24678 11864 24678 12020 24679 11865 24679 11866 24679 12020 24680 12021 24680 11865 24680 12018 24681 11866 24681 11867 24681 12018 24682 12020 24682 11866 24682 12051 24683 11101 24683 11100 24683 12052 24684 12051 24684 11100 24684 11406 24685 12052 24685 11100 24685 12053 24686 11101 24686 12051 24686 11095 24687 11101 24687 12053 24687 12054 24688 12051 24688 12052 24688 12053 24689 12051 24689 12054 24689 12054 24690 12052 24690 11406 24690 12055 24691 11406 24691 11407 24691 12054 24692 11406 24692 12055 24692 11408 24693 12056 24693 11409 24693 12055 24694 11407 24694 11240 24694 11240 24695 11407 24695 11234 24695 12057 24696 10989 24696 10987 24696 12057 24697 11230 24697 10989 24697 12058 24698 10987 24698 10991 24698 12058 24699 12057 24699 10987 24699 12059 24700 10991 24700 10990 24700 12059 24701 12058 24701 10991 24701 11011 24702 10990 24702 10992 24702 11011 24703 12059 24703 10990 24703 12055 24704 11240 24704 11239 24704 12060 24705 11239 24705 11243 24705 12060 24706 12055 24706 11239 24706 12061 24707 11243 24707 11245 24707 12061 24708 12060 24708 11243 24708 12062 24709 11245 24709 11250 24709 12062 24710 12061 24710 11245 24710 12063 24711 11250 24711 11253 24711 12063 24712 12062 24712 11250 24712 12064 24713 11253 24713 11256 24713 12064 24714 12063 24714 11253 24714 12065 24715 11256 24715 11261 24715 12065 24716 12064 24716 11256 24716 12066 24717 11261 24717 11266 24717 12066 24718 12065 24718 11261 24718 12067 24719 11266 24719 11271 24719 12067 24720 12066 24720 11266 24720 12068 24721 11271 24721 11274 24721 12068 24722 12067 24722 11271 24722 12069 24723 11274 24723 11279 24723 12069 24724 12068 24724 11274 24724 12070 24725 11279 24725 11283 24725 12070 24726 12069 24726 11279 24726 12071 24727 11283 24727 11288 24727 12071 24728 12070 24728 11283 24728 12072 24729 11288 24729 11293 24729 12072 24730 12071 24730 11288 24730 12073 24731 11293 24731 11296 24731 12073 24732 12072 24732 11293 24732 12074 24733 11296 24733 11300 24733 12074 24734 12073 24734 11296 24734 12075 24735 11300 24735 11302 24735 12075 24736 12074 24736 11300 24736 12076 24737 11302 24737 11305 24737 12076 24738 12075 24738 11302 24738 12077 24739 11305 24739 11309 24739 12077 24740 12076 24740 11305 24740 12078 24741 11309 24741 11313 24741 12078 24742 12077 24742 11309 24742 12079 24743 11313 24743 11312 24743 12079 24744 12078 24744 11313 24744 12080 24745 11312 24745 11318 24745 12080 24746 12079 24746 11312 24746 12081 24747 11318 24747 11321 24747 12081 24748 12080 24748 11318 24748 12082 24749 11321 24749 11326 24749 12082 24750 12081 24750 11321 24750 12083 24751 11326 24751 11330 24751 12083 24752 12082 24752 11326 24752 12084 24753 11330 24753 11335 24753 12084 24754 12083 24754 11330 24754 12085 24755 11335 24755 11341 24755 12085 24756 12084 24756 11335 24756 12086 24757 11341 24757 11346 24757 12086 24758 12085 24758 11341 24758 12087 24759 11346 24759 11351 24759 12087 24760 12086 24760 11346 24760 12088 24761 11351 24761 11356 24761 12088 24762 12087 24762 11351 24762 12089 24763 11356 24763 11361 24763 12089 24764 12088 24764 11356 24764 12090 24765 11361 24765 11367 24765 12090 24766 12089 24766 11361 24766 12091 24767 11367 24767 11230 24767 12091 24768 12090 24768 11367 24768 12057 24769 12091 24769 11230 24769 12054 24770 12055 24770 12060 24770 12092 24771 12060 24771 12061 24771 12092 24772 12054 24772 12060 24772 12093 24773 12061 24773 12062 24773 12093 24774 12092 24774 12061 24774 12094 24775 12062 24775 12063 24775 12094 24776 12093 24776 12062 24776 12095 24777 12063 24777 12064 24777 12095 24778 12094 24778 12063 24778 12096 24779 12064 24779 12065 24779 12096 24780 12095 24780 12064 24780 12097 24781 12065 24781 12066 24781 12097 24782 12096 24782 12065 24782 12098 24783 12066 24783 12067 24783 12098 24784 12097 24784 12066 24784 12099 24785 12067 24785 12068 24785 12099 24786 12098 24786 12067 24786 12100 24787 12068 24787 12069 24787 12100 24788 12099 24788 12068 24788 12101 24789 12069 24789 12070 24789 12101 24790 12100 24790 12069 24790 12102 24791 12070 24791 12071 24791 12102 24792 12101 24792 12070 24792 12103 24793 12071 24793 12072 24793 12103 24794 12102 24794 12071 24794 12104 24795 12072 24795 12073 24795 12104 24796 12103 24796 12072 24796 12105 24797 12073 24797 12074 24797 12105 24798 12104 24798 12073 24798 12106 24799 12074 24799 12075 24799 12106 24800 12105 24800 12074 24800 12107 24801 12075 24801 12076 24801 12107 24802 12106 24802 12075 24802 12108 24803 12076 24803 12077 24803 12108 24804 12107 24804 12076 24804 12109 24805 12077 24805 12078 24805 12109 24806 12108 24806 12077 24806 12110 24807 12078 24807 12079 24807 12110 24808 12109 24808 12078 24808 12111 24809 12079 24809 12080 24809 12111 24810 12110 24810 12079 24810 12112 24811 12080 24811 12081 24811 12112 24812 12111 24812 12080 24812 12113 24813 12081 24813 12082 24813 12113 24814 12112 24814 12081 24814 12114 24815 12082 24815 12083 24815 12114 24816 12113 24816 12082 24816 12115 24817 12083 24817 12084 24817 12115 24818 12114 24818 12083 24818 12116 24819 12084 24819 12085 24819 12116 24820 12115 24820 12084 24820 12117 24821 12085 24821 12086 24821 12117 24822 12116 24822 12085 24822 12118 24823 12086 24823 12087 24823 12118 24824 12117 24824 12086 24824 12119 24825 12087 24825 12088 24825 12119 24826 12118 24826 12087 24826 12120 24827 12088 24827 12089 24827 12120 24828 12119 24828 12088 24828 12121 24829 12089 24829 12090 24829 12121 24830 12120 24830 12089 24830 12122 24831 12090 24831 12091 24831 12122 24832 12121 24832 12090 24832 12123 24833 12091 24833 12057 24833 12123 24834 12122 24834 12091 24834 12058 24835 12123 24835 12057 24835 12053 24836 12054 24836 12092 24836 12124 24837 12092 24837 12093 24837 12124 24838 12053 24838 12092 24838 12125 24839 12093 24839 12094 24839 12125 24840 12124 24840 12093 24840 12126 24841 12094 24841 12095 24841 12126 24842 12125 24842 12094 24842 12127 24843 12095 24843 12096 24843 12127 24844 12126 24844 12095 24844 12128 24845 12096 24845 12097 24845 12128 24846 12127 24846 12096 24846 12129 24847 12097 24847 12098 24847 12129 24848 12128 24848 12097 24848 12130 24849 12098 24849 12099 24849 12130 24850 12129 24850 12098 24850 12131 24851 12099 24851 12100 24851 12131 24852 12130 24852 12099 24852 12132 24853 12100 24853 12101 24853 12132 24854 12131 24854 12100 24854 12133 24855 12101 24855 12102 24855 12133 24856 12132 24856 12101 24856 12134 24857 12102 24857 12103 24857 12134 24858 12133 24858 12102 24858 12135 24859 12103 24859 12104 24859 12135 24860 12134 24860 12103 24860 12136 24861 12104 24861 12105 24861 12136 24862 12135 24862 12104 24862 12137 24863 12105 24863 12106 24863 12137 24864 12136 24864 12105 24864 12138 24865 12106 24865 12107 24865 12138 24866 12137 24866 12106 24866 12139 24867 12107 24867 12108 24867 12139 24868 12138 24868 12107 24868 12140 24869 12108 24869 12109 24869 12140 24870 12139 24870 12108 24870 12141 24871 12109 24871 12110 24871 12141 24872 12140 24872 12109 24872 12142 24873 12110 24873 12111 24873 12142 24874 12141 24874 12110 24874 12143 24875 12111 24875 12112 24875 12143 24876 12142 24876 12111 24876 12144 24877 12112 24877 12113 24877 12144 24878 12143 24878 12112 24878 12145 24879 12113 24879 12114 24879 12145 24880 12144 24880 12113 24880 12146 24881 12114 24881 12115 24881 12146 24882 12145 24882 12114 24882 12147 24883 12115 24883 12116 24883 12147 24884 12146 24884 12115 24884 12148 24885 12116 24885 12117 24885 12148 24886 12147 24886 12116 24886 12149 24887 12117 24887 12118 24887 12149 24888 12148 24888 12117 24888 12150 24889 12118 24889 12119 24889 12150 24890 12149 24890 12118 24890 12151 24891 12119 24891 12120 24891 12151 24892 12150 24892 12119 24892 12152 24893 12120 24893 12121 24893 12152 24894 12151 24894 12120 24894 12153 24895 12121 24895 12122 24895 12153 24896 12152 24896 12121 24896 12154 24897 12122 24897 12123 24897 12154 24898 12153 24898 12122 24898 12155 24899 12123 24899 12058 24899 12155 24900 12154 24900 12123 24900 12059 24901 12155 24901 12058 24901 11095 24902 12053 24902 12124 24902 11091 24903 12124 24903 12125 24903 11091 24904 11095 24904 12124 24904 11092 24905 12125 24905 12126 24905 11092 24906 11091 24906 12125 24906 11086 24907 12126 24907 12127 24907 11086 24908 11092 24908 12126 24908 11088 24909 12127 24909 12128 24909 11088 24910 11086 24910 12127 24910 11081 24911 12128 24911 12129 24911 11081 24912 11088 24912 12128 24912 11083 24913 12129 24913 12130 24913 11083 24914 11081 24914 12129 24914 11076 24915 12130 24915 12131 24915 11076 24916 11083 24916 12130 24916 11077 24917 12131 24917 12132 24917 11077 24918 11076 24918 12131 24918 11078 24919 12132 24919 12133 24919 11078 24920 11077 24920 12132 24920 11071 24921 12133 24921 12134 24921 11071 24922 11078 24922 12133 24922 11073 24923 12134 24923 12135 24923 11073 24924 11071 24924 12134 24924 11067 24925 12135 24925 12136 24925 11067 24926 11073 24926 12135 24926 11063 24927 12136 24927 12137 24927 11063 24928 11067 24928 12136 24928 11064 24929 12137 24929 12138 24929 11064 24930 11063 24930 12137 24930 11060 24931 12138 24931 12139 24931 11060 24932 11064 24932 12138 24932 11056 24933 12139 24933 12140 24933 11056 24934 11060 24934 12139 24934 11057 24935 12140 24935 12141 24935 11057 24936 11056 24936 12140 24936 11053 24937 12141 24937 12142 24937 11053 24938 11057 24938 12141 24938 11051 24939 12142 24939 12143 24939 11051 24940 11053 24940 12142 24940 11048 24941 12143 24941 12144 24941 11048 24942 11051 24942 12143 24942 11046 24943 12144 24943 12145 24943 11046 24944 11048 24944 12144 24944 11043 24945 12145 24945 12146 24945 11043 24946 11046 24946 12145 24946 11040 24947 12146 24947 12147 24947 11040 24948 11043 24948 12146 24948 11036 24949 12147 24949 12148 24949 11036 24950 11040 24950 12147 24950 11034 24951 12148 24951 12149 24951 11034 24952 11036 24952 12148 24952 11030 24953 12149 24953 12150 24953 11030 24954 11034 24954 12149 24954 11027 24955 12150 24955 12151 24955 11027 24956 11030 24956 12150 24956 11024 24957 12151 24957 12152 24957 11024 24958 11027 24958 12151 24958 11019 24959 12152 24959 12153 24959 11019 24960 11024 24960 12152 24960 11016 24961 12153 24961 12154 24961 11016 24962 11019 24962 12153 24962 11013 24963 12154 24963 12155 24963 11013 24964 11016 24964 12154 24964 11012 24965 12155 24965 12059 24965 11012 24966 11013 24966 12155 24966 11011 24967 11012 24967 12059 24967 12156 24968 11404 24968 11190 24968 12056 24969 12157 24969 11409 24969 12158 24970 12156 24970 11190 24970 11191 24971 12158 24971 11190 24971 12056 24972 12159 24972 12157 24972 11402 24973 11404 24973 12156 24973 12160 24974 12156 24974 12158 24974 12160 24975 11402 24975 12156 24975 11192 24976 12158 24976 11191 24976 12161 24977 12158 24977 11192 24977 12160 24978 12158 24978 12161 24978 12162 24979 11192 24979 11189 24979 12161 24980 11192 24980 12162 24980 12162 24981 11189 24981 11193 24981 12163 24982 10980 24982 10981 24982 12163 24983 11115 24983 10980 24983 11410 24984 10981 24984 10979 24984 11410 24985 12163 24985 10981 24985 11408 24986 10979 24986 10984 24986 11408 24987 11410 24987 10979 24987 11369 24988 10984 24988 10983 24988 11408 24989 10984 24989 11369 24989 12056 24990 11369 24990 11370 24990 11408 24991 11369 24991 12056 24991 12159 24992 11370 24992 11371 24992 12056 24993 11370 24993 12159 24993 12164 24994 11371 24994 11372 24994 12159 24995 11371 24995 12164 24995 12165 24996 11372 24996 11373 24996 12164 24997 11372 24997 12165 24997 12166 24998 11373 24998 11374 24998 12165 24999 11373 24999 12166 24999 12167 25000 11374 25000 11375 25000 12166 25001 11374 25001 12167 25001 12168 25002 11375 25002 11376 25002 12167 25003 11375 25003 12168 25003 12169 25004 11376 25004 11377 25004 12168 25005 11376 25005 12169 25005 12170 25006 11377 25006 11378 25006 12169 25007 11377 25007 12170 25007 12171 25008 11378 25008 11379 25008 12170 25009 11378 25009 12171 25009 12172 25010 11379 25010 11380 25010 12171 25011 11379 25011 12172 25011 12173 25012 11380 25012 11381 25012 12172 25013 11380 25013 12173 25013 12174 25014 11381 25014 11382 25014 12173 25015 11381 25015 12174 25015 12175 25016 11382 25016 11383 25016 12174 25017 11382 25017 12175 25017 12176 25018 11383 25018 11384 25018 12175 25019 11383 25019 12176 25019 12177 25020 11384 25020 11385 25020 12176 25021 11384 25021 12177 25021 12178 25022 11385 25022 11386 25022 12177 25023 11385 25023 12178 25023 12179 25024 11386 25024 11387 25024 12178 25025 11386 25025 12179 25025 12180 25026 11387 25026 11388 25026 12179 25027 11387 25027 12180 25027 12181 25028 11388 25028 11389 25028 12180 25029 11388 25029 12181 25029 12182 25030 11389 25030 11390 25030 12181 25031 11389 25031 12182 25031 12183 25032 11390 25032 11391 25032 12182 25033 11390 25033 12183 25033 12184 25034 11391 25034 11392 25034 12183 25035 11391 25035 12184 25035 12185 25036 11392 25036 11393 25036 12184 25037 11392 25037 12185 25037 12186 25038 11393 25038 11394 25038 12185 25039 11393 25039 12186 25039 12187 25040 11394 25040 11395 25040 12186 25041 11394 25041 12187 25041 12188 25042 11395 25042 11396 25042 12187 25043 11395 25043 12188 25043 12189 25044 11396 25044 11397 25044 12188 25045 11396 25045 12189 25045 12190 25046 11397 25046 11398 25046 12189 25047 11397 25047 12190 25047 12191 25048 11398 25048 11399 25048 12190 25049 11398 25049 12191 25049 12192 25050 11399 25050 11401 25050 12191 25051 11399 25051 12192 25051 12193 25052 11401 25052 11400 25052 12192 25053 11401 25053 12193 25053 12160 25054 11400 25054 11402 25054 12193 25055 11400 25055 12160 25055 12194 25056 11193 25056 11194 25056 12194 25057 12162 25057 11193 25057 12195 25058 11194 25058 11196 25058 12195 25059 12194 25059 11194 25059 12196 25060 11196 25060 11195 25060 12196 25061 12195 25061 11196 25061 12197 25062 11195 25062 11197 25062 12197 25063 12196 25063 11195 25063 12198 25064 11197 25064 11199 25064 12198 25065 12197 25065 11197 25065 12199 25066 11199 25066 11200 25066 12199 25067 12198 25067 11199 25067 12200 25068 11200 25068 11198 25068 12200 25069 12199 25069 11200 25069 12201 25070 11198 25070 11202 25070 12201 25071 12200 25071 11198 25071 12202 25072 11202 25072 11201 25072 12202 25073 12201 25073 11202 25073 12203 25074 11201 25074 11204 25074 12203 25075 12202 25075 11201 25075 12204 25076 11204 25076 11205 25076 12204 25077 12203 25077 11204 25077 12205 25078 11205 25078 11203 25078 12205 25079 12204 25079 11205 25079 12206 25080 11203 25080 11207 25080 12206 25081 12205 25081 11203 25081 12207 25082 11207 25082 11206 25082 12207 25083 12206 25083 11207 25083 12208 25084 11206 25084 11209 25084 12208 25085 12207 25085 11206 25085 12209 25086 11209 25086 11208 25086 12209 25087 12208 25087 11209 25087 12210 25088 11208 25088 11210 25088 12210 25089 12209 25089 11208 25089 12211 25090 11210 25090 11212 25090 12211 25091 12210 25091 11210 25091 12212 25092 11212 25092 11211 25092 12212 25093 12211 25093 11212 25093 12213 25094 11211 25094 11213 25094 12213 25095 12212 25095 11211 25095 12214 25096 11213 25096 11214 25096 12214 25097 12213 25097 11213 25097 12215 25098 11214 25098 11215 25098 12215 25099 12214 25099 11214 25099 12216 25100 11215 25100 11216 25100 12216 25101 12215 25101 11215 25101 12217 25102 11216 25102 11217 25102 12217 25103 12216 25103 11216 25103 12218 25104 11217 25104 11218 25104 12218 25105 12217 25105 11217 25105 12219 25106 11218 25106 11219 25106 12219 25107 12218 25107 11218 25107 12220 25108 11219 25108 11220 25108 12220 25109 12219 25109 11219 25109 12221 25110 11220 25110 11221 25110 12221 25111 12220 25111 11220 25111 12222 25112 11221 25112 11222 25112 12222 25113 12221 25113 11221 25113 12223 25114 11222 25114 11223 25114 12223 25115 12222 25115 11222 25115 12224 25116 11223 25116 11224 25116 12224 25117 12223 25117 11223 25117 12225 25118 11224 25118 11225 25118 12225 25119 12224 25119 11224 25119 12163 25120 11225 25120 11115 25120 12163 25121 12225 25121 11225 25121 12226 25122 12162 25122 12194 25122 12226 25123 12161 25123 12162 25123 12227 25124 12194 25124 12195 25124 12227 25125 12226 25125 12194 25125 12228 25126 12195 25126 12196 25126 12228 25127 12227 25127 12195 25127 12229 25128 12196 25128 12197 25128 12229 25129 12228 25129 12196 25129 12230 25130 12197 25130 12198 25130 12230 25131 12229 25131 12197 25131 12231 25132 12198 25132 12199 25132 12231 25133 12230 25133 12198 25133 12232 25134 12199 25134 12200 25134 12232 25135 12231 25135 12199 25135 12233 25136 12200 25136 12201 25136 12233 25137 12232 25137 12200 25137 12234 25138 12201 25138 12202 25138 12234 25139 12233 25139 12201 25139 12235 25140 12202 25140 12203 25140 12235 25141 12234 25141 12202 25141 12236 25142 12203 25142 12204 25142 12236 25143 12235 25143 12203 25143 12237 25144 12204 25144 12205 25144 12237 25145 12236 25145 12204 25145 12238 25146 12205 25146 12206 25146 12238 25147 12237 25147 12205 25147 12239 25148 12206 25148 12207 25148 12239 25149 12238 25149 12206 25149 12240 25150 12207 25150 12208 25150 12240 25151 12239 25151 12207 25151 12241 25152 12208 25152 12209 25152 12241 25153 12240 25153 12208 25153 12242 25154 12209 25154 12210 25154 12242 25155 12241 25155 12209 25155 12243 25156 12210 25156 12211 25156 12243 25157 12242 25157 12210 25157 12244 25158 12211 25158 12212 25158 12244 25159 12243 25159 12211 25159 12245 25160 12212 25160 12213 25160 12245 25161 12244 25161 12212 25161 12246 25162 12213 25162 12214 25162 12246 25163 12245 25163 12213 25163 12247 25164 12214 25164 12215 25164 12247 25165 12246 25165 12214 25165 12248 25166 12215 25166 12216 25166 12248 25167 12247 25167 12215 25167 12249 25168 12216 25168 12217 25168 12249 25169 12248 25169 12216 25169 12250 25170 12217 25170 12218 25170 12250 25171 12249 25171 12217 25171 12251 25172 12218 25172 12219 25172 12251 25173 12250 25173 12218 25173 12252 25174 12219 25174 12220 25174 12252 25175 12251 25175 12219 25175 12253 25176 12220 25176 12221 25176 12253 25177 12252 25177 12220 25177 12254 25178 12221 25178 12222 25178 12254 25179 12253 25179 12221 25179 12255 25180 12222 25180 12223 25180 12255 25181 12254 25181 12222 25181 12157 25182 12223 25182 12224 25182 12157 25183 12255 25183 12223 25183 11409 25184 12224 25184 12225 25184 11409 25185 12157 25185 12224 25185 11410 25186 12225 25186 12163 25186 11410 25187 11409 25187 12225 25187 12193 25188 12161 25188 12226 25188 12193 25189 12160 25189 12161 25189 12192 25190 12226 25190 12227 25190 12192 25191 12193 25191 12226 25191 12191 25192 12227 25192 12228 25192 12191 25193 12192 25193 12227 25193 12190 25194 12228 25194 12229 25194 12190 25195 12191 25195 12228 25195 12189 25196 12229 25196 12230 25196 12189 25197 12190 25197 12229 25197 12188 25198 12230 25198 12231 25198 12188 25199 12189 25199 12230 25199 12187 25200 12231 25200 12232 25200 12187 25201 12188 25201 12231 25201 12186 25202 12232 25202 12233 25202 12186 25203 12187 25203 12232 25203 12185 25204 12233 25204 12234 25204 12185 25205 12186 25205 12233 25205 12184 25206 12234 25206 12235 25206 12184 25207 12185 25207 12234 25207 12183 25208 12235 25208 12236 25208 12183 25209 12184 25209 12235 25209 12182 25210 12236 25210 12237 25210 12182 25211 12183 25211 12236 25211 12181 25212 12237 25212 12238 25212 12181 25213 12182 25213 12237 25213 12180 25214 12238 25214 12239 25214 12180 25215 12181 25215 12238 25215 12179 25216 12239 25216 12240 25216 12179 25217 12180 25217 12239 25217 12178 25218 12240 25218 12241 25218 12178 25219 12179 25219 12240 25219 12177 25220 12241 25220 12242 25220 12177 25221 12178 25221 12241 25221 12176 25222 12242 25222 12243 25222 12176 25223 12177 25223 12242 25223 12175 25224 12243 25224 12244 25224 12175 25225 12176 25225 12243 25225 12174 25226 12244 25226 12245 25226 12174 25227 12175 25227 12244 25227 12173 25228 12245 25228 12246 25228 12173 25229 12174 25229 12245 25229 12172 25230 12246 25230 12247 25230 12172 25231 12173 25231 12246 25231 12171 25232 12247 25232 12248 25232 12171 25233 12172 25233 12247 25233 12170 25234 12248 25234 12249 25234 12170 25235 12171 25235 12248 25235 12169 25236 12249 25236 12250 25236 12169 25237 12170 25237 12249 25237 12168 25238 12250 25238 12251 25238 12168 25239 12169 25239 12250 25239 12167 25240 12251 25240 12252 25240 12167 25241 12168 25241 12251 25241 12166 25242 12252 25242 12253 25242 12166 25243 12167 25243 12252 25243 12165 25244 12253 25244 12254 25244 12165 25245 12166 25245 12253 25245 12164 25246 12254 25246 12255 25246 12164 25247 12165 25247 12254 25247 12159 25248 12255 25248 12157 25248 12159 25249 12164 25249 12255 25249 12256 25250 12257 25250 12258 25250 12258 25251 12259 25251 12260 25251 12260 25252 12261 25252 12262 25252 12262 25253 12263 25253 12264 25253 12264 25254 12265 25254 12266 25254 12266 25255 12267 25255 12268 25255 12268 25256 12269 25256 12270 25256 12270 25257 12271 25257 12272 25257 12272 25258 12273 25258 12275 25258 12274 25259 12275 25259 12277 25259 12276 25260 12277 25260 12279 25260 12278 25261 12279 25261 12281 25261 12280 25262 12281 25262 12283 25262 12282 25263 12283 25263 12285 25263 12284 25264 12285 25264 12287 25264 12286 25265 12287 25265 12289 25265 12288 25266 12289 25266 12291 25266 12290 25267 12291 25267 12293 25267 12292 25268 12293 25268 12295 25268 12294 25269 12295 25269 12297 25269 12296 25270 12297 25270 12299 25270 12298 25271 12299 25271 12301 25271 12300 25272 12301 25272 12303 25272 12302 25273 12303 25273 12305 25273 12304 25274 12305 25274 12306 25274 12306 25275 12307 25275 12308 25275 12308 25276 12309 25276 12310 25276 12310 25277 12311 25277 12312 25277 12312 25278 12313 25278 12314 25278 12314 25279 12315 25279 12316 25279 12259 25280 12257 25280 12319 25280 12318 25281 12319 25281 12256 25281 12316 25282 12317 25282 12318 25282 12306 25283 12302 25283 12304 25283 10803 25284 10805 25284 10804 25284 10805 25285 10807 25285 10806 25285 10807 25286 10809 25286 10808 25286 10809 25287 10811 25287 10810 25287 10811 25288 10813 25288 10812 25288 10813 25289 10815 25289 10814 25289 10815 25290 10817 25290 10816 25290 10817 25291 10819 25291 10818 25291 10820 25292 10818 25292 10821 25292 10822 25293 10820 25293 10823 25293 10824 25294 10822 25294 10825 25294 10826 25295 10824 25295 10827 25295 10828 25296 10826 25296 10829 25296 10830 25297 10828 25297 10831 25297 10832 25298 10830 25298 10833 25298 10834 25299 10832 25299 10835 25299 10836 25300 10834 25300 10837 25300 10838 25301 10836 25301 10839 25301 10840 25302 10838 25302 10841 25302 10842 25303 10840 25303 10843 25303 10844 25304 10842 25304 10845 25304 10846 25305 10844 25305 10847 25305 10848 25306 10846 25306 10849 25306 10850 25307 10848 25307 10851 25307 10851 25308 10853 25308 10852 25308 10853 25309 10855 25309 10854 25309 10855 25310 10857 25310 10856 25310 10857 25311 10859 25311 10858 25311 10859 25312 10861 25312 10860 25312 10861 25313 10863 25313 10862 25313 10807 25314 10805 25314 10809 25314 10805 25315 10865 25315 10809 25315 10865 25316 10863 25316 10861 25316 10809 25317 10865 25317 10811 25317 10865 25318 10861 25318 10859 25318 10865 25319 10859 25319 10857 25319 10865 25320 10857 25320 10855 25320 10847 25321 10851 25321 10849 25321 10845 25322 10851 25322 10847 25322 10843 25323 10851 25323 10845 25323 10839 25324 10843 25324 10841 25324 10839 25325 10851 25325 10843 25325 10835 25326 10839 25326 10837 25326 10831 25327 10835 25327 10833 25327 10827 25328 10831 25328 10829 25328 10825 25329 10831 25329 10827 25329 10813 25330 10811 25330 10815 25330 10815 25331 10811 25331 10817 25331 10823 25332 10831 25332 10825 25332 10819 25333 10823 25333 10821 25333 10819 25334 10831 25334 10823 25334 10819 25335 10835 25335 10831 25335 10819 25336 10839 25336 10835 25336 10811 25337 10865 25337 10817 25337 10865 25338 10855 25338 10817 25338 10855 25339 10853 25339 10817 25339 10853 25340 10851 25340 10817 25340 10851 25341 10839 25341 10817 25341 10839 25342 10819 25342 10817 25342 10865 25343 10803 25343 10802 25343 10863 25344 10865 25344 10864 25344 10852 25345 10846 25345 10848 25345 10854 25346 10846 25346 10852 25346 10854 25347 10844 25347 10846 25347 10856 25348 10844 25348 10854 25348 10856 25349 10842 25349 10844 25349 10858 25350 10842 25350 10856 25350 10858 25351 10840 25351 10842 25351 10860 25352 10840 25352 10858 25352 10860 25353 10838 25353 10840 25353 10862 25354 10838 25354 10860 25354 10862 25355 10836 25355 10838 25355 10864 25356 10836 25356 10862 25356 10864 25357 10834 25357 10836 25357 10864 25358 10802 25358 10834 25358 10802 25359 10804 25359 10834 25359 10834 25360 10804 25360 10832 25360 10804 25361 10806 25361 10832 25361 10832 25362 10806 25362 10830 25362 10806 25363 10808 25363 10830 25363 10830 25364 10808 25364 10828 25364 10808 25365 10810 25365 10828 25365 10828 25366 10810 25366 10826 25366 10810 25367 10812 25367 10826 25367 10826 25368 10812 25368 10824 25368 10812 25369 10814 25369 10824 25369 10824 25370 10814 25370 10822 25370 10814 25371 10816 25371 10822 25371 10816 25372 10818 25372 10820 25372 10822 25373 10816 25373 10820 25373 12257 25374 12259 25374 12258 25374 12259 25375 12261 25375 12260 25375 12261 25376 12263 25376 12262 25376 12263 25377 12265 25377 12264 25377 12265 25378 12267 25378 12266 25378 12267 25379 12269 25379 12268 25379 12269 25380 12271 25380 12270 25380 12271 25381 12273 25381 12272 25381 12274 25382 12272 25382 12275 25382 12276 25383 12274 25383 12277 25383 12278 25384 12276 25384 12279 25384 12280 25385 12278 25385 12281 25385 12282 25386 12280 25386 12283 25386 12284 25387 12282 25387 12285 25387 12286 25388 12284 25388 12287 25388 12288 25389 12286 25389 12289 25389 12290 25390 12288 25390 12291 25390 12292 25391 12290 25391 12293 25391 12294 25392 12292 25392 12295 25392 12296 25393 12294 25393 12297 25393 12298 25394 12296 25394 12299 25394 12300 25395 12298 25395 12301 25395 12302 25396 12300 25396 12303 25396 12304 25397 12302 25397 12305 25397 12305 25398 12307 25398 12306 25398 12307 25399 12309 25399 12308 25399 12309 25400 12311 25400 12310 25400 12311 25401 12313 25401 12312 25401 12313 25402 12315 25402 12314 25402 12315 25403 12317 25403 12316 25403 12261 25404 12259 25404 12263 25404 12259 25405 12319 25405 12263 25405 12319 25406 12317 25406 12315 25406 12263 25407 12319 25407 12265 25407 12319 25408 12315 25408 12313 25408 12319 25409 12313 25409 12311 25409 12319 25410 12311 25410 12309 25410 12301 25411 12305 25411 12303 25411 12299 25412 12305 25412 12301 25412 12297 25413 12305 25413 12299 25413 12293 25414 12297 25414 12295 25414 12293 25415 12305 25415 12297 25415 12289 25416 12293 25416 12291 25416 12285 25417 12289 25417 12287 25417 12281 25418 12285 25418 12283 25418 12279 25419 12285 25419 12281 25419 12273 25420 12277 25420 12275 25420 12273 25421 12279 25421 12277 25421 12273 25422 12285 25422 12279 25422 12273 25423 12289 25423 12285 25423 12273 25424 12293 25424 12289 25424 12267 25425 12271 25425 12269 25425 12267 25426 12265 25426 12271 25426 12265 25427 12319 25427 12271 25427 12319 25428 12309 25428 12271 25428 12309 25429 12307 25429 12271 25429 12307 25430 12305 25430 12271 25430 12305 25431 12293 25431 12271 25431 12293 25432 12273 25432 12271 25432 12319 25433 12257 25433 12256 25433 12317 25434 12319 25434 12318 25434 12306 25435 12300 25435 12302 25435 12308 25436 12300 25436 12306 25436 12308 25437 12298 25437 12300 25437 12310 25438 12298 25438 12308 25438 12310 25439 12296 25439 12298 25439 12312 25440 12296 25440 12310 25440 12312 25441 12294 25441 12296 25441 12314 25442 12294 25442 12312 25442 12314 25443 12292 25443 12294 25443 12316 25444 12292 25444 12314 25444 12316 25445 12290 25445 12292 25445 12318 25446 12290 25446 12316 25446 12318 25447 12288 25447 12290 25447 12318 25448 12256 25448 12288 25448 12256 25449 12258 25449 12288 25449 12288 25450 12258 25450 12286 25450 12258 25451 12260 25451 12286 25451 12286 25452 12260 25452 12284 25452 12260 25453 12262 25453 12284 25453 12284 25454 12262 25454 12282 25454 12262 25455 12264 25455 12282 25455 12282 25456 12264 25456 12280 25456 12264 25457 12266 25457 12280 25457 12280 25458 12266 25458 12278 25458 12266 25459 12268 25459 12278 25459 12278 25460 12268 25460 12276 25460 12268 25461 12270 25461 12276 25461 12270 25462 12272 25462 12274 25462 12276 25463 12270 25463 12274 25463</p> + </polylist> + <polylist material="mat_pc_embed-material" count="12"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>12321 25464 12320 25464 12325 25464 12325 25465 12326 25465 12321 25465 12326 25466 12327 25466 12323 25466 12320 25467 12323 25467 12327 25467 12320 25468 12321 25468 12322 25468 12327 25469 12326 25469 12324 25469 12320 25470 12324 25470 12325 25470 12326 25471 12322 25471 12321 25471 12322 25472 12326 25472 12323 25472 12324 25473 12320 25473 12327 25473 12323 25474 12320 25474 12322 25474 12326 25475 12325 25475 12324 25475</p> + </polylist> + <polylist material="mat_battery-material" count="12"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>12329 25476 12328 25476 12333 25476 12333 25477 12334 25477 12330 25477 12334 25478 12335 25478 12331 25478 12328 25479 12331 25479 12332 25479 12328 25480 12329 25480 12330 25480 12335 25481 12334 25481 12332 25481 12328 25482 12332 25482 12333 25482 12329 25483 12333 25483 12330 25483 12330 25484 12334 25484 12331 25484 12331 25485 12335 25485 12332 25485 12331 25486 12328 25486 12330 25486 12334 25487 12333 25487 12332 25487</p> + </polylist> + <polylist material="mat_marker-material" count="24"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>12345 25488 12344 25488 12349 25488 12349 25489 12350 25489 12345 25489 12350 25490 12351 25490 12347 25490 12344 25491 12347 25491 12351 25491 12344 25492 12345 25492 12346 25492 12351 25493 12350 25493 12348 25493 12353 25494 12352 25494 12357 25494 12357 25495 12358 25495 12354 25495 12358 25496 12359 25496 12355 25496 12352 25497 12355 25497 12356 25497 12352 25498 12353 25498 12354 25498 12359 25499 12358 25499 12356 25499 12344 25500 12348 25500 12349 25500 12350 25501 12346 25501 12345 25501 12346 25502 12350 25502 12347 25502 12348 25503 12344 25503 12351 25503 12347 25504 12344 25504 12346 25504 12350 25505 12349 25505 12348 25505 12352 25506 12356 25506 12357 25506 12353 25507 12357 25507 12354 25507 12354 25508 12358 25508 12355 25508 12355 25509 12359 25509 12356 25509 12355 25510 12352 25510 12354 25510 12358 25511 12357 25511 12356 25511</p> + </polylist> + <polylist material="mat_potes-material" count="6000"> + <input semantic="VERTEX" source="#Kinton-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Kinton-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>12360 25512 12361 25512 12363 25512 12900 25513 12872 25513 12838 25513 12900 25514 12903 25514 12873 25514 12361 25515 12365 25515 12362 25515 12837 25516 12838 25516 12873 25516 12366 25517 12367 25517 12362 25517 12360 25518 12363 25518 12367 25518 12371 25519 12368 25519 12367 25519 12379 25520 12368 25520 12378 25520 12379 25521 12394 25521 12368 25521 12371 25522 12395 25522 12378 25522 12394 25523 12413 25523 12368 25523 12371 25524 12390 25524 12395 25524 12415 25525 12397 25525 12368 25525 12368 25526 12436 25526 12415 25526 12413 25527 12435 25527 12436 25527 12435 25528 12494 25528 12462 25528 12435 25529 12529 25529 12494 25529 12397 25530 12380 25530 12368 25530 12435 25531 12462 25531 12436 25531 12372 25532 12368 25532 12380 25532 12377 25533 12391 25533 12371 25533 12564 25534 12602 25534 12563 25534 12564 25535 12605 25535 12602 25535 12563 25536 12527 25536 12564 25536 12372 25537 12414 25537 12399 25537 12372 25538 12396 25538 12414 25538 12493 25539 12527 25539 12563 25539 12526 25540 12525 25540 12493 25540 12372 25541 12381 25541 12396 25541 12529 25542 12435 25542 12525 25542 12605 25543 12653 25543 12602 25543 12383 25544 12417 25544 12438 25544 12383 25545 12398 25545 12417 25545 12372 25546 12399 25546 12398 25546 12377 25547 12409 25547 12430 25547 12430 25548 12411 25548 12377 25548 12411 25549 12391 25549 12377 25549 12377 25550 12388 25550 12409 25550 12630 25551 12659 25551 12657 25551 12653 25552 12605 25552 12630 25552 12383 25553 12438 25553 12441 25553 12723 25554 12689 25554 12659 25554 12690 25555 12657 25556 12689 25557 12691 25558 12756 25558 12723 25558 12383 25559 12441 25559 12418 25559 12756 25560 12754 25560 12723 25560 12401 25561 12418 25561 12440 25561 12463 25562 12477 25563 12440 25564 12401 25565 12383 25565 12418 25565 12407 25566 12458 25566 12409 25566 12407 25567 12456 25567 12458 25567 12409 25568 12388 25568 12407 25568 12825 25569 12826 25569 12791 25569 12826 25570 12863 25570 12824 25570 12401 25571 12468 25571 12443 25571 12754 25572 12756 25572 12792 25572 12792 25573 12825 25573 12790 25573 12401 25574 12477 25574 12468 25574 12891 25575 12824 25575 12925 25575 12973 25576 12974 25576 12925 25576 12863 25577 12971 25577 12973 25577 12419 25578 12466 25578 12496 25578 12419 25579 12443 25579 12466 25579 12419 25580 12401 25580 12443 25580 12427 25581 12487 25581 12455 25581 12520 25582 12559 25582 12523 25582 12427 25583 12523 25583 12487 25583 12407 25584 12427 25584 12455 25584 12427 25585 12483 25585 12520 25585 12980 25586 13017 25586 13038 25586 13037 25587 12976 25587 13038 25587 13037 25588 13016 25588 12976 25588 12976 25589 12930 25589 12980 25589 12419 25590 12513 25590 12530 25590 12898 25591 12934 25591 12930 25591 12934 25592 12980 25592 12930 25592 12868 25593 12831 25593 12897 25593 12499 25594 12470 25594 12530 25594 12973 25595 12971 25595 13015 25595 12971 25596 13016 25596 13015 25596 12419 25597 12496 25597 12513 25597 12975 25598 12981 25598 12935 25598 12831 25599 12929 25599 12975 25599 12935 25600 12897 25600 12831 25600 12445 25601 12469 25601 12503 25601 12532 25602 12534 25602 12503 25602 12419 25603 12470 25603 12469 25603 12557 25604 12518 25604 12556 25604 12557 25605 12585 25605 12518 25605 12556 25606 12584 25606 12557 25606 12482 25607 12519 25607 12518 25607 12518 25608 12558 25608 12483 25608 12483 25609 12427 25609 12453 25609 12725 25610 12693 25610 12694 25610 12726 25611 12758 25611 12725 25611 12471 25612 12566 25612 12567 25612 12795 25613 12830 25613 12829 25613 12725 25614 12758 25614 12795 25614 12829 25615 12831 25615 12796 25615 12471 25616 12505 25616 12533 25616 12533 25617 12566 25617 12471 25617 12693 25618 12661 25618 12662 25618 12537 25619 12471 25619 12567 25619 12894 25620 12928 25620 12929 25620 12831 25621 12829 25621 12894 25621 12445 25622 12534 25622 12504 25622 12471 25623 12445 25623 12504 25623 12580 25624 12581 25624 12552 25624 12482 25625 12481 25625 12552 25625 12481 25626 12549 25626 12576 25626 12481 25627 12576 25627 12580 25627 12482 25628 12453 25628 12481 25628 12597 25629 12577 25629 12515 25629 12507 25630 12606 25630 12597 25630 12577 25631 12548 25631 12515 25631 12507 25632 12568 25632 12593 25632 12593 25633 12606 25633 12507 25633 12593 25634 12632 25634 12606 25634 12507 25635 12536 25635 12568 25635 12661 25636 12606 25636 12662 25636 12471 25637 12537 25637 12507 25637 12481 25638 12515 25638 12549 25638 12515 25639 12547 25639 12538 25639 12575 25640 12569 25640 12538 25640 12594 25641 12569 25641 12608 25641 12575 25642 12641 25642 12633 25642 12607 25643 12569 25643 12633 25643 12575 25644 12651 25644 12652 25644 12648 25645 12641 25645 12652 25645 12575 25646 12647 25646 12651 25646 12649 25647 12650 25647 12648 25647 12652 25648 12649 25648 12648 25648 12575 25649 12624 25649 12647 25649 12607 25650 12634 25650 12569 25650 12634 25651 12608 25651 12569 25651 12635 25652 12663 25652 12594 25652 12774 25653 12739 25653 12773 25653 12739 25654 12738 25654 12751 25654 12683 25655 12749 25655 12713 25655 12706 25656 12719 25656 12750 25656 12750 25657 12751 25657 12738 25657 12624 25658 12713 25658 12717 25658 12717 25659 12714 25659 12624 25659 12714 25660 12715 25660 12624 25660 12624 25661 12683 25661 12713 25661 12609 25662 12594 25662 12636 25662 12706 25663 12685 25663 12686 25663 12718 25664 12719 25664 12706 25664 12624 25665 12715 25665 12684 25665 12594 25666 12665 25666 12636 25666 12594 25667 12672 25667 12665 25667 12594 25668 12663 25668 12672 25668 12685 25669 12648 25669 12650 25669 12624 25670 12684 25670 12646 25670 12845 25671 12881 25671 12880 25671 12845 25672 12844 25672 12881 25672 12878 25673 12879 25673 12880 25673 12748 25674 12785 25674 12786 25674 12783 25675 12683 25675 12786 25675 12748 25676 12784 25676 12785 25676 12882 25677 12879 25677 12878 25677 12748 25678 12823 25678 12784 25678 12775 25679 12774 25679 12813 25679 12811 25680 12812 25680 12775 25680 12683 25681 12788 25681 12749 25681 12844 25682 12845 25682 12812 25682 12683 25683 12783 25683 12788 25683 12638 25684 12609 25684 12667 25684 12609 25685 12664 25685 12696 25685 12698 25686 12667 25686 12696 25686 12999 25687 12998 25687 13025 25687 13026 25688 13027 25688 12999 25688 12822 25689 12889 25689 12859 25689 12822 25690 12888 25690 12889 25690 12996 25691 12995 25691 13024 25691 13024 25692 13025 25692 12998 25692 12822 25693 12859 25693 12861 25693 12861 25694 12858 25694 12822 25694 12857 25695 12748 25695 12858 25695 12995 25696 12996 25696 12951 25696 12951 25697 12906 25697 12997 25697 12748 25698 12857 25698 12862 25698 12882 25699 12905 25699 12949 25699 12949 25700 12906 25700 12882 25700 12823 25701 12748 25701 12862 25701 12668 25702 12638 25702 12699 25702 12759 25703 12731 25704 12728 25705 12638 25706 12697 25706 12728 25706 12731 25707 12699 25707 12638 25707 13093 25708 13092 25708 13091 25708 13100 25709 13101 25709 13093 25709 12914 25710 12886 25710 12967 25710 13096 25711 13095 25711 13093 25711 13093 25712 13101 25712 13102 25712 12886 25713 13013 25713 12967 25713 13098 25714 13103 25714 13100 25714 13090 25715 13099 25716 13098 25717 13098 25718 13091 25718 13080 25718 12966 25719 12822 25719 12917 25719 12920 25720 12921 25720 12919 25720 12822 25721 12915 25721 12920 25721 12916 25722 12917 25722 12919 25722 12822 25723 12886 25723 12915 25723 13080 25724 13079 25724 13062 25724 13062 25725 13077 25725 13090 25725 12822 25726 12966 25726 13012 25726 13061 25727 13046 25727 13060 25727 13077 25728 13062 25728 13061 25728 13046 25729 13047 25729 13060 25729 12969 25730 12922 25730 13012 25730 13028 25731 13027 25731 13047 25731 12888 25732 12822 25732 12922 25732 12701 25733 12668 25733 12732 25733 12799 25734 12764 25734 12761 25734 12764 25735 12732 25735 12668 25735 12668 25736 12730 25736 12761 25736 13056 25737 13069 25737 13054 25737 13067 25738 13068 25738 13069 25738 13033 25739 12886 25739 13004 25739 13040 25740 13053 25740 13055 25740 13053 25741 13054 25741 13055 25741 13010 25742 13011 25742 13009 25742 12899 25743 13006 25743 13010 25743 13007 25744 13004 25744 13009 25744 12899 25745 13005 25745 13006 25745 13004 25746 12886 25746 12899 25746 13076 25747 13088 25747 13089 25747 13095 25748 13070 25748 13076 25748 13070 25749 13075 25749 13076 25749 13095 25750 13097 25750 13070 25750 13095 25751 13096 25751 13097 25751 13013 25752 12886 25752 13034 25752 13068 25753 13067 25753 13070 25753 12886 25754 13033 25754 13034 25754 12733 25755 12701 25755 12768 25755 12701 25756 12763 25756 12801 25756 12833 25757 12810 25757 12801 25757 12810 25758 12768 25758 12701 25758 12990 25759 13021 25759 13020 25759 12989 25760 12944 25760 12990 25760 12899 25761 12988 25761 13019 25761 12940 25762 12941 25762 12944 25762 12899 25763 12835 25763 12937 25763 12835 25764 12942 25764 12943 25764 12835 25765 12902 25765 12942 25765 12902 25766 12941 25766 12942 25766 12944 25767 12989 25767 12940 25767 12939 25768 12938 25768 12835 25768 12938 25769 12937 25769 12835 25769 12835 25770 12943 25770 12939 25770 12765 25771 12877 25771 12871 25771 12871 25772 12902 25772 12835 25772 13040 25773 13041 25773 13021 25773 13005 25774 12899 25774 13019 25774 12765 25775 12843 25775 12877 25775 12765 25776 12806 25776 12843 25776 12871 25777 12835 25777 12765 25777 12733 25778 12807 25778 12806 25778 12836 25779 12802 25779 12835 25779 12836 25780 12870 25780 12802 25780 12903 25781 12874 25781 12873 25781 12839 25782 12803 25782 12837 25782 12839 25783 12840 25783 12766 25783 12766 25784 12840 25784 12876 25784 12876 25785 12842 25785 12766 25785 12840 25786 12904 25786 12875 25786 12840 25787 12948 25787 12947 25787 12947 25788 12904 25788 12840 25788 12945 25789 12946 25789 12904 25789 12991 25790 12946 25790 12994 25790 12992 25791 12993 25791 12991 25791 12994 25792 12992 25792 12991 25792 12840 25793 12987 25793 12986 25793 12840 25794 12985 25794 12987 25794 12986 25795 12948 25795 12840 25795 12840 25796 12913 25796 12984 25796 12842 25797 12804 25797 12766 25797 12734 25798 12766 25798 12805 25798 13058 25799 13059 25799 13057 25799 13043 25800 13042 25800 13057 25800 13032 25801 12913 25801 13003 25801 13073 25802 13057 25802 13074 25802 13073 25803 13058 25803 13057 25803 13071 25804 13072 25804 13073 25804 12913 25805 12958 25805 13003 25805 13044 25806 13022 25806 13023 25806 13042 25807 13043 25807 13045 25807 13018 25808 12913 25808 13032 25808 13087 25809 13072 25809 13085 25809 13072 25810 13071 25810 13085 25810 12962 25811 12964 25811 12849 25811 12963 25812 12961 25812 12849 25812 12849 25813 12959 25813 12960 25813 12958 25814 12913 25814 12849 25814 13022 25815 12991 25815 13023 25815 12984 25816 12913 25816 13018 25816 12734 25817 12841 25817 12869 25817 12808 25818 12767 25818 12734 25818 12734 25819 12805 25819 12841 25819 12767 25820 12700 25820 12734 25820 13063 25821 13064 25821 13065 25821 13050 25822 13049 25822 13066 25822 12911 25823 12849 25823 12912 25823 13030 25824 13029 25824 13051 25824 13048 25825 13049 25825 13050 25825 12849 25826 12848 25826 12885 25826 13081 25827 13065 25827 13083 25827 13081 25828 13082 25828 13065 25828 12957 25829 12849 25829 12911 25829 13001 25830 13029 25830 13031 25830 13029 25831 13030 25831 13031 25831 12855 25832 12856 25832 12782 25832 12782 25833 12851 25833 12853 25833 12852 25834 12850 25834 12782 25834 12782 25835 12820 25835 12851 25835 12848 25836 12849 25836 12782 25836 13081 25837 13086 25837 13094 25837 13081 25838 13087 25838 13086 25838 12959 25839 12849 25839 12957 25839 12700 25840 12769 25840 12770 25840 12700 25841 12767 25841 12809 25841 12735 25842 12669 25842 12700 25842 12954 25843 12956 25843 12952 25843 12909 25844 12908 25844 12952 25844 12952 25845 12953 25845 12954 25845 12712 25846 12781 25846 12817 25846 12883 25847 12846 25847 12907 25847 12907 25848 12908 25848 12910 25848 12712 25849 12745 25849 12780 25849 13001 25850 13002 25850 13000 25850 13000 25851 12954 25851 12953 25851 12782 25852 12817 25852 12818 25852 12819 25853 12820 25853 12782 25853 12782 25854 12712 25854 12817 25854 12669 25855 12762 25855 12798 25855 12736 25856 12702 25856 12669 25856 12669 25857 12735 25857 12762 25857 12702 25858 12637 25858 12669 25858 12740 25859 12709 25859 12776 25859 12776 25860 12777 25860 12779 25860 12645 25861 12678 25861 12711 25861 12814 25862 12847 25862 12815 25862 12815 25863 12816 25863 12777 25863 12814 25864 12846 25864 12847 25864 12645 25865 12711 25865 12742 25865 12883 25866 12884 25866 12846 25866 12712 25867 12743 25867 12746 25867 12744 25868 12745 25868 12712 25868 12712 25869 12645 25869 12743 25869 12637 25870 12703 25870 12704 25870 12637 25871 12702 25871 12729 25871 12639 25872 12610 25872 12637 25872 12600 25873 12677 25873 12680 25873 12707 25874 12709 25874 12708 25874 12675 25875 12674 25875 12707 25875 12600 25876 12644 25876 12677 25876 12643 25877 12642 25877 12676 25877 12674 25878 12675 25878 12676 25878 12600 25879 12616 25879 12644 25879 12620 25880 12619 25880 12643 25880 12740 25881 12741 25881 12709 25881 12600 25882 12682 25882 12679 25882 12600 25883 12680 25883 12681 25883 12600 25884 12681 25884 12682 25884 12678 25885 12645 25885 12600 25885 12595 25886 12639 25886 12670 25886 12671 25887 12640 25887 12595 25887 12640 25888 12612 25888 12595 25888 12595 25889 12610 25889 12639 25889 12570 25890 12613 25890 12574 25890 12614 25891 12618 25891 12574 25891 12570 25892 12611 25892 12613 25892 12623 25893 12622 25893 12574 25893 12574 25894 12618 25894 12619 25894 12622 25895 12617 25895 12574 25895 12619 25896 12620 25896 12621 25896 12619 25897 12621 25897 12623 25897 12616 25898 12600 25898 12574 25898 12595 25899 12612 25899 12570 25899 12546 25900 12539 25900 12574 25900 12546 25901 12516 25901 12539 25901 12596 25902 12506 25902 12579 25902 12596 25903 12615 25903 12506 25903 12516 25904 12550 25904 12579 25904 12599 25905 12572 25905 12506 25905 12506 25906 12615 25906 12599 25906 12615 25907 12631 25907 12599 25907 12572 25908 12540 25908 12506 25908 12673 25909 12660 25909 12631 25909 12472 25910 12506 25910 12540 25910 12480 25911 12551 25911 12550 25911 12472 25912 12571 25912 12598 25912 12692 25913 12705 25913 12724 25913 12737 25914 12771 25914 12724 25914 12866 25915 12865 25915 12797 25915 12797 25916 12867 25916 12866 25916 12832 25917 12794 25917 12797 25917 12794 25918 12771 25918 12737 25918 12573 25919 12472 25919 12598 25919 12472 25920 12573 25920 12542 25920 12542 25921 12509 25921 12472 25921 12472 25922 12541 25922 12571 25922 12660 25923 12673 25923 12692 25923 12933 25924 12927 25924 12867 25924 12895 25925 12866 25925 12867 25925 12444 25926 12508 25926 12543 25926 12472 25927 12509 25927 12444 25927 12554 25928 12583 25928 12480 25928 12517 25929 12555 25929 12480 25929 12578 25930 12551 25930 12480 25930 12582 25931 12578 25931 12480 25931 12480 25932 12454 25932 12517 25932 12936 25933 12982 25933 12977 25933 12977 25934 12972 25934 12983 25934 12978 25935 12931 25935 12977 25935 12977 25936 12983 25936 12936 25936 12444 25937 12512 25937 12473 25937 12867 25938 12896 25938 12933 25938 12978 25939 12979 25939 12896 25939 12896 25940 12931 25940 12978 25940 12444 25941 12544 25941 12545 25941 13014 25942 13036 25942 12972 25942 12924 25943 12970 25943 12972 25943 13035 25944 13039 25944 12972 25944 12420 25945 12511 25945 12531 25945 12420 25946 12473 25946 12510 25946 12420 25947 12444 25947 12473 25947 12560 25948 12588 25948 12589 25948 12484 25949 12587 25949 12560 25949 12586 25950 12561 25950 12601 25950 12517 25951 12484 25951 12561 25951 12517 25952 12454 25952 12484 25952 12426 25953 12485 25953 12454 25953 12893 25954 12926 25954 12864 25954 12864 25955 12828 25955 12892 25955 12923 25956 12890 25956 12864 25956 12864 25957 12827 25957 12828 25957 12420 25958 12501 25958 12514 25958 12793 25959 12828 25959 12757 25959 12757 25960 12720 25960 12793 25960 12476 25961 12446 25961 12420 25961 12924 25962 12890 25962 12970 25962 12420 25963 12500 25963 12501 25963 12720 25964 12721 25964 12752 25964 12753 25965 12789 25965 12720 25965 12400 25966 12475 25966 12497 25966 12400 25967 12446 25967 12474 25967 12498 25968 12478 25968 12400 25968 12400 25969 12420 25969 12446 25969 12426 25970 12457 25970 12489 25970 12485 25971 12426 25971 12522 25971 12408 25972 12428 25972 12426 25972 12490 25973 12521 25973 12426 25973 12604 25974 12592 25974 12629 25974 12655 25975 12604 25975 12656 25975 12400 25976 12449 25976 12421 25976 12687 25977 12655 25977 12688 25977 12720 25978 12687 25978 12721 25978 12400 25979 12478 25979 12449 25979 12592 25980 12627 25980 12654 25980 12382 25981 12421 25981 12447 25981 12464 25982 12451 25982 12382 25982 12382 25983 12400 25983 12421 25983 12389 25984 12410 25984 12433 25984 12460 25985 12428 25985 12389 25985 12428 25986 12408 25986 12389 25986 12603 25987 12592 25987 12591 25987 12528 25988 12562 25988 12565 25988 12373 25989 12403 25989 12416 25989 12461 25990 12524 25990 12528 25990 12461 25991 12492 25991 12524 25991 12404 25992 12373 25992 12416 25992 12461 25993 12425 25993 12491 25993 12385 25994 12373 25994 12404 25994 12592 25995 12603 25995 12626 25995 12382 25996 12451 25996 12450 25996 12422 25997 12402 25997 12382 25997 12373 25998 12382 25998 12403 25998 12376 25999 12431 25999 12432 25999 12376 26000 12412 26000 12431 26000 12376 26001 12393 26001 12412 26001 12410 26002 12389 26002 12376 26002 12370 26003 12369 26003 12374 26003 12375 26004 12386 26004 12370 26004 12369 26005 12387 26005 12374 26005 12369 26006 12406 26006 12387 26006 12386 26007 12392 26007 12370 26007 12424 26008 12452 26008 12425 26008 12406 26009 12369 26009 12425 26009 12369 26010 12405 26010 12423 26010 12452 26011 12479 26011 12425 26011 12479 26012 12491 26012 12425 26012 12369 26013 12384 26013 12405 26013 12369 26014 12423 26014 12424 26014 12373 26015 12385 26015 12369 26015 12376 26016 12370 26016 12392 26016 12370 26017 12366 26017 12365 26017 12361 26018 12360 26018 12364 26018 12365 26019 12364 26019 12369 26019 12368 26020 12372 26020 12369 26020 12372 26021 12383 26021 12373 26021 12383 26022 12401 26022 12382 26022 12401 26023 12419 26023 12400 26023 12419 26024 12445 26024 12420 26024 12445 26025 12471 26025 12444 26025 12471 26026 12507 26026 12506 26026 12506 26027 12507 26027 12538 26027 12538 26028 12569 26028 12570 26028 12569 26029 12594 26029 12595 26029 12594 26030 12609 26030 12610 26030 12609 26031 12638 26031 12637 26031 12638 26032 12668 26032 12669 26032 12668 26033 12701 26033 12700 26033 12700 26034 12701 26034 12734 26034 12734 26035 12733 26035 12765 26035 12765 26036 12802 26036 12803 26036 12802 26037 12838 26037 12837 26037 12903 26038 12900 26038 12870 26038 12874 26039 12870 26039 12836 26039 12836 26040 12835 26040 12839 26040 12840 26041 12835 26041 12899 26041 12913 26042 12899 26042 12886 26042 12849 26043 12886 26043 12822 26043 12782 26044 12822 26044 12748 26044 12712 26045 12748 26045 12683 26045 12645 26046 12683 26046 12624 26046 12600 26047 12624 26047 12575 26047 12575 26048 12547 26048 12546 26048 12546 26049 12547 26049 12515 26049 12515 26050 12481 26050 12480 26050 12481 26051 12453 26051 12454 26051 12453 26052 12427 26052 12426 26052 12427 26053 12407 26053 12408 26053 12407 26054 12388 26054 12389 26054 12388 26055 12377 26055 12376 26055 12377 26056 12371 26056 12376 26056 12370 26057 12371 26057 12366 26057 12379 26058 12378 26058 12375 26058 12577 26059 12597 26059 12579 26059 12606 26060 12615 26060 12597 26060 12386 26061 12375 26061 12395 26061 12374 26062 12387 26062 12394 26062 12387 26063 12406 26063 12413 26063 12425 26064 12461 26064 12435 26064 12413 26065 12406 26065 12425 26065 12461 26066 12493 26066 12435 26066 12461 26067 12528 26067 12527 26067 12528 26068 12565 26068 12564 26068 12592 26069 12604 26069 12605 26069 12564 26070 12565 26070 12592 26070 12604 26071 12630 26071 12605 26071 12655 26072 12659 26072 12630 26072 12687 26073 12691 26073 12659 26073 12720 26074 12757 26074 12756 26074 12757 26075 12792 26075 12756 26075 12691 26076 12687 26076 12720 26076 12757 26077 12827 26077 12825 26077 12827 26078 12864 26078 12826 26078 12864 26079 12890 26079 12863 26079 12924 26080 12972 26080 12971 26080 12972 26081 13016 26081 12971 26081 12863 26082 12890 26082 12924 26082 12972 26083 12977 26083 12976 26083 12977 26084 12931 26084 12930 26084 12931 26085 12896 26085 12930 26085 12867 26086 12797 26086 12831 26086 12868 26087 12896 26087 12867 26087 12797 26088 12796 26088 12831 26088 12796 26089 12797 26089 12737 26089 12737 26090 12705 26090 12725 26090 12673 26091 12615 26091 12693 26091 12693 26092 12705 26092 12673 26092 12615 26093 12606 26093 12661 26093 12579 26094 12550 26094 12577 26094 12551 26095 12576 26095 12550 26095 12551 26096 12578 26096 12576 26096 12549 26097 12548 26097 12550 26097 12578 26098 12582 26098 12576 26098 12583 26099 12581 26099 12580 26099 12554 26100 12552 26100 12583 26100 12555 26101 12553 26101 12552 26101 12517 26102 12519 26102 12482 26102 12517 26103 12561 26103 12519 26103 12553 26104 12555 26104 12517 26104 12586 26105 12556 26105 12519 26105 12601 26106 12584 26106 12586 26106 12589 26107 12557 26107 12601 26107 12588 26108 12585 26108 12589 26108 12560 26109 12518 26109 12588 26109 12587 26110 12558 26110 12560 26110 12484 26111 12485 26111 12520 26111 12558 26112 12587 26112 12483 26112 12522 26113 12559 26113 12485 26113 12521 26114 12523 26114 12522 26114 12490 26115 12487 26115 12523 26115 12490 26116 12489 26116 12488 26116 12489 26117 12457 26117 12455 26117 12455 26118 12457 26118 12428 26118 12460 26119 12486 26119 12456 26119 12434 26120 12458 26120 12486 26120 12433 26121 12459 26121 12458 26121 12410 26122 12429 26122 12409 26122 12410 26123 12432 26123 12429 26123 12409 26124 12459 26124 12433 26124 12432 26125 12431 26125 12430 26125 12431 26126 12412 26126 12411 26126 12393 26127 12390 26127 12391 26127 12393 26128 12392 26128 12390 26128 12391 26129 12411 26129 12412 26129 12392 26130 12386 26130 12395 26130 12423 26131 12415 26131 12436 26131 12599 26132 12593 26132 12572 26132 12536 26133 12540 26133 12568 26133 12462 26134 12452 26134 12424 26134 12415 26135 12423 26135 12405 26135 12397 26136 12405 26136 12384 26136 12404 26137 12416 26137 12396 26137 12404 26138 12396 26138 12385 26138 12416 26139 12414 26139 12396 26139 12416 26140 12399 26140 12414 26140 12380 26141 12384 26141 12381 26141 12396 26142 12381 26142 12385 26142 12403 26143 12398 26143 12399 26143 12403 26144 12402 26144 12398 26144 12422 26145 12417 26145 12398 26145 12417 26146 12422 26146 12450 26146 12451 26147 12418 26147 12441 26147 12438 26148 12437 26148 12441 26148 12437 26149 12450 26149 12451 26149 12464 26150 12439 26150 12418 26150 12439 26151 12464 26151 12448 26151 12447 26152 12463 26152 12440 26152 12449 26153 12478 26153 12421 26153 12498 26154 12467 26154 12468 26154 12477 26155 12447 26155 12421 26155 12477 26156 12463 26156 12447 26156 12443 26157 12467 26157 12498 26157 12497 26158 12465 26158 12443 26158 12465 26159 12497 26159 12475 26159 12466 26160 12475 26160 12474 26160 12514 26161 12499 26161 12513 26161 12513 26162 12446 26162 12514 26162 12501 26163 12470 26163 12499 26163 12496 26164 12474 26164 12446 26164 12500 26165 12469 26165 12470 26165 12496 26166 12495 26166 12474 26166 12500 26167 12531 26167 12469 26167 12469 26168 12531 26168 12511 26168 12502 26169 12511 26169 12510 26169 12473 26170 12512 26170 12510 26170 12532 26171 12503 26171 12512 26171 12544 26172 12543 26172 12534 26172 12532 26173 12545 26173 12544 26173 12543 26174 12535 26174 12534 26174 12508 26175 12504 26175 12535 26175 12509 26176 12533 26176 12508 26176 12509 26177 12542 26177 12533 26177 12505 26178 12504 26178 12508 26178 12567 26179 12573 26179 12598 26179 12566 26180 12542 26180 12567 26180 12541 26181 12537 26181 12571 26181 12566 26182 12533 26182 12542 26182 12540 26183 12536 26183 12541 26183 12593 26184 12599 26184 12632 26184 12692 26185 12724 26185 12662 26185 12724 26186 12726 26186 12694 26186 12662 26187 12632 26187 12692 26187 12632 26188 12631 26188 12660 26188 12771 26189 12794 26189 12726 26189 12794 26190 12795 26190 12758 26190 12726 26191 12724 26191 12771 26191 12832 26192 12865 26192 12794 26192 12865 26193 12866 26193 12830 26193 12866 26194 12895 26194 12829 26194 12829 26195 12830 26195 12866 26195 12927 26196 12928 26196 12894 26196 12933 26197 12975 26197 12929 26197 12933 26198 12932 26198 12975 26198 12928 26199 12927 26199 12933 26199 12979 26200 12981 26200 12975 26200 12978 26201 12982 26201 12981 26201 12982 26202 12935 26202 12981 26202 12936 26203 12934 26203 12898 26203 12982 26204 12936 26204 12935 26204 12983 26205 13017 26205 12980 26205 12934 26206 12936 26206 12983 26206 13039 26207 13035 26207 13017 26207 13035 26208 13036 26208 13017 26208 13036 26209 13052 26209 13038 26209 13037 26210 13052 26210 13014 26210 13014 26211 12970 26211 13037 26211 12970 26212 12923 26212 13015 26212 12974 26213 12973 26213 12926 26213 12893 26214 12925 26214 12926 26214 12892 26215 12891 26215 12925 26215 12793 26216 12789 26217 12828 26218 12791 26219 12824 26219 12789 26219 12892 26220 12828 26220 12824 26220 12790 26221 12791 26221 12753 26221 12752 26222 12755 26222 12790 26222 12721 26223 12688 26223 12754 26223 12755 26224 12752 26224 12721 26224 12688 26225 12722 26225 12754 26225 12629 26226 12690 26226 12689 26226 12723 26227 12722 26228 12689 25557 12722 26229 12688 26229 12656 26229 12628 26230 12658 26230 12657 26230 12628 26231 12654 26231 12658 26231 12657 26232 12690 26232 12629 26232 12627 26233 12625 26233 12653 26233 12627 26234 12626 26234 12625 26234 12653 26235 12658 26235 12654 26235 12603 26236 12591 26236 12602 26236 12591 26237 12590 26237 12602 26237 12625 26238 12626 26238 12603 26238 12562 26239 12524 26239 12563 26239 12524 26240 12526 26240 12563 26240 12590 26241 12591 26241 12562 26241 12491 26242 12479 26242 12529 26242 12479 26243 12494 26243 12529 26243 12525 26244 12526 26244 12492 26244 12526 26245 12524 26245 12492 26245 12494 26246 12479 26246 12462 26246 12607 26247 12633 26247 12614 26247 12613 26248 12634 26248 12607 26248 12901 26249 12877 26249 12875 26249 12875 26250 12871 26250 12901 26250 12876 26251 12877 26251 12842 26251 12618 26252 12614 26252 12633 26252 12611 26253 12635 26253 12608 26253 12613 26254 12611 26254 12608 26254 12672 26255 12663 26255 12635 26255 12635 26256 12611 26256 12612 26256 12612 26257 12640 26257 12672 26257 12640 26258 12671 26258 12665 26258 12670 26259 12666 26259 12665 26259 12636 26260 12666 26260 12670 26260 12695 26261 12664 26261 12636 26261 12639 26262 12704 26262 12695 26262 12703 26263 12696 26263 12695 26263 12698 26264 12696 26264 12703 26264 12727 26265 12697 26265 12667 26265 12702 26266 12736 26266 12727 26266 12729 26267 12702 26267 12667 26267 12760 26268 12728 26268 12736 26268 12798 26269 12759 26269 12728 26269 12731 26270 12759 26270 12798 26270 12761 26271 12730 26271 12699 26271 12762 26272 12735 26272 12699 26272 12735 26273 12770 26273 12761 26273 12799 26274 12761 26274 12770 26274 12809 26275 12764 26275 12769 26275 12808 26276 12800 26276 12763 26276 12764 26277 12767 26277 12763 26277 12764 26278 12809 26278 12767 26278 12801 26279 12800 26279 12808 26279 12833 26280 12801 26280 12834 26280 12810 26281 12833 26281 12869 26281 12805 26282 12804 26282 12768 26282 12841 26283 12805 26283 12810 26283 12804 26284 12806 26284 12807 26284 12842 26285 12843 26285 12804 26285 12944 26286 12902 26286 12904 26286 12871 26287 12875 26287 12904 26287 12946 26288 12990 26288 12904 26288 12991 26289 13022 26289 12990 26289 13022 26290 13053 26290 13040 26290 12990 26291 12946 26291 12991 26291 13044 26292 13056 26292 13053 26292 13070 26293 13067 26293 13043 26293 13056 26294 13044 26294 13043 26294 13059 26295 13075 26295 13070 26295 13058 26296 13076 26296 13059 26296 13073 26297 13088 26297 13076 26297 13072 26298 13089 26298 13073 26298 13087 26299 13095 26299 13072 26299 13081 26300 13093 26300 13087 26300 13083 26301 13092 26301 13081 26301 13064 26302 13063 26302 13091 26302 13092 26303 13083 26303 13091 26303 13063 26304 13079 26304 13080 26304 13049 26305 13062 26305 13063 26305 13048 26306 13061 26306 13049 26306 13029 26307 13046 26307 13048 26307 12999 26308 13028 26308 13046 26308 13046 26309 13029 26309 13001 26309 13001 26310 12953 26310 12999 26310 12953 26311 12952 26311 12998 26311 12952 26312 12996 26312 12998 26312 12908 26313 12951 26313 12996 26313 12907 26314 12906 26314 12951 26314 12846 26315 12882 26315 12907 26315 12846 26316 12814 26316 12879 26316 12777 26317 12812 26317 12845 26317 12845 26318 12879 26318 12814 26318 12775 26319 12812 26319 12777 26319 12739 26320 12774 26320 12775 26320 12709 26321 12707 26321 12739 26321 12775 26322 12776 26322 12709 26322 12707 26323 12674 26323 12738 26323 12674 26324 12706 26324 12738 26324 12642 26325 12685 26325 12706 26325 12619 26326 12641 26326 12648 26326 12619 26327 12618 26327 12641 26327 12648 26328 12685 26328 12642 26328 12652 26329 12651 26329 12622 26329 12943 26330 12942 26330 12948 26330 12942 26331 12947 26331 12948 26331 12994 26332 12945 26332 12942 26332 12945 26333 12947 26333 12942 26333 12617 26334 12622 26334 12651 26334 12621 26335 12649 26335 12652 26335 12620 26336 12643 26336 12686 26336 12676 26337 12718 26337 12686 26337 12649 26338 12621 26338 12620 26338 12675 26339 12708 26339 12719 26339 12708 26340 12750 26340 12719 26340 12718 26341 12676 26341 12675 26341 12708 26342 12710 26342 12750 26342 12710 26343 12741 26343 12751 26343 12740 26344 12813 26344 12772 26344 12772 26345 12741 26345 12740 26345 12740 26346 12779 26346 12813 26346 12778 26347 12844 26347 12813 26347 12778 26348 12816 26348 12844 26348 12813 26349 12779 26349 12778 26349 12815 26350 12847 26351 12816 26352 12884 26353 12880 26353 12847 26353 12950 26354 12905 26354 12878 26354 12883 26355 12910 26355 12950 26355 12880 26356 12884 26356 12878 26356 12909 26357 12949 26357 12910 26357 12955 26358 12997 26358 12909 26358 12956 26359 12995 26359 12955 26359 12956 26360 13024 26360 12995 26360 12956 26361 12954 26361 13024 26361 12954 26362 13000 26362 13025 26362 13060 26363 13047 26363 13027 26363 13002 26364 13031 26364 13078 26364 13026 26365 13000 26365 13002 26365 13030 26366 13090 26366 13077 26366 13030 26367 13051 26367 13090 26367 13078 26368 13031 26368 13077 26368 13050 26369 13098 26369 13051 26369 13066 26370 13103 26370 13050 26370 13082 26371 13094 26371 13101 26371 13100 26372 13103 26372 13065 26372 13094 26373 13102 26373 13101 26373 13103 26374 13066 26374 13065 26374 13086 26375 13085 26375 13096 26375 13102 26376 13094 26376 13086 26376 13085 26377 13097 26377 13096 26377 13071 26378 13069 26378 13084 26378 13084 26379 13097 26379 13071 26379 13071 26380 13074 26380 13069 26380 13074 26381 13057 26381 13054 26381 13042 26382 13045 26382 13057 26382 13045 26383 13055 26383 13054 26383 13023 26384 12993 26384 13021 26384 12993 26385 12992 26385 13020 26385 13041 26386 13055 26386 13045 26386 12941 26387 12940 26387 12989 26387 12992 26388 12994 26388 13020 26388 12987 26389 12939 26389 12986 26389 12985 26390 12938 26390 12987 26390 13018 26391 13032 26391 12988 26391 13003 26392 12958 26392 13019 26392 12937 26393 12984 26393 13018 26393 12958 26394 12961 26394 13019 26394 12938 26395 12985 26395 12984 26395 12961 26396 13006 26396 13005 26396 12963 26397 13008 26397 13006 26397 12965 26398 13010 26398 12963 26398 12964 26399 13011 26399 13010 26399 12962 26400 13009 26400 12964 26400 12960 26401 13007 26401 13009 26401 12957 26402 12911 26402 13034 26402 13033 26403 13004 26403 12957 26403 12912 26404 12967 26404 12911 26404 12912 26405 12968 26405 12967 26405 13004 26406 13007 26406 12957 26406 13007 26407 12960 26407 12959 26407 12885 26408 12848 26408 12968 26408 12848 26409 12850 26409 12968 26409 12850 26410 12852 26410 12914 26410 12852 26411 12918 26411 12915 26411 12854 26412 12920 26412 12852 26412 12856 26413 12921 26413 12854 26413 12855 26414 12919 26414 12856 26414 12853 26415 12916 26415 12855 26415 12889 26416 12969 26416 13012 26416 13012 26417 12966 26417 12889 26417 12889 26418 12888 26418 12922 26418 12917 26419 12916 26419 12889 26419 12916 26420 12853 26420 12889 26420 12820 26421 12859 26421 12889 26421 12820 26422 12819 26422 12859 26422 12819 26423 12821 26423 12861 26423 12821 26424 12818 26424 12858 26424 12781 26425 12780 26426 12817 26427 12780 26428 12887 26428 12857 26428 12857 26429 12858 26429 12817 26429 12784 26430 12823 26430 12887 26430 12887 26431 12780 26431 12784 26431 12745 26432 12744 26432 12785 26432 12744 26433 12747 26433 12787 26433 12747 26434 12746 26434 12786 26434 12742 26435 12711 26435 12743 26435 12711 26436 12713 26436 12788 26436 12783 26437 12746 26437 12743 26437 12678 26438 12716 26438 12713 26438 12783 26439 12786 26439 12746 26439 12678 26440 12679 26440 12716 26440 12679 26441 12682 26441 12717 26441 12682 26442 12681 26442 12714 26442 12677 26443 12644 26443 12680 26443 12616 26444 12647 26444 12684 26444 12715 26445 12681 26445 12680 26445 12616 26446 12617 26446 12647 26446 12644 26447 12616 26447 12684 26447 12715 26448 12714 26448 12681 26448 13104 26449 13105 26449 13107 26449 13644 26450 13616 26450 13614 26450 13644 26451 13647 26451 13617 26451 13105 26452 13109 26452 13110 26452 13581 26453 13582 26453 13616 26453 13110 26454 13111 26454 13106 26454 13104 26455 13107 26455 13108 26455 13115 26456 13112 26456 13108 26456 13123 26457 13112 26457 13115 26457 13123 26458 13138 26458 13112 26458 13115 26459 13139 26459 13122 26459 13138 26460 13157 26460 13112 26460 13115 26461 13134 26461 13139 26461 13159 26462 13141 26462 13112 26462 13112 26463 13180 26463 13159 26463 13157 26464 13179 26464 13112 26464 13179 26465 13238 26465 13206 26465 13179 26466 13273 26466 13238 26466 13141 26467 13124 26467 13112 26467 13179 26468 13206 26468 13180 26468 13116 26469 13112 26469 13125 26469 13121 26470 13135 26470 13134 26470 13308 26471 13346 26471 13334 26471 13308 26472 13349 26472 13346 26472 13307 26473 13271 26473 13308 26473 13116 26474 13158 26474 13143 26474 13116 26475 13140 26475 13158 26475 13237 26476 13271 26476 13270 26476 13270 26477 13269 26477 13237 26477 13116 26478 13125 26478 13140 26478 13273 26479 13179 26479 13237 26479 13349 26480 13397 26480 13369 26480 13127 26481 13161 26481 13181 26481 13127 26482 13142 26482 13161 26482 13116 26483 13143 26483 13127 26483 13121 26484 13153 26484 13173 26484 13174 26485 13155 26485 13121 26485 13155 26486 13135 26486 13121 26486 13121 26487 13132 26487 13153 26487 13374 26488 13403 26488 13402 26488 13397 26489 13349 26489 13402 26489 13127 26490 13182 26490 13185 26490 13467 26491 13433 26491 13435 26491 13434 26492 13401 26492 13403 26492 13435 26493 13500 26493 13467 26493 13127 26494 13185 26494 13186 26494 13500 26495 13498 26495 13466 26495 13145 26496 13162 26496 13183 26496 13207 26497 13221 26497 13145 26497 13145 26498 13127 26498 13162 26498 13151 26499 13202 26499 13203 26499 13151 26500 13200 26500 13230 26500 13153 26501 13132 26501 13151 26501 13569 26502 13570 26502 13534 26502 13570 26503 13607 26503 13535 26503 13145 26504 13212 26504 13211 26504 13498 26505 13500 26505 13499 26505 13536 26506 13569 26506 13499 26506 13145 26507 13221 26507 13212 26507 13635 26508 13568 26508 13607 26508 13717 26509 13718 26509 13607 26509 13607 26510 13715 26510 13717 26510 13163 26511 13210 26511 13239 26511 13163 26512 13187 26512 13209 26512 13163 26513 13145 26513 13187 26513 13171 26514 13231 26514 13232 26514 13264 26515 13303 26515 13171 26515 13171 26516 13267 26516 13231 26516 13151 26517 13171 26517 13200 26517 13171 26518 13227 26518 13264 26518 13724 26519 13761 26519 13720 26519 13781 26520 13720 26520 13796 26520 13781 26521 13760 26521 13720 26521 13720 26522 13674 26522 13724 26522 13163 26523 13257 26523 13274 26523 13642 26524 13678 26524 13612 26524 13678 26525 13724 26525 13674 26525 13612 26526 13575 26526 13642 26526 13243 26527 13214 26527 13163 26527 13717 26528 13715 26528 13759 26528 13715 26529 13760 26529 13781 26529 13163 26530 13240 26530 13257 26530 13719 26531 13725 26531 13575 26531 13575 26532 13673 26532 13719 26532 13679 26533 13641 26533 13575 26533 13189 26534 13213 26534 13246 26534 13276 26535 13278 26535 13189 26535 13163 26536 13214 26536 13189 26536 13301 26537 13262 26537 13263 26537 13301 26538 13329 26538 13262 26538 13300 26539 13328 26539 13301 26539 13226 26540 13263 26540 13227 26540 13262 26541 13302 26541 13227 26541 13227 26542 13171 26542 13226 26542 13469 26543 13437 26543 13470 26543 13470 26544 13502 26544 13469 26544 13215 26545 13310 26545 13311 26545 13539 26546 13574 26546 13540 26546 13469 26547 13502 26547 13540 26547 13573 26548 13575 26548 13540 26548 13215 26549 13249 26549 13277 26549 13277 26550 13310 26550 13215 26550 13437 26551 13405 26551 13438 26551 13281 26552 13215 26552 13311 26552 13638 26553 13672 26553 13575 26553 13575 26554 13573 26554 13638 26554 13189 26555 13278 26555 13279 26555 13215 26556 13189 26556 13249 26556 13324 26557 13325 26557 13225 26557 13226 26558 13225 26558 13297 26558 13225 26559 13293 26559 13320 26559 13225 26560 13320 26560 13324 26560 13226 26561 13197 26561 13225 26561 13341 26562 13321 26562 13251 26562 13251 26563 13350 26563 13341 26563 13321 26564 13292 26564 13259 26564 13251 26565 13312 26565 13337 26565 13337 26566 13350 26566 13251 26566 13337 26567 13376 26567 13350 26567 13251 26568 13280 26568 13312 26568 13405 26569 13350 26569 13376 26569 13215 26570 13281 26570 13280 26570 13225 26571 13259 26571 13292 26571 13259 26572 13291 26572 13251 26572 13319 26573 13313 26573 13291 26573 13338 26574 13313 26574 13379 26574 13319 26575 13385 26575 13377 26575 13351 26576 13313 26576 13319 26576 13319 26577 13395 26577 13396 26577 13392 26578 13385 26578 13319 26578 13319 26579 13391 26579 13395 26579 13393 26580 13394 26580 13392 26580 13396 26581 13393 26581 13392 26581 13319 26582 13368 26582 13390 26582 13351 26583 13378 26583 13313 26583 13378 26584 13352 26584 13313 26584 13379 26585 13407 26585 13338 26585 13518 26586 13483 26586 13516 26586 13483 26587 13482 26587 13516 26587 13427 26588 13493 26588 13457 26588 13450 26589 13463 26589 13482 26589 13494 26590 13495 26590 13482 26590 13368 26591 13457 26591 13460 26591 13461 26592 13458 26592 13368 26592 13458 26593 13459 26593 13368 26593 13368 26594 13427 26594 13457 26594 13353 26595 13338 26595 13408 26595 13450 26596 13429 26596 13462 26596 13462 26597 13463 26597 13450 26597 13368 26598 13459 26598 13428 26598 13338 26599 13409 26599 13410 26599 13338 26600 13416 26600 13409 26600 13338 26601 13407 26601 13416 26601 13429 26602 13392 26602 13430 26602 13368 26603 13428 26603 13390 26603 13589 26604 13625 26604 13624 26604 13589 26605 13588 26605 13625 26605 13622 26606 13623 26606 13589 26606 13492 26607 13529 26607 13531 26607 13527 26608 13427 26608 13492 26608 13492 26609 13528 26609 13529 26609 13626 26610 13623 26610 13649 26610 13492 26611 13567 26611 13528 26611 13519 26612 13518 26612 13517 26612 13555 26613 13556 26613 13557 26613 13427 26614 13532 26614 13493 26614 13588 26615 13589 26615 13555 26615 13427 26616 13527 26616 13532 26616 13382 26617 13353 26617 13441 26617 13353 26618 13408 26618 13439 26618 13442 26619 13411 26619 13353 26619 13743 26620 13742 26620 13770 26620 13770 26621 13771 26621 13772 26621 13566 26622 13633 26622 13603 26622 13566 26623 13632 26623 13633 26623 13740 26624 13739 26624 13742 26624 13768 26625 13769 26625 13742 26625 13566 26626 13603 26626 13604 26626 13605 26627 13602 26627 13566 26627 13601 26628 13492 26628 13566 26628 13739 26629 13740 26629 13741 26629 13695 26630 13650 26630 13693 26630 13492 26631 13601 26631 13631 26631 13626 26632 13649 26632 13694 26632 13693 26633 13650 26633 13626 26633 13567 26634 13492 26634 13606 26634 13412 26635 13382 26635 13474 26635 13503 26636 13475 26636 13382 26636 13382 26637 13441 26637 13471 26637 13475 26638 13443 26638 13382 26638 13837 26639 13836 26639 13844 26639 13844 26640 13845 26640 13837 26640 13658 26641 13630 26641 13712 26641 13840 26642 13839 26642 13846 26642 13837 26643 13845 26643 13846 26643 13630 26644 13757 26644 13711 26644 13842 26645 13847 26645 13835 26645 13834 26646 13843 26646 13824 26646 13842 26647 13835 26647 13824 26647 13710 26648 13566 26648 13661 26648 13664 26649 13665 26649 13566 26649 13566 26650 13659 26650 13662 26650 13660 26651 13661 26651 13566 26651 13566 26652 13630 26652 13658 26652 13824 26653 13823 26653 13834 26653 13806 26654 13821 26654 13834 26654 13566 26655 13710 26655 13756 26655 13805 26656 13790 26656 13822 26656 13821 26657 13806 26657 13822 26657 13790 26658 13791 26658 13804 26658 13713 26659 13666 26659 13566 26659 13772 26660 13771 26660 13790 26660 13632 26661 13566 26661 13666 26661 13445 26662 13412 26662 13507 26662 13543 26663 13508 26663 13412 26663 13508 26664 13476 26664 13412 26664 13412 26665 13474 26665 13505 26665 13800 26666 13813 26666 13797 26666 13811 26667 13812 26667 13800 26667 13777 26668 13630 26668 13748 26668 13784 26669 13797 26669 13785 26669 13797 26670 13798 26670 13799 26670 13754 26671 13755 26671 13643 26671 13643 26672 13750 26672 13752 26672 13751 26673 13748 26673 13643 26673 13643 26674 13749 26674 13750 26674 13748 26675 13630 26675 13643 26675 13820 26676 13832 26676 13833 26676 13839 26677 13814 26677 13833 26677 13814 26678 13819 26678 13820 26678 13839 26679 13841 26679 13828 26679 13839 26680 13840 26680 13841 26680 13757 26681 13630 26681 13778 26681 13812 26682 13811 26682 13828 26682 13630 26683 13777 26683 13778 26683 13477 26684 13445 26684 13551 26684 13445 26685 13507 26685 13544 26685 13577 26686 13554 26686 13445 26686 13554 26687 13512 26687 13445 26687 13734 26688 13765 26688 13764 26688 13733 26689 13688 26689 13764 26689 13643 26690 13732 26690 13763 26690 13684 26691 13685 26691 13646 26691 13643 26692 13579 26692 13732 26692 13579 26693 13686 26693 13687 26693 13579 26694 13646 26694 13686 26694 13646 26695 13685 26695 13686 26695 13688 26696 13733 26696 13684 26696 13683 26697 13682 26697 13579 26697 13682 26698 13681 26698 13579 26698 13579 26699 13687 26699 13683 26699 13509 26700 13621 26700 13645 26700 13615 26701 13646 26701 13579 26701 13784 26702 13785 26702 13734 26702 13749 26703 13643 26703 13763 26703 13509 26704 13587 26704 13621 26704 13509 26705 13550 26705 13587 26705 13615 26706 13579 26706 13509 26706 13477 26707 13551 26707 13509 26707 13580 26708 13546 26708 13509 26708 13580 26709 13614 26709 13582 26709 13647 26710 13618 26710 13581 26710 13583 26711 13547 26711 13618 26711 13583 26712 13584 26712 13547 26712 13510 26713 13584 26713 13619 26713 13620 26714 13586 26714 13510 26714 13584 26715 13648 26715 13619 26715 13584 26716 13692 26716 13691 26716 13691 26717 13648 26717 13584 26717 13689 26718 13690 26718 13691 26718 13735 26719 13690 26719 13689 26719 13736 26720 13737 26720 13735 26720 13738 26721 13736 26721 13735 26721 13584 26722 13731 26722 13730 26722 13584 26723 13729 26723 13731 26723 13730 26724 13692 26724 13584 26724 13584 26725 13657 26725 13729 26725 13586 26726 13548 26726 13510 26726 13478 26727 13510 26727 13548 26727 13802 26728 13803 26728 13787 26728 13787 26729 13786 26729 13801 26729 13776 26730 13657 26730 13747 26730 13817 26731 13801 26731 13815 26731 13817 26732 13802 26732 13801 26732 13815 26733 13816 26733 13817 26733 13657 26734 13702 26734 13747 26734 13788 26735 13766 26735 13789 26735 13786 26736 13787 26736 13788 26736 13762 26737 13657 26737 13776 26737 13831 26738 13816 26738 13830 26738 13816 26739 13815 26739 13829 26739 13706 26740 13708 26740 13709 26740 13707 26741 13705 26741 13709 26741 13593 26742 13703 26742 13706 26742 13702 26743 13657 26743 13705 26743 13766 26744 13735 26744 13737 26744 13728 26745 13657 26745 13762 26745 13478 26746 13585 26746 13578 26746 13552 26747 13511 26747 13578 26747 13478 26748 13549 26748 13585 26748 13511 26749 13444 26749 13478 26749 13807 26750 13808 26750 13810 26750 13794 26751 13793 26751 13807 26751 13655 26752 13593 26752 13629 26752 13774 26753 13773 26753 13792 26753 13792 26754 13793 26754 13795 26754 13593 26755 13592 26755 13629 26755 13825 26756 13809 26756 13808 26756 13825 26757 13826 26757 13809 26757 13701 26758 13593 26758 13655 26758 13745 26759 13773 26759 13746 26759 13773 26760 13774 26760 13775 26760 13599 26761 13600 26761 13598 26761 13526 26762 13595 26762 13599 26762 13596 26763 13594 26763 13598 26763 13526 26764 13564 26764 13595 26764 13592 26765 13593 26765 13594 26765 13825 26766 13830 26766 13826 26766 13825 26767 13831 26767 13830 26767 13703 26768 13593 26768 13701 26768 13444 26769 13513 26769 13479 26769 13444 26770 13511 26770 13513 26770 13479 26771 13413 26771 13444 26771 13698 26772 13700 26772 13699 26772 13653 26773 13652 26773 13699 26773 13696 26774 13697 26774 13698 26774 13456 26775 13525 26775 13561 26775 13627 26776 13590 26776 13654 26776 13651 26777 13652 26777 13653 26777 13456 26778 13489 26778 13525 26778 13745 26779 13746 26779 13697 26779 13744 26780 13698 26780 13697 26780 13526 26781 13561 26781 13565 26781 13563 26782 13564 26782 13565 26782 13526 26783 13456 26783 13561 26783 13413 26784 13506 26784 13504 26784 13480 26785 13446 26785 13504 26785 13413 26786 13479 26786 13506 26786 13446 26787 13381 26787 13413 26787 13484 26788 13453 26788 13523 26788 13520 26789 13521 26789 13522 26789 13389 26790 13422 26790 13455 26790 13558 26791 13591 26791 13521 26791 13559 26792 13560 26793 13522 26794 13558 26795 13590 26795 13591 26795 13389 26796 13455 26796 13487 26796 13627 26797 13628 26797 13591 26797 13456 26798 13487 26798 13491 26798 13488 26799 13489 26799 13491 26799 13456 26800 13389 26800 13487 26800 13381 26801 13447 26801 13383 26801 13381 26802 13446 26802 13447 26802 13383 26803 13354 26803 13381 26803 13344 26804 13421 26804 13424 26804 13451 26805 13453 26805 13454 26805 13419 26806 13418 26806 13452 26806 13344 26807 13388 26807 13421 26807 13387 26808 13386 26808 13418 26808 13418 26809 13419 26809 13420 26809 13344 26810 13360 26810 13388 26810 13364 26811 13363 26811 13386 26811 13484 26812 13485 26813 13454 26814 13344 26815 13426 26815 13422 26815 13344 26816 13424 26816 13425 26816 13344 26817 13425 26817 13426 26817 13422 26818 13389 26818 13344 26818 13339 26819 13383 26819 13415 26819 13415 26820 13384 26820 13339 26820 13384 26821 13356 26821 13339 26821 13339 26822 13354 26822 13383 26822 13314 26823 13357 26823 13358 26823 13358 26824 13362 26824 13318 26824 13314 26825 13355 26825 13357 26825 13367 26826 13366 26826 13318 26826 13318 26827 13362 26827 13367 26827 13366 26828 13361 26828 13318 26828 13363 26829 13364 26829 13365 26829 13363 26830 13365 26830 13367 26830 13360 26831 13344 26831 13361 26831 13339 26832 13356 26832 13355 26832 13290 26833 13283 26833 13314 26833 13290 26834 13260 26834 13250 26834 13340 26835 13250 26835 13260 26835 13340 26836 13359 26836 13250 26836 13260 26837 13294 26837 13323 26837 13343 26838 13316 26838 13250 26838 13250 26839 13359 26839 13343 26839 13359 26840 13375 26840 13343 26840 13316 26841 13284 26841 13250 26841 13417 26842 13404 26842 13359 26842 13216 26843 13250 26843 13285 26843 13224 26844 13295 26844 13260 26844 13216 26845 13315 26845 13342 26845 13436 26846 13449 26846 13481 26846 13481 26847 13515 26847 13468 26847 13610 26848 13609 26848 13576 26848 13541 26849 13611 26849 13610 26849 13576 26850 13538 26850 13481 26850 13538 26851 13515 26851 13481 26851 13317 26852 13216 26852 13342 26852 13216 26853 13317 26853 13286 26853 13286 26854 13253 26854 13216 26854 13216 26855 13285 26855 13315 26855 13404 26856 13417 26856 13449 26856 13677 26857 13671 26857 13639 26857 13639 26858 13610 26858 13611 26858 13188 26859 13252 26859 13288 26859 13216 26860 13253 26860 13252 26860 13298 26861 13327 26861 13326 26861 13261 26862 13299 26862 13298 26862 13322 26863 13295 26863 13224 26863 13326 26864 13322 26864 13224 26864 13224 26865 13198 26865 13261 26865 13680 26866 13726 26866 13722 26866 13721 26867 13716 26867 13783 26867 13722 26868 13675 26868 13721 26868 13721 26869 13727 26869 13680 26869 13188 26870 13256 26870 13217 26870 13611 26871 13640 26871 13676 26871 13722 26872 13723 26872 13676 26872 13640 26873 13675 26873 13722 26873 13188 26874 13288 26874 13256 26874 13758 26875 13780 26875 13779 26875 13668 26876 13714 26876 13758 26876 13779 26877 13783 26877 13716 26877 13164 26878 13255 26878 13244 26878 13164 26879 13217 26879 13255 26879 13164 26880 13188 26880 13217 26880 13304 26881 13332 26881 13305 26881 13228 26882 13331 26882 13304 26882 13330 26883 13305 26883 13333 26883 13261 26884 13228 26884 13304 26884 13261 26885 13198 26885 13228 26885 13170 26886 13229 26886 13228 26886 13637 26887 13670 26887 13667 26887 13608 26888 13572 26888 13637 26888 13667 26889 13634 26889 13608 26889 13608 26890 13571 26890 13572 26890 13164 26891 13245 26891 13258 26891 13537 26892 13572 26892 13571 26892 13501 26893 13464 26893 13533 26893 13220 26894 13190 26894 13258 26894 13668 26895 13634 26895 13667 26895 13164 26896 13244 26896 13245 26896 13464 26897 13465 26897 13497 26897 13497 26898 13533 26898 13464 26898 13144 26899 13219 26899 13242 26899 13144 26900 13190 26900 13219 26900 13242 26901 13222 26901 13144 26901 13144 26902 13164 26902 13190 26902 13170 26903 13201 26903 13234 26903 13229 26904 13170 26904 13265 26904 13152 26905 13172 26905 13201 26905 13234 26906 13265 26906 13170 26906 13348 26907 13336 26907 13372 26907 13399 26908 13348 26908 13373 26908 13144 26909 13193 26909 13165 26909 13431 26910 13399 26910 13400 26910 13464 26911 13431 26911 13432 26911 13144 26912 13222 26912 13193 26912 13336 26913 13371 26913 13372 26913 13126 26914 13165 26914 13192 26914 13208 26915 13195 26916 13192 26917 13126 26918 13144 26918 13165 26918 13133 26919 13154 26919 13178 26919 13204 26920 13172 26921 13178 26922 13172 26923 13152 26923 13133 26923 13347 26924 13336 26924 13309 26924 13272 26925 13306 26925 13335 26925 13117 26926 13147 26926 13160 26926 13205 26927 13268 26927 13306 26927 13205 26928 13236 26928 13268 26928 13148 26929 13117 26929 13160 26929 13205 26930 13169 26930 13236 26930 13129 26931 13117 26931 13148 26931 13336 26932 13347 26932 13371 26932 13126 26933 13195 26933 13166 26933 13166 26934 13146 26934 13126 26934 13117 26935 13126 26935 13146 26935 13120 26936 13175 26936 13154 26936 13120 26937 13156 26937 13175 26937 13120 26938 13137 26938 13156 26938 13154 26939 13133 26939 13120 26939 13114 26940 13113 26940 13119 26940 13119 26941 13130 26941 13114 26941 13113 26942 13131 26942 13118 26942 13113 26943 13150 26943 13131 26943 13130 26944 13136 26944 13114 26944 13168 26945 13196 26945 13169 26945 13150 26946 13113 26946 13168 26946 13113 26947 13149 26947 13167 26947 13196 26948 13223 26948 13169 26948 13223 26949 13235 26949 13169 26949 13113 26950 13128 26950 13149 26950 13113 26951 13167 26951 13168 26951 13117 26952 13129 26952 13128 26952 13120 26953 13114 26953 13137 26953 13114 26954 13110 26954 13113 26954 13105 26955 13104 26955 13109 26955 13109 26956 13108 26956 13113 26956 13112 26957 13116 26957 13117 26957 13116 26958 13127 26958 13126 26958 13127 26959 13145 26959 13144 26959 13145 26960 13163 26960 13144 26960 13163 26961 13189 26961 13188 26961 13189 26962 13215 26962 13216 26962 13215 26963 13251 26963 13250 26963 13250 26964 13251 26964 13283 26964 13282 26965 13313 26965 13314 26965 13313 26966 13338 26966 13339 26966 13338 26967 13353 26967 13354 26967 13353 26968 13382 26968 13381 26968 13382 26969 13412 26969 13413 26969 13412 26970 13445 26970 13444 26970 13444 26971 13445 26971 13477 26971 13478 26972 13477 26972 13509 26972 13509 26973 13546 26973 13547 26973 13546 26974 13582 26974 13581 26974 13647 26975 13644 26975 13618 26975 13618 26976 13614 26976 13580 26976 13580 26977 13579 26977 13584 26977 13584 26978 13579 26978 13643 26978 13657 26979 13643 26979 13630 26979 13593 26980 13630 26980 13566 26980 13526 26981 13566 26981 13456 26981 13456 26982 13492 26982 13389 26982 13389 26983 13427 26983 13344 26983 13344 26984 13368 26984 13318 26984 13319 26985 13291 26985 13318 26985 13290 26986 13291 26986 13260 26986 13259 26987 13225 26987 13260 26987 13225 26988 13197 26988 13198 26988 13197 26989 13171 26989 13198 26989 13171 26990 13151 26990 13170 26990 13151 26991 13132 26991 13133 26991 13132 26992 13121 26992 13120 26992 13121 26993 13115 26993 13120 26993 13114 26994 13115 26994 13110 26994 13123 26995 13122 26995 13119 26995 13321 26996 13341 26996 13323 26996 13350 26997 13359 26997 13341 26997 13130 26998 13119 26998 13122 26998 13118 26999 13131 26999 13123 26999 13131 27000 13150 27000 13157 27000 13169 27001 13205 27001 13179 27001 13157 27002 13150 27002 13169 27002 13205 27003 13237 27003 13179 27003 13205 27004 13272 27004 13271 27004 13272 27005 13309 27005 13308 27005 13336 27006 13348 27006 13349 27006 13308 27007 13309 27007 13336 27007 13348 27008 13374 27008 13349 27008 13399 27009 13403 27009 13374 27009 13431 27010 13435 27010 13399 27010 13464 27011 13501 27011 13500 27011 13501 27012 13536 27012 13500 27012 13435 27013 13431 27013 13464 27013 13501 27014 13571 27014 13536 27014 13571 27015 13608 27015 13570 27015 13608 27016 13634 27016 13570 27016 13668 27017 13716 27017 13607 27017 13716 27018 13760 27018 13715 27018 13607 27019 13634 27019 13668 27019 13716 27020 13721 27020 13760 27020 13721 27021 13675 27021 13720 27021 13675 27022 13640 27022 13674 27022 13611 27023 13541 27023 13612 27023 13612 27024 13640 27024 13611 27024 13541 27025 13540 27025 13575 27025 13540 27026 13541 27026 13469 27026 13481 27027 13449 27027 13469 27027 13417 27028 13359 27028 13437 27028 13437 27029 13449 27029 13417 27029 13359 27030 13350 27030 13405 27030 13323 27031 13294 27031 13321 27031 13295 27032 13320 27032 13294 27032 13295 27033 13322 27033 13320 27033 13293 27034 13292 27034 13294 27034 13322 27035 13326 27035 13324 27035 13327 27036 13325 27036 13324 27036 13298 27037 13296 27037 13325 27037 13299 27038 13297 27038 13296 27038 13261 27039 13263 27039 13297 27039 13261 27040 13305 27040 13263 27040 13297 27041 13299 27041 13261 27041 13330 27042 13300 27042 13263 27042 13345 27043 13328 27043 13300 27043 13333 27044 13301 27044 13345 27044 13332 27045 13329 27045 13301 27045 13304 27046 13262 27046 13332 27046 13331 27047 13302 27047 13262 27047 13228 27048 13229 27048 13227 27048 13302 27049 13331 27049 13227 27049 13266 27050 13303 27050 13264 27050 13265 27051 13267 27051 13266 27051 13234 27052 13231 27052 13267 27052 13234 27053 13233 27053 13232 27053 13233 27054 13201 27054 13232 27054 13199 27055 13201 27055 13172 27055 13204 27056 13230 27056 13172 27056 13178 27057 13202 27057 13230 27057 13177 27058 13203 27058 13202 27058 13154 27059 13173 27059 13153 27059 13154 27060 13176 27060 13173 27060 13153 27061 13203 27061 13177 27061 13176 27062 13175 27062 13174 27062 13175 27063 13156 27063 13155 27063 13137 27064 13134 27064 13135 27064 13137 27065 13136 27065 13134 27065 13135 27066 13155 27066 13156 27066 13136 27067 13130 27067 13139 27067 13167 27068 13159 27068 13180 27068 13343 27069 13337 27069 13316 27069 13280 27070 13284 27070 13312 27070 13206 27071 13196 27071 13168 27071 13159 27072 13167 27072 13141 27072 13141 27073 13149 27073 13128 27073 13148 27074 13160 27074 13140 27074 13148 27075 13140 27075 13129 27075 13160 27076 13158 27076 13140 27076 13160 27077 13143 27077 13158 27077 13124 27078 13128 27078 13125 27078 13140 27079 13125 27079 13129 27079 13147 27080 13142 27080 13143 27080 13147 27081 13146 27081 13142 27081 13166 27082 13161 27082 13146 27082 13161 27083 13166 27083 13181 27083 13195 27084 13162 27084 13186 27084 13182 27085 13181 27085 13195 27085 13181 27086 13194 27086 13195 27086 13208 27087 13183 27087 13195 27087 13183 27088 13208 27088 13184 27088 13191 27089 13207 27089 13184 27089 13193 27090 13222 27090 13212 27090 13242 27091 13211 27091 13222 27091 13221 27092 13191 27092 13212 27092 13221 27093 13207 27093 13191 27093 13187 27094 13211 27094 13241 27094 13241 27095 13209 27095 13187 27095 13209 27096 13241 27096 13210 27096 13210 27097 13219 27097 13239 27097 13258 27098 13243 27098 13257 27098 13257 27099 13190 27099 13258 27099 13245 27100 13214 27100 13243 27100 13240 27101 13218 27101 13190 27101 13244 27102 13213 27102 13214 27102 13240 27103 13239 27103 13218 27103 13244 27104 13275 27104 13213 27104 13213 27105 13275 27105 13255 27105 13246 27106 13255 27106 13254 27106 13217 27107 13256 27108 13254 27109 13276 27110 13247 27110 13256 27110 13288 27111 13287 27111 13276 27111 13276 27112 13289 27112 13288 27112 13287 27113 13279 27113 13278 27113 13252 27114 13248 27114 13287 27114 13253 27115 13277 27115 13252 27115 13253 27116 13286 27116 13277 27116 13249 27117 13248 27117 13252 27117 13311 27118 13317 27118 13342 27118 13310 27119 13286 27119 13311 27119 13285 27120 13281 27120 13315 27120 13310 27121 13277 27121 13286 27121 13284 27122 13280 27122 13285 27122 13337 27123 13343 27123 13376 27123 13436 27124 13468 27124 13406 27124 13468 27125 13470 27125 13438 27125 13406 27126 13376 27126 13436 27126 13376 27127 13375 27127 13404 27127 13515 27128 13538 27128 13470 27128 13538 27129 13539 27129 13502 27129 13470 27130 13468 27130 13515 27130 13576 27131 13609 27131 13538 27131 13609 27132 13610 27132 13539 27132 13610 27133 13639 27133 13573 27133 13573 27134 13574 27134 13610 27134 13671 27135 13672 27135 13638 27135 13677 27136 13719 27136 13672 27136 13677 27137 13676 27137 13719 27137 13672 27138 13671 27138 13677 27138 13723 27139 13725 27139 13719 27139 13722 27140 13726 27141 13723 27142 13726 27143 13679 27143 13725 27143 13680 27144 13678 27144 13642 27144 13726 27145 13680 27145 13679 27145 13727 27146 13761 27146 13678 27146 13678 27147 13680 27147 13727 27147 13783 27148 13779 27148 13761 27148 13779 27149 13780 27149 13782 27149 13780 27150 13796 27150 13782 27150 13781 27151 13796 27151 13758 27151 13758 27152 13714 27152 13759 27152 13714 27153 13667 27153 13717 27153 13718 27154 13717 27154 13667 27154 13637 27155 13669 27155 13670 27155 13636 27156 13635 27156 13669 27156 13537 27157 13533 27158 13572 27159 13535 27160 13568 27160 13533 27160 13636 27161 13572 27161 13568 27161 13534 27162 13535 27162 13497 27162 13496 27163 13499 27163 13534 27163 13465 27164 13432 27164 13498 27164 13499 27165 13496 27165 13465 27165 13432 27166 13466 27166 13498 27166 13373 27167 13434 27167 13433 27167 13467 27168 13466 27168 13433 27168 13466 27169 13432 27169 13400 27169 13372 27170 13402 27170 13401 27170 13372 27171 13398 27171 13402 27171 13401 27172 13434 27172 13373 27172 13371 27173 13369 27173 13397 27173 13371 27174 13370 27174 13369 27174 13397 27175 13402 27175 13398 27175 13347 27176 13335 27176 13346 27176 13335 27177 13334 27177 13346 27177 13369 27178 13370 27178 13347 27178 13306 27179 13268 27179 13307 27179 13268 27180 13270 27180 13307 27180 13334 27181 13335 27181 13306 27181 13235 27182 13223 27182 13273 27182 13223 27183 13238 27183 13273 27183 13269 27184 13270 27184 13236 27184 13270 27185 13268 27185 13236 27185 13238 27186 13223 27186 13196 27186 13351 27187 13377 27187 13358 27187 13357 27188 13378 27188 13351 27188 13645 27189 13621 27189 13619 27189 13619 27190 13615 27190 13645 27190 13620 27191 13621 27191 13586 27191 13362 27192 13358 27192 13377 27192 13355 27193 13379 27193 13352 27193 13357 27194 13355 27194 13352 27194 13416 27195 13407 27195 13379 27195 13379 27196 13355 27196 13356 27196 13356 27197 13384 27197 13416 27197 13384 27198 13415 27198 13409 27198 13414 27199 13410 27199 13415 27199 13380 27200 13410 27200 13383 27200 13439 27201 13408 27201 13383 27201 13383 27202 13448 27202 13439 27202 13447 27203 13440 27203 13439 27203 13442 27204 13440 27204 13447 27204 13471 27205 13441 27205 13446 27205 13446 27206 13480 27206 13471 27206 13473 27207 13446 27207 13442 27207 13504 27208 13472 27208 13471 27208 13542 27209 13503 27209 13472 27209 13475 27210 13503 27210 13542 27210 13505 27211 13474 27211 13443 27211 13506 27212 13479 27212 13443 27212 13479 27213 13514 27213 13505 27213 13543 27214 13505 27214 13514 27214 13553 27215 13508 27215 13513 27215 13552 27216 13544 27216 13507 27216 13508 27217 13511 27217 13476 27217 13508 27218 13553 27218 13511 27218 13545 27219 13544 27219 13552 27219 13577 27220 13545 27220 13613 27220 13554 27221 13577 27221 13585 27221 13549 27222 13548 27222 13512 27222 13585 27223 13549 27223 13554 27223 13548 27224 13550 27224 13551 27224 13586 27225 13587 27225 13548 27225 13688 27226 13646 27226 13648 27226 13615 27227 13619 27227 13648 27227 13690 27228 13734 27228 13648 27228 13735 27229 13766 27229 13734 27229 13766 27230 13797 27230 13784 27230 13734 27231 13690 27231 13735 27231 13788 27232 13800 27232 13797 27232 13814 27233 13811 27233 13800 27233 13800 27234 13788 27234 13787 27234 13803 27235 13819 27235 13814 27235 13802 27236 13820 27236 13819 27236 13817 27237 13832 27237 13820 27237 13816 27238 13833 27238 13832 27238 13831 27239 13839 27239 13816 27239 13825 27240 13837 27240 13831 27240 13827 27241 13836 27241 13837 27241 13808 27242 13807 27242 13824 27242 13836 27243 13827 27243 13835 27243 13807 27244 13823 27244 13824 27244 13793 27245 13806 27245 13807 27245 13792 27246 13805 27246 13806 27246 13773 27247 13790 27247 13792 27247 13743 27248 13772 27248 13790 27248 13790 27249 13773 27249 13745 27249 13745 27250 13697 27250 13743 27250 13697 27251 13696 27251 13742 27251 13696 27252 13740 27252 13742 27252 13652 27253 13695 27253 13740 27253 13651 27254 13650 27254 13695 27254 13590 27255 13626 27255 13650 27255 13590 27256 13558 27256 13623 27256 13521 27257 13556 27257 13589 27257 13589 27258 13623 27258 13558 27258 13519 27259 13556 27259 13520 27259 13483 27260 13518 27260 13519 27260 13453 27261 13451 27261 13483 27261 13519 27262 13520 27262 13453 27262 13451 27263 13418 27263 13482 27263 13418 27264 13450 27264 13482 27264 13386 27265 13429 27265 13450 27265 13363 27266 13385 27266 13392 27266 13363 27267 13362 27267 13385 27267 13392 27268 13429 27268 13386 27268 13396 27269 13395 27269 13366 27269 13687 27270 13686 27270 13730 27270 13686 27271 13691 27271 13692 27271 13738 27272 13689 27272 13686 27272 13689 27273 13691 27273 13686 27273 13361 27274 13366 27274 13395 27274 13365 27275 13393 27275 13396 27275 13364 27276 13387 27276 13430 27276 13420 27277 13462 27277 13387 27277 13393 27278 13365 27278 13364 27278 13419 27279 13452 27279 13463 27279 13452 27280 13494 27280 13463 27280 13462 27281 13420 27281 13419 27281 13452 27282 13454 27282 13494 27282 13454 27283 13485 27283 13495 27283 13484 27284 13557 27284 13516 27284 13516 27285 13485 27285 13484 27285 13484 27286 13523 27286 13557 27286 13522 27287 13588 27287 13557 27287 13522 27288 13560 27288 13588 27288 13557 27289 13523 27289 13522 27289 13559 26792 13591 27290 13560 26793 13628 27291 13624 27291 13591 27291 13694 27292 13649 27292 13627 27292 13627 27293 13654 27293 13694 27293 13624 27294 13628 27294 13627 27294 13653 27295 13693 27295 13694 27295 13699 27296 13741 27296 13693 27296 13700 27297 13739 27297 13741 27297 13700 27298 13768 27298 13739 27298 13700 27299 13698 27299 13769 27299 13698 27300 13744 27300 13770 27300 13804 27301 13791 27301 13746 27301 13746 27302 13775 27302 13822 27302 13770 27303 13744 27303 13771 27303 13774 27304 13834 27304 13821 27304 13774 27305 13795 27305 13843 27305 13822 27306 13775 27306 13774 27306 13794 27307 13842 27307 13843 27307 13810 27308 13847 27308 13842 27308 13826 27309 13838 27309 13844 27309 13844 27310 13847 27310 13826 27310 13838 27311 13846 27311 13845 27311 13847 27312 13810 27312 13809 27312 13830 27313 13829 27313 13846 27313 13846 27314 13838 27314 13830 27314 13829 27315 13841 27315 13840 27315 13815 27316 13813 27316 13812 27316 13828 27317 13841 27317 13829 27317 13815 27318 13818 27318 13813 27318 13818 27319 13801 27319 13798 27319 13786 27320 13789 27321 13801 27322 13789 27323 13799 27323 13798 27323 13767 27324 13737 27324 13765 27324 13737 27325 13736 27325 13764 27325 13785 27326 13799 27326 13789 27326 13685 27327 13684 27327 13733 27327 13736 27328 13738 27328 13764 27328 13731 27329 13683 27329 13730 27329 13729 27330 13682 27330 13731 27330 13762 27331 13776 27331 13732 27331 13747 27332 13702 27332 13763 27332 13681 27333 13728 27333 13762 27333 13702 27334 13705 27334 13763 27334 13682 27335 13729 27335 13728 27335 13705 27336 13750 27336 13749 27336 13707 27337 13752 27337 13750 27337 13709 27338 13754 27338 13752 27338 13708 27339 13755 27339 13754 27339 13706 27340 13753 27340 13755 27340 13704 27341 13751 27341 13753 27341 13701 27342 13655 27342 13757 27342 13777 27343 13748 27343 13778 27343 13656 27344 13711 27344 13757 27344 13656 27345 13712 27345 13711 27345 13748 27346 13751 27346 13703 27346 13751 27347 13704 27347 13703 27347 13629 27348 13592 27348 13712 27348 13592 27349 13594 27349 13712 27349 13594 27350 13596 27350 13659 27350 13596 27351 13662 27351 13659 27351 13598 27352 13664 27352 13596 27352 13600 27353 13665 27353 13664 27353 13599 27354 13663 27354 13600 27354 13597 27355 13660 27355 13663 27355 13633 27356 13713 27356 13756 27356 13756 27357 13710 27357 13633 27357 13633 27358 13632 27358 13713 27358 13661 27359 13660 27359 13710 27359 13660 27360 13597 27360 13633 27360 13564 27361 13603 27361 13633 27361 13564 27362 13563 27362 13603 27362 13563 27363 13565 27363 13605 27363 13565 27364 13562 27364 13602 27364 13525 27365 13524 27365 13561 27365 13524 27366 13631 27366 13601 27366 13601 27367 13602 27367 13561 27367 13528 27368 13567 27368 13631 27368 13631 27369 13524 27369 13528 27369 13489 27370 13488 27370 13529 27370 13488 27371 13491 27371 13531 27371 13491 27372 13490 27372 13530 27372 13486 27373 13455 27374 13487 27375 13455 27376 13457 27376 13532 27376 13527 27377 13490 27377 13487 27377 13422 27378 13460 27378 13457 27378 13527 27379 13530 27379 13490 27379 13422 27380 13423 27380 13460 27380 13423 27381 13426 27381 13461 27381 13426 27382 13425 27382 13458 27382 13421 27383 13388 27383 13424 27383 13360 27384 13391 27384 13428 27384 13459 27385 13425 27385 13424 27385 13360 27386 13361 27386 13391 27386 13388 27387 13360 27387 13428 27387 13459 27388 13458 27388 13425 27388 13848 27389 13849 27389 13850 27389 14388 27390 14360 27390 14358 27390 14388 27391 14391 27391 14360 27391 13849 27392 13853 27392 13854 27392 14325 27393 14326 27393 14360 27393 13854 27394 13855 27394 13851 27394 13848 27395 13851 27395 13852 27395 13859 27396 13856 27396 13852 27396 13867 27397 13856 27397 13859 27397 13867 27398 13882 27398 13856 27398 13859 27399 13883 27399 13866 27399 13882 27400 13901 27400 13856 27400 13859 27401 13878 27401 13883 27401 13903 27402 13885 27402 13856 27402 13856 27403 13924 27403 13903 27403 13901 27404 13923 27404 13856 27404 13923 27405 13982 27405 13950 27405 13923 27406 14017 27406 13982 27406 13885 27407 13868 27407 13856 27407 13923 27408 13950 27408 13924 27408 13860 27409 13856 27409 13869 27409 13865 27410 13879 27410 13878 27410 14052 27411 14090 27411 14078 27411 14052 27412 14093 27412 14090 27412 14051 27413 14015 27413 14052 27413 13860 27414 13902 27414 13887 27414 13860 27415 13884 27415 13902 27415 13981 27416 14015 27416 14014 27416 14014 27417 14013 27417 13981 27417 13860 27418 13869 27418 13884 27418 14017 27419 13923 27419 13981 27419 14093 27420 14141 27420 14113 27420 13871 27421 13905 27421 13925 27421 13871 27422 13886 27422 13905 27422 13860 27423 13887 27423 13871 27423 13865 27424 13897 27424 13917 27424 13918 27425 13899 27425 13865 27425 13899 27426 13879 27426 13865 27426 13865 27427 13876 27427 13897 27427 14118 27428 14147 27428 14146 27428 14141 27429 14093 27429 14146 27429 13871 27430 13926 27430 13929 27430 14211 27431 14177 27431 14179 27431 14178 27432 14145 27432 14147 27432 14179 27433 14244 27433 14211 27433 13871 27434 13929 27434 13930 27434 14244 27435 14242 27435 14210 27435 13889 27436 13906 27436 13927 27436 13951 27437 13965 27437 13889 27437 13889 27438 13871 27438 13906 27438 13895 27439 13946 27439 13947 27439 13895 27440 13944 27440 13974 27440 13897 27441 13876 27441 13895 27441 14313 27442 14314 27442 14278 27442 14314 27443 14351 27443 14279 27443 13889 27444 13956 27444 13955 27444 14242 27445 14244 27445 14243 27445 14280 27446 14313 27446 14243 27446 13889 27447 13965 27447 13956 27447 14379 27448 14312 27448 14351 27448 14461 27449 14462 27449 14351 27449 14351 27450 14459 27450 14461 27450 13907 27451 13954 27451 13983 27451 13907 27452 13931 27452 13953 27452 13907 27453 13889 27453 13931 27453 13915 27454 13975 27454 13976 27454 14008 27455 14047 27455 13915 27455 13915 27456 14011 27456 13975 27456 13895 27457 13915 27457 13944 27457 13915 27458 13971 27458 14008 27458 14468 27459 14505 27459 14464 27459 14525 27460 14464 27460 14540 27460 14525 27461 14504 27461 14464 27461 14464 27462 14418 27462 14468 27462 13907 27463 14001 27463 14018 27463 14386 27464 14422 27464 14356 27464 14422 27465 14468 27465 14418 27465 14356 27466 14319 27466 14386 27466 13987 27467 13958 27467 13907 27467 14461 27468 14459 27468 14503 27468 14459 27469 14504 27469 14525 27469 13907 27470 13984 27470 14001 27470 14463 27471 14469 27471 14319 27471 14319 27472 14417 27472 14463 27472 14423 27473 14385 27473 14319 27473 13933 27474 13957 27474 13990 27474 14020 27475 14022 27475 13933 27475 13907 27476 13958 27476 13933 27476 14045 27477 14006 27477 14007 27477 14045 27478 14073 27478 14006 27478 14044 27479 14072 27479 14045 27479 13970 27480 14007 27480 13971 27480 14006 27481 14046 27481 13971 27481 13971 27482 13915 27482 13970 27482 14213 27483 14181 27483 14214 27483 14214 27484 14246 27484 14213 27484 13959 27485 14054 27485 14055 27485 14283 27486 14318 27486 14284 27486 14213 27487 14246 27487 14284 27487 14317 27488 14319 27488 14284 27488 13959 27489 13993 27489 14021 27489 14021 27490 14054 27490 13959 27490 14181 27491 14149 27491 14182 27491 14025 27492 13959 27492 14055 27492 14382 27493 14416 27493 14319 27493 14319 27494 14317 27494 14382 27494 13933 27495 14022 27495 14023 27495 13959 27496 13933 27496 13993 27496 14068 27497 14069 27497 13969 27497 13970 27498 13969 27498 14041 27498 13969 27499 14037 27499 14064 27499 13969 27500 14064 27500 14068 27500 13970 27501 13941 27501 13969 27501 14085 27502 14065 27502 13995 27502 13995 27503 14094 27503 14085 27503 14065 27504 14036 27504 14003 27504 13995 27505 14056 27505 14081 27505 14081 27506 14094 27506 13995 27506 14081 27507 14120 27507 14094 27507 13995 27508 14024 27508 14056 27508 14149 27509 14094 27509 14120 27509 13959 27510 14025 27510 14024 27510 13969 27511 14003 27511 14036 27511 14003 27512 14035 27512 13995 27512 14063 27513 14057 27513 14035 27513 14082 27514 14057 27514 14123 27514 14063 27515 14129 27515 14121 27515 14095 27516 14057 27516 14063 27516 14063 27517 14139 27517 14140 27517 14136 27518 14129 27518 14063 27518 14063 27519 14135 27519 14139 27519 14137 27520 14138 27520 14136 27520 14140 27521 14137 27521 14136 27521 14063 27522 14112 27522 14134 27522 14095 27523 14122 27523 14057 27523 14122 27524 14096 27524 14057 27524 14123 27525 14151 27525 14082 27525 14262 27526 14227 27526 14260 27526 14227 27527 14226 27527 14260 27527 14171 27528 14237 27528 14201 27528 14194 27529 14207 27529 14226 27529 14238 27530 14239 27530 14226 27530 14112 27531 14201 27531 14204 27531 14205 27532 14202 27532 14112 27532 14202 27533 14203 27533 14112 27533 14112 27534 14171 27534 14201 27534 14097 27535 14082 27535 14152 27535 14194 27536 14173 27536 14206 27536 14206 27537 14207 27537 14194 27537 14112 27538 14203 27538 14172 27538 14082 27539 14153 27539 14154 27539 14082 27540 14160 27540 14153 27540 14082 27541 14151 27541 14160 27541 14173 27542 14136 27542 14174 27542 14112 27543 14172 27543 14134 27543 14333 27544 14369 27544 14368 27544 14333 27545 14332 27545 14369 27545 14366 27546 14367 27546 14333 27546 14236 27547 14273 27547 14275 27547 14271 27548 14171 27548 14236 27548 14236 27549 14272 27549 14273 27549 14370 27550 14367 27550 14393 27550 14236 27551 14311 27551 14272 27551 14263 27552 14262 27552 14261 27552 14299 27553 14300 27553 14301 27553 14171 27554 14276 27554 14237 27554 14332 27555 14333 27555 14299 27555 14171 27556 14271 27556 14276 27556 14126 27557 14097 27557 14185 27557 14097 27558 14152 27558 14183 27558 14186 27559 14155 27559 14097 27559 14487 27560 14486 27560 14514 27560 14514 27561 14515 27561 14516 27561 14310 27562 14377 27562 14347 27562 14310 27563 14376 27563 14377 27563 14484 27564 14483 27564 14486 27564 14512 27565 14513 27565 14486 27565 14310 27566 14347 27566 14348 27566 14349 27567 14346 27567 14310 27567 14345 27568 14236 27568 14310 27568 14483 27569 14484 27569 14485 27569 14439 27570 14394 27570 14437 27570 14236 27571 14345 27571 14375 27571 14370 27572 14393 27572 14438 27572 14437 27573 14394 27573 14370 27573 14311 27574 14236 27574 14350 27574 14156 27575 14126 27575 14218 27575 14247 27576 14219 27576 14126 27576 14126 27577 14185 27577 14215 27577 14219 27578 14187 27578 14126 27578 14581 27579 14580 27579 14588 27579 14588 27580 14589 27580 14581 27580 14402 27581 14374 27581 14456 27581 14584 27582 14583 27582 14590 27582 14581 27583 14589 27583 14590 27583 14374 27584 14501 27584 14455 27584 14586 27585 14591 27585 14579 27585 14578 27586 14587 27586 14568 27586 14586 27587 14579 27587 14568 27587 14454 27588 14310 27588 14405 27588 14408 27589 14409 27589 14310 27589 14310 27590 14403 27590 14406 27590 14404 27591 14405 27591 14310 27591 14310 27592 14374 27592 14402 27592 14568 27593 14567 27593 14578 27593 14550 27594 14565 27594 14578 27594 14310 27595 14454 27595 14500 27595 14549 27596 14534 27596 14566 27596 14565 27597 14550 27597 14566 27597 14534 27598 14535 27598 14548 27598 14457 27599 14410 27599 14310 27599 14516 27600 14515 27600 14534 27600 14376 27601 14310 27601 14410 27601 14189 27602 14156 27602 14251 27602 14287 27603 14252 27603 14156 27603 14252 27604 14220 27604 14156 27604 14156 27605 14218 27605 14249 27605 14544 27606 14557 27606 14541 27606 14555 27607 14556 27607 14544 27607 14521 27608 14374 27608 14492 27608 14528 27609 14541 27609 14529 27609 14541 27610 14542 27610 14543 27610 14498 27611 14499 27611 14387 27611 14387 27612 14494 27612 14496 27612 14495 27613 14492 27613 14387 27613 14387 27614 14493 27614 14494 27614 14492 27615 14374 27615 14387 27615 14564 27616 14576 27616 14577 27616 14583 27617 14558 27617 14577 27617 14558 27618 14563 27618 14564 27618 14583 27619 14585 27619 14572 27619 14583 27620 14584 27620 14585 27620 14501 27621 14374 27621 14522 27621 14556 27622 14555 27622 14572 27622 14374 27623 14521 27623 14522 27623 14221 27624 14189 27624 14295 27624 14189 27625 14251 27625 14288 27625 14321 27626 14298 27626 14189 27626 14298 27627 14256 27627 14189 27627 14478 27628 14509 27628 14508 27628 14477 27629 14432 27629 14508 27629 14387 27630 14476 27630 14507 27630 14428 27631 14429 27631 14390 27631 14387 27632 14323 27632 14476 27632 14323 27633 14430 27633 14431 27633 14323 27634 14390 27634 14430 27634 14390 27635 14429 27635 14430 27635 14432 27636 14477 27636 14428 27636 14427 27637 14426 27637 14323 27637 14426 27638 14425 27638 14323 27638 14323 27639 14431 27639 14427 27639 14253 27640 14365 27640 14389 27640 14359 27641 14390 27641 14323 27641 14528 27642 14529 27642 14478 27642 14493 27643 14387 27643 14507 27643 14253 27644 14331 27644 14365 27644 14253 27645 14294 27645 14331 27645 14359 27646 14323 27646 14253 27646 14221 27647 14295 27647 14253 27647 14324 27648 14290 27648 14253 27648 14324 27649 14358 27649 14326 27649 14391 27650 14362 27650 14325 27650 14327 27651 14291 27651 14362 27651 14327 27652 14328 27652 14291 27652 14254 27653 14328 27653 14363 27653 14364 27654 14330 27654 14254 27654 14328 27655 14392 27655 14363 27655 14328 27656 14436 27656 14435 27656 14435 27657 14392 27657 14328 27657 14433 27658 14434 27658 14435 27658 14479 27659 14434 27659 14433 27659 14480 27660 14481 27660 14479 27660 14482 27661 14480 27661 14479 27661 14328 27662 14475 27662 14474 27662 14328 27663 14473 27663 14475 27663 14474 27664 14436 27664 14328 27664 14328 27665 14401 27665 14473 27665 14330 27666 14292 27666 14254 27666 14222 27667 14254 27667 14292 27667 14546 27668 14547 27668 14531 27668 14531 27669 14530 27669 14545 27669 14520 27670 14401 27670 14491 27670 14561 27671 14545 27671 14559 27671 14561 27672 14546 27672 14545 27672 14559 27673 14560 27673 14561 27673 14401 27674 14446 27674 14491 27674 14532 27675 14510 27675 14533 27675 14530 27676 14531 27676 14532 27676 14506 27677 14401 27677 14520 27677 14575 27678 14560 27678 14574 27678 14560 27679 14559 27679 14573 27679 14450 27680 14452 27680 14453 27680 14451 27681 14449 27681 14453 27681 14337 27682 14447 27682 14450 27682 14446 27683 14401 27683 14449 27683 14510 27684 14479 27684 14481 27684 14472 27685 14401 27685 14506 27685 14222 27686 14329 27686 14322 27686 14296 27687 14255 27688 14322 27689 14222 27690 14293 27690 14329 27690 14255 27691 14188 27691 14222 27691 14551 27692 14552 27692 14554 27692 14538 27693 14537 27693 14551 27693 14399 27694 14337 27694 14373 27694 14518 27695 14517 27695 14536 27695 14536 27696 14537 27696 14539 27696 14337 27697 14336 27697 14373 27697 14569 27698 14553 27698 14552 27698 14569 27699 14570 27699 14553 27699 14445 27700 14337 27700 14399 27700 14489 27701 14517 27701 14490 27701 14517 27702 14518 27702 14519 27702 14343 27703 14344 27703 14342 27703 14270 27704 14339 27704 14343 27704 14340 27705 14338 27705 14342 27705 14270 27706 14308 27706 14339 27706 14336 27707 14337 27707 14338 27707 14569 27708 14574 27708 14570 27708 14569 27709 14575 27709 14574 27709 14447 27710 14337 27710 14445 27710 14188 27711 14257 27711 14223 27711 14188 27712 14255 27712 14257 27712 14223 27713 14157 27713 14188 27713 14442 27714 14444 27714 14443 27714 14397 27715 14396 27715 14443 27715 14440 27716 14441 27716 14442 27716 14200 27717 14269 27717 14305 27717 14371 27718 14334 27718 14398 27718 14395 27719 14396 27719 14397 27719 14200 27720 14233 27720 14269 27720 14489 27721 14490 27721 14441 27721 14488 27722 14442 27722 14441 27722 14270 27723 14305 27723 14309 27723 14307 27724 14308 27724 14309 27724 14270 27725 14200 27725 14305 27725 14157 27726 14250 27726 14248 27726 14224 27727 14190 27727 14248 27727 14157 27728 14223 27728 14250 27728 14190 27729 14125 27729 14157 27729 14228 27730 14197 27730 14267 27730 14264 27731 14265 27731 14266 27731 14133 27732 14166 27732 14199 27732 14302 27733 14335 27733 14265 27733 14303 27734 14304 27735 14266 27736 14302 27737 14334 27737 14335 27737 14133 27738 14199 27738 14231 27738 14371 27739 14372 27740 14335 27741 14200 27742 14231 27742 14235 27742 14232 27743 14233 27744 14235 27745 14200 27746 14133 27746 14231 27746 14125 27747 14191 27747 14127 27747 14125 27748 14190 27748 14191 27748 14127 27749 14098 27749 14125 27749 14088 27750 14165 27750 14168 27750 14195 27751 14197 27751 14198 27751 14163 27752 14162 27752 14196 27752 14088 27753 14132 27753 14165 27753 14131 27754 14130 27754 14162 27754 14162 27755 14163 27755 14164 27755 14088 27756 14104 27756 14132 27756 14108 27757 14107 27757 14130 27757 14228 27758 14229 27758 14198 27758 14088 27759 14170 27759 14166 27759 14088 27760 14168 27760 14169 27760 14088 27761 14169 27761 14170 27761 14166 27762 14133 27762 14088 27762 14083 27763 14127 27763 14159 27763 14159 27764 14128 27764 14083 27764 14128 27765 14100 27765 14083 27765 14083 27766 14098 27766 14127 27766 14058 27767 14101 27767 14102 27767 14102 27768 14106 27768 14062 27768 14058 27769 14099 27769 14101 27769 14111 27770 14110 27770 14062 27770 14062 27771 14106 27771 14111 27771 14110 27772 14105 27772 14062 27772 14107 27773 14108 27773 14109 27773 14107 27774 14109 27774 14111 27774 14104 27775 14088 27775 14105 27775 14083 27776 14100 27776 14099 27776 14034 27777 14027 27777 14058 27777 14034 27778 14004 27778 13994 27778 14084 27779 13994 27779 14004 27779 14084 27780 14103 27780 13994 27780 14004 27781 14038 27781 14067 27781 14087 27782 14060 27782 13994 27782 13994 27783 14103 27783 14087 27783 14103 27784 14119 27784 14087 27784 14060 27785 14028 27785 13994 27785 14161 27786 14148 27786 14103 27786 13960 27787 13994 27787 14029 27787 13968 27788 14039 27788 14004 27788 13960 27789 14059 27789 14086 27789 14180 27790 14193 27790 14225 27790 14225 27791 14259 27791 14212 27791 14354 27792 14353 27792 14320 27792 14285 27793 14355 27793 14354 27793 14320 27794 14282 27794 14225 27794 14282 27795 14259 27795 14225 27795 14061 27796 13960 27796 14086 27796 13960 27797 14061 27797 14030 27797 14030 27798 13997 27798 13960 27798 13960 27799 14029 27799 14059 27799 14148 27800 14161 27800 14193 27800 14421 27801 14415 27801 14383 27801 14383 27802 14354 27802 14355 27802 13932 27803 13996 27803 14032 27803 13960 27804 13997 27804 13996 27804 14042 27805 14071 27805 14070 27805 14005 27806 14043 27806 14042 27806 14066 27807 14039 27807 13968 27807 14070 27808 14066 27808 13968 27808 13968 27809 13942 27809 14005 27809 14424 27810 14470 27810 14466 27810 14465 27811 14460 27811 14527 27811 14466 27812 14419 27812 14465 27812 14465 27813 14471 27813 14424 27813 13932 27814 14000 27814 13961 27814 14355 27815 14384 27815 14420 27815 14466 27816 14467 27816 14420 27816 14384 27817 14419 27817 14466 27817 13932 27818 14032 27818 14000 27818 14502 27819 14524 27819 14523 27819 14412 27820 14458 27820 14502 27820 14523 27821 14527 27821 14460 27821 13908 27822 13999 27822 13988 27822 13908 27823 13961 27823 13999 27823 13908 27824 13932 27824 13961 27824 14048 27825 14076 27825 14049 27825 13972 27826 14075 27826 14048 27826 14074 27827 14049 27827 14077 27827 14005 27828 13972 27828 14048 27828 14005 27829 13942 27829 13972 27829 13914 27830 13973 27830 13972 27830 14381 27831 14414 27831 14411 27831 14352 27832 14316 27832 14381 27832 14411 27833 14378 27833 14352 27833 14352 27834 14315 27834 14316 27834 13908 27835 13989 27835 14002 27835 14281 27836 14316 27836 14315 27836 14245 27837 14208 27837 14277 27837 13964 27838 13934 27839 14002 27840 14412 27841 14378 27841 14411 27841 13908 27842 13988 27842 13989 27842 14208 27843 14209 27843 14241 27843 14241 27844 14277 27844 14208 27844 13888 27845 13963 27845 13986 27845 13888 27846 13934 27846 13963 27846 13986 27847 13966 27847 13888 27847 13888 27848 13908 27848 13934 27848 13914 27849 13945 27849 13978 27849 13973 27850 13914 27850 14009 27850 13896 27851 13916 27851 13945 27851 13978 27852 14009 27852 13914 27852 14092 27853 14080 27853 14116 27853 14143 27854 14092 27854 14117 27854 13888 27855 13937 27855 13909 27855 14175 27856 14143 27856 14144 27856 14208 27857 14175 27857 14176 27857 13888 27858 13966 27858 13937 27858 14080 27859 14115 27859 14116 27859 13870 27860 13909 27860 13936 27860 13952 27861 13939 27861 13936 27861 13870 27862 13888 27862 13909 27862 13877 27863 13898 27863 13922 27863 13948 27864 13916 27864 13922 27864 13916 27865 13896 27865 13877 27865 14091 27866 14080 27866 14053 27866 14016 27867 14050 27867 14079 27867 13861 27868 13891 27868 13904 27868 13949 27869 14012 27869 14050 27869 13949 27870 13980 27870 14012 27870 13892 27871 13861 27871 13904 27871 13949 27872 13913 27872 13980 27872 13873 27873 13861 27873 13892 27873 14080 27874 14091 27874 14115 27874 13870 27875 13939 27875 13910 27875 13910 27876 13890 27876 13870 27876 13861 27877 13870 27877 13890 27877 13864 27878 13919 27878 13898 27878 13864 27879 13900 27879 13919 27879 13864 27880 13881 27880 13900 27880 13898 27881 13877 27881 13864 27881 13858 27882 13857 27882 13863 27882 13863 27883 13874 27883 13858 27883 13857 27884 13875 27884 13862 27884 13857 27885 13894 27885 13875 27885 13874 27886 13880 27886 13858 27886 13912 27887 13940 27887 13913 27887 13894 27888 13857 27888 13912 27888 13857 27889 13893 27889 13911 27889 13940 27890 13967 27890 13913 27890 13967 27891 13979 27891 13913 27891 13857 27892 13872 27892 13893 27892 13857 27893 13911 27893 13912 27893 13861 27894 13873 27894 13872 27894 13864 27895 13858 27895 13881 27895 13858 27896 13854 27896 13857 27896 13849 27897 13848 27897 13852 27897 13853 27898 13852 27898 13856 27898 13856 27899 13860 27899 13861 27899 13860 27900 13871 27900 13870 27900 13871 27901 13889 27901 13888 27901 13889 27902 13907 27902 13908 27902 13907 27903 13933 27903 13932 27903 13933 27904 13959 27904 13960 27904 13959 27905 13995 27905 13994 27905 13994 27906 13995 27906 14027 27906 14026 27907 14057 27907 14027 27907 14057 27908 14082 27908 14083 27908 14082 27909 14097 27909 14098 27909 14097 27910 14126 27910 14125 27910 14126 27911 14156 27911 14157 27911 14156 27912 14189 27912 14188 27912 14188 27913 14189 27913 14221 27913 14222 27914 14221 27914 14253 27914 14253 27915 14290 27915 14254 27915 14290 27916 14326 27916 14325 27916 14391 27917 14388 27917 14362 27917 14362 27918 14358 27918 14327 27918 14324 27919 14323 27919 14327 27919 14328 27920 14323 27920 14401 27920 14401 27921 14387 27921 14337 27921 14337 27922 14374 27922 14270 27922 14270 27923 14310 27923 14200 27923 14200 27924 14236 27924 14133 27924 14133 27925 14171 27925 14088 27925 14088 27926 14112 27926 14062 27926 14063 27927 14035 27927 14034 27927 14034 27928 14035 27928 14003 27928 14003 27929 13969 27929 13968 27929 13969 27930 13941 27930 13968 27930 13941 27931 13915 27931 13914 27931 13915 27932 13895 27932 13914 27932 13895 27933 13876 27933 13877 27933 13876 27934 13865 27934 13864 27934 13865 27935 13859 27935 13858 27935 13858 27936 13859 27936 13855 27936 13867 27937 13866 27937 13862 27937 14065 27938 14085 27938 14084 27938 14094 27939 14103 27939 14085 27939 13874 27940 13863 27940 13883 27940 13862 27941 13875 27941 13882 27941 13875 27942 13894 27942 13882 27942 13913 27943 13949 27943 13901 27943 13901 27944 13894 27944 13913 27944 13949 27945 13981 27945 13923 27945 13949 27946 14016 27946 14015 27946 14016 27947 14053 27947 14052 27947 14080 27948 14092 27948 14093 27948 14052 27949 14053 27949 14080 27949 14092 27950 14118 27950 14093 27950 14143 27951 14147 27951 14118 27951 14175 27952 14179 27952 14147 27952 14208 27953 14245 27953 14244 27953 14245 27954 14280 27954 14244 27954 14179 27955 14175 27955 14208 27955 14245 27956 14315 27956 14313 27956 14315 27957 14352 27957 14314 27957 14352 27958 14378 27958 14314 27958 14412 27959 14460 27959 14459 27959 14460 27960 14504 27960 14459 27960 14351 27961 14378 27961 14412 27961 14460 27962 14465 27962 14504 27962 14465 27963 14419 27963 14418 27963 14419 27964 14384 27964 14418 27964 14355 27965 14285 27965 14319 27965 14356 27966 14384 27966 14355 27966 14285 27967 14284 27967 14319 27967 14284 27968 14285 27968 14225 27968 14225 27969 14193 27969 14181 27969 14161 27970 14103 27970 14149 27970 14181 27971 14193 27971 14161 27971 14103 27972 14094 27972 14149 27972 14067 27973 14038 27973 14036 27973 14039 27974 14064 27974 14037 27974 14039 27975 14066 27975 14064 27975 14037 27976 14036 27976 14038 27976 14066 27977 14070 27977 14068 27977 14071 27978 14069 27978 14070 27978 14042 27979 14040 27979 14069 27979 14043 27980 14041 27980 14042 27980 14005 27981 14007 27981 14041 27981 14005 27982 14049 27982 14007 27982 14041 27983 14043 27983 14005 27983 14074 27984 14044 27984 14049 27984 14089 27985 14072 27985 14044 27985 14077 27986 14045 27986 14072 27986 14076 27987 14073 27987 14045 27987 14048 27988 14006 27988 14073 27988 14075 27989 14046 27989 14006 27989 13972 27990 13973 27990 13971 27990 14046 27991 14075 27991 13972 27991 14010 27992 14047 27992 14008 27992 14009 27993 14011 27993 14047 27993 13978 27994 13975 27994 14011 27994 13978 27995 13977 27995 13975 27995 13977 27996 13945 27996 13943 27996 13943 27997 13945 27997 13944 27997 13948 27998 13974 27998 13944 27998 13922 27999 13946 27999 13974 27999 13921 28000 13947 28000 13946 28000 13898 28001 13917 28001 13897 28001 13898 28002 13920 28002 13917 28002 13897 28003 13947 28003 13921 28003 13920 28004 13919 28004 13918 28004 13919 28005 13900 28005 13899 28005 13881 28006 13878 28006 13900 28006 13881 28007 13880 28007 13878 28007 13879 28008 13899 28008 13900 28008 13880 28009 13874 28009 13878 28009 13911 28010 13903 28010 13912 28010 14087 28011 14081 28011 14056 28011 14024 28012 14028 28012 14060 28012 13950 28013 13940 28013 13924 28013 13903 28014 13911 28014 13893 28014 13885 28015 13893 28015 13868 28015 13892 28016 13904 28016 13884 28016 13892 28017 13884 28017 13873 28017 13904 28018 13902 28018 13884 28018 13904 28019 13887 28019 13902 28019 13868 28020 13872 28020 13869 28020 13884 28021 13869 28021 13873 28021 13891 28022 13886 28022 13904 28022 13891 28023 13890 28023 13886 28023 13910 28024 13905 28024 13886 28024 13905 28025 13910 28025 13938 28025 13939 28026 13906 28026 13929 28026 13926 28027 13925 28028 13929 28029 13925 28030 13938 28030 13939 28030 13952 28031 13927 28031 13906 28031 13927 28032 13952 28032 13936 28032 13935 28033 13951 28033 13928 28033 13937 28034 13966 28034 13909 28034 13986 28035 13955 28035 13956 28035 13965 28036 13935 28036 13909 28036 13965 28037 13951 28037 13935 28037 13931 28038 13955 28038 13986 28038 13985 28039 13953 28039 13931 28039 13953 28040 13985 28040 13954 28040 13954 28041 13963 28041 13962 28041 14002 28042 13987 28042 14001 28042 14001 28043 13934 28043 14002 28043 13989 28044 13958 28044 13987 28044 13984 28045 13962 28045 13934 28045 13988 28046 13957 28046 13958 28046 13984 28047 13983 28047 13962 28047 13988 28048 14019 28048 13957 28048 13957 28049 14019 28049 13999 28049 13990 28050 13999 28050 13991 28050 13961 28051 14000 28051 13998 28051 14020 28052 13991 28052 14000 28052 14032 28053 14031 28053 14022 28053 14020 28054 14033 28054 14032 28054 14031 28055 14023 28055 14022 28055 13996 28056 13992 28056 14023 28056 13997 28057 14021 28057 13993 28057 13997 28058 14030 28058 14021 28058 13993 28059 13992 28059 13996 28059 14055 28060 14061 28060 14059 28060 14054 28061 14030 28061 14061 28061 14029 28062 14025 28062 14059 28062 14054 28063 14021 28063 14030 28063 14028 28064 14024 28064 14025 28064 14081 28065 14087 28065 14120 28065 14180 28066 14212 28066 14182 28066 14212 28067 14214 28067 14182 28067 14150 28068 14120 28068 14148 28068 14120 28069 14119 28069 14148 28069 14259 28070 14282 28070 14246 28070 14282 28071 14283 28071 14246 28071 14214 28072 14212 28072 14259 28072 14320 28073 14353 28073 14283 28073 14353 28074 14354 28074 14283 28074 14354 28075 14383 28075 14382 28075 14317 28076 14318 28076 14354 28076 14415 28077 14416 28077 14383 28077 14421 28078 14463 28078 14416 28078 14421 28079 14420 28079 14463 28079 14416 28080 14415 28080 14421 28080 14467 28081 14469 28081 14420 28081 14466 28082 14470 28083 14467 28084 14470 28085 14423 28085 14469 28085 14424 28086 14422 28086 14385 28086 14470 28087 14424 28087 14385 28087 14471 28088 14505 28088 14422 28088 14422 28089 14424 28089 14471 28089 14527 28090 14523 28090 14471 28090 14523 28091 14524 28091 14526 28091 14524 28092 14540 28092 14526 28092 14525 28093 14540 28093 14524 28093 14502 28094 14458 28094 14503 28094 14458 28095 14411 28095 14461 28095 14462 28096 14461 28096 14411 28096 14381 28097 14413 28097 14462 28097 14380 28098 14379 28098 14413 28098 14281 28099 14277 28099 14316 28099 14279 28100 14312 28100 14277 28100 14380 28101 14316 28101 14312 28101 14278 28102 14279 28102 14241 28102 14240 28103 14243 28103 14278 28103 14209 28104 14176 28104 14242 28104 14243 28105 14240 28105 14209 28105 14176 28106 14210 28106 14242 28106 14117 28107 14178 28107 14177 28107 14211 28108 14210 28108 14177 28108 14210 28109 14176 28109 14144 28109 14116 28110 14146 28110 14145 28110 14116 28111 14142 28111 14146 28111 14145 28112 14178 28112 14117 28112 14115 28113 14113 28113 14141 28113 14115 28114 14114 28114 14113 28114 14141 28115 14146 28115 14142 28115 14091 28116 14079 28116 14090 28116 14079 28117 14078 28117 14090 28117 14113 28118 14114 28118 14091 28118 14050 28119 14012 28119 14051 28119 14012 28120 14014 28120 14051 28120 14078 28121 14079 28121 14050 28121 13979 28122 13967 28122 14013 28122 13967 28123 13982 28123 14017 28123 14013 28124 14014 28124 13979 28124 14014 28125 14012 28125 13980 28125 13982 28126 13967 28126 13950 28126 14095 28127 14121 28127 14101 28127 14101 28128 14122 28128 14095 28128 14389 28129 14365 28129 14364 28129 14363 28130 14359 28130 14389 28130 14364 28131 14365 28131 14331 28131 14106 28132 14102 28132 14129 28132 14099 28133 14123 28133 14096 28133 14101 28134 14099 28134 14122 28134 14160 28135 14151 28135 14100 28135 14123 28136 14099 28136 14100 28136 14100 28137 14128 28137 14160 28137 14128 28138 14159 28138 14153 28138 14158 28139 14154 28139 14153 28139 14124 28140 14154 28140 14158 28140 14183 28141 14152 28141 14124 28141 14127 28142 14192 28142 14183 28142 14191 28143 14184 28143 14183 28143 14186 28144 14184 28144 14191 28144 14215 28145 14185 28145 14155 28145 14190 28146 14224 28146 14215 28146 14217 28147 14190 28147 14155 28147 14248 28148 14216 28148 14224 28148 14286 28149 14247 28149 14216 28149 14219 28150 14247 28150 14286 28150 14249 28151 14218 28151 14187 28151 14250 28152 14223 28152 14187 28152 14223 28153 14258 28153 14249 28153 14287 28154 14249 28154 14258 28154 14297 28155 14252 28155 14257 28155 14296 28156 14288 28156 14251 28156 14252 28157 14255 28157 14251 28157 14252 28158 14297 28158 14255 28158 14289 28159 14288 28159 14296 28159 14321 28160 14289 28160 14322 28160 14298 28161 14321 28161 14357 28161 14293 28162 14292 28162 14295 28162 14329 28163 14293 28163 14256 28163 14292 28164 14294 28164 14295 28164 14330 28165 14331 28165 14294 28165 14432 28166 14390 28166 14359 28166 14359 28167 14363 28167 14392 28167 14434 28168 14478 28168 14432 28168 14479 28169 14510 28169 14528 28169 14510 28170 14541 28170 14528 28170 14478 28171 14434 28171 14479 28171 14532 28172 14544 28172 14510 28172 14558 28173 14555 28173 14544 28173 14544 28174 14532 28174 14531 28174 14547 28175 14563 28175 14531 28175 14546 28176 14564 28176 14563 28176 14561 28177 14576 28177 14546 28177 14560 28178 14577 28178 14576 28178 14575 28179 14583 28179 14577 28179 14569 28180 14581 28180 14583 28180 14571 28181 14580 28181 14581 28181 14552 28182 14551 28182 14568 28182 14580 28183 14571 28183 14552 28183 14551 28184 14567 28184 14568 28184 14537 28185 14550 28185 14567 28185 14536 28186 14549 28186 14550 28186 14517 28187 14534 28187 14549 28187 14487 28188 14516 28188 14534 28188 14534 28189 14517 28189 14489 28189 14489 28190 14441 28190 14487 28190 14441 28191 14440 28191 14486 28191 14440 28192 14484 28192 14486 28192 14396 28193 14439 28193 14484 28193 14395 28194 14394 28194 14439 28194 14334 28195 14370 28195 14395 28195 14334 28196 14302 28196 14367 28196 14265 28197 14300 28197 14333 28197 14333 28198 14367 28198 14302 28198 14263 28199 14300 28199 14265 28199 14227 28200 14262 28200 14197 28200 14197 28201 14195 28201 14227 28201 14263 28202 14264 28202 14197 28202 14195 28203 14162 28203 14226 28203 14162 28204 14194 28204 14226 28204 14130 28205 14173 28205 14162 28205 14107 28206 14129 28206 14130 28206 14107 28207 14106 28207 14129 28207 14136 28208 14173 28208 14130 28208 14140 28209 14139 28209 14111 28209 14431 28210 14430 28210 14436 28210 14430 28211 14435 28211 14436 28211 14482 28212 14433 28212 14429 28212 14433 28213 14435 28213 14430 28213 14105 28214 14110 28214 14135 28214 14109 28215 14137 28215 14111 28215 14108 28216 14131 28216 14138 28216 14164 28217 14206 28217 14174 28217 14137 28218 14109 28218 14138 28218 14163 28219 14196 28219 14206 28219 14196 28220 14238 28220 14207 28220 14206 28221 14164 28221 14163 28221 14196 28222 14198 28222 14238 28222 14198 28223 14229 28223 14260 28223 14228 28224 14301 28224 14261 28224 14260 28225 14229 28225 14228 28225 14228 28226 14267 28226 14301 28226 14266 28227 14332 28227 14301 28227 14266 28228 14304 28228 14332 28228 14301 28229 14267 28229 14266 28229 14303 27734 14335 27741 14304 27735 14372 28230 14368 28230 14335 28230 14438 28231 14393 28231 14366 28231 14371 28232 14398 28232 14438 28232 14368 28233 14372 28233 14366 28233 14397 28234 14437 28234 14398 28234 14443 28235 14485 28235 14397 28235 14444 28236 14483 28236 14443 28236 14444 28237 14512 28237 14483 28237 14444 28238 14442 28238 14512 28238 14442 28239 14488 28239 14513 28239 14548 28240 14535 28241 14515 28242 14490 28243 14519 28243 14548 28243 14514 28244 14488 28244 14490 28244 14518 28245 14578 28245 14565 28245 14518 28246 14539 28246 14578 28246 14566 28247 14519 28247 14565 28247 14538 28248 14586 28248 14539 28248 14554 28249 14591 28249 14538 28249 14570 28250 14582 28250 14589 28250 14588 28251 14591 28251 14553 28251 14582 28252 14590 28252 14589 28252 14591 28253 14554 28253 14553 28253 14574 28254 14573 28254 14584 28254 14590 28255 14582 28255 14574 28255 14573 28256 14585 28256 14584 28256 14559 28257 14557 28257 14572 28257 14572 28258 14585 28258 14559 28258 14559 28259 14562 28259 14557 28259 14562 28260 14545 28260 14542 28260 14530 28261 14533 28262 14545 28263 14533 28264 14543 28264 14542 28264 14511 28265 14481 28265 14529 28265 14481 28266 14480 28266 14509 28266 14529 28267 14543 28267 14511 28267 14429 28268 14428 28268 14508 28268 14480 28269 14482 28269 14429 28269 14475 28270 14427 28270 14431 28270 14473 28271 14426 28271 14427 28271 14506 28272 14520 28272 14507 28272 14491 28273 14446 28273 14520 28273 14425 28274 14472 28274 14476 28274 14446 28275 14449 28275 14493 28275 14426 28276 14473 28276 14425 28276 14449 28277 14494 28277 14493 28277 14451 28278 14496 28278 14449 28278 14453 28279 14498 28279 14496 28279 14452 28280 14499 28280 14453 28280 14450 28281 14497 28281 14499 28281 14448 28282 14495 28282 14450 28282 14445 28283 14399 28283 14501 28283 14521 28284 14492 28284 14522 28284 14400 28285 14455 28285 14501 28285 14400 28286 14456 28286 14455 28286 14492 28287 14495 28287 14447 28287 14495 28288 14448 28288 14447 28288 14373 28289 14336 28289 14400 28289 14336 28290 14338 28290 14402 28290 14338 28291 14340 28291 14403 28291 14340 28292 14406 28292 14403 28292 14342 28293 14408 28293 14406 28293 14344 28294 14409 28294 14408 28294 14343 28295 14407 28295 14409 28295 14341 28296 14404 28296 14407 28296 14377 28297 14457 28297 14500 28297 14500 28298 14454 28298 14377 28298 14377 28299 14376 28299 14457 28299 14405 28300 14404 28300 14454 28300 14404 28301 14341 28301 14339 28301 14308 28302 14347 28302 14377 28302 14308 28303 14307 28303 14347 28303 14307 28304 14309 28304 14349 28304 14309 28305 14306 28305 14346 28305 14269 28306 14268 28307 14305 28308 14268 28309 14375 28309 14345 28309 14345 28310 14346 28310 14305 28310 14272 28311 14311 28311 14375 28311 14375 28312 14268 28312 14272 28312 14233 28313 14232 28313 14273 28313 14232 28314 14235 28314 14275 28314 14235 28315 14234 28315 14274 28315 14230 28316 14199 28317 14231 28318 14199 28319 14201 28319 14237 28319 14271 28320 14234 28320 14231 28320 14166 28321 14204 28321 14199 28321 14271 28322 14274 28322 14234 28322 14166 28323 14167 28323 14204 28323 14167 28324 14170 28324 14205 28324 14170 28325 14169 28325 14205 28325 14165 28326 14132 28326 14172 28326 14104 28327 14135 28327 14134 28327 14203 28328 14169 28328 14172 28328 14104 28329 14105 28329 14135 28329 14132 28330 14104 28330 14172 28330 14203 28331 14202 28331 14169 28331 14592 28332 14593 28332 14594 28332 15132 28333 15104 28333 15070 28333 15132 28334 15135 28334 15104 28334 14593 28335 14597 28335 14594 28335 15069 28336 15070 28336 15105 28336 14598 28337 14599 28337 14595 28337 14592 28338 14595 28338 14599 28338 14603 28339 14600 28339 14599 28339 14611 28340 14600 28340 14610 28340 14611 28341 14626 28341 14600 28341 14603 28342 14627 28342 14610 28342 14626 28343 14645 28343 14600 28343 14603 28344 14622 28344 14627 28344 14647 28345 14629 28345 14600 28345 14600 28346 14668 28346 14647 28346 14645 28347 14667 28347 14668 28347 14667 28348 14726 28348 14694 28348 14667 28349 14761 28349 14726 28349 14629 28350 14612 28350 14600 28350 14667 28351 14694 28351 14668 28351 14604 28352 14600 28352 14612 28352 14609 28353 14623 28353 14603 28353 14796 28354 14834 28354 14795 28354 14796 28355 14837 28355 14834 28355 14795 28356 14759 28356 14796 28356 14604 28357 14646 28357 14631 28357 14604 28358 14628 28358 14646 28358 14725 28359 14759 28359 14795 28359 14758 28360 14757 28360 14725 28360 14604 28361 14613 28361 14628 28361 14761 28362 14667 28362 14757 28362 14837 28363 14885 28363 14834 28363 14615 28364 14649 28364 14670 28364 14615 28365 14630 28365 14649 28365 14604 28366 14631 28366 14630 28366 14609 28367 14641 28367 14662 28367 14662 28368 14643 28368 14609 28368 14643 28369 14623 28369 14609 28369 14609 28370 14620 28370 14641 28370 14862 28371 14891 28371 14889 28371 14885 28372 14837 28372 14862 28372 14615 28373 14670 28373 14673 28373 14955 28374 14921 28374 14891 28374 14922 28375 14889 28375 14921 28375 14923 28376 14988 28376 14955 28376 14615 28377 14673 28377 14650 28377 14988 28378 14986 28378 14955 28378 14633 28379 14650 28379 14672 28379 14695 28380 14709 28381 14672 28382 14633 28383 14615 28383 14650 28383 14639 28384 14690 28384 14641 28384 14639 28385 14688 28385 14690 28385 14641 28386 14620 28386 14639 28386 15057 28387 15058 28387 15023 28387 15058 28388 15095 28388 15056 28388 14633 28389 14700 28389 14675 28389 14986 28390 14988 28390 15024 28390 15024 28391 15057 28391 15022 28391 14633 28392 14709 28392 14700 28392 15123 28393 15056 28393 15157 28393 15205 28394 15206 28394 15157 28394 15095 28395 15203 28395 15205 28395 14651 28396 14698 28396 14728 28396 14651 28397 14675 28397 14698 28397 14651 28398 14633 28398 14675 28398 14659 28399 14719 28399 14687 28399 14752 28400 14791 28400 14755 28400 14659 28401 14755 28401 14719 28401 14639 28402 14659 28402 14687 28402 14659 28403 14715 28403 14752 28403 15212 28404 15249 28404 15270 28404 15269 28405 15208 28405 15270 28405 15269 28406 15248 28406 15208 28406 15208 28407 15162 28407 15212 28407 14651 28408 14745 28408 14762 28408 15130 28409 15166 28409 15162 28409 15166 28410 15212 28410 15162 28410 15100 28411 15063 28411 15129 28411 14731 28412 14702 28412 14762 28412 15205 28413 15203 28413 15247 28413 15203 28414 15248 28414 15247 28414 14651 28415 14728 28415 14745 28415 15207 28416 15213 28416 15167 28416 15063 28417 15161 28417 15207 28417 15167 28418 15129 28418 15063 28418 14677 28419 14701 28419 14735 28419 14764 28420 14766 28420 14735 28420 14651 28421 14702 28421 14701 28421 14789 28422 14750 28422 14788 28422 14789 28423 14817 28423 14750 28423 14788 28424 14816 28424 14789 28424 14714 28425 14751 28425 14750 28425 14750 28426 14790 28426 14715 28426 14715 28427 14659 28427 14685 28427 14957 28428 14925 28428 14926 28428 14958 28429 14990 28429 14957 28429 14703 28430 14798 28430 14799 28430 15027 28431 15062 28431 15061 28431 14957 28432 14990 28432 15027 28432 15061 28433 15063 28433 15028 28433 14703 28434 14737 28434 14765 28434 14765 28435 14798 28435 14703 28435 14925 28436 14893 28436 14894 28436 14769 28437 14703 28437 14799 28437 15126 28438 15160 28438 15161 28438 15063 28439 15061 28439 15126 28439 14677 28440 14766 28440 14736 28440 14703 28441 14677 28441 14736 28441 14812 28442 14813 28442 14784 28442 14714 28443 14713 28443 14784 28443 14713 28444 14781 28444 14808 28444 14713 28445 14808 28445 14812 28445 14714 28446 14685 28446 14713 28446 14829 28447 14809 28447 14747 28447 14739 28448 14838 28448 14829 28448 14809 28449 14780 28449 14747 28449 14739 28450 14800 28450 14825 28450 14825 28451 14838 28451 14739 28451 14825 28452 14864 28452 14838 28452 14739 28453 14768 28453 14800 28453 14893 28454 14838 28454 14894 28454 14703 28455 14769 28455 14739 28455 14713 28456 14747 28456 14781 28456 14747 28457 14779 28457 14770 28457 14807 28458 14801 28458 14770 28458 14826 28459 14801 28459 14840 28459 14807 28460 14873 28460 14865 28460 14839 28461 14801 28461 14865 28461 14807 28462 14883 28462 14884 28462 14880 28463 14873 28463 14884 28463 14807 28464 14879 28464 14883 28464 14881 28465 14882 28465 14880 28465 14884 28466 14881 28466 14880 28466 14807 28467 14856 28467 14879 28467 14839 28468 14866 28468 14801 28468 14866 28469 14840 28469 14801 28469 14867 28470 14895 28470 14826 28470 15006 28471 14971 28471 15005 28471 14971 28472 14970 28472 14983 28472 14915 28473 14981 28473 14945 28473 14938 28474 14951 28474 14982 28474 14982 28475 14983 28475 14970 28475 14856 28476 14945 28476 14949 28476 14949 28477 14946 28477 14856 28477 14946 28478 14947 28478 14856 28478 14856 28479 14915 28479 14945 28479 14841 28480 14826 28480 14868 28480 14938 28481 14917 28481 14918 28481 14950 28482 14951 28482 14938 28482 14856 28483 14947 28483 14916 28483 14826 28484 14897 28484 14868 28484 14826 28485 14904 28485 14897 28485 14826 28486 14895 28486 14904 28486 14917 28487 14880 28487 14882 28487 14856 28488 14916 28488 14878 28488 15077 28489 15113 28489 15112 28489 15077 28490 15076 28490 15113 28490 15110 28491 15111 28491 15112 28491 14980 28492 15017 28492 15018 28492 15015 28493 14915 28493 15018 28493 14980 28494 15016 28494 15017 28494 15114 28495 15111 28495 15110 28495 14980 28496 15055 28496 15016 28496 15007 28497 15006 28497 15045 28497 15043 28498 15044 28498 15007 28498 14915 28499 15020 28499 14981 28499 15076 28500 15077 28500 15044 28500 14915 28501 15015 28501 15020 28501 14870 28502 14841 28502 14899 28502 14841 28503 14896 28503 14928 28503 14930 28504 14899 28504 14928 28504 15231 28505 15230 28505 15257 28505 15258 28506 15259 28506 15231 28506 15054 28507 15121 28507 15091 28507 15054 28508 15120 28508 15121 28508 15228 28509 15227 28509 15256 28509 15256 28510 15257 28510 15230 28510 15054 28511 15091 28511 15093 28511 15093 28512 15090 28512 15054 28512 15089 28513 14980 28513 15090 28513 15227 28514 15228 28514 15183 28514 15183 28515 15138 28515 15229 28515 14980 28516 15089 28516 15094 28516 15114 28517 15137 28517 15181 28517 15181 28518 15138 28518 15114 28518 15055 28519 14980 28519 15094 28519 14900 28520 14870 28520 14931 28520 14991 28521 14963 28521 14960 28521 14870 28522 14929 28522 14960 28522 14963 28523 14931 28523 14870 28523 15325 28524 15324 28524 15323 28524 15332 28525 15333 28525 15325 28525 15146 28526 15118 28526 15199 28526 15328 28527 15327 28527 15325 28527 15325 28528 15333 28528 15334 28528 15118 28529 15245 28529 15199 28529 15330 28530 15335 28530 15332 28530 15322 28531 15331 28532 15330 28533 15330 28534 15323 28534 15312 28534 15198 28535 15054 28535 15149 28535 15152 28536 15153 28536 15151 28536 15054 28537 15147 28537 15152 28537 15148 28538 15149 28538 15151 28538 15054 28539 15118 28539 15147 28539 15312 28540 15311 28540 15294 28540 15294 28541 15309 28541 15322 28541 15054 28542 15198 28542 15244 28542 15293 28543 15278 28543 15292 28543 15309 28544 15294 28544 15293 28544 15278 28545 15279 28545 15292 28545 15201 28546 15154 28546 15244 28546 15260 28547 15259 28547 15279 28547 15120 28548 15054 28548 15154 28548 14933 28549 14900 28549 14964 28549 15031 28550 14996 28550 14993 28550 14996 28551 14964 28551 14900 28551 14900 28552 14962 28552 14993 28552 15288 28553 15301 28553 15286 28553 15299 28554 15300 28554 15301 28554 15265 28555 15118 28555 15236 28555 15272 28556 15285 28556 15287 28556 15285 28557 15286 28557 15287 28557 15242 28558 15243 28558 15241 28558 15131 28559 15238 28559 15242 28559 15239 28560 15236 28560 15241 28560 15131 28561 15237 28561 15238 28561 15236 28562 15118 28562 15131 28562 15308 28563 15320 28563 15321 28563 15327 28564 15302 28564 15308 28564 15302 28565 15307 28565 15308 28565 15327 28566 15329 28566 15302 28566 15327 28567 15328 28567 15329 28567 15245 28568 15118 28568 15266 28568 15300 28569 15299 28569 15302 28569 15118 28570 15265 28570 15266 28570 14965 28571 14933 28571 15000 28571 14933 28572 14995 28572 15033 28572 15065 28573 15042 28574 15033 28575 15042 28576 15000 28576 14933 28576 15222 28577 15253 28577 15252 28577 15221 28578 15176 28578 15222 28578 15131 28579 15220 28579 15251 28579 15172 28580 15173 28580 15176 28580 15131 28581 15067 28581 15169 28581 15067 28582 15174 28582 15175 28582 15067 28583 15134 28583 15174 28583 15134 28584 15173 28584 15174 28584 15176 28585 15221 28585 15172 28585 15171 28586 15170 28586 15067 28586 15170 28587 15169 28587 15067 28587 15067 28588 15175 28588 15171 28588 14997 28589 15109 28589 15103 28589 15103 28590 15134 28590 15067 28590 15272 28591 15273 28591 15253 28591 15237 28592 15131 28592 15251 28592 14997 28593 15075 28593 15109 28593 14997 28594 15038 28594 15075 28594 15103 28595 15067 28595 14997 28595 14965 28596 15039 28596 15038 28596 15068 28597 15034 28597 15067 28597 15068 28598 15102 28598 15034 28598 15135 28599 15106 28599 15105 28599 15071 28600 15035 28600 15069 28600 15071 28601 15072 28601 14998 28601 14998 28602 15072 28602 15108 28602 15108 28603 15074 28603 14998 28603 15072 28604 15136 28604 15107 28604 15072 28605 15180 28605 15179 28605 15179 28606 15136 28606 15072 28606 15177 28607 15178 28607 15136 28607 15223 28608 15178 28608 15226 28608 15224 28609 15225 28609 15223 28609 15226 28610 15224 28610 15223 28610 15072 28611 15219 28611 15218 28611 15072 28612 15217 28612 15219 28612 15218 28613 15180 28613 15072 28613 15072 28614 15145 28614 15216 28614 15074 28615 15036 28615 14998 28615 14966 28616 14998 28616 15037 28616 15290 28617 15291 28617 15289 28617 15275 28618 15274 28618 15289 28618 15264 28619 15145 28619 15235 28619 15305 28620 15289 28620 15306 28620 15305 28621 15290 28621 15289 28621 15303 28622 15304 28622 15305 28622 15145 28623 15190 28623 15235 28623 15276 28624 15254 28624 15255 28624 15274 28625 15275 28625 15277 28625 15250 28626 15145 28626 15264 28626 15319 28627 15304 28627 15317 28627 15304 28628 15303 28628 15317 28628 15194 28629 15196 28629 15081 28629 15195 28630 15193 28630 15081 28630 15081 28631 15191 28631 15192 28631 15190 28632 15145 28632 15081 28632 15254 28633 15223 28633 15255 28633 15216 28634 15145 28634 15250 28634 14966 28635 15073 28635 15101 28635 15040 28636 14999 28636 14966 28636 14966 28637 15037 28637 15073 28637 14999 28638 14932 28638 14966 28638 15295 28639 15296 28639 15297 28639 15282 28640 15281 28640 15298 28640 15143 28641 15081 28641 15144 28641 15262 28642 15261 28642 15283 28642 15280 28643 15281 28643 15282 28643 15081 28644 15080 28644 15117 28644 15313 28645 15297 28645 15315 28645 15313 28646 15314 28646 15297 28646 15189 28647 15081 28647 15143 28647 15233 28648 15261 28648 15263 28648 15261 28649 15262 28649 15263 28649 15087 28650 15088 28650 15014 28650 15014 28651 15083 28651 15085 28651 15084 28652 15082 28652 15014 28652 15014 28653 15052 28653 15083 28653 15080 28654 15081 28654 15014 28654 15313 28655 15318 28655 15326 28655 15313 28656 15319 28656 15318 28656 15191 28657 15081 28657 15189 28657 14932 28658 15001 28658 15002 28658 14932 28659 14999 28659 15041 28659 14967 28660 14901 28660 14932 28660 15186 28661 15188 28661 15184 28661 15141 28662 15140 28662 15184 28662 15184 28663 15185 28663 15186 28663 14944 28664 15013 28664 15049 28664 15115 28665 15078 28665 15139 28665 15139 28666 15140 28666 15142 28666 14944 28667 14977 28667 15012 28667 15233 28668 15234 28668 15232 28668 15232 28669 15186 28669 15185 28669 15014 28670 15049 28670 15050 28670 15051 28671 15052 28671 15014 28671 15014 28672 14944 28672 15049 28672 14901 28673 14994 28673 15030 28673 14968 28674 14934 28674 14901 28674 14901 28675 14967 28675 14994 28675 14934 28676 14869 28676 14901 28676 14972 28677 14941 28677 15008 28677 15008 28678 15009 28678 15011 28678 14877 28679 14910 28679 14943 28679 15046 28680 15079 28680 15047 28680 15047 28681 15048 28681 15009 28681 15046 28682 15078 28682 15079 28682 14877 28683 14943 28683 14974 28683 15115 28684 15116 28684 15078 28684 14944 28685 14975 28685 14978 28685 14976 28686 14977 28686 14944 28686 14944 28687 14877 28687 14975 28687 14869 28688 14935 28688 14936 28688 14869 28689 14934 28689 14961 28689 14871 28690 14842 28690 14869 28690 14832 28691 14909 28691 14912 28691 14939 28692 14941 28692 14940 28692 14907 28693 14906 28693 14939 28693 14832 28694 14876 28694 14909 28694 14875 28695 14874 28695 14908 28695 14906 28696 14907 28696 14908 28696 14832 28697 14848 28697 14876 28697 14852 28698 14851 28698 14875 28698 14972 28699 14973 28699 14941 28699 14832 28700 14914 28700 14911 28700 14832 28701 14912 28701 14913 28701 14832 28702 14913 28702 14914 28702 14910 28703 14877 28703 14832 28703 14827 28704 14871 28704 14902 28704 14903 28705 14872 28705 14827 28705 14872 28706 14844 28706 14827 28706 14827 28707 14842 28707 14871 28707 14802 28708 14845 28708 14806 28708 14846 28709 14850 28709 14806 28709 14802 28710 14843 28710 14845 28710 14855 28711 14854 28711 14806 28711 14806 28712 14850 28712 14851 28712 14854 28713 14849 28713 14806 28713 14851 28714 14852 28714 14853 28714 14851 28715 14853 28715 14855 28715 14848 28716 14832 28716 14806 28716 14827 28717 14844 28717 14802 28717 14778 28718 14771 28718 14806 28718 14778 28719 14748 28719 14771 28719 14828 28720 14738 28720 14811 28720 14828 28721 14847 28721 14738 28721 14748 28722 14782 28722 14811 28722 14831 28723 14804 28723 14738 28723 14738 28724 14847 28724 14831 28724 14847 28725 14863 28725 14831 28725 14804 28726 14772 28726 14738 28726 14905 28727 14892 28727 14863 28727 14704 28728 14738 28728 14772 28728 14712 28729 14783 28729 14782 28729 14704 28730 14803 28730 14830 28730 14924 28731 14937 28731 14956 28731 14969 28732 15003 28732 14956 28732 15098 28733 15097 28733 15029 28733 15029 28734 15099 28734 15098 28734 15064 28735 15026 28735 15029 28735 15026 28736 15003 28736 14969 28736 14805 28737 14704 28737 14830 28737 14704 28738 14805 28738 14774 28738 14774 28739 14741 28739 14704 28739 14704 28740 14773 28740 14803 28740 14892 28741 14905 28741 14924 28741 15165 28742 15159 28742 15099 28742 15127 28743 15098 28743 15099 28743 14676 28744 14740 28744 14775 28744 14704 28745 14741 28745 14676 28745 14786 28746 14815 28746 14712 28746 14749 28747 14787 28747 14712 28747 14810 28748 14783 28748 14712 28748 14814 28749 14810 28749 14712 28749 14712 28750 14686 28750 14749 28750 15168 28751 15214 28751 15209 28751 15209 28752 15204 28752 15215 28752 15210 28753 15163 28753 15209 28753 15209 28754 15215 28754 15168 28754 14676 28755 14744 28755 14705 28755 15099 28756 15128 28756 15165 28756 15210 28757 15211 28757 15128 28757 15128 28758 15163 28758 15210 28758 14676 28759 14776 28759 14777 28759 15246 28760 15268 28760 15204 28760 15156 28761 15202 28761 15204 28761 15267 28762 15271 28762 15204 28762 14652 28763 14743 28763 14763 28763 14652 28764 14705 28764 14742 28764 14652 28765 14676 28765 14705 28765 14792 28766 14820 28766 14821 28766 14716 28767 14819 28767 14792 28767 14818 28768 14793 28768 14833 28768 14749 28769 14716 28769 14793 28769 14749 28770 14686 28770 14716 28770 14658 28771 14717 28771 14686 28771 15125 28772 15158 28772 15096 28772 15096 28773 15060 28773 15124 28773 15155 28774 15122 28774 15096 28774 15096 28775 15059 28775 15060 28775 14652 28776 14733 28776 14746 28776 15025 28777 15060 28777 14989 28777 14989 28778 14952 28778 15025 28778 14708 28779 14678 28779 14652 28779 15156 28780 15122 28780 15202 28780 14652 28781 14732 28781 14733 28781 14952 28782 14953 28782 14984 28782 14985 28783 15021 28783 14952 28783 14632 28784 14707 28784 14729 28784 14632 28785 14678 28785 14706 28785 14730 28786 14710 28786 14632 28786 14632 28787 14652 28787 14678 28787 14658 28788 14689 28788 14721 28788 14717 28789 14658 28789 14754 28789 14640 28790 14660 28790 14658 28790 14722 28791 14753 28791 14658 28791 14836 28792 14824 28792 14861 28792 14887 28793 14836 28793 14888 28793 14632 28794 14681 28794 14653 28794 14919 28795 14887 28795 14920 28795 14952 28796 14919 28796 14953 28796 14632 28797 14710 28797 14681 28797 14824 28798 14859 28798 14886 28798 14614 28799 14653 28799 14679 28799 14696 28800 14683 28800 14614 28800 14614 28801 14632 28801 14653 28801 14621 28802 14642 28802 14665 28802 14692 28803 14660 28803 14621 28803 14660 28804 14640 28804 14621 28804 14835 28805 14824 28805 14823 28805 14760 28806 14794 28806 14797 28806 14605 28807 14635 28807 14648 28807 14693 28808 14756 28808 14760 28808 14693 28809 14724 28809 14756 28809 14636 28810 14605 28810 14648 28810 14693 28811 14657 28811 14723 28811 14617 28812 14605 28812 14636 28812 14824 28813 14835 28813 14858 28813 14614 28814 14683 28814 14682 28814 14654 28815 14634 28815 14614 28815 14605 28816 14614 28816 14635 28816 14608 28817 14663 28817 14664 28817 14608 28818 14644 28818 14663 28818 14608 28819 14625 28819 14644 28819 14642 28820 14621 28820 14608 28820 14602 28821 14601 28821 14606 28821 14607 28822 14618 28822 14602 28822 14601 28823 14619 28823 14606 28823 14601 28824 14638 28824 14619 28824 14618 28825 14624 28825 14602 28825 14656 28826 14684 28826 14657 28826 14638 28827 14601 28827 14657 28827 14601 28828 14637 28828 14655 28828 14684 28829 14711 28829 14657 28829 14711 28830 14723 28830 14657 28830 14601 28831 14616 28831 14637 28831 14601 28832 14655 28832 14656 28832 14605 28833 14617 28833 14601 28833 14608 28834 14602 28834 14624 28834 14602 28835 14598 28835 14597 28835 14593 28836 14592 28836 14597 28836 14597 28837 14596 28837 14600 28837 14600 28838 14604 28838 14605 28838 14604 28839 14615 28839 14614 28839 14615 28840 14633 28840 14632 28840 14633 28841 14651 28841 14652 28841 14651 28842 14677 28842 14676 28842 14677 28843 14703 28843 14704 28843 14703 28844 14739 28844 14738 28844 14738 28845 14739 28845 14771 28845 14770 28846 14801 28846 14802 28846 14801 28847 14826 28847 14827 28847 14826 28848 14841 28848 14842 28848 14841 28849 14870 28849 14842 28849 14870 28850 14900 28850 14901 28850 14900 28851 14933 28851 14901 28851 14932 28852 14933 28852 14965 28852 14966 28853 14965 28853 14997 28853 14997 28854 15034 28854 14998 28854 15034 28855 15070 28855 15035 28855 15135 28856 15132 28856 15106 28856 15106 28857 15102 28857 15068 28857 15068 28858 15067 28858 15071 28858 15072 28859 15067 28859 15145 28859 15145 28860 15131 28860 15081 28860 15081 28861 15118 28861 15014 28861 15014 28862 15054 28862 14980 28862 14944 28863 14980 28863 14915 28863 14877 28864 14915 28864 14856 28864 14832 28865 14856 28865 14807 28865 14807 28866 14779 28866 14778 28866 14778 28867 14779 28867 14748 28867 14747 28868 14713 28868 14712 28868 14713 28869 14685 28869 14686 28869 14685 28870 14659 28870 14658 28870 14659 28871 14639 28871 14640 28871 14639 28872 14620 28872 14621 28872 14620 28873 14609 28873 14608 28873 14609 28874 14603 28874 14602 28874 14602 28875 14603 28875 14599 28875 14611 28876 14610 28876 14606 28876 14809 28877 14829 28877 14828 28877 14838 28878 14847 28878 14828 28878 14618 28879 14607 28879 14627 28879 14606 28880 14619 28880 14626 28880 14619 28881 14638 28881 14626 28881 14657 28882 14693 28882 14645 28882 14645 28883 14638 28883 14657 28883 14693 28884 14725 28884 14667 28884 14693 28885 14760 28885 14759 28885 14760 28886 14797 28886 14759 28886 14824 28887 14836 28887 14837 28887 14796 28888 14797 28888 14824 28888 14836 28889 14862 28889 14837 28889 14887 28890 14891 28890 14862 28890 14919 28891 14923 28891 14891 28891 14952 28892 14989 28892 14988 28892 14989 28893 15024 28893 14988 28893 14923 28894 14919 28894 14952 28894 14989 28895 15059 28895 15024 28895 15059 28896 15096 28896 15058 28896 15096 28897 15122 28897 15058 28897 15156 28898 15204 28898 15203 28898 15204 28899 15248 28899 15203 28899 15095 28900 15122 28900 15156 28900 15204 28901 15209 28901 15208 28901 15209 28902 15163 28902 15208 28902 15163 28903 15128 28903 15100 28903 15099 28904 15029 28904 15063 28904 15100 28905 15128 28905 15099 28905 15029 28906 15028 28906 15063 28906 15028 28907 15029 28907 14957 28907 14969 28908 14937 28908 14925 28908 14905 28909 14847 28909 14893 28909 14925 28910 14937 28910 14905 28910 14847 28911 14838 28911 14893 28911 14811 28912 14782 28912 14780 28912 14783 28913 14808 28913 14781 28913 14783 28914 14810 28914 14808 28914 14781 28915 14780 28915 14782 28915 14810 28916 14814 28916 14812 28916 14815 28917 14813 28917 14814 28917 14786 28918 14784 28918 14815 28918 14787 28919 14785 28919 14786 28919 14749 28920 14751 28920 14714 28920 14749 28921 14793 28921 14751 28921 14785 28922 14787 28922 14749 28922 14818 28923 14788 28923 14793 28923 14833 28924 14816 28924 14818 28924 14821 28925 14789 28925 14816 28925 14820 28926 14817 28926 14821 28926 14792 28927 14750 28927 14817 28927 14819 28928 14790 28928 14792 28928 14716 28929 14717 28929 14752 28929 14790 28930 14819 28930 14716 28930 14754 28931 14791 28931 14717 28931 14753 28932 14755 28932 14791 28932 14722 28933 14719 28933 14755 28933 14722 28934 14721 28934 14719 28934 14721 28935 14689 28935 14687 28935 14687 28936 14689 28936 14660 28936 14692 28937 14718 28937 14688 28937 14666 28938 14690 28938 14718 28938 14665 28939 14691 28939 14690 28939 14642 28940 14661 28940 14641 28940 14642 28941 14664 28941 14661 28941 14641 28942 14691 28942 14665 28942 14664 28943 14663 28943 14662 28943 14663 28944 14644 28944 14662 28944 14625 28945 14622 28945 14644 28945 14625 28946 14624 28946 14622 28946 14623 28947 14643 28947 14644 28947 14624 28948 14618 28948 14622 28948 14655 28949 14647 28949 14656 28949 14831 28950 14825 28950 14800 28950 14768 28951 14772 28951 14804 28951 14694 28952 14684 28952 14668 28952 14647 28953 14655 28953 14637 28953 14629 28954 14637 28954 14612 28954 14636 28955 14648 28955 14628 28955 14636 28956 14628 28956 14617 28956 14648 28957 14646 28957 14628 28957 14648 28958 14631 28958 14646 28958 14612 28959 14616 28959 14617 28959 14628 28960 14613 28960 14617 28960 14635 28961 14630 28961 14648 28961 14635 28962 14634 28962 14630 28962 14654 28963 14649 28963 14630 28963 14649 28964 14654 28964 14682 28964 14683 28965 14650 28965 14673 28965 14670 28966 14669 28967 14673 28968 14669 28969 14682 28969 14683 28969 14696 28970 14671 28970 14650 28970 14671 28971 14696 28971 14680 28971 14679 28972 14695 28972 14672 28972 14681 28973 14710 28973 14653 28973 14730 28974 14699 28974 14700 28974 14709 28975 14679 28975 14653 28975 14709 28976 14695 28976 14679 28976 14675 28977 14699 28977 14730 28977 14729 28978 14697 28978 14675 28978 14697 28979 14729 28979 14707 28979 14698 28980 14707 28980 14727 28980 14746 28981 14731 28981 14762 28981 14745 28982 14678 28982 14708 28982 14733 28983 14702 28983 14746 28983 14728 28984 14706 28984 14745 28984 14732 28985 14701 28985 14733 28985 14728 28986 14727 28986 14706 28986 14732 28987 14763 28987 14701 28987 14701 28988 14763 28988 14743 28988 14734 28989 14743 28989 14742 28989 14705 28990 14744 28991 14742 28992 14764 28993 14735 28993 14744 28993 14776 28994 14775 28994 14766 28994 14764 28995 14777 28995 14776 28995 14775 28996 14767 28996 14766 28996 14740 28997 14736 28997 14767 28997 14741 28998 14765 28998 14737 28998 14741 28999 14774 28999 14765 28999 14737 29000 14736 29000 14740 29000 14799 29001 14805 29001 14803 29001 14798 29002 14774 29002 14805 29002 14773 29003 14769 29003 14803 29003 14798 29004 14765 29004 14774 29004 14772 29005 14768 29005 14769 29005 14825 29006 14831 29006 14864 29006 14924 29007 14956 29007 14926 29007 14956 29008 14958 29008 14926 29008 14894 29009 14864 29009 14892 29009 14864 29010 14863 29010 14892 29010 15003 29011 15026 29011 14990 29011 15026 29012 15027 29012 14990 29012 14958 29013 14956 29013 15003 29013 15064 29014 15097 29014 15027 29014 15097 29015 15098 29015 15062 29015 15098 29016 15127 29016 15126 29016 15061 29017 15062 29017 15098 29017 15159 29018 15160 29018 15127 29018 15165 29019 15207 29019 15161 29019 15165 29020 15164 29020 15207 29020 15160 29021 15159 29021 15165 29021 15211 29022 15213 29022 15164 29022 15210 29023 15214 29023 15213 29023 15214 29024 15167 29024 15213 29024 15168 29025 15166 29025 15129 29025 15214 29026 15168 29026 15129 29026 15215 29027 15249 29027 15212 29027 15166 29028 15168 29028 15215 29028 15271 29029 15267 29029 15215 29029 15267 29030 15268 29030 15249 29030 15268 29031 15284 29031 15270 29031 15269 29032 15284 29032 15268 29032 15246 29033 15202 29033 15269 29033 15202 29034 15155 29034 15247 29034 15206 29035 15205 29035 15158 29035 15125 29036 15157 29036 15206 29036 15124 29037 15123 29037 15157 29037 15025 29038 15021 29038 15060 29038 15023 29039 15056 29039 15021 29039 15124 29040 15060 29040 15056 29040 15022 29041 15023 29041 14985 29041 14984 29042 14987 29042 15022 29042 14953 29043 14920 29043 14986 29043 14987 29044 14984 29044 14953 29044 14920 29045 14954 29045 14986 29045 14861 29046 14922 29046 14921 29046 14955 29047 14954 29047 14921 29047 14954 29048 14920 29048 14888 29048 14860 29049 14890 29049 14889 29049 14860 29050 14886 29050 14890 29050 14889 29051 14922 29051 14861 29051 14859 29052 14857 29052 14885 29052 14859 29053 14858 29053 14857 29053 14885 29054 14890 29054 14886 29054 14835 29055 14823 29055 14834 29055 14823 29056 14822 29056 14834 29056 14857 29057 14858 29057 14835 29057 14794 29058 14756 29058 14795 29058 14756 29059 14758 29059 14795 29059 14822 29060 14823 29060 14794 29060 14723 29061 14711 29061 14757 29061 14711 29062 14726 29062 14761 29062 14757 29063 14758 29063 14723 29063 14758 29064 14756 29064 14724 29064 14726 29065 14711 29065 14694 29065 14839 29066 14865 29066 14845 29066 14845 29067 14866 29067 14839 29067 15133 29068 15109 29068 15108 29068 15107 29069 15103 29069 15133 29069 15108 29070 15109 29070 15075 29070 14850 29071 14846 29071 14873 29071 14843 29072 14867 29072 14840 29072 14845 29073 14843 29073 14866 29073 14904 29074 14895 29074 14844 29074 14867 29075 14843 29075 14844 29075 14844 29076 14872 29076 14904 29076 14872 29077 14903 29077 14904 29077 14902 29078 14898 29078 14897 29078 14868 29079 14898 29079 14902 29079 14927 29080 14896 29080 14868 29080 14871 29081 14936 29081 14927 29081 14935 29082 14928 29082 14927 29082 14930 29083 14928 29083 14961 29083 14959 29084 14929 29084 14899 29084 14934 29085 14968 29085 14959 29085 14961 29086 14934 29086 14899 29086 14992 29087 14960 29087 14959 29087 15030 29088 14991 29088 14992 29088 14963 29089 14991 29089 14994 29089 14993 29090 14962 29090 14967 29090 14994 29091 14967 29091 14963 29091 14967 29092 15002 29092 14993 29092 15031 29093 14993 29093 15002 29093 15041 29094 14996 29094 15031 29094 15040 29095 15032 29095 14995 29095 14996 29096 14999 29096 14995 29096 14996 29097 15041 29097 14999 29097 15033 29098 15032 29098 15040 29098 15065 29099 15033 29099 15066 29099 15042 29100 15065 29100 15101 29100 15037 29101 15036 29101 15039 29101 15073 29102 15037 29102 15000 29102 15036 29103 15038 29103 15039 29103 15074 29104 15075 29104 15038 29104 15176 29105 15134 29105 15103 29105 15103 29106 15107 29106 15136 29106 15178 29107 15222 29107 15176 29107 15223 29108 15254 29108 15272 29108 15254 29109 15285 29109 15272 29109 15222 29110 15178 29110 15223 29110 15276 29111 15288 29111 15254 29111 15302 29112 15299 29112 15275 29112 15288 29113 15276 29113 15275 29113 15291 29114 15307 29114 15275 29114 15290 29115 15308 29115 15291 29115 15305 29116 15320 29116 15290 29116 15304 29117 15321 29117 15305 29117 15319 29118 15327 29118 15321 29118 15313 29119 15325 29119 15327 29119 15315 29120 15324 29120 15313 29120 15296 29121 15295 29121 15323 29121 15324 29122 15315 29122 15296 29122 15295 29123 15311 29123 15312 29123 15281 29124 15294 29124 15311 29124 15280 29125 15293 29125 15281 29125 15261 29126 15278 29126 15293 29126 15231 29127 15260 29127 15278 29127 15278 29128 15261 29128 15233 29128 15233 29129 15185 29129 15231 29129 15185 29130 15184 29130 15230 29130 15184 29131 15228 29131 15230 29131 15140 29132 15183 29132 15228 29132 15139 29133 15138 29133 15183 29133 15078 29134 15114 29134 15138 29134 15078 29135 15046 29135 15111 29135 15009 29136 15044 29136 15046 29136 15077 29137 15111 29137 15046 29137 15007 29138 15044 29138 15009 29138 14971 29139 15006 29139 15007 29139 14941 29140 14939 29140 14971 29140 15007 29141 15008 29141 14941 29141 14939 29142 14906 29142 14970 29142 14906 29143 14938 29143 14970 29143 14874 29144 14917 29144 14906 29144 14851 29145 14873 29145 14874 29145 14851 29146 14850 29146 14873 29146 14880 29147 14917 29147 14874 29147 14884 29148 14883 29148 14855 29148 15175 29149 15174 29149 15218 29149 15174 29150 15179 29150 15180 29150 15226 29151 15177 29151 15173 29151 15177 29152 15179 29152 15174 29152 14849 29153 14854 29153 14879 29153 14853 29154 14881 29154 14855 29154 14852 29155 14875 29155 14882 29155 14908 29156 14950 29156 14875 29156 14881 29157 14853 29157 14882 29157 14907 29158 14940 29158 14950 29158 14940 29159 14982 29159 14951 29159 14950 29160 14908 29160 14907 29160 14940 29161 14942 29161 14982 29161 14942 29162 14973 29162 14983 29162 14972 29163 15045 29163 15004 29163 15004 29164 14973 29164 14972 29164 14972 29165 15011 29165 15045 29165 15010 29166 15076 29166 15043 29166 15010 29167 15048 29167 15113 29167 15045 29168 15011 29168 15010 29168 15047 29169 15079 29169 15048 29169 15116 29170 15112 29170 15079 29170 15182 29171 15137 29171 15110 29171 15115 29172 15142 29172 15182 29172 15112 29173 15116 29173 15110 29173 15141 29174 15181 29174 15142 29174 15187 29175 15229 29175 15141 29175 15188 29176 15227 29176 15187 29176 15188 29177 15256 29177 15227 29177 15188 29178 15186 29178 15256 29178 15186 29179 15232 29179 15257 29179 15292 29180 15279 29180 15259 29180 15234 29181 15263 29181 15292 29181 15258 29182 15232 29182 15234 29182 15262 29183 15322 29183 15309 29183 15262 29184 15283 29184 15322 29184 15310 29185 15263 29185 15309 29185 15282 29186 15330 29186 15283 29186 15298 29187 15335 29187 15282 29187 15314 29188 15326 29188 15333 29188 15332 29189 15335 29189 15297 29189 15326 29190 15334 29190 15333 29190 15335 29191 15298 29191 15297 29191 15318 29192 15317 29192 15328 29192 15334 29193 15326 29193 15318 29193 15317 29194 15329 29194 15328 29194 15303 29195 15301 29195 15316 29195 15316 29196 15329 29196 15303 29196 15303 29197 15306 29197 15301 29197 15306 29198 15289 29198 15286 29198 15274 29199 15277 29200 15289 29201 15277 29202 15287 29202 15286 29202 15255 29203 15225 29203 15273 29203 15225 29204 15224 29204 15253 29204 15273 29205 15287 29205 15255 29205 15173 29206 15172 29206 15252 29206 15224 29207 15226 29207 15173 29207 15219 29208 15171 29208 15175 29208 15217 29209 15170 29209 15171 29209 15250 29210 15264 29210 15251 29210 15235 29211 15190 29211 15264 29211 15169 29212 15216 29212 15220 29212 15190 29213 15193 29213 15237 29213 15170 29214 15217 29214 15169 29214 15193 29215 15238 29215 15237 29215 15195 29216 15240 29216 15193 29216 15197 29217 15242 29217 15195 29217 15196 29218 15243 29218 15197 29218 15194 29219 15241 29219 15196 29219 15192 29220 15239 29220 15194 29220 15189 29221 15143 29221 15266 29221 15265 29222 15236 29222 15189 29222 15144 29223 15199 29223 15143 29223 15144 29224 15200 29224 15199 29224 15236 29225 15239 29225 15189 29225 15239 29226 15192 29226 15191 29226 15117 29227 15080 29227 15144 29227 15080 29228 15082 29228 15146 29228 15082 29229 15084 29229 15146 29229 15084 29230 15150 29230 15147 29230 15086 29231 15152 29231 15150 29231 15088 29232 15153 29232 15086 29232 15087 29233 15151 29233 15153 29233 15085 29234 15148 29234 15087 29234 15121 29235 15201 29235 15244 29235 15244 29236 15198 29236 15121 29236 15121 29237 15120 29237 15154 29237 15149 29238 15148 29238 15121 29238 15148 29239 15085 29239 15083 29239 15052 29240 15091 29240 15121 29240 15052 29241 15051 29241 15091 29241 15051 29242 15053 29242 15093 29242 15053 29243 15050 29243 15090 29243 15013 29244 15012 29245 15049 29246 15012 29247 15119 29247 15089 29247 15089 29248 15090 29248 15049 29248 15016 29249 15055 29249 15119 29249 15119 29250 15012 29250 15016 29250 14977 29251 14976 29251 15017 29251 14976 29252 14979 29252 15019 29252 14979 29253 14978 29253 15018 29253 14974 29254 14943 29255 14975 29256 14943 29257 14945 29257 15020 29257 15015 29258 14978 29258 14975 29258 14910 29259 14948 29259 14945 29259 15015 29260 15018 29260 14978 29260 14910 29261 14911 29261 14948 29261 14911 29262 14914 29262 14949 29262 14914 29263 14913 29263 14949 29263 14909 29264 14876 29264 14916 29264 14848 29265 14879 29265 14878 29265 14947 29266 14913 29266 14916 29266 14848 29267 14849 29267 14879 29267 14876 29268 14848 29268 14916 29268 14947 29269 14946 29269 14913 29269 12361 29270 12362 29270 12363 29270 12870 29271 12900 29271 12838 29271 12872 29272 12900 29272 12873 29272 12365 29273 12366 29273 12362 29273 12838 29274 12872 29274 12873 29274 12367 29275 12363 29275 12362 29275 12364 29276 12360 29276 12367 29276 12368 29277 12364 29277 12367 29277 12368 29278 12371 29278 12378 29278 12368 29279 12413 29279 12436 29279 12381 29280 12372 29280 12380 29280 12391 29281 12390 29281 12371 29281 12602 29282 12590 29282 12563 29282 12526 29283 12493 29283 12563 29283 12435 29284 12493 29284 12525 29284 12653 29285 12625 29286 12602 29287 12417 29288 12437 29288 12438 29288 12383 29289 12372 29289 12398 29289 12409 29290 12429 29290 12430 29290 12658 29291 12630 29291 12657 29291 12658 29292 12653 29292 12630 29292 12691 29293 12723 29293 12659 29293 12657 29294 12659 29294 12689 29294 12441 29295 12442 29296 12418 29297 12754 29298 12722 26228 12723 26227 12418 29297 12439 29299 12440 25564 12477 29300 12401 29300 12440 29300 12458 29301 12459 29301 12409 29301 12456 29302 12486 29303 12458 29304 12790 29305 12825 29305 12791 29305 12791 29306 12826 29306 12824 29306 12468 29307 12467 29308 12443 29309 12755 29310 12754 29310 12792 29310 12755 29311 12792 29311 12790 29311 12824 29312 12863 29312 12925 29312 12863 29313 12973 29313 12925 29313 12466 29314 12495 29315 12496 29316 12443 29317 12465 29317 12466 29317 12487 29318 12488 29319 12455 29320 12427 29321 12520 29321 12523 29321 12456 29322 12407 29322 12455 29322 12976 29323 12980 29323 13038 29323 13052 29324 13037 29324 13038 29324 12868 29325 12898 29325 12930 29325 12898 29326 12868 29326 12897 29326 12470 29327 12419 29327 12530 29327 13016 29328 13037 29328 13015 29328 12831 29329 12975 29329 12935 29329 12469 29330 12502 29331 12503 29332 12534 29333 12445 29333 12503 29333 12445 29334 12419 29334 12469 29334 12518 29335 12519 29335 12556 29335 12483 29336 12482 29336 12518 29336 12482 29337 12483 29337 12453 29337 12726 29338 12725 29338 12694 29338 12796 29339 12795 29339 12829 29339 12796 29340 12725 29340 12795 29340 12694 29341 12693 29341 12662 29341 12831 29342 12894 29342 12929 29342 12534 29343 12535 29343 12504 29343 12505 29344 12471 29344 12504 29344 12481 29345 12580 29345 12552 29345 12553 29346 12482 29346 12552 29346 12507 29347 12597 29347 12515 29347 12606 29348 12632 29348 12662 29348 12537 29349 12536 29349 12507 29349 12515 29350 12548 29350 12549 29350 12507 29351 12515 29351 12538 29351 12547 29352 12575 29352 12538 29352 12635 29353 12594 29353 12608 29353 12569 29354 12575 29354 12633 29354 12641 29355 12575 29355 12652 29355 12624 29356 12646 29356 12647 29356 12739 29357 12772 29357 12773 29357 12772 29358 12739 29358 12751 29358 12738 29359 12706 29359 12750 29359 12713 29360 12716 29360 12717 29360 12664 29361 12609 29361 12636 29361 12718 29362 12706 29362 12686 29362 12665 29363 12666 29364 12636 29365 12686 29366 12685 29366 12650 29366 12879 29367 12845 29367 12880 29367 12785 29368 12787 29368 12786 29368 12683 29369 12748 29369 12786 29369 12905 29370 12882 29370 12878 29370 12774 29371 12773 29371 12813 29371 12813 29372 12811 29372 12775 29372 12811 29373 12844 29373 12812 29373 12697 29374 12638 29374 12667 29374 12664 29375 12695 29376 12696 29377 12667 29378 12609 29378 12696 29378 13026 29379 12999 29379 13025 29379 13027 29380 13028 29380 12999 29380 12998 29381 12996 29381 13024 29381 12859 29382 12860 29382 12861 29382 12748 29383 12822 29383 12858 29383 12997 29384 12995 29384 12951 29384 12906 29385 12949 29385 12997 29385 12857 29386 12887 29387 12862 29388 12905 29389 12950 29389 12949 29389 12730 29390 12668 29390 12699 29390 12731 29391 12638 29391 12728 29391 12697 29392 12727 29392 12728 29392 13100 29393 13093 29393 13091 29393 12968 29394 12914 29394 12967 29394 13102 29395 13096 29395 13093 29395 13091 29396 13098 29396 13100 29396 13080 29397 13090 29397 13098 29397 12822 29398 12920 29398 12919 29398 12915 29399 12918 29399 12920 29399 12917 29400 12822 29400 12919 29400 12886 29401 12914 29401 12915 29401 13090 29402 13080 29402 13062 29402 13078 29403 13061 29403 13060 29403 13078 29404 13077 29404 13061 29404 12922 29405 12822 29405 13012 29405 13046 29406 13028 29406 13047 29406 12763 29407 12701 29407 12732 29407 12764 29408 12668 29408 12761 29408 13053 29409 13056 29409 13054 29409 13056 29410 13067 29410 13069 29410 13041 29411 13040 29411 13055 29411 12899 29412 13010 29412 13009 29412 13006 29413 13008 29413 13010 29413 13004 29414 12899 29414 13009 29414 13089 29415 13095 29415 13076 29415 13097 29416 13084 29416 13070 29416 13084 29417 13068 29417 13070 29417 12807 29418 12733 29418 12768 29418 12763 29419 12800 29420 12801 29421 12810 29422 12701 29422 12801 29422 13020 29423 12989 29423 12990 29423 12941 29424 12902 29424 12944 29424 12988 29425 12899 29425 12937 29425 12877 29426 12901 29426 12871 29426 12990 29427 13040 29427 13021 29427 12765 29428 12733 29428 12806 29428 12802 29429 12765 29429 12835 29429 12870 29430 12838 29430 12802 29430 12874 29431 12837 29431 12873 29431 12874 29432 12839 29432 12837 29432 12803 29433 12839 29433 12766 29433 12840 29434 12875 29434 12876 29434 12947 29435 12945 29435 12904 29435 12946 29436 12945 29436 12994 29436 12985 29437 12840 29437 12984 29437 12766 29438 12804 29438 12805 29438 13059 29439 13043 29439 13057 29439 13071 29440 13073 29440 13074 29440 13045 29441 13044 29441 13023 29441 13043 29442 13044 29442 13045 29442 13086 29443 13087 29443 13085 29443 12964 29444 12965 29444 12849 29444 12965 29445 12963 29445 12849 29445 12962 29446 12849 29446 12960 29446 12961 29447 12958 29447 12849 29447 12991 29448 12993 29448 13023 29448 12834 29449 12734 29449 12869 29449 12834 29450 12808 29450 12734 29450 13066 29451 13063 29451 13065 29451 13049 29452 13063 29452 13066 29452 12849 29453 12885 29453 12912 29453 13029 29454 13048 29454 13051 29454 13051 29455 13048 29455 13050 29455 13065 29456 13064 29456 13083 29456 13002 29457 13001 29457 13031 29457 12856 29458 12854 29458 12782 29458 12855 29459 12782 29459 12853 29459 12854 29460 12852 29460 12782 29460 12850 29461 12848 29461 12782 29461 13082 29462 13081 29462 13094 29462 12735 29463 12700 29463 12770 29463 12769 29464 12700 29464 12809 29464 12956 29465 12955 29465 12952 29465 12955 29466 12909 29466 12952 29466 12910 29467 12883 29467 12907 29467 12908 29468 12909 29468 12910 29468 12781 29469 12712 29469 12780 29469 12953 29470 13001 29470 13000 29470 12821 29471 12782 29471 12818 29471 12821 29472 12819 29472 12782 29472 12760 29473 12669 29473 12798 29473 12760 29474 12736 29474 12669 29474 12779 29475 12740 29475 12776 29475 12777 29476 12778 29476 12779 29476 12777 29477 12814 29477 12815 29477 12816 29478 12778 29478 12777 29478 12743 29479 12645 29479 12742 29479 12884 29480 12847 29480 12846 29480 12747 29481 12712 29481 12746 29481 12747 29482 12744 29482 12712 29482 12639 29483 12637 29483 12704 29483 12703 29484 12637 29484 12729 29484 12709 29485 12710 29485 12708 29485 12708 29486 12675 29486 12707 29486 12642 29487 12674 29487 12676 29487 12619 29488 12642 29488 12643 29488 12741 29489 12710 29489 12709 29489 12678 29490 12600 29490 12679 29490 12671 29491 12595 29491 12670 29491 12613 29492 12614 29492 12574 29492 12623 29493 12574 29493 12619 29493 12617 29494 12616 29494 12574 29494 12612 29495 12611 29495 12570 29495 12539 29496 12570 29496 12574 29496 12516 29497 12506 29497 12539 29497 12506 29498 12516 29498 12579 29498 12615 29499 12673 29499 12631 29499 12541 29500 12472 29500 12540 29500 12516 29501 12480 29501 12550 29501 12705 29502 12737 29502 12724 29502 12865 29503 12832 29503 12797 29503 12794 29504 12737 29504 12797 29504 12673 29505 12705 29505 12692 29505 12927 29506 12895 29506 12867 29506 12544 29507 12444 29507 12543 29507 12509 29508 12508 29508 12444 29508 12583 29509 12582 29509 12480 29509 12555 29510 12554 29510 12480 29510 12982 29511 12978 29511 12977 29511 12972 29512 13039 29512 12983 29512 12896 29513 12932 29513 12933 29513 12979 29514 12932 29514 12896 29514 12512 29515 12444 29515 12545 29515 13036 29516 13035 29516 12972 29516 12970 29517 13014 29517 12972 29517 12500 29518 12420 29518 12531 29518 12511 29519 12420 29519 12510 29519 12561 29520 12560 29520 12589 29520 12561 29521 12589 29521 12601 29521 12484 29522 12560 29522 12561 29522 12485 29523 12484 29523 12454 29523 12926 29524 12923 29524 12864 29524 12893 29525 12864 29525 12892 29525 12828 29526 12827 29526 12757 29526 12720 29527 12789 29527 12793 29527 12514 29528 12476 29528 12420 29528 12890 29529 12923 29529 12970 29529 12753 29530 12720 29530 12752 29530 12498 29531 12400 29531 12497 29531 12475 29532 12400 29532 12474 29532 12490 29533 12426 29533 12489 29533 12426 29534 12521 29534 12522 29534 12428 29535 12457 29535 12426 29535 12592 29536 12628 29536 12629 29536 12604 29537 12629 29537 12656 29537 12655 29538 12656 29538 12688 29538 12687 29539 12688 29539 12721 29539 12628 29540 12592 29540 12654 29540 12448 29541 12382 29541 12447 29541 12448 29542 12464 29542 12382 29542 12434 29543 12389 29543 12433 29543 12434 29544 12460 29544 12389 29544 12592 29545 12565 29545 12591 29545 12562 29546 12591 29546 12565 29546 12524 29547 12562 29547 12528 29547 12492 29548 12461 29548 12491 29548 12627 29549 12592 29549 12626 29549 12422 29550 12382 29550 12450 29550 12382 29551 12402 29551 12403 29551 12410 29552 12376 29552 12432 29552 12375 29553 12370 29553 12374 29553 12369 29554 12424 29554 12425 29554 12385 29555 12384 29555 12369 29555 12393 29556 12376 29556 12392 29556 12369 29557 12370 29557 12365 29557 12365 29558 12361 29558 12364 29558 12364 29559 12368 29559 12369 29559 12372 29560 12373 29560 12369 29560 12383 29561 12382 29561 12373 29561 12401 29562 12400 29562 12382 29562 12419 29563 12420 29563 12400 29563 12445 29564 12444 29564 12420 29564 12471 29565 12472 29565 12444 29565 12472 29566 12471 29566 12506 29566 12539 29567 12506 29567 12538 29567 12539 29568 12538 29568 12570 29568 12570 29569 12569 29569 12595 29569 12595 29570 12594 29570 12610 29570 12610 29571 12609 29571 12637 29571 12637 29572 12638 29572 12669 29572 12669 29573 12668 29573 12700 29573 12701 29574 12733 29574 12734 29574 12766 29575 12734 29575 12765 29575 12766 29576 12765 29576 12803 29576 12803 29577 12802 29577 12837 29577 12874 29578 12903 29578 12870 29578 12839 29579 12874 29579 12836 29579 12835 29580 12840 29580 12839 29580 12913 29581 12840 29581 12899 29581 12849 29582 12913 29582 12886 29582 12782 29583 12849 29583 12822 29583 12712 29584 12782 29584 12748 29584 12645 29585 12712 29585 12683 29585 12600 29586 12645 29586 12624 29586 12574 29587 12600 29587 12575 29587 12574 29588 12575 29588 12546 29588 12516 29589 12546 29589 12515 29589 12516 29590 12515 29590 12480 29590 12480 29591 12481 29591 12454 29591 12454 29592 12453 29592 12426 29592 12426 29593 12427 29593 12408 29593 12408 29594 12407 29594 12389 29594 12389 29595 12388 29595 12376 29595 12371 29596 12370 29596 12376 29596 12371 29597 12367 29597 12366 29597 12374 29598 12379 29598 12375 29598 12597 29599 12596 29599 12579 29599 12615 29600 12596 29600 12597 29600 12375 29601 12378 29601 12395 29601 12379 29602 12374 29602 12394 29602 12394 29603 12387 29603 12413 29603 12413 29604 12425 29604 12435 29604 12493 29605 12461 29605 12527 29605 12527 29606 12528 29606 12564 29606 12564 29607 12592 29607 12605 29607 12604 29608 12655 29608 12630 29608 12655 29609 12687 29609 12659 29609 12691 29610 12720 29610 12756 29610 12792 29611 12757 29611 12825 29611 12825 29612 12827 29612 12826 29612 12826 29613 12864 29613 12863 29613 12863 29614 12924 29614 12971 29614 13016 29615 12972 29615 12976 29615 12976 29616 12977 29616 12930 29616 12896 29617 12868 29617 12930 29617 12868 29618 12867 29618 12831 29618 12725 29619 12796 29619 12737 29619 12705 29620 12693 29620 12725 29620 12615 29621 12661 29621 12693 29621 12550 29622 12548 29622 12577 29622 12576 29623 12549 29623 12550 29623 12582 29624 12580 29624 12576 29624 12582 29625 12583 29625 12580 29625 12552 29626 12581 29626 12583 29626 12554 29627 12555 29627 12552 29627 12553 29628 12517 29628 12482 29628 12561 29629 12586 29629 12519 29629 12584 29630 12556 29630 12586 29630 12557 29631 12584 29631 12601 29631 12585 29632 12557 29632 12589 29632 12518 29633 12585 29633 12588 29633 12558 29634 12518 29634 12560 29634 12483 29635 12484 29635 12520 29635 12587 29636 12484 29636 12483 29636 12559 29637 12520 29637 12485 29637 12523 29638 12559 29638 12522 29638 12521 29639 12490 29639 12523 29639 12487 29640 12490 29640 12488 29640 12488 29641 12489 29641 12455 29641 12456 29642 12455 29642 12428 29642 12428 29643 12460 29643 12456 29643 12460 29644 12434 29644 12486 29644 12434 29645 12433 29645 12458 29645 12433 29646 12410 29646 12409 29646 12429 29647 12432 29647 12430 29647 12430 29648 12431 29648 12411 29648 12412 29649 12393 29649 12391 29649 12390 29650 12392 29650 12395 29650 12424 29651 12423 29651 12436 29651 12593 29652 12568 29652 12572 29652 12540 29653 12572 29653 12568 29653 12436 29654 12462 29654 12424 29654 12397 29655 12415 29655 12405 29655 12380 29656 12397 29656 12384 29656 12384 29657 12385 29657 12381 29657 12416 29658 12403 29658 12399 29658 12402 29659 12422 29659 12398 29659 12437 29660 12417 29660 12450 29660 12418 29297 12442 29296 12441 29295 12437 29661 12451 29661 12441 29661 12451 29662 12464 29662 12418 29662 12440 29663 12439 29663 12448 29663 12448 29664 12447 29664 12440 29664 12478 29665 12468 29665 12421 29665 12478 29666 12498 29666 12468 29666 12468 29667 12477 29667 12421 29667 12497 29668 12443 29668 12498 29668 12466 29669 12465 29669 12475 29669 12495 29670 12466 29670 12474 29670 12499 29671 12530 29672 12513 29673 12446 29674 12476 29675 12514 29676 12514 29677 12501 29677 12499 29677 12513 29678 12496 29678 12446 29678 12501 29679 12500 29679 12470 29679 12502 29680 12469 29680 12511 29680 12503 29681 12502 29681 12510 29681 12512 29682 12503 29682 12510 29682 12545 29683 12532 29683 12512 29683 12532 29684 12544 29684 12534 29684 12543 29685 12508 29685 12535 29685 12533 29686 12505 29686 12508 29686 12571 29687 12567 29687 12598 29687 12542 29688 12573 29688 12567 29688 12537 29689 12567 29689 12571 29689 12536 29690 12537 29690 12541 29690 12599 29691 12631 29691 12632 29691 12724 29692 12694 29692 12662 29692 12632 29693 12660 29693 12692 29693 12794 29694 12758 29694 12726 29694 12865 29695 12795 29695 12794 29695 12795 29696 12865 29696 12830 29696 12895 29697 12894 29697 12829 29697 12895 29698 12927 29698 12894 29698 12928 29699 12933 29699 12929 29699 12932 29700 12979 29700 12975 29700 12979 29701 12978 29701 12981 29701 12897 29702 12936 29702 12898 29702 12936 29703 12897 29703 12935 29703 12934 29704 12983 29704 12980 29704 12983 29705 13039 29705 13017 29705 13036 29706 13038 29706 13017 29706 13052 29707 13036 29707 13014 29707 12970 29708 13015 29708 13037 29708 12923 29709 12973 29709 13015 29709 12973 29710 12923 29710 12926 29710 12925 29711 12974 29711 12926 29711 12893 29712 12892 29712 12925 29712 12789 29713 12824 29713 12828 29713 12753 29714 12791 29714 12789 29714 12891 29715 12892 29715 12824 29715 12752 29716 12790 29716 12753 29716 12755 29717 12721 29717 12754 29717 12656 29718 12629 29718 12689 29718 12722 29719 12656 29719 12689 29719 12629 29720 12628 29720 12657 29720 12654 29721 12627 29721 12653 29721 12625 29722 12603 29722 12602 29722 12590 29723 12562 29723 12563 29723 12525 29724 12491 29724 12529 29724 12491 29725 12525 29725 12492 29725 12479 29726 12452 29726 12462 29726 12613 29727 12607 29727 12614 29727 12877 29728 12876 29728 12875 29728 12877 29729 12843 29729 12842 29729 12641 29730 12618 29730 12633 29730 12634 29731 12613 29731 12608 29731 12612 29732 12672 29732 12635 29732 12672 29733 12640 29733 12665 29733 12671 29734 12670 29734 12665 29734 12639 29735 12636 29735 12670 29735 12639 29736 12695 29736 12636 29736 12704 29737 12703 29737 12695 29737 12729 29738 12698 29738 12703 29738 12702 29739 12727 29739 12667 29739 12698 29740 12729 29740 12667 29740 12728 29741 12727 29741 12736 29741 12760 29742 12798 29742 12728 29742 12762 29743 12731 29743 12798 29743 12735 29744 12761 29744 12699 29744 12731 29745 12762 29745 12699 29745 12769 29746 12799 29746 12770 29746 12764 29747 12799 29747 12769 29747 12767 29748 12808 29748 12763 29748 12732 29749 12764 29749 12763 29749 12834 29750 12801 29750 12808 29750 12869 29751 12833 29751 12834 29751 12841 29752 12810 29752 12869 29752 12804 29753 12807 29753 12768 29753 12805 29754 12768 29754 12810 29754 12843 29755 12806 29755 12804 29755 12902 29756 12871 29756 12904 29756 12990 29757 12944 29757 12904 29757 13022 29758 13040 29758 12990 29758 13022 29759 13044 29759 13053 29759 13067 29760 13056 29760 13043 29760 13043 29761 13059 29761 13070 29761 13076 29762 13075 29762 13059 29762 13058 29763 13073 29763 13076 29763 13089 29764 13088 29764 13073 29764 13095 29765 13089 29765 13072 29765 13093 29766 13095 29766 13087 29766 13092 29767 13093 29767 13081 29767 13063 29768 13080 29768 13091 29768 13083 29769 13064 29769 13091 29769 13062 29770 13079 29770 13063 29770 13061 29771 13062 29771 13049 29771 13046 29772 13061 29772 13048 29772 13001 29773 12999 29773 13046 29773 12999 29774 12953 29774 12998 29774 12952 29775 12908 29775 12996 29775 12908 29776 12907 29776 12951 29776 12882 29777 12906 29777 12907 29777 12882 29778 12846 29778 12879 29778 12814 29779 12777 29779 12845 29779 12776 29780 12775 29780 12777 29780 12709 29781 12739 29781 12775 29781 12739 29782 12707 29782 12738 29782 12674 29783 12642 29783 12706 29783 12642 29784 12619 29784 12648 29784 12623 29785 12652 29785 12622 29785 12986 29786 12943 29786 12948 29786 12941 29787 12994 29787 12942 29787 12647 29788 12617 29788 12651 29788 12623 29789 12621 29789 12652 29789 12650 29790 12620 29790 12686 29790 12643 29791 12676 29791 12686 29791 12650 29792 12649 29792 12620 29792 12718 29793 12675 29793 12719 29793 12710 29794 12751 29794 12750 29794 12741 29795 12772 29795 12751 29795 12813 29796 12773 29796 12772 29796 12844 29797 12811 29798 12813 29799 12816 29800 12881 29800 12844 29800 12847 29801 12881 29801 12816 29801 12880 29802 12881 29802 12847 29802 12883 29803 12950 29803 12878 29803 12884 29804 12883 29804 12878 29804 12949 29805 12950 29805 12910 29805 12997 29806 12949 29806 12909 29806 12995 29807 12997 29807 12955 29807 12954 29808 13025 29808 13024 29808 13000 29809 13026 29809 13025 29809 13002 29810 13060 29810 13027 29810 13060 29811 13002 29811 13078 29811 13027 29812 13026 29812 13002 29812 13051 29813 13099 29813 13090 29813 13031 29814 13030 29814 13077 29814 13098 29815 13099 29815 13051 29815 13103 29816 13098 29816 13050 29816 13100 29817 13082 29817 13101 29817 13082 29818 13100 29818 13065 29818 13102 29819 13086 29819 13096 29819 13069 29820 13068 29820 13084 29820 13097 29821 13085 29821 13071 29821 13069 29822 13074 29822 13054 29822 13045 29823 13054 29823 13057 29823 13041 29824 13023 29824 13021 29824 13021 29825 12993 29825 13020 29825 13023 29826 13041 29826 13045 29826 13020 29827 12941 29827 12989 29827 12994 29828 12941 29828 13020 29828 12939 29829 12943 29829 12986 29829 12938 29830 12939 29830 12987 29830 13032 29831 13019 29831 12988 29831 13032 29832 13003 29832 13019 29832 12988 29833 12937 29833 13018 29833 12961 29834 13005 29834 13019 29834 12937 29835 12938 29835 12984 29835 12961 29836 12963 29836 13006 29836 13010 29837 13008 29837 12963 29837 12965 29838 12964 29838 13010 29838 13009 29839 13011 29839 12964 29839 12962 29840 12960 29840 13009 29840 12911 29841 13013 29841 13034 29841 13034 29842 13033 29842 12957 29842 12967 29843 13013 29843 12911 29843 13007 29844 12959 29844 12957 29844 12912 29845 12885 29845 12968 29845 12850 29846 12914 29846 12968 29846 12852 29847 12915 29847 12914 29847 12920 29848 12918 29848 12852 29848 12921 29849 12920 29849 12854 29849 12919 29850 12921 29850 12856 29850 12916 29851 12919 29851 12855 29851 12969 29852 12889 29852 12922 29852 12966 29853 12917 29853 12889 29853 12853 29854 12851 29854 12889 29854 12851 29855 12820 29855 12889 29855 12819 29856 12860 29856 12859 29856 12860 29857 12819 29857 12861 29857 12861 29858 12821 29858 12858 29858 12780 29859 12857 29859 12817 29859 12858 29860 12818 29860 12817 29860 12823 29861 12862 29861 12887 29861 12780 29862 12745 29862 12784 29862 12784 29863 12745 29863 12785 29863 12785 29864 12744 29864 12787 29864 12787 29865 12747 29865 12786 29865 12711 29866 12788 29866 12743 29866 12713 29867 12749 29867 12788 29867 12788 29868 12783 29868 12743 29868 12711 29869 12678 29869 12713 29869 12716 29870 12679 29870 12717 29870 12717 29871 12682 29871 12714 29871 12644 29872 12684 29872 12680 29872 12647 29873 12646 29873 12684 29873 12684 29874 12715 29874 12680 29874 13105 29875 13106 29875 13107 29875 13616 29876 13582 29876 13614 29876 13616 29877 13644 29877 13617 29877 13106 29878 13105 29878 13110 29878 13617 29879 13581 29879 13616 29879 13111 29880 13107 29880 13106 29880 13107 29881 13111 29881 13108 29881 13111 29882 13115 29882 13108 29882 13122 29883 13123 29883 13115 29883 13179 29884 13180 29884 13112 29884 13112 29885 13124 29885 13125 29885 13115 29886 13121 29886 13134 29886 13307 29887 13308 29887 13334 29887 13271 29888 13307 29888 13270 29888 13269 29889 13273 29889 13237 29889 13346 29890 13349 29890 13369 29890 13182 29891 13127 29891 13181 29891 13143 29892 13142 29892 13127 29892 13174 29893 13121 29893 13173 29893 13403 29894 13401 29894 13402 29894 13349 29895 13374 29895 13402 29895 13433 29896 13403 29896 13435 29896 13433 29897 13434 29897 13403 29897 13162 29898 13127 29898 13186 29898 13467 29899 13500 29899 13466 29899 13184 29900 13145 29900 13183 29900 13184 29901 13207 29901 13145 29901 13153 29902 13151 29902 13203 29902 13202 29903 13151 29903 13230 29903 13570 29904 13535 29904 13534 29904 13607 29905 13568 29905 13535 29905 13187 29906 13145 29906 13211 29906 13500 29907 13536 29907 13499 29907 13569 29908 13534 29908 13499 29908 13669 29909 13635 29909 13607 29909 13718 29910 13669 29910 13607 29910 13240 29911 13163 29911 13239 29911 13210 29912 13163 29912 13209 29912 13199 29913 13171 29913 13232 29913 13303 29914 13267 29914 13171 29914 13171 29915 13199 29915 13200 29915 13761 29916 13782 29916 13720 29916 13720 29917 13782 29917 13796 29917 13678 29918 13674 29918 13612 29918 13575 29919 13641 29919 13642 29919 13274 29920 13243 29920 13163 29920 13759 29921 13715 29921 13781 29921 13725 29922 13679 29922 13575 29922 13247 29923 13189 29923 13246 29923 13247 29924 13276 29924 13189 29924 13214 29925 13213 29925 13189 29925 13300 29926 13301 29926 13263 29926 13263 29927 13262 29927 13227 29927 13171 29928 13197 29928 13226 29928 13437 29929 13438 29929 13470 29929 13574 29930 13573 29930 13540 29930 13502 29931 13539 29931 13540 29931 13405 29932 13406 29932 13438 29932 13672 29933 13673 29933 13575 29933 13248 29934 13189 29934 13279 29934 13189 29935 13248 29935 13249 29935 13325 29936 13296 29936 13225 29936 13225 29937 13296 29937 13297 29937 13321 29938 13259 29938 13251 29938 13406 29939 13405 29939 13376 29939 13251 29940 13215 29940 13280 29940 13293 29941 13225 29941 13292 29941 13291 29942 13282 29942 13251 29942 13313 29943 13282 29943 13291 29943 13313 29944 13352 29944 13379 29944 13377 29945 13351 29945 13319 29945 13396 29946 13392 29946 13319 29946 13391 29947 13319 29947 13390 29947 13517 29948 13518 29948 13516 29948 13482 29949 13495 29949 13516 29949 13463 29950 13494 29950 13482 29950 13461 29951 13368 29951 13460 29951 13338 29952 13380 29952 13408 29952 13429 29953 13430 29953 13462 29953 13380 29954 13338 29954 13410 29954 13392 29955 13394 29955 13430 29955 13624 29956 13622 29956 13589 29956 13530 29957 13492 29957 13531 29957 13530 29958 13527 29958 13492 29958 13623 29959 13622 29959 13649 29959 13557 29960 13519 29960 13517 29960 13556 29961 13519 29961 13557 29961 13589 29962 13556 29962 13555 29962 13353 29963 13411 29963 13441 29963 13440 29964 13353 29964 13439 29964 13440 29965 13442 29965 13353 29965 13742 29966 13769 29966 13770 29966 13743 29967 13770 29967 13772 29967 13739 29968 13768 29968 13742 29968 13605 29969 13566 29969 13604 29969 13602 29970 13601 29970 13566 29970 13740 29971 13695 29971 13741 29971 13741 29972 13695 29972 13693 29972 13606 29973 13492 29973 13631 29973 13693 29974 13626 29974 13694 29974 13382 29975 13443 29975 13474 29975 13472 29976 13503 29976 13382 29976 13472 29977 13382 29977 13471 29977 13836 29978 13835 29978 13844 29978 13630 29979 13711 29979 13712 29979 13839 29980 13837 29980 13846 29980 13847 29981 13844 29981 13835 29981 13843 29982 13842 29982 13824 29982 13665 29983 13663 29983 13566 29983 13664 29984 13566 29984 13662 29984 13663 29985 13660 29985 13566 29985 13659 29986 13566 29986 13658 29986 13823 29987 13806 29987 13834 29987 13790 29988 13804 29988 13822 29988 13806 29989 13805 29989 13822 29989 13756 29990 13713 29990 13566 29990 13771 29991 13791 29991 13790 29991 13412 29992 13476 29992 13507 29992 13505 29993 13543 29993 13412 29993 13813 29994 13798 29994 13797 29994 13812 29995 13813 29995 13800 29995 13797 29996 13799 29996 13785 29996 13755 29997 13753 29997 13643 29997 13754 29998 13643 29998 13752 29998 13753 29999 13751 29999 13643 29999 13814 30000 13820 30000 13833 30000 13814 30001 13839 30001 13828 30001 13811 30002 13814 30002 13828 30002 13445 30003 13512 30003 13551 30003 13545 30004 13445 30004 13544 30004 13545 30005 13577 30005 13445 30005 13688 30006 13734 30006 13764 30006 13688 30007 13684 30007 13646 30007 13579 30008 13681 30008 13732 30008 13615 30009 13509 30009 13645 30009 13785 30010 13765 30010 13734 30010 13551 30011 13550 30011 13509 30011 13579 30012 13580 30012 13509 30012 13546 30013 13580 30013 13582 30013 13617 30014 13647 30014 13581 30014 13547 30015 13581 30015 13618 30015 13584 30016 13510 30016 13547 30016 13620 30017 13510 30017 13619 30017 13690 30018 13648 30018 13691 30018 13738 30019 13735 30019 13689 30019 13657 30020 13728 30020 13729 30020 13549 30021 13478 30021 13548 30021 13801 30022 13802 30022 13787 30022 13801 30023 13818 30023 13815 30023 13766 30024 13767 30024 13789 30024 13789 30025 13786 30025 13788 30025 13816 30026 13829 30026 13830 30026 13593 30027 13706 30027 13709 30027 13705 30028 13593 30028 13709 30028 13703 30029 13704 30029 13706 30029 13657 30030 13593 30030 13705 30030 13767 30031 13766 30031 13737 30031 13585 30032 13613 30033 13578 30034 13511 30035 13478 30035 13578 30035 13808 30036 13809 30036 13810 30036 13810 30037 13794 30037 13807 30037 13656 30038 13655 30038 13629 30038 13795 30039 13774 30039 13792 30039 13793 30040 13794 30040 13795 30040 13827 30041 13825 30041 13808 30041 13773 30042 13775 30042 13746 30042 13526 30043 13599 30043 13598 30043 13595 30044 13597 30044 13599 30044 13594 30045 13526 30045 13598 30045 13593 30046 13526 30046 13594 30046 13830 30047 13838 30047 13826 30047 13513 30048 13514 30049 13479 30050 13511 30051 13553 30052 13513 30048 13696 30053 13698 30053 13699 30053 13652 30054 13696 30054 13699 30054 13590 30055 13651 30055 13654 30055 13654 30056 13651 30056 13653 30056 13489 30057 13524 30057 13525 30057 13746 30058 13744 30058 13697 30058 13561 30059 13562 30059 13565 30059 13564 30060 13526 30060 13565 30060 13506 30061 13542 30061 13504 30061 13446 30062 13413 30062 13504 30062 13453 30063 13520 30063 13523 30063 13523 30064 13520 30064 13522 30064 13591 30065 13559 30065 13521 30065 13521 30066 13559 30066 13522 30066 13455 27374 13486 27373 13487 27375 13590 30067 13627 30067 13591 30067 13487 27375 13490 30068 13491 30069 13489 30070 13456 30070 13491 30070 13447 30071 13448 30071 13383 30071 13446 30072 13473 30072 13447 30072 13452 30073 13451 30073 13454 30073 13418 30074 13451 30074 13452 30074 13420 30075 13387 30075 13418 30075 13387 30076 13364 30076 13386 30076 13453 30077 13484 30077 13454 30077 13426 30078 13423 30078 13422 30078 13383 30079 13414 30079 13415 30079 13318 30080 13314 30080 13358 30080 13362 30081 13363 30081 13367 30081 13344 30082 13318 30082 13361 30082 13314 30083 13339 30083 13355 30083 13318 30084 13290 30084 13314 30084 13283 30085 13290 30085 13250 30085 13323 30086 13340 30086 13260 30086 13404 30087 13375 30087 13359 30087 13250 30088 13284 30088 13285 30088 13295 30089 13294 30089 13260 30089 13468 30090 13436 30090 13481 30090 13541 30091 13610 30091 13576 30091 13541 30092 13576 30092 13481 30092 13436 30093 13404 30093 13449 30093 13611 30094 13677 30094 13639 30094 13252 30095 13287 30095 13288 30095 13188 30096 13216 30096 13252 30096 13224 30097 13298 30097 13326 30097 13224 30098 13261 30098 13298 30098 13721 30099 13680 30099 13722 30099 13727 30100 13721 30100 13783 30100 13677 30101 13611 30101 13676 30101 13640 30102 13722 30102 13676 30102 13288 30103 13289 30103 13256 30103 13716 30104 13758 30104 13779 30104 13716 30105 13668 30105 13758 30105 13255 30106 13275 30107 13244 30108 13217 27107 13254 27109 13255 30106 13332 30109 13333 30109 13305 30109 13345 30110 13330 30110 13333 30110 13305 30111 13261 30111 13304 30111 13198 30112 13170 30112 13228 30112 13608 30113 13637 30113 13667 30113 13572 30114 13636 30114 13637 30114 13501 30115 13537 30115 13571 30115 13537 30116 13501 30116 13533 30116 13190 30117 13164 30117 13258 30117 13714 30118 13668 30118 13667 30118 13465 30119 13496 30119 13497 30119 13219 30120 13241 30120 13242 30120 13190 30121 13218 30121 13219 30121 13201 30122 13233 30122 13234 30122 13266 30123 13229 30123 13265 30123 13170 30124 13152 30124 13201 30124 13373 30125 13348 30125 13372 30125 13400 30126 13399 30126 13373 30126 13432 30127 13431 30127 13400 30127 13465 30128 13464 30128 13432 30128 13371 30129 13398 30130 13372 30131 13165 30132 13191 30132 13192 30132 13195 30133 13126 30133 13192 30133 13154 30134 13177 30135 13178 26922 13172 30136 13133 30136 13178 30136 13335 30137 13347 30137 13309 30137 13309 30138 13272 30138 13335 30138 13272 30139 13205 30139 13306 30139 13169 30140 13235 30140 13236 30140 13347 30141 13370 30142 13371 30129 13195 26916 13194 30143 13166 30144 13147 30145 13117 30145 13146 30145 13175 30146 13176 30147 13154 30134 13113 30148 13118 30148 13119 30148 13169 30149 13150 30149 13168 30149 13113 30150 13117 30150 13128 30150 13114 30151 13136 30151 13137 30151 13110 30152 13109 30152 13113 30152 13104 30153 13108 30153 13109 30153 13108 30154 13112 30154 13113 30154 13113 30155 13112 30155 13117 30155 13117 30156 13116 30156 13126 30156 13126 30157 13127 30157 13144 30157 13163 30158 13164 30158 13144 30158 13164 30159 13163 30159 13188 30159 13188 30160 13189 30160 13216 30160 13216 30161 13215 30161 13250 30161 13251 30162 13282 30162 13283 30162 13283 30163 13282 30163 13314 30163 13314 30164 13313 30164 13339 30164 13339 30165 13338 30165 13354 30165 13354 30166 13353 30166 13381 30166 13381 30167 13382 30167 13413 30167 13413 30168 13412 30168 13444 30168 13478 30169 13444 30169 13477 30169 13510 30170 13478 30170 13509 30170 13510 30171 13509 30171 13547 30171 13547 30172 13546 30172 13581 30172 13644 30173 13614 30173 13618 30173 13583 30174 13618 30174 13580 30174 13583 30175 13580 30175 13584 30175 13657 30176 13584 30176 13643 30176 13593 30177 13657 30177 13630 30177 13526 30178 13593 30178 13566 30178 13566 30179 13492 30179 13456 30179 13492 30180 13427 30180 13389 30180 13427 30181 13368 30181 13344 30181 13368 30182 13319 30182 13318 30182 13291 30183 13290 30183 13318 30183 13291 30184 13259 30184 13260 30184 13225 30185 13224 30185 13260 30185 13224 30186 13225 30186 13198 30186 13171 30187 13170 30187 13198 30187 13151 30188 13152 30188 13170 30188 13152 30189 13151 30189 13133 30189 13133 30190 13132 30190 13120 30190 13115 30191 13114 30191 13120 30191 13115 30192 13111 30192 13110 30192 13118 30193 13123 30193 13119 30193 13341 30194 13340 30194 13323 30194 13359 30195 13340 30195 13341 30195 13139 30196 13130 30196 13122 30196 13131 30197 13138 30197 13123 30197 13138 30198 13131 30198 13157 30198 13157 30199 13169 30199 13179 30199 13237 30200 13205 30200 13271 30200 13271 30201 13272 30201 13308 30201 13308 30202 13336 30202 13349 30202 13348 30203 13399 30203 13374 30203 13435 30204 13403 30204 13399 30204 13435 30205 13464 30205 13500 30205 13571 30206 13569 30206 13536 30206 13569 30207 13571 30207 13570 30207 13634 30208 13607 30208 13570 30208 13716 30209 13715 30209 13607 30209 13721 30210 13720 30210 13760 30210 13675 30211 13674 30211 13720 30211 13640 30212 13612 30212 13674 30212 13541 30213 13575 30213 13612 30213 13541 30214 13481 30214 13469 30214 13449 30215 13437 30215 13469 30215 13359 30216 13405 30216 13437 30216 13294 30217 13292 30217 13321 30217 13320 30218 13293 30218 13294 30218 13320 30219 13322 30219 13324 30219 13326 30220 13327 30220 13324 30220 13327 30221 13298 30221 13325 30221 13298 30222 13299 30222 13296 30222 13263 30223 13226 30223 13297 30223 13305 30224 13330 30224 13263 30224 13330 30225 13345 30225 13300 30225 13301 30226 13328 30226 13345 30226 13333 30227 13332 30227 13301 30227 13262 30228 13329 30228 13332 30228 13304 30229 13331 30229 13262 30229 13229 30230 13264 30230 13227 30230 13331 30231 13228 30231 13227 30231 13229 30232 13266 30232 13264 30232 13267 30233 13303 30233 13266 30233 13265 30234 13234 30234 13267 30234 13231 30235 13234 30235 13232 30235 13201 30236 13199 30236 13232 30236 13200 30237 13199 30237 13172 30237 13230 30238 13200 30238 13172 30238 13204 30239 13178 30239 13230 30239 13178 30240 13177 30240 13202 30240 13177 30241 13154 30241 13153 30241 13173 30242 13176 30242 13174 30242 13174 30243 13175 30243 13155 30243 13156 30244 13137 30244 13135 30244 13134 30245 13136 30245 13139 30245 13168 30246 13167 30246 13180 30246 13337 30247 13312 30247 13316 30247 13284 30248 13316 30248 13312 30248 13180 30249 13206 30249 13168 30249 13167 30250 13149 30250 13141 30250 13124 30251 13141 30251 13128 30251 13128 30252 13129 30252 13125 30252 13160 30253 13147 30253 13143 30253 13161 30254 13142 30254 13146 30254 13166 30255 13194 30255 13181 30255 13185 30256 13195 30256 13186 30256 13185 30257 13182 30257 13195 30257 13183 30258 13162 30258 13195 30258 13208 30259 13192 30259 13184 30259 13192 30260 13191 30260 13184 30260 13165 30261 13193 30261 13212 30261 13211 30262 13212 30262 13222 30262 13191 30263 13165 30263 13212 30263 13211 30264 13242 30264 13241 30264 13241 30265 13219 30265 13210 30265 13219 30266 13218 30266 13239 30266 13243 30267 13274 30267 13257 30267 13190 30268 13220 30268 13258 30268 13258 30269 13245 30269 13243 30269 13257 30270 13240 30270 13190 30270 13245 30271 13244 30271 13214 30271 13246 30272 13213 30272 13255 30272 13247 30273 13246 30273 13254 30273 13256 30274 13247 30274 13254 30274 13289 30275 13276 30275 13256 30275 13287 30276 13278 30276 13276 30276 13248 30277 13279 30277 13287 30277 13277 30278 13249 30278 13252 30278 13315 30279 13311 30279 13342 30279 13286 30280 13317 30280 13311 30280 13281 30281 13311 30281 13315 30281 13280 30282 13281 30282 13285 30282 13343 30283 13375 30283 13376 30283 13468 30284 13438 30284 13406 30284 13376 30285 13404 30285 13436 30285 13538 30286 13502 30286 13470 30286 13609 30287 13539 30287 13538 30287 13610 30288 13574 30288 13539 30288 13639 30289 13638 30289 13573 30289 13639 30290 13671 30290 13638 30290 13719 30291 13673 30291 13672 30291 13676 30292 13723 30292 13719 30292 13726 30293 13725 30293 13723 30293 13641 30294 13680 30294 13642 30294 13680 30295 13641 30295 13679 30295 13761 30296 13724 30297 13678 30298 13727 30299 13783 30299 13761 30299 13761 30300 13779 30300 13782 30300 13796 30301 13780 30301 13758 30301 13781 30302 13758 30302 13759 30302 13759 30303 13714 30303 13717 30303 13670 30304 13718 30304 13667 30304 13669 30305 13718 30305 13670 30305 13637 30306 13636 30306 13669 30306 13533 30307 13568 30307 13572 30307 13497 30308 13535 30308 13533 30308 13635 30309 13636 30309 13568 30309 13496 30310 13534 30310 13497 30310 13499 30311 13465 30311 13498 30311 13400 30312 13373 30312 13433 30312 13466 30313 13400 30313 13433 30313 13373 30314 13372 30314 13401 30314 13398 30315 13371 30315 13397 30315 13369 30316 13347 30316 13346 30316 13334 30317 13306 30317 13307 30317 13269 30318 13235 30318 13273 30318 13235 30319 13269 30319 13236 30319 13206 30320 13238 30320 13196 30320 13357 30321 13351 30321 13358 30321 13621 30322 13620 30322 13619 30322 13621 30323 13587 30323 13586 30323 13385 30324 13362 30324 13377 30324 13378 30325 13357 30325 13352 30325 13356 30326 13416 30326 13379 30326 13416 30327 13384 30327 13409 30327 13410 30328 13409 30328 13415 30328 13410 30329 13414 30329 13383 30329 13408 30330 13380 30330 13383 30330 13448 30331 13447 30331 13439 30331 13473 30332 13442 30332 13447 30332 13441 30333 13411 30333 13446 30333 13446 30334 13411 30334 13442 30334 13480 30335 13504 30335 13471 30335 13504 30336 13542 30336 13472 30336 13506 30337 13475 30337 13542 30337 13479 30338 13505 30338 13443 30338 13475 30339 13506 30339 13443 30339 13513 30340 13543 30340 13514 30340 13508 30341 13543 30341 13513 30341 13511 30342 13552 30342 13507 30342 13511 30343 13507 30343 13476 30343 13578 30344 13545 30344 13552 30344 13545 30345 13578 30345 13613 30345 13577 30346 13613 30346 13585 30346 13548 30347 13551 30347 13512 30347 13549 30348 13512 30348 13554 30348 13587 30349 13550 30349 13548 30349 13646 30350 13615 30350 13648 30350 13734 30351 13688 30351 13648 30351 13766 30352 13784 30352 13734 30352 13766 30353 13788 30353 13797 30353 13787 30354 13814 30354 13800 30354 13787 30355 13803 30355 13814 30355 13803 30356 13802 30356 13819 30356 13802 30357 13817 30357 13820 30357 13817 30358 13816 30358 13832 30358 13839 30359 13833 30359 13816 30359 13837 30360 13839 30360 13831 30360 13825 30361 13827 30361 13837 30361 13835 30362 13808 30362 13824 30362 13827 30363 13808 30363 13835 30363 13806 30364 13823 30364 13807 30364 13793 30365 13792 30365 13806 30365 13790 30366 13805 30366 13792 30366 13745 30367 13743 30367 13790 30367 13743 30368 13697 30368 13742 30368 13696 30369 13652 30369 13740 30369 13652 30370 13651 30370 13695 30370 13651 30371 13590 30371 13650 30371 13626 30372 13590 30372 13623 30372 13558 30373 13521 30373 13589 30373 13556 30374 13521 30374 13520 30374 13453 30375 13483 30375 13519 30375 13483 30376 13451 30376 13482 30376 13418 30377 13386 30377 13450 30377 13386 30378 13363 30378 13392 30378 13367 30379 13396 30379 13366 30379 13686 30380 13692 30380 13730 30380 13685 30381 13738 30381 13686 30381 13391 30382 13361 30382 13395 30382 13367 30383 13365 30383 13396 30383 13394 30384 13364 30384 13430 30384 13462 30385 13430 30385 13387 30385 13394 30386 13393 30386 13364 30386 13462 30387 13419 30387 13463 30387 13454 30388 13495 30388 13494 30388 13485 30389 13516 30389 13495 30389 13557 30390 13517 30390 13516 30390 13588 30391 13555 30391 13557 30391 13560 30392 13625 30392 13588 30392 13591 30393 13625 30393 13560 30393 13624 30394 13625 30394 13591 30394 13649 30395 13622 30395 13627 30395 13622 30396 13624 30396 13627 30396 13654 30397 13653 30397 13694 30397 13653 30398 13699 30398 13693 30398 13699 30399 13700 30399 13741 30399 13768 30400 13700 30400 13769 30400 13769 30401 13698 30401 13770 30401 13791 30402 13771 30402 13746 30402 13804 30403 13746 30403 13822 30403 13744 30404 13746 30404 13771 30404 13834 30405 13774 30405 13843 30405 13821 30406 13822 30406 13774 30406 13795 30407 13794 30407 13843 30407 13794 30408 13810 30408 13842 30408 13838 30409 13845 30409 13844 30409 13847 30410 13809 30410 13826 30410 13829 30411 13840 30411 13846 30411 13828 30412 13815 30412 13812 30412 13815 30413 13828 30413 13829 30413 13813 30414 13818 30414 13798 30414 13789 30415 13798 30415 13801 30415 13785 30416 13767 30416 13765 30416 13765 30417 13737 30417 13764 30417 13767 30418 13785 30418 13789 30418 13764 30419 13685 30419 13733 30419 13738 30420 13685 30420 13764 30420 13683 30421 13687 30421 13730 30421 13682 30422 13683 30422 13731 30422 13776 30423 13763 30423 13732 30423 13776 30424 13747 30424 13763 30424 13732 30425 13681 30425 13762 30425 13705 30426 13749 30426 13763 30426 13681 30427 13682 30427 13728 30427 13705 30428 13707 30428 13750 30428 13707 30429 13709 30429 13752 30429 13709 30430 13708 30430 13754 30430 13708 30431 13706 30431 13755 30431 13706 30432 13704 30432 13753 30432 13778 30433 13701 30433 13757 30433 13748 30434 13701 30434 13778 30434 13655 30435 13656 30435 13757 30435 13701 30436 13748 30436 13703 30436 13656 30437 13629 30437 13712 30437 13594 30438 13658 30438 13712 30438 13658 30439 13594 30439 13659 30439 13664 30440 13662 30440 13596 30440 13598 30441 13600 30441 13664 30441 13663 30442 13665 30442 13600 30442 13599 30443 13597 30443 13663 30443 13632 30444 13666 30444 13713 30444 13660 30445 13633 30445 13710 30445 13597 30446 13595 30446 13633 30446 13595 30447 13564 30447 13633 30447 13563 30448 13604 30448 13603 30448 13604 30449 13563 30449 13605 30449 13605 30450 13565 30450 13602 30450 13524 30451 13601 30451 13561 30451 13602 30452 13562 30452 13561 30452 13567 30453 13606 30453 13631 30453 13524 30454 13489 30454 13528 30454 13528 30455 13489 30455 13529 30455 13529 30456 13488 30456 13531 30456 13531 30457 13491 30457 13530 30457 13455 30458 13532 30458 13487 30458 13457 30459 13493 30459 13532 30459 13532 30460 13527 30460 13487 30460 13455 30461 13422 30461 13457 30461 13460 30462 13423 30462 13461 30462 13461 30463 13426 30463 13458 30463 13388 30464 13428 30464 13424 30464 13391 30465 13390 30465 13428 30465 13428 30466 13459 30466 13424 30466 13851 30467 13848 30467 13850 30467 14360 30468 14326 30468 14358 30468 14391 30469 14361 30469 14360 30469 13850 30470 13849 30470 13854 30470 14361 30471 14325 30471 14360 30471 13850 30472 13854 30472 13851 30472 13851 30473 13855 30473 13852 30473 13855 30474 13859 30474 13852 30474 13866 30475 13867 30475 13859 30475 13923 30476 13924 30476 13856 30476 13856 30477 13868 30477 13869 30477 13859 30478 13865 30478 13878 30478 14051 30479 14052 30479 14078 30479 14015 30480 14051 30480 14014 30480 14013 30481 14017 30481 13981 30481 14090 30482 14093 30482 14113 30482 13926 30483 13871 30483 13925 30483 13887 30484 13886 30484 13871 30484 13918 30485 13865 30485 13917 30485 14147 30486 14145 30486 14146 30486 14093 30487 14118 30487 14146 30487 14177 30488 14147 30488 14179 30488 14177 30489 14178 30489 14147 30489 13906 30490 13871 30490 13930 30490 14211 30491 14244 30491 14210 30491 13928 30492 13889 30492 13927 30492 13928 30493 13951 30493 13889 30493 13897 30494 13895 30494 13947 30494 13946 30495 13895 30495 13974 30495 14314 30496 14279 30496 14278 30496 14351 30497 14312 30497 14279 30497 13931 30498 13889 30498 13955 30498 14244 30499 14280 30499 14243 30499 14313 30500 14278 30500 14243 30500 14413 30501 14379 30501 14351 30501 14462 30502 14413 30502 14351 30502 13984 30503 13907 30503 13983 30503 13954 30504 13907 30504 13953 30504 13943 30505 13915 30505 13976 30505 14047 30506 14011 30506 13915 30506 13915 30507 13943 30507 13944 30507 14505 30508 14526 30508 14464 30508 14464 30509 14526 30509 14540 30509 14422 30510 14418 30510 14356 30510 14319 30511 14385 30511 14386 30511 14018 30512 13987 30512 13907 30512 14503 30513 14459 30513 14525 30513 14469 30514 14423 30514 14319 30514 13991 30515 13933 30515 13990 30515 13991 30516 14020 30516 13933 30516 13958 30517 13957 30517 13933 30517 14044 30518 14045 30518 14007 30518 14007 30519 14006 30519 13971 30519 13915 30520 13941 30520 13970 30520 14181 30521 14182 30521 14214 30521 14318 30522 14317 30522 14284 30522 14246 30523 14283 30523 14284 30523 14149 30524 14150 30524 14182 30524 14416 30525 14417 30525 14319 30525 13992 30526 13933 30526 14023 30526 13933 30527 13992 30527 13993 30527 14069 30528 14040 30528 13969 30528 13969 30529 14040 30529 14041 30529 14065 30530 14003 30530 13995 30530 14150 30531 14149 30531 14120 30531 13995 30532 13959 30532 14024 30532 14037 30533 13969 30533 14036 30533 14035 30534 14026 30534 13995 30534 14057 30535 14026 30535 14035 30535 14057 30536 14096 30536 14123 30536 14121 30537 14095 30537 14063 30537 14140 30538 14136 30538 14063 30538 14135 30539 14063 30539 14134 30539 14261 30540 14262 30540 14260 30540 14226 30541 14239 30541 14260 30541 14207 30542 14238 30542 14226 30542 14205 30543 14112 30543 14204 30543 14082 30544 14124 30544 14152 30544 14173 30545 14174 30545 14206 30545 14124 30546 14082 30546 14154 30546 14136 30547 14138 30547 14174 30547 14368 30548 14366 30548 14333 30548 14274 30549 14236 30549 14275 30549 14274 30550 14271 30550 14236 30550 14367 30551 14366 30551 14393 30551 14301 30552 14263 30552 14261 30552 14300 30553 14263 30553 14301 30553 14333 30554 14300 30554 14299 30554 14097 30555 14155 30555 14185 30555 14184 30556 14097 30556 14183 30556 14184 30557 14186 30557 14097 30557 14486 30558 14513 30558 14514 30558 14487 30559 14514 30559 14516 30559 14483 30560 14512 30560 14486 30560 14349 30561 14310 30561 14348 30561 14346 30562 14345 30562 14310 30562 14484 30563 14439 30563 14485 30563 14485 30564 14439 30564 14437 30564 14350 30565 14236 30565 14375 30565 14437 30566 14370 30566 14438 30566 14126 30567 14187 30567 14218 30567 14216 30568 14247 30568 14126 30568 14216 30569 14126 30569 14215 30569 14580 30570 14579 30570 14588 30570 14374 30571 14455 30571 14456 30571 14583 30572 14581 30572 14590 30572 14591 30573 14588 30573 14579 30573 14587 30574 14586 30574 14568 30574 14409 30575 14407 30575 14310 30575 14408 30576 14310 30576 14406 30576 14407 30577 14404 30577 14310 30577 14403 30578 14310 30578 14402 30578 14567 30579 14550 30579 14578 30579 14534 30580 14548 30580 14566 30580 14550 30581 14549 30581 14566 30581 14500 30582 14457 30582 14310 30582 14515 30583 14535 30583 14534 30583 14156 30584 14220 30584 14251 30584 14249 30585 14287 30585 14156 30585 14557 30586 14542 30586 14541 30586 14556 30587 14557 30587 14544 30587 14541 30588 14543 30588 14529 30588 14499 30589 14497 30589 14387 30589 14498 30590 14387 30590 14496 30590 14497 30591 14495 30591 14387 30591 14558 30592 14564 30592 14577 30592 14558 30593 14583 30593 14572 30593 14555 30594 14558 30594 14572 30594 14189 30595 14256 30595 14295 30595 14289 30596 14189 30596 14288 30596 14289 30597 14321 30597 14189 30597 14432 30598 14478 30598 14508 30598 14432 30599 14428 30599 14390 30599 14323 30600 14425 30600 14476 30600 14359 30601 14253 30601 14389 30601 14529 30602 14509 30602 14478 30602 14295 30603 14294 30603 14253 30603 14323 30604 14324 30604 14253 30604 14290 30605 14324 30605 14326 30605 14361 30606 14391 30606 14325 30606 14291 30607 14325 30607 14362 30607 14328 30608 14254 30608 14291 30608 14364 30609 14254 30609 14363 30609 14434 30610 14392 30610 14435 30610 14482 30611 14479 30611 14433 30611 14401 30612 14472 30612 14473 30612 14293 30613 14222 30613 14292 30613 14545 30614 14546 30614 14531 30614 14545 28263 14562 30615 14559 30616 14510 30617 14511 30617 14533 30617 14533 30618 14530 30618 14532 30618 14560 30619 14573 30619 14574 30619 14337 30620 14450 30620 14453 30620 14449 30621 14337 30621 14453 30621 14447 30622 14448 30622 14450 30622 14401 30623 14337 30623 14449 30623 14511 30624 14510 30624 14481 30624 14329 30625 14357 30626 14322 27689 14255 30627 14222 30627 14322 30627 14552 30628 14553 30628 14554 30628 14554 30629 14538 30629 14551 30629 14400 30630 14399 30630 14373 30630 14539 30631 14518 30631 14536 30631 14537 30632 14538 30632 14539 30632 14571 30633 14569 30633 14552 30633 14517 30634 14519 30634 14490 30634 14270 30635 14343 30635 14342 30635 14339 30636 14341 30636 14343 30636 14338 30637 14270 30637 14342 30637 14337 30638 14270 30638 14338 30638 14574 30639 14582 30640 14570 30641 14257 30642 14258 30643 14223 30644 14255 30645 14297 30645 14257 30645 14440 30646 14442 30646 14443 30646 14396 30647 14440 30647 14443 30647 14334 30648 14395 30648 14398 30648 14398 30649 14395 30649 14397 30649 14233 27744 14268 28307 14269 28306 14490 30650 14488 30650 14441 30650 14305 28308 14306 30651 14309 30652 14308 30653 14270 30653 14309 30653 14250 30654 14286 30655 14248 30656 14190 30657 14157 30657 14248 30657 14197 30658 14264 30658 14267 30658 14267 30659 14264 30659 14266 30659 14335 30660 14303 30660 14265 30660 14265 30661 14303 30661 14266 30661 14199 28317 14230 28316 14231 28318 14334 30662 14371 30662 14335 30662 14231 28318 14234 30663 14235 27745 14233 30664 14200 30664 14235 30664 14191 30665 14192 30665 14127 30665 14190 30666 14217 30666 14191 30666 14196 30667 14195 30667 14198 30667 14162 30668 14195 30668 14196 30668 14164 30669 14131 30669 14162 30669 14131 30670 14108 30670 14130 30670 14197 30671 14228 30671 14198 30671 14170 30672 14167 30672 14166 30672 14127 30673 14158 30673 14159 30673 14062 30674 14058 30674 14102 30674 14106 30675 14107 30675 14111 30675 14088 30676 14062 30676 14105 30676 14058 30677 14083 30677 14099 30677 14062 30678 14034 30678 14058 30678 14027 30679 14034 30679 13994 30679 14067 30680 14084 30680 14004 30680 14148 30681 14119 30681 14103 30681 13994 30682 14028 30682 14029 30682 14039 30683 14038 30683 14004 30683 14212 30684 14180 30684 14225 30684 14285 30685 14354 30685 14320 30685 14285 30686 14320 30686 14225 30686 14180 30687 14148 30687 14193 30687 14355 30688 14421 30688 14383 30688 13996 30689 14031 30690 14032 30691 13932 30692 13960 30692 13996 30692 13968 30693 14042 30693 14070 30693 13968 30694 14005 30694 14042 30694 14465 30695 14424 30695 14466 30695 14471 30696 14465 30696 14527 30696 14421 30697 14355 30697 14420 30697 14384 30698 14466 30698 14420 30698 14032 30691 14033 30699 14000 30700 14460 30701 14502 30701 14523 30701 14460 30702 14412 30702 14502 30702 13999 30703 14019 30703 13988 30703 13961 30704 13998 30704 13999 30704 14076 30705 14077 30705 14049 30705 14089 30706 14074 30706 14077 30706 14049 30707 14005 30707 14048 30707 13942 30708 13914 30708 13972 30708 14352 30709 14381 30709 14411 30709 14316 30710 14380 30710 14381 30710 14245 30711 14281 30711 14315 30711 14281 30712 14245 30712 14277 30712 13934 30713 13908 30713 14002 30713 14458 30714 14412 30714 14411 30714 14209 30715 14240 30715 14241 30715 13963 30716 13985 30716 13986 30716 13934 30717 13962 30717 13963 30717 13945 30718 13977 30718 13978 30718 14010 30719 13973 30719 14009 30719 13914 30720 13896 30720 13945 30720 14117 30721 14092 30721 14116 30721 14144 30722 14143 30722 14117 30722 14176 30723 14175 30723 14144 30723 14209 30724 14208 30724 14176 30724 14115 30725 14142 30726 14116 30727 13909 30728 13935 30729 13936 30730 13939 30731 13870 30731 13936 30731 13898 30732 13921 30733 13922 30734 13916 30735 13877 30735 13922 30735 14079 30736 14091 30736 14053 30736 14053 30737 14016 30737 14079 30737 14016 30738 13949 30738 14050 30738 13913 30739 13979 30739 13980 30739 14091 30740 14114 30741 14115 30725 13939 30742 13938 30743 13910 30744 13891 30745 13861 30745 13890 30745 13919 30746 13920 30747 13898 30732 13857 30748 13862 30748 13863 30748 13913 30749 13894 30749 13912 30749 13857 30750 13861 30750 13872 30750 13858 30751 13880 30751 13881 30751 13854 30752 13853 30752 13857 30752 13853 30753 13849 30753 13852 30753 13857 30754 13853 30754 13856 30754 13857 30755 13856 30755 13861 30755 13861 30756 13860 30756 13870 30756 13870 30757 13871 30757 13888 30757 13888 30758 13889 30758 13908 30758 13908 30759 13907 30759 13932 30759 13932 30760 13933 30760 13960 30760 13960 30761 13959 30761 13994 30761 13995 30762 14026 30762 14027 30762 14057 30763 14058 30763 14027 30763 14058 30764 14057 30764 14083 30764 14083 30765 14082 30765 14098 30765 14098 30766 14097 30766 14125 30766 14125 30767 14126 30767 14157 30767 14157 30768 14156 30768 14188 30768 14222 30769 14188 30769 14221 30769 14254 30770 14222 30770 14253 30770 14290 30771 14291 30771 14254 30771 14291 30772 14290 30772 14325 30772 14388 30773 14358 30773 14362 30773 14358 30774 14324 30774 14327 30774 14323 30775 14328 30775 14327 30775 14323 30776 14387 30776 14401 30776 14387 30777 14374 30777 14337 30777 14374 30778 14310 30778 14270 30778 14310 30779 14236 30779 14200 30779 14236 30780 14171 30780 14133 30780 14171 30781 14112 30781 14088 30781 14112 30782 14063 30782 14062 30782 14062 30783 14063 30783 14034 30783 14004 30784 14034 30784 14003 30784 14004 30785 14003 30785 13968 30785 13941 30786 13942 30786 13968 30786 13942 30787 13941 30787 13914 30787 13895 30788 13896 30788 13914 30788 13896 30789 13895 30789 13877 30789 13877 30790 13876 30790 13864 30790 13864 30791 13865 30791 13858 30791 13854 30792 13858 30792 13855 30792 13866 30793 13863 30793 13862 30793 14067 30794 14065 30794 14084 30794 14103 30795 14084 30795 14085 30795 13863 30796 13866 30796 13883 30796 13867 30797 13862 30797 13882 30797 13894 30798 13901 30798 13882 30798 13949 30799 13923 30799 13901 30799 13981 30800 13949 30800 14015 30800 14015 30801 14016 30801 14052 30801 14052 30802 14080 30802 14093 30802 14092 30803 14143 30803 14118 30803 14143 30804 14175 30804 14147 30804 14179 30805 14208 30805 14244 30805 14280 30806 14245 30806 14313 30806 14313 30807 14315 30807 14314 30807 14378 30808 14351 30808 14314 30808 14351 30809 14412 30809 14459 30809 14465 30810 14464 30810 14504 30810 14464 30811 14465 30811 14418 30811 14384 30812 14356 30812 14418 30812 14356 30813 14355 30813 14319 30813 14213 30814 14284 30814 14225 30814 14213 30815 14225 30815 14181 30815 14181 30816 14161 30816 14149 30816 14065 30817 14067 30817 14036 30817 14038 30818 14039 30818 14037 30818 14064 30819 14066 30819 14068 30819 14069 30820 14068 30820 14070 30820 14071 30821 14042 30821 14069 30821 14041 30822 14040 30822 14042 30822 14007 30823 13970 30823 14041 30823 14044 30824 14007 30824 14049 30824 14074 30825 14089 30825 14044 30825 14089 30826 14077 30826 14072 30826 14077 30827 14076 30827 14045 30827 14076 30828 14048 30828 14073 30828 14048 30829 14075 30829 14006 30829 13973 30830 14008 30830 13971 30830 13971 30831 14046 30831 13972 30831 13973 30832 14010 30832 14008 30832 14010 30833 14009 30833 14047 30833 14009 30834 13978 30834 14011 30834 13977 30835 13976 30835 13975 30835 13976 30836 13977 30836 13943 30836 13945 30837 13916 30837 13944 30837 13916 30838 13948 30838 13944 30838 13948 30839 13922 30839 13974 30839 13922 30840 13921 30840 13946 30840 13921 30841 13898 30841 13897 30841 13917 30842 13920 30842 13918 30842 13918 30843 13919 30843 13899 30843 13878 30844 13879 30844 13900 30844 13874 30845 13883 30845 13878 30845 13903 30846 13924 30846 13912 30846 14060 30847 14087 30847 14056 30847 14056 30848 14024 30848 14060 30848 13940 30849 13912 30849 13924 30849 13885 30850 13903 30850 13893 30850 13893 30851 13872 30851 13868 30851 13872 30852 13873 30852 13869 30852 13886 30853 13887 30853 13904 30853 13890 30854 13910 30854 13886 30854 13925 30855 13905 30855 13938 30855 13906 30856 13930 30856 13929 30856 13925 30857 13939 30857 13929 30857 13939 30858 13952 30858 13906 30858 13928 30859 13927 30859 13936 30859 13936 30860 13935 30860 13928 30860 13966 30861 13956 30861 13909 30861 13966 30862 13986 30862 13956 30862 13956 30863 13965 30863 13909 30863 13985 30864 13931 30864 13986 30864 13985 30865 13963 30865 13954 30865 13983 30866 13954 30866 13962 30866 13987 30867 14018 30867 14001 30867 13934 27839 13964 27838 14002 27840 14002 30868 13989 30868 13987 30868 14001 30869 13984 30869 13934 30869 13989 30870 13988 30870 13958 30870 13990 30871 13957 30871 13999 30871 13999 30872 13998 30872 13991 30872 14000 30873 13991 30873 13998 30873 14033 30874 14020 30874 14000 30874 14020 30875 14032 30875 14022 30875 14031 30876 13996 30876 14023 30876 13996 30877 13997 30877 13993 30877 14061 30878 14086 30878 14059 30878 14055 30879 14054 30879 14061 30879 14025 30880 14055 30880 14059 30880 14029 30881 14028 30881 14025 30881 14087 30882 14119 30882 14120 30882 14150 30883 14180 30883 14182 30883 14180 30884 14150 30884 14148 30884 14214 30885 14259 30885 14246 30885 14282 30886 14320 30886 14283 30886 14354 30887 14318 30887 14283 30887 14317 30888 14354 30888 14382 30888 14416 30889 14382 30889 14383 30889 14463 30890 14417 30891 14416 30892 14469 30893 14463 30893 14420 30893 14470 30894 14469 30894 14467 30894 14422 30895 14386 30895 14385 30895 14423 30896 14470 30896 14385 30896 14505 30897 14468 30897 14422 30897 14523 30898 14505 30898 14471 30898 14505 30899 14523 30899 14526 30899 14502 30900 14525 30900 14524 30900 14525 30901 14502 30901 14503 30901 14503 30902 14458 30902 14461 30902 14414 30903 14462 30903 14411 30903 14414 30904 14381 30904 14462 30904 14381 30905 14380 30905 14413 30905 14277 30906 14312 30906 14316 30906 14241 30907 14279 30907 14277 30907 14379 30908 14380 30908 14312 30908 14240 30909 14278 30909 14241 30909 14243 30910 14209 30910 14242 30910 14144 30911 14117 30911 14177 30911 14210 30912 14144 30912 14177 30912 14117 30913 14116 30913 14145 30913 14142 30914 14115 30914 14141 30914 14113 30915 14091 30915 14090 30915 14078 30916 14050 30916 14051 30916 13967 30917 14017 30917 14013 30917 14014 30918 13980 30918 13979 30918 13967 30919 13940 30919 13950 30919 14121 30920 14102 30920 14101 30920 14363 30921 14389 30921 14364 30921 14330 30922 14364 30922 14331 30922 14102 30923 14121 30923 14129 30923 14099 30924 14096 30924 14122 30924 14151 30925 14123 30925 14100 30925 14160 30926 14128 30926 14153 30926 14159 30927 14158 30927 14153 30927 14127 30928 14124 30928 14158 30928 14127 30929 14183 30929 14124 30929 14192 30930 14191 30930 14183 30930 14217 30931 14186 30931 14191 30931 14190 30932 14215 30932 14155 30932 14186 30933 14217 30933 14155 30933 14216 30934 14215 30934 14224 30934 14248 30935 14286 30935 14216 30935 14250 30936 14219 30936 14286 30936 14223 30937 14249 30937 14187 30937 14219 30938 14250 30938 14187 30938 14257 30939 14287 30939 14258 30939 14252 30940 14287 30940 14257 30940 14255 30941 14296 30941 14251 30941 14220 30942 14252 30942 14251 30942 14322 30943 14289 30943 14296 30943 14357 30944 14321 30944 14322 30944 14329 30945 14298 30945 14357 30945 14256 30946 14293 30946 14295 30946 14298 30947 14329 30947 14256 30947 14292 30948 14330 30948 14294 30948 14392 30949 14432 30949 14359 30949 14392 30950 14434 30950 14432 30950 14478 30951 14479 30951 14528 30951 14544 30952 14541 30952 14510 30952 14531 30953 14558 30953 14544 30953 14563 30954 14558 30954 14531 30954 14547 30955 14546 30955 14563 30955 14576 30956 14564 30956 14546 30956 14561 30957 14560 30957 14576 30957 14560 30958 14575 30958 14577 30958 14575 30959 14569 30959 14583 30959 14569 30960 14571 30960 14581 30960 14579 30961 14552 30961 14568 30961 14579 30962 14580 30962 14552 30962 14551 30963 14537 30963 14567 30963 14537 30964 14536 30964 14550 30964 14536 30965 14517 30965 14549 30965 14489 30966 14487 30966 14534 30966 14487 30967 14441 30967 14486 30967 14440 30968 14396 30968 14484 30968 14396 30969 14395 30969 14439 30969 14370 30970 14394 30970 14395 30970 14370 30971 14334 30971 14367 30971 14302 30972 14265 30972 14333 30972 14264 30973 14263 30973 14265 30973 14262 30974 14263 30974 14197 30974 14227 30975 14195 30975 14226 30975 14173 30976 14194 30976 14162 30976 14129 30977 14136 30977 14130 30977 14139 30978 14110 30978 14111 30978 14474 30979 14431 30979 14436 30979 14433 30980 14430 30980 14429 30980 14110 30981 14139 30981 14135 30981 14137 30982 14140 30982 14111 30982 14131 30983 14174 30983 14138 30983 14131 30984 14164 30984 14174 30984 14109 30985 14108 30985 14138 30985 14196 30986 14207 30986 14206 30986 14198 30987 14239 30987 14238 30987 14239 30988 14198 30988 14260 30988 14260 30989 14228 30989 14261 30989 14332 30990 14299 30990 14301 30990 14304 30991 14369 30991 14332 30991 14335 30992 14369 30992 14304 30992 14368 30993 14369 30993 14335 30993 14371 30994 14438 30994 14366 30994 14372 30995 14371 30995 14366 30995 14437 30996 14438 30996 14398 30996 14485 30997 14437 30997 14397 30997 14483 30998 14485 30998 14443 30998 14442 30999 14513 30999 14512 30999 14488 31000 14514 31000 14513 31000 14490 31001 14548 31001 14515 31001 14519 31002 14566 31002 14548 31002 14515 31003 14514 31003 14490 31003 14539 31004 14587 31004 14578 31004 14519 31005 14518 31005 14565 31005 14586 31006 14587 31006 14539 31006 14591 31007 14586 31007 14538 31007 14588 31008 14570 31008 14589 31008 14570 31009 14588 31009 14553 31009 14590 31010 14574 31010 14584 31010 14557 31011 14556 31011 14572 31011 14585 31012 14573 31012 14559 31012 14557 31013 14562 31013 14542 31013 14533 31014 14542 31014 14545 31014 14481 31015 14509 31015 14529 31015 14480 31016 14508 31016 14509 31016 14543 31017 14533 31017 14511 31017 14428 31018 14477 31018 14508 31018 14508 31019 14480 31019 14429 31019 14474 31020 14475 31020 14431 31020 14475 31021 14473 31021 14427 31021 14476 31022 14506 31022 14507 31022 14446 31023 14507 31023 14520 31023 14472 31024 14506 31024 14476 31024 14507 31025 14446 31025 14493 31025 14473 31026 14472 31026 14425 31026 14496 31027 14494 31027 14449 31027 14451 31028 14453 31028 14496 31028 14499 31029 14498 31029 14453 31029 14452 31030 14450 31030 14499 31030 14495 31031 14497 31031 14450 31031 14522 31032 14445 31032 14501 31032 14492 31033 14445 31033 14522 31033 14399 31034 14400 31034 14501 31034 14445 31035 14492 31035 14447 31035 14336 31036 14456 31036 14400 31036 14456 31037 14336 31037 14402 31037 14402 31038 14338 31038 14403 31038 14340 31039 14342 31039 14406 31039 14342 31040 14344 31040 14408 31040 14344 31041 14343 31041 14409 31041 14343 31042 14341 31042 14407 31042 14376 31043 14410 31043 14457 31043 14404 31044 14377 31044 14454 31044 14377 31045 14404 31045 14339 31045 14339 31046 14308 31046 14377 31046 14307 31047 14348 31047 14347 31047 14348 31048 14307 31048 14349 31048 14349 31049 14309 31049 14346 31049 14268 31050 14345 31050 14305 31050 14346 31051 14306 31051 14305 31051 14311 31052 14350 31053 14375 31054 14268 31055 14233 31055 14272 31055 14272 31056 14233 31056 14273 31056 14273 31057 14232 31057 14275 31057 14275 31058 14235 31058 14274 31058 14199 31059 14276 31059 14231 31059 14276 31060 14199 31060 14237 31060 14276 31061 14271 31061 14231 31061 14204 31062 14201 31062 14199 31062 14204 31063 14167 31063 14205 31063 14169 31064 14202 31064 14205 31064 14168 31065 14165 31065 14172 31065 14172 31066 14104 31066 14134 31066 14169 31067 14168 31067 14172 31067 14595 31068 14592 31068 14594 31068 15102 31069 15132 31069 15070 31069 15135 31070 15105 31070 15104 31070 14597 31071 14598 31071 14594 31071 15070 31072 15104 31072 15105 31072 14594 31073 14598 31073 14595 31073 14596 31074 14592 31074 14599 31074 14600 31075 14596 31075 14599 31075 14600 31076 14603 31076 14610 31076 14600 31077 14645 31077 14668 31077 14613 31078 14604 31078 14612 31078 14623 31079 14622 31079 14603 31079 14834 31080 14822 31081 14795 31082 14758 31083 14725 31083 14795 31083 14667 31084 14725 31084 14757 31084 14885 31085 14857 31086 14834 31080 14649 31087 14669 28967 14670 28966 14615 31088 14604 31088 14630 31088 14641 31089 14661 31089 14662 31089 14890 31090 14862 31090 14889 31090 14890 31091 14885 31091 14862 31091 14923 31092 14955 31092 14891 31092 14889 31093 14891 31093 14921 31093 14673 28968 14674 31094 14650 31095 14986 31096 14954 31096 14955 31096 14650 31095 14671 31097 14672 28382 14709 31098 14633 31098 14672 31098 14690 31099 14691 31100 14641 31101 14688 31102 14718 31103 14690 31099 15022 31104 15057 31104 15023 31104 15023 31105 15058 31105 15056 31105 14700 31106 14699 31107 14675 31108 14987 31109 14986 31109 15024 31109 14987 31110 15024 31110 15022 31110 15056 31111 15095 31111 15157 31111 15095 31112 15205 31112 15157 31112 14698 31113 14727 31113 14728 31113 14675 31114 14697 31114 14698 31114 14719 31115 14720 31115 14687 31115 14659 31116 14752 31116 14755 31116 14688 31117 14639 31117 14687 31117 15208 31118 15212 31118 15270 31118 15284 31119 15269 31119 15270 31119 15100 31120 15130 31120 15162 31120 15130 31121 15100 31121 15129 31121 14702 31122 14651 31122 14762 31122 15248 31123 15269 31123 15247 31123 15063 31124 15207 31124 15167 31124 14701 31125 14734 31126 14735 31127 14766 31128 14677 31128 14735 31128 14677 31129 14651 31129 14701 31129 14750 31130 14751 31130 14788 31130 14715 31131 14714 31131 14750 31131 14714 31132 14715 31132 14685 31132 14958 31133 14957 31133 14926 31133 15028 31134 15027 31134 15061 31134 15028 31135 14957 31135 15027 31135 14926 31136 14925 31136 14894 31136 15063 31137 15126 31137 15161 31137 14766 31138 14767 31138 14736 31138 14737 31139 14703 31139 14736 31139 14713 31140 14812 31140 14784 31140 14785 31141 14714 31141 14784 31141 14739 31142 14829 31142 14747 31142 14838 31143 14864 31143 14894 31143 14769 31144 14768 31144 14739 31144 14747 31145 14780 31145 14781 31145 14739 31146 14747 31146 14770 31146 14779 31147 14807 31147 14770 31147 14867 31148 14826 31148 14840 31148 14801 31149 14807 31149 14865 31149 14873 31150 14807 31150 14884 31150 14856 31151 14878 31151 14879 31151 14971 31152 15004 31152 15005 31152 15004 31153 14971 31153 14983 31153 14970 31154 14938 31154 14982 31154 14945 31155 14948 31155 14949 31155 14896 31156 14841 31156 14868 31156 14950 31157 14938 31157 14918 31157 14897 31158 14898 31158 14868 31158 14918 31159 14917 31159 14882 31159 15111 31160 15077 31160 15112 31160 15017 31161 15019 31161 15018 31161 14915 31162 14980 31162 15018 31162 15137 31163 15114 31163 15110 31163 15006 31164 15005 31164 15045 31164 15045 31165 15043 31165 15007 31165 15043 31166 15076 31166 15044 31166 14929 31167 14870 31167 14899 31167 14896 31168 14927 31168 14928 31168 14899 31169 14841 31169 14928 31169 15258 31170 15231 31170 15257 31170 15259 31171 15260 31171 15231 31171 15230 31172 15228 31172 15256 31172 15091 31173 15092 31173 15093 31173 14980 31174 15054 31174 15090 31174 15229 31175 15227 31175 15183 31175 15138 31176 15181 31176 15229 31176 15089 31177 15119 31177 15094 31177 15137 31178 15182 31179 15181 31180 14962 31181 14900 31181 14931 31181 14963 31182 14870 31182 14960 31182 14929 31183 14959 31184 14960 31185 15332 31186 15325 31186 15323 31186 15200 31187 15146 31187 15199 31187 15334 31188 15328 31188 15325 31188 15323 31189 15330 31189 15332 31189 15312 31190 15322 31190 15330 31190 15054 31191 15152 31191 15151 31191 15147 31192 15150 31192 15152 31192 15149 31193 15054 31193 15151 31193 15118 31194 15146 31194 15147 31194 15322 31195 15312 31195 15294 31195 15310 31196 15293 31196 15292 31196 15310 31197 15309 31197 15293 31197 15154 31198 15054 31198 15244 31198 15278 31199 15260 31199 15279 31199 14995 31200 14933 31200 14964 31200 14996 31201 14900 31201 14993 31201 15285 31202 15288 31202 15286 31202 15288 31203 15299 31203 15301 31203 15273 31204 15272 31204 15287 31204 15131 31205 15242 31205 15241 31205 15238 31206 15240 31206 15242 31206 15236 31207 15131 31207 15241 31207 15321 31208 15327 31208 15308 31208 15329 31209 15316 31209 15302 31209 15316 31210 15300 31210 15302 31210 15039 31211 14965 31211 15000 31211 14995 31212 15032 31212 15033 31212 15042 31213 14933 31213 15033 31213 15252 31214 15221 31214 15222 31214 15173 31215 15134 31215 15176 31215 15220 31216 15131 31216 15169 31216 15109 31217 15133 31217 15103 31217 15222 31218 15272 31218 15253 31218 14997 31219 14965 31219 15038 31219 15034 31220 14997 31220 15067 31220 15102 31221 15070 31221 15034 31221 15106 31222 15069 31222 15105 31222 15106 31223 15071 31223 15069 31223 15035 31224 15071 31224 14998 31224 15072 31225 15107 31225 15108 31225 15179 31226 15177 31226 15136 31226 15178 31227 15177 31227 15226 31227 15217 31228 15072 31228 15216 31228 14998 31229 15036 31229 15037 31229 15291 31230 15275 31230 15289 31230 15303 31231 15305 31231 15306 31231 15277 31232 15276 31232 15255 31232 15275 31233 15276 31233 15277 31233 15318 31234 15319 31234 15317 31234 15196 31235 15197 31235 15081 31235 15197 31236 15195 31236 15081 31236 15194 31237 15081 31237 15192 31237 15193 31238 15190 31238 15081 31238 15223 31239 15225 31239 15255 31239 15066 31240 14966 31240 15101 31240 15066 31241 15040 31241 14966 31241 15298 31242 15295 31242 15297 31242 15281 31243 15295 31243 15298 31243 15081 31244 15117 31244 15144 31244 15261 31245 15280 31245 15283 31245 15283 31246 15280 31246 15282 31246 15297 31247 15296 31247 15315 31247 15234 31248 15233 31248 15263 31248 15088 31249 15086 31249 15014 31249 15087 31250 15014 31250 15085 31250 15086 31251 15084 31251 15014 31251 15082 31252 15080 31252 15014 31252 15314 31253 15313 31253 15326 31253 14967 31254 14932 31254 15002 31254 15001 31255 14932 31255 15041 31255 15188 31256 15187 31256 15184 31256 15187 31257 15141 31257 15184 31257 15142 31258 15115 31258 15139 31258 15140 31259 15141 31259 15142 31259 15013 31260 14944 31260 15012 31260 15185 31261 15233 31261 15232 31261 15053 31262 15014 31262 15050 31262 15053 31263 15051 31263 15014 31263 14992 31264 14901 31264 15030 31264 14992 31265 14968 31265 14901 31265 15011 31266 14972 31266 15008 31266 15009 31267 15010 31267 15011 31267 15009 31268 15046 31268 15047 31268 15048 31269 15010 31269 15009 31269 14975 31270 14877 31270 14974 31270 15116 31271 15079 31271 15078 31271 14979 31272 14944 31272 14978 31272 14979 31273 14976 31273 14944 31273 14871 31274 14869 31274 14936 31274 14935 31275 14869 31275 14961 31275 14941 31276 14942 31276 14940 31276 14940 31277 14907 31277 14939 31277 14874 31278 14906 31278 14908 31278 14851 31279 14874 31279 14875 31279 14973 31280 14942 31280 14941 31280 14910 31281 14832 31281 14911 31281 14903 31282 14827 31282 14902 31282 14845 31283 14846 31283 14806 31283 14855 31284 14806 31284 14851 31284 14849 31285 14848 31285 14806 31285 14844 31286 14843 31286 14802 31286 14771 31287 14802 31287 14806 31287 14748 31288 14738 31288 14771 31288 14738 31289 14748 31289 14811 31289 14847 31290 14905 31290 14863 31290 14773 31291 14704 31291 14772 31291 14748 31292 14712 31292 14782 31292 14937 31293 14969 31293 14956 31293 15097 31294 15064 31294 15029 31294 15026 31295 14969 31295 15029 31295 14905 31296 14937 31296 14924 31296 15159 31297 15127 31297 15099 31297 14776 31298 14676 31298 14775 31298 14741 31299 14740 31299 14676 31299 14815 31300 14814 31300 14712 31300 14787 31301 14786 31301 14712 31301 15214 31302 15210 31302 15209 31302 15204 31303 15271 31303 15215 31303 15128 31304 15164 31304 15165 31304 15211 31305 15164 31305 15128 31305 14744 31306 14676 31306 14777 31306 15268 31307 15267 31307 15204 31307 15202 31308 15246 31308 15204 31308 14732 31309 14652 31309 14763 31309 14743 31310 14652 31310 14742 31310 14793 31311 14792 31311 14821 31311 14793 31312 14821 31312 14833 31312 14716 31313 14792 31313 14793 31313 14717 31314 14716 31314 14686 31314 15158 31315 15155 31315 15096 31315 15125 31316 15096 31316 15124 31316 15060 31317 15059 31317 14989 31317 14952 31318 15021 31318 15025 31318 14746 31319 14708 31319 14652 31319 15122 31320 15155 31320 15202 31320 14985 31321 14952 31321 14984 31321 14730 31322 14632 31322 14729 31322 14707 31323 14632 31323 14706 31323 14722 31324 14658 31324 14721 31324 14658 31325 14753 31325 14754 31325 14660 31326 14689 31326 14658 31326 14824 31327 14860 31327 14861 31327 14836 31328 14861 31328 14888 31328 14887 31329 14888 31329 14920 31329 14919 31330 14920 31330 14953 31330 14860 31331 14824 31331 14886 31331 14680 31332 14614 31332 14679 31332 14680 31333 14696 31333 14614 31333 14666 31334 14621 31334 14665 31334 14666 31335 14692 31335 14621 31335 14824 31336 14797 31336 14823 31336 14794 31337 14823 31337 14797 31337 14756 31338 14794 31338 14760 31338 14724 31339 14693 31339 14723 31339 14859 31340 14824 31340 14858 31340 14654 31341 14614 31341 14682 31341 14614 31342 14634 31342 14635 31342 14642 31343 14608 31343 14664 31343 14607 31344 14602 31344 14606 31344 14601 31345 14656 31345 14657 31345 14617 31346 14616 31346 14601 31346 14625 31347 14608 31347 14624 31347 14601 31348 14602 31348 14597 31348 14592 31349 14596 31349 14597 31349 14601 31350 14597 31350 14600 31350 14601 31351 14600 31351 14605 31351 14605 31352 14604 31352 14614 31352 14614 31353 14615 31353 14632 31353 14632 31354 14633 31354 14652 31354 14652 31355 14651 31355 14676 31355 14676 31356 14677 31356 14704 31356 14704 31357 14703 31357 14738 31357 14739 31358 14770 31358 14771 31358 14771 31359 14770 31359 14802 31359 14802 31360 14801 31360 14827 31360 14827 31361 14826 31361 14842 31361 14870 31362 14869 31362 14842 31362 14869 31363 14870 31363 14901 31363 14933 31364 14932 31364 14901 31364 14966 31365 14932 31365 14965 31365 14998 31366 14966 31366 14997 31366 15034 31367 15035 31367 14998 31367 15070 31368 15069 31368 15035 31368 15132 31369 15102 31369 15106 31369 15071 31370 15106 31370 15068 31370 15067 31371 15072 31371 15071 31371 15067 31372 15131 31372 15145 31372 15131 31373 15118 31373 15081 31373 15118 31374 15054 31374 15014 31374 14944 31375 15014 31375 14980 31375 14877 31376 14944 31376 14915 31376 14832 31377 14877 31377 14856 31377 14806 31378 14832 31378 14807 31378 14806 31379 14807 31379 14778 31379 14779 31380 14747 31380 14748 31380 14748 31381 14747 31381 14712 31381 14712 31382 14713 31382 14686 31382 14686 31383 14685 31383 14658 31383 14658 31384 14659 31384 14640 31384 14640 31385 14639 31385 14621 31385 14621 31386 14620 31386 14608 31386 14608 31387 14609 31387 14602 31387 14598 31388 14602 31388 14599 31388 14610 31389 14607 31389 14606 31389 14811 31390 14809 31390 14828 31390 14829 31391 14838 31391 14828 31391 14607 31392 14610 31392 14627 31392 14611 31393 14606 31393 14626 31393 14638 31394 14645 31394 14626 31394 14693 31395 14667 31395 14645 31395 14725 31396 14693 31396 14759 31396 14797 31397 14796 31397 14759 31397 14796 31398 14824 31398 14837 31398 14836 31399 14887 31399 14862 31399 14887 31400 14919 31400 14891 31400 14923 31401 14952 31401 14988 31401 15059 31402 15057 31402 15024 31402 15057 31403 15059 31403 15058 31403 15122 31404 15095 31404 15058 31404 15095 31405 15156 31405 15203 31405 15248 31406 15204 31406 15208 31406 15163 31407 15162 31407 15208 31407 15162 31408 15163 31408 15100 31408 15100 31409 15099 31409 15063 31409 15029 31410 14969 31410 14957 31410 14957 31411 14969 31411 14925 31411 14925 31412 14905 31412 14893 31412 14809 31413 14811 31413 14780 31413 14782 31414 14783 31414 14781 31414 14808 31415 14810 31415 14812 31415 14813 31416 14812 31416 14814 31416 14784 31417 14813 31417 14815 31417 14785 31418 14784 31418 14786 31418 14785 31419 14749 31419 14714 31419 14788 31420 14751 31420 14793 31420 14816 31421 14788 31421 14818 31421 14833 31422 14821 31422 14816 31422 14817 31423 14789 31423 14821 31423 14820 31424 14792 31424 14817 31424 14790 31425 14750 31425 14792 31425 14715 31426 14716 31426 14752 31426 14715 31427 14790 31427 14716 31427 14791 31428 14752 31428 14717 31428 14754 31429 14753 31429 14791 31429 14753 31430 14722 31430 14755 31430 14721 31431 14720 31431 14719 31431 14720 31432 14721 31432 14687 31432 14688 31433 14687 31433 14660 31433 14660 31434 14692 31434 14688 31434 14692 31435 14666 31435 14718 31435 14666 31436 14665 31436 14690 31436 14665 31437 14642 31437 14641 31437 14661 31438 14664 31438 14662 31438 14644 31439 14643 31439 14662 31439 14622 31440 14623 31440 14644 31440 14618 31441 14627 31441 14622 31441 14647 31442 14668 31442 14656 31442 14804 31443 14831 31443 14800 31443 14800 31444 14768 31444 14804 31444 14684 31445 14656 31445 14668 31445 14629 31446 14647 31446 14637 31446 14637 31447 14616 31447 14612 31447 14613 31448 14612 31448 14617 31448 14630 31449 14631 31449 14648 31449 14634 31450 14654 31450 14630 31450 14669 31451 14649 31451 14682 31451 14650 31095 14674 31094 14673 28968 14669 31452 14683 31452 14673 31452 14683 31453 14696 31453 14650 31453 14672 31454 14671 31454 14680 31454 14680 31455 14679 31455 14672 31455 14710 31456 14700 31456 14653 31456 14710 31457 14730 31457 14700 31457 14700 31458 14709 31458 14653 31458 14729 31459 14675 31459 14730 31459 14698 31460 14697 31460 14707 31460 14707 31461 14706 31461 14727 31461 14745 31462 14746 31462 14762 31462 14746 31463 14745 31463 14708 31463 14702 31464 14731 31464 14746 31464 14706 31465 14678 31465 14745 31465 14701 31466 14702 31466 14733 31466 14734 31467 14701 31467 14743 31467 14735 31468 14734 31468 14742 31468 14744 31469 14735 31469 14742 31469 14777 31470 14764 31470 14744 31470 14764 31471 14776 31471 14766 31471 14775 31472 14740 31472 14767 31472 14740 31473 14741 31473 14737 31473 14805 31474 14830 31474 14803 31474 14799 31475 14798 31475 14805 31475 14769 31476 14799 31476 14803 31476 14773 31477 14772 31477 14769 31477 14831 31478 14863 31478 14864 31478 14894 31479 14924 31479 14926 31479 14924 31480 14894 31480 14892 31480 14958 31481 15003 31481 14990 31481 15026 31482 15064 31482 15027 31482 15027 31483 15097 31483 15062 31483 15061 31484 15098 31484 15126 31484 15160 31485 15126 31485 15127 31485 15160 31486 15165 31486 15161 31486 15213 31487 15207 31487 15164 31487 15211 31488 15210 31488 15213 31488 15166 31489 15130 31489 15129 31489 15167 31490 15214 31490 15129 31490 15166 31491 15215 31491 15212 31491 15267 31492 15249 31492 15215 31492 15268 31493 15270 31493 15249 31493 15246 31494 15269 31494 15268 31494 15202 31495 15247 31495 15269 31495 15155 31496 15205 31496 15247 31496 15205 31497 15155 31497 15158 31497 15158 31498 15125 31498 15206 31498 15125 31499 15124 31499 15157 31499 15021 31500 15056 31500 15060 31500 14985 31501 15023 31501 15021 31501 15123 31502 15124 31502 15056 31502 14984 31503 15022 31503 14985 31503 14987 31504 14953 31504 14986 31504 14888 31505 14861 31505 14921 31505 14954 31506 14888 31506 14921 31506 14861 31507 14860 31507 14889 31507 14886 31508 14859 31508 14885 31508 14857 31509 14835 31509 14834 31509 14822 31510 14794 31510 14795 31510 14711 31511 14761 31511 14757 31511 14758 31512 14724 31512 14723 31512 14711 31513 14684 31513 14694 31513 14865 31514 14846 31514 14845 31514 15107 31515 15133 31515 15108 31515 15074 31516 15108 31516 15075 31516 14846 31517 14865 31517 14873 31517 14843 31518 14840 31518 14866 31518 14895 31519 14867 31519 14844 31519 14903 31520 14897 31520 14904 31520 14903 31521 14902 31521 14897 31521 14871 31522 14868 31522 14902 31522 14871 31523 14927 31523 14868 31523 14936 31524 14935 31524 14927 31524 14928 31525 14935 31525 14961 31525 14934 31526 14959 31526 14899 31526 14930 31527 14961 31527 14899 31527 14968 31528 14992 31528 14959 31528 14991 31529 14960 31529 14992 31529 14991 31530 15030 31530 14994 31530 14962 31531 14931 31531 14967 31531 14967 31532 14931 31532 14963 31532 15001 31533 15031 31533 15002 31533 15001 31534 15041 31534 15031 31534 14999 31535 15040 31535 14995 31535 14964 31536 14996 31536 14995 31536 15066 31537 15033 31537 15040 31537 15101 31538 15065 31538 15066 31538 15073 31539 15042 31539 15101 31539 15000 31540 15037 31540 15039 31540 15042 31541 15073 31541 15000 31541 15036 31542 15074 31542 15038 31542 15136 31543 15176 31543 15103 31543 15136 31544 15178 31544 15176 31544 15222 31545 15223 31545 15272 31545 15288 31546 15285 31546 15254 31546 15299 31547 15288 31547 15275 31547 15307 31548 15302 31548 15275 31548 15308 31549 15307 31549 15291 31549 15320 31550 15308 31550 15290 31550 15321 31551 15320 31551 15305 31551 15304 31552 15319 31552 15321 31552 15319 31553 15313 31553 15327 31553 15324 31554 15325 31554 15313 31554 15295 31555 15312 31555 15323 31555 15323 31556 15324 31556 15296 31556 15295 31557 15281 31557 15311 31557 15293 31558 15294 31558 15281 31558 15280 31559 15261 31559 15293 31559 15233 31560 15231 31560 15278 31560 15231 31561 15185 31561 15230 31561 15184 31562 15140 31562 15228 31562 15140 31563 15139 31563 15183 31563 15139 31564 15078 31564 15138 31564 15114 31565 15078 31565 15111 31565 15044 31566 15077 31566 15046 31566 15008 31567 15007 31567 15009 31567 14941 31568 14971 31568 15007 31568 14971 31569 14939 31569 14970 31569 14917 31570 14938 31570 14906 31570 14873 31571 14880 31571 14874 31571 14883 31572 14854 31572 14855 31572 15174 31573 15180 31573 15218 31573 15177 31574 15174 31574 15173 31574 14854 31575 14883 31575 14879 31575 14881 31576 14884 31576 14855 31576 14875 31577 14918 31577 14882 31577 14950 31578 14918 31578 14875 31578 14853 31579 14852 31579 14882 31579 14940 31580 14951 31580 14950 31580 14942 31581 14983 31581 14982 31581 14973 31582 15004 31582 14983 31582 15045 31583 15005 31583 15004 31583 15045 31584 15010 31584 15043 31584 15076 31585 15010 31585 15113 31585 15079 31586 15113 31586 15048 31586 15112 31587 15113 31587 15079 31587 15115 31588 15182 31588 15110 31588 15116 31589 15115 31589 15110 31589 15181 31590 15182 31590 15142 31590 15229 31591 15181 31591 15141 31591 15227 31592 15229 31592 15187 31592 15186 31593 15257 31593 15256 31593 15232 31594 15258 31594 15257 31594 15234 31595 15292 31595 15259 31595 15263 31596 15310 31596 15292 31596 15259 31597 15258 31597 15234 31597 15283 31598 15331 31598 15322 31598 15263 31599 15262 31599 15309 31599 15330 31600 15331 31600 15283 31600 15335 31601 15330 31601 15282 31601 15332 31602 15314 31602 15333 31602 15314 31603 15332 31603 15297 31603 15334 31604 15318 31604 15328 31604 15301 31605 15300 31605 15316 31605 15329 31606 15317 31606 15303 31606 15301 31607 15306 31607 15286 31607 15277 31608 15286 31608 15289 31608 15225 31609 15253 31609 15273 31609 15224 31610 15252 31610 15253 31610 15287 31611 15277 31611 15255 31611 15172 31612 15221 31612 15252 31612 15252 31613 15224 31613 15173 31613 15218 31614 15219 31614 15175 31614 15219 31615 15217 31615 15171 31615 15220 31616 15250 31616 15251 31616 15190 31617 15251 31617 15264 31617 15216 31618 15250 31618 15220 31618 15251 31619 15190 31619 15237 31619 15217 31620 15216 31620 15169 31620 15240 31621 15238 31621 15193 31621 15242 31622 15240 31622 15195 31622 15243 31623 15242 31623 15197 31623 15241 31624 15243 31624 15196 31624 15239 31625 15241 31625 15194 31625 15143 31626 15245 31626 15266 31626 15266 31627 15265 31627 15189 31627 15199 31628 15245 31628 15143 31628 15239 31629 15191 31629 15189 31629 15080 31630 15200 31630 15144 31630 15200 31631 15080 31631 15146 31631 15084 31632 15147 31632 15146 31632 15084 31633 15086 31633 15150 31633 15153 31634 15152 31634 15086 31634 15088 31635 15087 31635 15153 31635 15148 31636 15151 31636 15087 31636 15201 31637 15121 31637 15154 31637 15198 31638 15149 31638 15121 31638 15121 31639 15148 31639 15083 31639 15083 31640 15052 31640 15121 31640 15051 31641 15092 31641 15091 31641 15092 31642 15051 31642 15093 31642 15093 31643 15053 31643 15090 31643 15012 31644 15089 31644 15049 31644 15090 31645 15050 31645 15049 31645 15055 31646 15094 31647 15119 31648 15012 31649 14977 31649 15016 31649 15016 31650 14977 31650 15017 31650 15017 31651 14976 31651 15019 31651 15019 31652 14979 31652 15018 31652 14943 31653 15020 31653 14975 31653 14945 31654 14981 31654 15020 31654 15020 31655 15015 31655 14975 31655 14943 31656 14910 31656 14945 31656 14948 31657 14911 31657 14949 31657 14913 31658 14946 31658 14949 31658 14912 31659 14909 31659 14916 31659 14916 31660 14848 31660 14878 31660 14913 31661 14912 31661 14916 31661</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_controllers/> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Kinton" name="Kinton" type="NODE"> + <matrix sid="transform">-6.39758e-10 -6.39758e-10 -0.001 0 -0.001 -7.82652e-12 6.39758e-10 0 -7.82693e-12 0.001 -6.39758e-10 0 0 0 0 1</matrix> + <instance_geometry url="#Kinton-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="mat_kinton_struct-material" target="#mat_kinton_struct-material"/> + <instance_material symbol="mat_helix_front-material" target="#mat_helix_front-material"/> + <instance_material symbol="mat_helix_back-material" target="#mat_helix_back-material"/> + <instance_material symbol="mat_pc_embed-material" target="#mat_pc_embed-material"/> + <instance_material symbol="mat_battery-material" target="#mat_battery-material"/> + <instance_material symbol="mat_marker-material" target="#mat_marker-material"/> + <instance_material symbol="mat_potes-material" target="#mat_potes-material"/> + </technique_common> + </bind_material> + </instance_geometry> + <node id="Camera_001" name="Camera_001" type="NODE"> + <matrix sid="parentinverse">0.7071065 0.707107 -7.82691e-9 0 4.57912e-7 -4.46842e-7 1 0 0.707107 -0.7071065 -6.39758e-7 0 0 0 0 1</matrix> + <matrix sid="transform">-7.07107e-4 7.07106e-4 4.96011e-13 -1.43438e-4 -7.07106e-4 -7.07107e-4 -7.82707e-12 -4.64445e-5 -5.18379e-12 -5.8853e-12 0.001 -0.0018667 0 0 0 1</matrix> + <instance_camera url="#Camera_001-camera"/> + </node> + <node id="Lamp_001" name="Lamp_001" type="NODE"> + <matrix sid="parentinverse">0.7071065 0.707107 -7.82691e-9 0 4.57912e-7 -4.46842e-7 1 0 0.707107 -0.7071065 -6.39758e-7 0 0 0 0 1</matrix> + <matrix sid="transform">-7.07108e-7 7.07106e-4 4.96011e-13 -1.43438e-4 -7.07106e-7 -7.07107e-4 -7.82707e-12 -4.64445e-5 -5.18379e-15 -5.8853e-12 0.001 -0.0018667 0 0 0 1</matrix> + <instance_light url="#Lamp_001-light"/> + </node> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/kinton/kinton.stl b/kinton_description/meshes/kinton/kinton.stl new file mode 100644 index 0000000000000000000000000000000000000000..9d3f82ceb385f1cb7755e89d943d31e1808b1167 Binary files /dev/null and b/kinton_description/meshes/kinton/kinton.stl differ diff --git a/kinton_description/meshes/kinton/kinton2.dae b/kinton_description/meshes/kinton/kinton2.dae new file mode 100644 index 0000000000000000000000000000000000000000..5483a48efda9ca8b860afa7820a3b066e677eab9 --- /dev/null +++ b/kinton_description/meshes/kinton/kinton2.dae @@ -0,0 +1,319 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.67.0 r57123</authoring_tool> + </contributor> + <created>2015-07-28T13:18:28</created> + <modified>2015-07-28T13:18:28</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_images/> + <library_effects> + <effect id="mat_pc_embed-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.01503303 0.05598268 0.01891075 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_kinton_struct-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0.2 0.2 0.2 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.02485064 0.02485064 0.02485064 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_marker-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0.2 0.2 0.2 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.8 0.16 0.01876392 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_helix_front-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0.2 0.2 0.2 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.8 0.7547448 0.7886858 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_helix_back-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.1752779 0.1752779 0.1752779 1</color> + </diffuse> + <specular> + <color sid="specular">1 1 1 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <transparency> + <float sid="transparency">0.2</float> + </transparency> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="mat_battery-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0.2 0.2 0.2 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0 0.00206358 0 1</color> + </diffuse> + <specular> + <color sid="specular">0.1328631 0.1328631 0.1328631 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="mat_pc_embed-material" name="mat_pc_embed"> + <instance_effect url="#mat_pc_embed-effect"/> + </material> + <material id="mat_kinton_struct-material" name="mat_kinton_struct"> + <instance_effect url="#mat_kinton_struct-effect"/> + </material> + <material id="mat_marker-material" name="mat_marker"> + <instance_effect url="#mat_marker-effect"/> + </material> + <material id="mat_helix_front-material" name="mat_helix_front"> + <instance_effect url="#mat_helix_front-effect"/> + </material> + <material id="mat_helix_back-material" name="mat_helix_back"> + <instance_effect url="#mat_helix_back-effect"/> + </material> + <material id="mat_battery-material" name="mat_battery"> + <instance_effect url="#mat_battery-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="battery_001-mesh" name="battery.001"> + <mesh> + <source id="battery_001-mesh-positions"> + <float_array id="battery_001-mesh-positions-array" count="37848">-0.9321771 -0.9840878 -0.2849236 -0.9321771 1.015912 -0.2849236 1.067823 1.015912 -0.2849236 1.067823 -0.9840878 -0.2849236 -0.9321771 -0.9840878 1.715076 -0.9321771 1.015912 1.715076 1.067823 1.015912 1.715076 1.067823 -0.9840878 1.715076 1.844654 1.648557 2.884062 1.612723 1.416626 1.684062 1.844654 1.648557 1.684062 1.68909 1.804121 1.684063 2.011531 1.815435 1.576883 1.844654 1.648557 1.384062 2.011532 1.815432 18.48406 1.445845 1.24975 -0.3159387 1.612723 1.416626 1.384062 1.457159 1.57219 1.384063 1.612723 1.416626 2.884062 1.457159 1.57219 1.684062 1.954962 1.758866 0.8840625 1.68909 1.804121 1.384063 1.844654 1.648557 4.384063 1.612723 1.416626 3.184062 1.844654 1.648557 3.184062 1.68909 1.804121 3.184063 1.45716 1.57219 2.884063 1.612723 1.416626 4.384062 1.45716 1.57219 3.184062 1.68909 1.804121 2.884063 1.844654 1.648557 5.884063 1.612723 1.416626 4.684062 1.844654 1.648557 4.684063 1.689091 1.80412 4.684063 1.45716 1.572189 4.384063 1.612723 1.416626 5.884062 1.45716 1.572189 4.684063 1.68909 1.80412 4.384063 1.844654 1.648556 7.384062 1.612723 1.416626 6.184062 1.844654 1.648557 6.184062 1.689091 1.80412 6.184063 1.45716 1.572189 5.884063 1.612723 1.416625 7.384061 1.45716 1.572189 6.184062 1.689091 1.80412 5.884063 1.844654 1.648556 8.884062 1.612723 1.416625 7.684062 1.844654 1.648556 7.684062 1.689091 1.80412 7.684062 1.45716 1.572189 7.384062 1.612723 1.416625 8.884061 1.45716 1.572189 7.684062 1.689091 1.80412 7.384062 1.844654 1.648556 10.38406 1.612723 1.416625 9.184062 1.844654 1.648556 9.184062 1.689091 1.80412 9.184062 1.45716 1.572189 8.884062 1.612724 1.416625 10.38406 1.45716 1.572188 9.184062 1.689091 1.80412 8.884062 1.844654 1.648555 11.88406 1.612724 1.416625 10.68406 1.844654 1.648556 10.68406 1.689091 1.804119 10.68406 1.45716 1.572188 10.38406 1.612724 1.416625 11.88406 1.45716 1.572188 10.68406 1.689091 1.804119 10.38406 1.844654 1.648555 13.38406 1.612724 1.416624 12.18406 1.844654 1.648555 12.18406 1.689091 1.804119 12.18406 1.45716 1.572188 11.88406 1.612724 1.416624 13.38406 1.45716 1.572188 12.18406 1.689091 1.804119 11.88406 1.844655 1.648555 14.88406 1.612724 1.416624 13.68406 1.844654 1.648555 13.68406 1.689091 1.804119 13.68406 1.45716 1.572188 13.38406 1.612724 1.416624 14.88406 1.45716 1.572188 13.68406 1.689091 1.804119 13.38406 1.844655 1.648555 16.38406 1.612724 1.416624 15.18406 1.844655 1.648555 15.18406 1.689091 1.804118 15.18406 1.45716 1.572187 14.88406 1.612724 1.416624 16.38406 1.45716 1.572187 15.18406 1.689091 1.804118 14.88406 1.612724 1.416624 16.68406 1.844655 1.648555 16.68406 1.689091 1.804118 16.68406 1.45716 1.572187 16.38406 1.844655 1.648554 17.88406 1.612724 1.416623 17.88406 1.45716 1.572187 16.68406 1.689091 1.804118 16.38406 1.612724 1.416623 18.18406 1.844655 1.648554 18.18406 1.689091 1.804118 18.18406 1.457161 1.572187 17.88406 1.445847 1.249746 18.48406 1.457161 1.572187 18.18406 1.689091 1.804118 17.88406 2.294373 2.098278 -0.3159363 1.895565 1.69947 -1.815937 2.127496 1.931401 -1.815937 1.971933 2.086964 -1.815936 2.127496 1.931401 -2.115936 1.728687 1.532595 -14.71594 1.895565 1.69947 -2.115937 1.740002 1.855033 -2.115936 2.124668 1.928572 -0.3159368 1.954962 1.758866 -0.3159371 1.728688 1.532592 -0.3159381 1.740002 1.855033 -1.815936 1.895565 1.69947 -3.315937 2.127496 1.931401 -3.315936 1.971933 2.086964 -2.115936 1.971932 2.086964 -3.315935 2.127496 1.931401 -3.615936 1.895565 1.69947 -3.615936 1.740002 1.855033 -3.615936 1.740002 1.855033 -3.315937 1.895565 1.69947 -4.815936 2.127496 1.931401 -4.815936 1.971932 2.086964 -3.615935 1.971932 2.086965 -4.815935 2.127496 1.931401 -5.115936 1.895565 1.69947 -5.115936 1.740002 1.855034 -5.115936 1.740002 1.855034 -4.815936 1.895565 1.699471 -6.315936 2.127496 1.931402 -6.315936 1.971932 2.086965 -5.115935 1.971932 2.086965 -6.315935 2.127496 1.931402 -6.615936 1.895565 1.699471 -6.615937 1.740001 1.855034 -6.615936 1.740002 1.855034 -6.315936 1.895565 1.699471 -7.815937 2.127496 1.931402 -7.815936 1.971932 2.086965 -6.615936 1.971932 2.086965 -7.815936 2.127496 1.931402 -8.115938 1.895565 1.699471 -8.115938 1.740001 1.855034 -8.115937 1.740001 1.855034 -7.815936 1.895565 1.699471 -9.315937 2.127496 1.931402 -9.315937 1.971932 2.086965 -8.115936 1.971932 2.086966 -9.315936 2.127496 1.931402 -9.615938 1.895565 1.699471 -9.615938 1.740001 1.855035 -9.615937 1.740001 1.855035 -9.315937 1.895564 1.699471 -10.81594 2.127496 1.931402 -10.81594 1.971932 2.086966 -9.615936 1.971932 2.086966 -10.81593 2.127496 1.931403 -11.11594 1.895564 1.699471 -11.11594 1.740001 1.855035 -11.11594 1.740001 1.855035 -10.81594 1.895564 1.699472 -12.31594 2.127496 1.931403 -12.31594 1.971932 2.086966 -11.11594 1.971932 2.086966 -12.31593 2.127496 1.931403 -12.61594 1.895564 1.699472 -12.61594 1.740001 1.855035 -12.61594 1.740001 1.855035 -12.31594 1.895564 1.699472 -13.81594 2.127495 1.931403 -13.81594 1.971932 2.086966 -12.61594 1.971932 2.086966 -13.81593 2.127495 1.931403 -14.11594 1.895564 1.699472 -14.11594 1.740001 1.855035 -14.11593 1.740001 1.855035 -13.81593 2.294373 2.09828 -15.11593 1.971932 2.086966 -14.11593 2.407511 2.211415 0.9524115 2.124668 1.928572 0.08406323 1.969105 2.084136 0.08406412 1.799399 1.91443 -0.3159363 1.969105 2.084136 -0.3159359 2.127409 1.931313 0.2798309 2.135447 1.939352 0.4667049 1.971846 2.086877 0.2798321 2.148487 1.952391 0.639365 1.979884 2.094915 0.4667057 2.166089 1.969993 0.7911701 1.992923 2.107954 0.6393663 2.187558 1.991461 0.915638 2.010526 2.125556 0.791171 2.211976 2.015879 1.007842 2.031994 2.147025 0.9156393 2.266089 2.069993 1.084064 2.238404 2.042307 1.064679 2.056412 2.171443 1.007843 2.08284 2.197871 1.06468 2.251947 2.366978 0.9524124 2.110526 2.225557 1.084064 2.40751 2.211415 -0.3159361 2.13881 2.253841 -0.3159355 2.251947 2.366978 -0.3159352 2.068098 1.872007 -17.11594 3.284322 3.08823 -15.11593 2.138809 2.253844 -15.11593 3.284321 3.08823 -17.11594 3.128758 3.243793 -15.11593 3.128758 3.243794 -17.11593 1.912535 2.02757 -17.11594 1.573124 1.688158 -14.71594 1.573125 1.688156 -0.3159368 1.290282 1.405313 -0.3159378 1.813543 1.617441 19.88406 1.643837 1.447736 19.88406 1.290283 1.40531 18.48406 1.488273 1.603299 19.88406 1.657979 1.773005 19.88406 1.855969 1.970995 18.48406 1.799399 1.91443 0.8840637 1.855967 1.970998 1.576884 -1.555115 1.80412 2.884069 -1.323184 1.572189 1.684068 -1.555115 1.80412 1.684069 -1.710678 1.648557 1.684069 -1.721993 1.970997 1.576891 -1.555115 1.80412 1.384069 -1.721991 1.970994 18.48407 -1.156307 1.405312 -0.3159331 -1.323184 1.572189 1.384068 -1.478747 1.416626 1.384068 -1.323184 1.572189 2.884068 -1.478747 1.416626 1.684067 -1.665424 1.914429 0.8840701 -1.710678 1.648557 1.384069 -1.555115 1.80412 4.384069 -1.323184 1.572189 3.184067 -1.555115 1.80412 3.184069 -1.710678 1.648556 3.184069 -1.478747 1.416626 2.884067 -1.323184 1.572189 4.384068 -1.478747 1.416625 3.184067 -1.710678 1.648556 2.884069 -1.555115 1.804119 5.884069 -1.323184 1.572189 4.684067 -1.555115 1.804119 4.684069 -1.710678 1.648556 4.684069 -1.478747 1.416625 4.384068 -1.323184 1.572188 5.884068 -1.478747 1.416625 4.684067 -1.710678 1.648556 4.384069 -1.555115 1.804119 7.384069 -1.323184 1.572188 6.184067 -1.555115 1.804119 6.184069 -1.710678 1.648556 6.184069 -1.478747 1.416625 5.884068 -1.323184 1.572188 7.384068 -1.478747 1.416625 6.184067 -1.710678 1.648556 5.884069 -1.555115 1.804119 8.884069 -1.323184 1.572188 7.684068 -1.555115 1.804119 7.684069 -1.710678 1.648556 7.684069 -1.478747 1.416625 7.384068 -1.323184 1.572188 8.884067 -1.478747 1.416625 7.684068 -1.710678 1.648556 7.384069 -1.555114 1.804118 10.38407 -1.323184 1.572188 9.184067 -1.555115 1.804119 9.184069 -1.710678 1.648555 9.184069 -1.478747 1.416625 8.884068 -1.323183 1.572188 10.38407 -1.478747 1.416624 9.184068 -1.710678 1.648555 8.884069 -1.555114 1.804118 11.88407 -1.323183 1.572188 10.68407 -1.555114 1.804118 10.68407 -1.710678 1.648555 10.68407 -1.478747 1.416624 10.38407 -1.323183 1.572187 11.88407 -1.478747 1.416624 10.68407 -1.710678 1.648555 10.38407 -1.555114 1.804118 13.38407 -1.323183 1.572187 12.18407 -1.555114 1.804118 12.18407 -1.710678 1.648555 12.18407 -1.478747 1.416624 11.88407 -1.323183 1.572187 13.38407 -1.478747 1.416624 12.18407 -1.710678 1.648555 11.88407 -1.555114 1.804118 14.88407 -1.323183 1.572187 13.68407 -1.555114 1.804118 13.68407 -1.710678 1.648555 13.68407 -1.478747 1.416624 13.38407 -1.323183 1.572187 14.88407 -1.478747 1.416624 13.68407 -1.710678 1.648555 13.38407 -1.555114 1.804117 16.38407 -1.323183 1.572187 15.18407 -1.555114 1.804118 15.18407 -1.710678 1.648554 15.18407 -1.478746 1.416623 14.88407 -1.323183 1.572187 16.38407 -1.478746 1.416623 15.18407 -1.710678 1.648554 14.88407 -1.323183 1.572187 16.68407 -1.555114 1.804117 16.68407 -1.710677 1.648554 16.68407 -1.478746 1.416623 16.38407 -1.555114 1.804117 17.88407 -1.323183 1.572186 17.88407 -1.478746 1.416623 16.68407 -1.710677 1.648554 16.38407 -1.323183 1.572186 18.18407 -1.555114 1.804117 18.18407 -1.710677 1.648554 18.18407 -1.478746 1.416623 17.88407 -1.156306 1.405309 18.48407 -1.478746 1.416623 18.18407 -1.710677 1.648554 17.88407 -2.004835 2.25384 -0.3159276 -1.606027 1.855032 -1.81593 -1.837958 2.086963 -1.815929 -1.993521 1.9314 -1.815929 -1.837958 2.086963 -2.115929 -1.439151 1.688158 -14.71593 -1.606027 1.855032 -2.11593 -1.761591 1.699469 -2.115931 -1.83513 2.084135 -0.3159289 -1.665424 1.914429 -0.3159299 -1.43915 1.688155 -0.3159315 -1.761591 1.699469 -1.815931 -1.606027 1.855033 -3.31593 -1.837958 2.086964 -3.315929 -1.993521 1.9314 -2.115929 -1.993522 1.9314 -3.315929 -1.837958 2.086964 -3.615928 -1.606027 1.855033 -3.61593 -1.761591 1.699469 -3.615931 -1.761591 1.699469 -3.315931 -1.606027 1.855033 -4.81593 -1.837958 2.086964 -4.815928 -1.993522 1.9314 -3.615928 -1.993522 1.931401 -4.815928 -1.837958 2.086964 -5.115928 -1.606027 1.855033 -5.115931 -1.761591 1.69947 -5.115931 -1.761591 1.69947 -4.81593 -1.606027 1.855033 -6.31593 -1.837958 2.086964 -6.315928 -1.993522 1.931401 -5.115928 -1.993522 1.931401 -6.315928 -1.837958 2.086964 -6.615928 -1.606028 1.855033 -6.615931 -1.761591 1.69947 -6.615931 -1.761591 1.69947 -6.31593 -1.606028 1.855033 -7.815929 -1.837958 2.086964 -7.815928 -1.993522 1.931401 -6.615928 -1.993522 1.931401 -7.815928 -1.837958 2.086964 -8.115928 -1.606028 1.855033 -8.115929 -1.761591 1.69947 -8.11593 -1.761591 1.69947 -7.815929 -1.606028 1.855034 -9.31593 -1.837959 2.086965 -9.315929 -1.993522 1.931401 -8.115929 -1.993522 1.931401 -9.31593 -1.837959 2.086965 -9.615928 -1.606028 1.855034 -9.615929 -1.761591 1.69947 -9.61593 -1.761591 1.69947 -9.315931 -1.606028 1.855034 -10.81593 -1.837959 2.086965 -10.81593 -1.993522 1.931402 -9.615929 -1.993522 1.931402 -10.81593 -1.837959 2.086965 -11.11593 -1.606028 1.855034 -11.11593 -1.761591 1.699471 -11.11593 -1.761591 1.699471 -10.81593 -1.606028 1.855034 -12.31593 -1.837959 2.086965 -12.31593 -1.993522 1.931402 -11.11593 -1.993522 1.931402 -12.31593 -1.837959 2.086965 -12.61593 -1.606028 1.855034 -12.61593 -1.761591 1.699471 -12.61593 -1.761591 1.699471 -12.31593 -1.606028 1.855035 -13.81593 -1.837959 2.086966 -13.81593 -1.993522 1.931402 -12.61593 -1.993523 1.931402 -13.81593 -1.837959 2.086966 -14.11593 -1.606028 1.855035 -14.11593 -1.761591 1.699471 -14.11593 -1.761591 1.699471 -13.81593 -2.004836 2.253843 -15.11593 -1.993523 1.931402 -14.11593 -2.117972 2.366977 0.9524206 -1.83513 2.084135 0.08407104 -1.990693 1.928571 0.08407068 -1.820987 1.758866 -0.3159303 -1.990693 1.928571 -0.3159293 -1.837871 2.086876 0.279839 -1.845909 2.094914 0.4667127 -1.993434 1.931313 0.2798387 -1.858949 2.107954 0.6393732 -2.001472 1.939351 0.4667124 -1.876551 2.125556 0.7911781 -2.014512 1.95239 0.6393728 -1.898019 2.147024 0.9156464 -2.032114 1.969992 0.7911776 -1.922437 2.171442 1.00785 -2.053583 1.991461 0.9156461 -1.976551 2.225556 1.084072 -1.948865 2.19787 1.064687 -2.078001 2.015879 1.00785 -2.104429 2.042307 1.064687 -2.273536 2.211414 0.9524202 -2.132114 2.069992 1.084071 -2.117972 2.366977 -0.315927 -2.160399 2.098277 -0.3159283 -2.273536 2.211414 -0.3159274 -1.778562 2.027569 -17.11593 -2.994786 3.243792 -15.11592 -2.1604 2.09828 -15.11593 -2.994786 3.243792 -17.11592 -3.150349 3.088228 -15.11592 -3.15035 3.088229 -17.11592 -1.934126 1.872006 -17.11593 -1.594714 1.532594 -14.71593 -1.594713 1.532592 -0.3159319 -1.31187 1.249749 -0.3159335 -1.524001 1.773004 19.88407 -1.354295 1.603299 19.88407 -1.311869 1.249746 18.48407 -1.509859 1.447735 19.88407 -1.679565 1.617441 19.88407 -1.877555 1.815431 18.48407 -1.820987 1.758866 0.8840698 -1.877556 1.815434 1.57689 -1.710678 -1.595649 2.884054 -1.478747 -1.363718 1.684054 -1.710678 -1.595649 1.684054 -1.555114 -1.751212 1.684053 -1.877555 -1.762526 1.576874 -1.710678 -1.595649 1.384054 -1.877554 -1.762529 18.48405 -1.31187 -1.19684 -0.3159449 -1.478747 -1.363718 1.384055 -1.323184 -1.519281 1.384054 -1.478747 -1.363718 2.884055 -1.323184 -1.519281 1.684054 -1.820987 -1.705957 0.8840538 -1.555114 -1.751212 1.384053 -1.710678 -1.595649 4.384054 -1.478747 -1.363718 3.184054 -1.710678 -1.595649 3.184054 -1.555114 -1.751212 3.184053 -1.323183 -1.519281 2.884054 -1.478747 -1.363718 4.384055 -1.323183 -1.519281 3.184053 -1.555114 -1.751212 2.884053 -1.710677 -1.595649 5.884054 -1.478747 -1.363718 4.684054 -1.710677 -1.595649 4.684054 -1.555114 -1.751213 4.684053 -1.323183 -1.519282 4.384054 -1.478747 -1.363718 5.884055 -1.323183 -1.519282 4.684053 -1.555114 -1.751213 4.384053 -1.710677 -1.59565 7.384053 -1.478747 -1.363719 6.184054 -1.710677 -1.59565 6.184054 -1.555114 -1.751213 6.184053 -1.323183 -1.519282 5.884054 -1.478747 -1.363719 7.384054 -1.323183 -1.519282 6.184053 -1.555114 -1.751213 5.884053 -1.710677 -1.59565 8.884053 -1.478747 -1.363719 7.684054 -1.710677 -1.59565 7.684053 -1.555114 -1.751213 7.684052 -1.323183 -1.519282 7.384053 -1.478747 -1.363719 8.884054 -1.323183 -1.519282 7.684053 -1.555114 -1.751213 7.384052 -1.710677 -1.59565 10.38405 -1.478747 -1.363719 9.184054 -1.710677 -1.59565 9.184053 -1.555114 -1.751214 9.184053 -1.323183 -1.519283 8.884053 -1.478746 -1.363719 10.38405 -1.323183 -1.519283 9.184053 -1.555114 -1.751214 8.884053 -1.710677 -1.595651 11.88405 -1.478746 -1.36372 10.68405 -1.710677 -1.595651 10.68405 -1.555114 -1.751214 10.68405 -1.323183 -1.519283 10.38405 -1.478746 -1.36372 11.88405 -1.323183 -1.519283 10.68405 -1.555114 -1.751214 10.38405 -1.710677 -1.595651 13.38405 -1.478746 -1.36372 12.18405 -1.710677 -1.595651 12.18405 -1.555114 -1.751214 12.18405 -1.323183 -1.519283 11.88405 -1.478746 -1.36372 13.38405 -1.323183 -1.519283 12.18405 -1.555114 -1.751214 11.88405 -1.710677 -1.595651 14.88405 -1.478746 -1.36372 13.68405 -1.710677 -1.595651 13.68405 -1.555114 -1.751214 13.68405 -1.323183 -1.519283 13.38405 -1.478746 -1.36372 14.88405 -1.323183 -1.519283 13.68405 -1.555114 -1.751214 13.38405 -1.710677 -1.595651 16.38405 -1.478746 -1.36372 15.18405 -1.710677 -1.595651 15.18405 -1.555114 -1.751215 15.18405 -1.323183 -1.519284 14.88405 -1.478746 -1.363721 16.38405 -1.323183 -1.519284 15.18405 -1.555114 -1.751215 14.88405 -1.478746 -1.363721 16.68405 -1.710677 -1.595652 16.68405 -1.555113 -1.751215 16.68405 -1.323183 -1.519284 16.38405 -1.710677 -1.595652 17.88405 -1.478746 -1.363721 17.88405 -1.323183 -1.519284 16.68405 -1.555113 -1.751215 16.38405 -1.478746 -1.363721 18.18405 -1.710677 -1.595652 18.18405 -1.555113 -1.751215 18.18405 -1.323182 -1.519284 17.88405 -1.311868 -1.196844 18.48406 -1.323182 -1.519284 18.18405 -1.555113 -1.751215 17.88405 -2.160398 -2.045368 -0.3159473 -1.76159 -1.64656 -1.815946 -1.993521 -1.878491 -1.815947 -1.837957 -2.034054 -1.815947 -1.993521 -1.878491 -2.115946 -1.594714 -1.47968 -14.71594 -1.76159 -1.64656 -2.115946 -1.606026 -1.802123 -2.115947 -1.990692 -1.875663 -0.3159465 -1.820987 -1.705957 -0.3159461 -1.594713 -1.479683 -0.3159456 -1.606026 -1.802123 -1.815947 -1.76159 -1.646559 -3.315946 -1.993521 -1.878491 -3.315946 -1.837957 -2.034054 -2.115947 -1.837957 -2.034054 -3.315947 -1.993521 -1.87849 -3.615946 -1.76159 -1.646559 -3.615945 -1.606027 -1.802123 -3.615946 -1.606027 -1.802123 -3.315947 -1.76159 -1.646559 -4.815946 -1.993521 -1.87849 -4.815946 -1.837957 -2.034054 -3.615947 -1.837957 -2.034054 -4.815947 -1.993521 -1.87849 -5.115945 -1.76159 -1.646559 -5.115945 -1.606027 -1.802123 -5.115946 -1.606027 -1.802123 -4.815947 -1.76159 -1.646559 -6.315946 -1.993521 -1.87849 -6.315946 -1.837957 -2.034054 -5.115947 -1.837957 -2.034054 -6.315947 -1.993521 -1.87849 -6.615946 -1.76159 -1.646559 -6.615946 -1.606027 -1.802122 -6.615947 -1.606027 -1.802122 -6.315947 -1.76159 -1.646559 -7.815946 -1.993521 -1.87849 -7.815946 -1.837958 -2.034054 -6.615947 -1.837958 -2.034053 -7.815947 -1.993521 -1.87849 -8.115948 -1.76159 -1.646559 -8.115947 -1.606027 -1.802122 -8.115947 -1.606027 -1.802122 -7.815947 -1.76159 -1.646559 -9.315947 -1.993521 -1.878489 -9.315948 -1.837958 -2.034053 -8.115948 -1.837958 -2.034053 -9.315948 -1.993521 -1.878489 -9.615948 -1.76159 -1.646558 -9.615947 -1.606027 -1.802122 -9.615947 -1.606027 -1.802122 -9.315947 -1.76159 -1.646558 -10.81595 -1.993522 -1.878489 -10.81595 -1.837958 -2.034053 -9.615948 -1.837958 -2.034053 -10.81595 -1.993522 -1.878489 -11.11595 -1.76159 -1.646558 -11.11595 -1.606027 -1.802122 -11.11595 -1.606027 -1.802122 -10.81595 -1.76159 -1.646558 -12.31595 -1.993522 -1.878489 -12.31595 -1.837958 -2.034053 -11.11595 -1.837958 -2.034052 -12.31595 -1.993522 -1.878489 -12.61595 -1.76159 -1.646558 -12.61595 -1.606027 -1.802121 -12.61595 -1.606027 -1.802121 -12.31595 -1.761591 -1.646558 -13.81595 -1.993522 -1.878489 -13.81595 -1.837958 -2.034052 -12.61595 -1.837958 -2.034052 -13.81595 -1.993522 -1.878489 -14.11595 -1.761591 -1.646558 -14.11595 -1.606027 -1.802121 -14.11595 -1.606027 -1.802121 -13.81595 -2.160399 -2.045366 -15.11595 -1.837958 -2.034052 -14.11595 -2.273535 -2.158506 0.9524 -1.990692 -1.875663 0.08405345 -1.835129 -2.031226 0.0840522 -1.665423 -1.86152 -0.3159474 -1.835129 -2.031226 -0.3159477 -1.993434 -1.878404 0.279821 -2.001471 -1.886442 0.4666947 -1.83787 -2.033968 0.2798202 -2.014511 -1.899482 0.6393551 -1.845908 -2.042006 0.4666938 -2.032113 -1.917084 0.7911602 -1.858947 -2.055045 0.6393542 -2.053582 -1.938553 0.915628 -1.87655 -2.072648 0.7911589 -2.078 -1.962971 1.007831 -1.898018 -2.094116 0.9156271 -2.132113 -2.017084 1.084053 -2.104428 -1.989399 1.064669 -1.922436 -2.118534 1.00783 -1.948864 -2.144962 1.064668 -2.117971 -2.314069 0.9523992 -1.97655 -2.172648 1.084052 -2.273535 -2.158506 -0.3159475 -2.004834 -2.200932 -0.3159481 -2.117971 -2.314069 -0.3159484 -1.934125 -1.819091 -17.11595 -3.150348 -3.035316 -15.11595 -2.004835 -2.200929 -15.11595 -3.150348 -3.035315 -17.11595 -2.994784 -3.190879 -15.11595 -2.994785 -3.190879 -17.11595 -1.778562 -1.974654 -17.11595 -1.43915 -1.635244 -14.71595 -1.439149 -1.635246 -0.3159465 -1.156306 -1.352404 -0.3159458 -1.679564 -1.564539 19.88405 -1.509858 -1.394834 19.88405 -1.156305 -1.352407 18.48405 -1.354295 -1.550397 19.88405 -1.524 -1.720103 19.88405 -1.72199 -1.918093 18.48405 -1.665423 -1.861521 0.8840526 -1.721992 -1.91809 1.576873 1.689091 -1.751212 2.884047 1.45716 -1.519281 1.684048 1.689091 -1.751212 1.684047 1.844655 -1.595648 1.684047 1.855968 -1.918089 1.576866 1.689091 -1.751211 1.384047 1.85597 -1.918092 18.48404 1.290283 -1.352403 -0.3159502 1.45716 -1.519281 1.384048 1.612723 -1.363717 1.384049 1.45716 -1.519281 2.884048 1.612723 -1.363717 1.684049 1.7994 -1.86152 0.8840463 1.844655 -1.595648 1.384047 1.689091 -1.751212 4.384047 1.45716 -1.519281 3.184048 1.689091 -1.751212 3.184047 1.844655 -1.595648 3.184047 1.612723 -1.363718 2.884049 1.45716 -1.519281 4.384049 1.612723 -1.363718 3.184049 1.844655 -1.595648 2.884047 1.689091 -1.751212 5.884047 1.45716 -1.519281 4.684049 1.689091 -1.751212 4.684047 1.844655 -1.595649 4.684048 1.612723 -1.363718 4.384049 1.45716 -1.519281 5.884049 1.612723 -1.363718 4.68405 1.844655 -1.595649 4.384047 1.689092 -1.751212 7.384047 1.45716 -1.519281 6.184048 1.689091 -1.751212 6.184047 1.844655 -1.595649 6.184047 1.612723 -1.363718 5.884049 1.45716 -1.519282 7.384048 1.612723 -1.363718 6.184049 1.844655 -1.595649 5.884047 1.689092 -1.751213 8.884047 1.45716 -1.519282 7.684049 1.689092 -1.751212 7.684047 1.844655 -1.595649 7.684048 1.612724 -1.363718 7.384049 1.457161 -1.519282 8.884049 1.612724 -1.363718 7.684049 1.844655 -1.595649 7.384047 1.689092 -1.751213 10.38405 1.457161 -1.519282 9.184049 1.689092 -1.751213 9.184047 1.844655 -1.595649 9.184047 1.612724 -1.363719 8.884048 1.457161 -1.519282 10.38405 1.612724 -1.363719 9.184048 1.844655 -1.595649 8.884047 1.689092 -1.751213 11.88405 1.457161 -1.519282 10.68405 1.689092 -1.751213 10.68405 1.844655 -1.59565 10.68405 1.612724 -1.363719 10.38405 1.457161 -1.519282 11.88405 1.612724 -1.363719 10.68405 1.844655 -1.59565 10.38405 1.689092 -1.751214 13.38405 1.457161 -1.519283 12.18405 1.689092 -1.751213 12.18405 1.844655 -1.59565 12.18405 1.612724 -1.363719 11.88405 1.457161 -1.519283 13.38405 1.612724 -1.363719 12.18405 1.844655 -1.59565 11.88405 1.689092 -1.751214 14.88405 1.457161 -1.519283 13.68405 1.689092 -1.751214 13.68404 1.844655 -1.59565 13.68404 1.612724 -1.363719 13.38405 1.457161 -1.519283 14.88405 1.612724 -1.363719 13.68405 1.844655 -1.59565 13.38405 1.689092 -1.751214 16.38405 1.457161 -1.519283 15.18405 1.689092 -1.751214 15.18404 1.844655 -1.595651 15.18404 1.612724 -1.36372 14.88405 1.457161 -1.519283 16.38405 1.612724 -1.36372 15.18405 1.844655 -1.595651 14.88405 1.457161 -1.519283 16.68405 1.689092 -1.751214 16.68405 1.844655 -1.595651 16.68405 1.612725 -1.36372 16.38405 1.689092 -1.751214 17.88405 1.457161 -1.519284 17.88405 1.612725 -1.36372 16.68405 1.844655 -1.595651 16.38405 1.457161 -1.519284 18.18405 1.689092 -1.751214 18.18405 1.844656 -1.595651 18.18405 1.612725 -1.36372 17.88405 1.290284 -1.352406 18.48405 1.612725 -1.36372 18.18405 1.844656 -1.595651 17.88405 2.138811 -2.200931 -0.3159556 1.740002 -1.802123 -1.815953 1.971934 -2.034054 -1.815954 2.127497 -1.87849 -1.815954 1.971934 -2.034054 -2.115954 1.573125 -1.635243 -14.71595 1.740002 -1.802122 -2.115953 1.895566 -1.646559 -2.115953 1.969105 -2.031225 -0.3159547 1.7994 -1.86152 -0.3159537 1.573125 -1.635246 -0.3159521 1.895566 -1.646559 -1.815953 1.740002 -1.802122 -3.315953 1.971934 -2.034053 -3.315954 2.127497 -1.87849 -2.115954 2.127497 -1.87849 -3.315954 1.971934 -2.034053 -3.615954 1.740002 -1.802122 -3.615953 1.895566 -1.646559 -3.615953 1.895566 -1.646559 -3.315953 1.740002 -1.802122 -4.815953 1.971933 -2.034053 -4.815955 2.127497 -1.87849 -3.615954 2.127497 -1.87849 -4.815954 1.971933 -2.034053 -5.115954 1.740002 -1.802122 -5.115953 1.895566 -1.646559 -5.115952 1.895566 -1.646559 -4.815953 1.740002 -1.802122 -6.315953 1.971933 -2.034053 -6.315955 2.127497 -1.878489 -5.115953 2.127497 -1.878489 -6.315954 1.971933 -2.034053 -6.615955 1.740002 -1.802122 -6.615953 1.895565 -1.646558 -6.615953 1.895566 -1.646558 -6.315953 1.740002 -1.802121 -7.815952 1.971933 -2.034052 -7.815953 2.127497 -1.878489 -6.615954 2.127497 -1.878489 -7.815952 1.971933 -2.034052 -8.115954 1.740002 -1.802121 -8.115953 1.895565 -1.646558 -8.115953 1.895565 -1.646558 -7.815951 1.740002 -1.802121 -9.315953 1.971933 -2.034052 -9.315954 2.127497 -1.878489 -8.115955 2.127496 -1.878489 -9.315955 1.971933 -2.034052 -9.615954 1.740002 -1.802121 -9.615953 1.895565 -1.646558 -9.615953 1.895565 -1.646558 -9.315953 1.740002 -1.802121 -10.81595 1.971933 -2.034052 -10.81595 2.127496 -1.878489 -9.615955 2.127496 -1.878489 -10.81595 1.971933 -2.034052 -11.11595 1.740002 -1.802121 -11.11595 1.895565 -1.646557 -11.11595 1.895565 -1.646557 -10.81595 1.740002 -1.802121 -12.31595 1.971933 -2.034052 -12.31595 2.127496 -1.878488 -11.11595 2.127496 -1.878488 -12.31595 1.971933 -2.034052 -12.61595 1.740002 -1.802121 -12.61595 1.895565 -1.646557 -12.61595 1.895565 -1.646557 -12.31595 1.740002 -1.80212 -13.81595 1.971933 -2.034051 -13.81595 2.127496 -1.878488 -12.61595 2.127496 -1.878488 -13.81595 1.971933 -2.034051 -14.11595 1.740002 -1.80212 -14.11595 1.895565 -1.646557 -14.11595 1.895565 -1.646557 -13.81595 2.13881 -2.200928 -15.11596 2.127496 -1.878488 -14.11595 2.251948 -2.314068 0.9523909 1.969105 -2.031225 0.08404529 2.124669 -1.875662 0.08404564 1.954963 -1.705956 -0.315953 2.124669 -1.875662 -0.3159543 1.971847 -2.033967 0.2798133 1.979885 -2.042005 0.4666869 2.12741 -1.878404 0.2798137 1.992924 -2.055044 0.6393473 2.135448 -1.886441 0.4666872 2.010527 -2.072647 0.7911519 2.148487 -1.899481 0.6393476 2.031995 -2.094115 0.9156196 2.16609 -1.917083 0.7911522 2.056413 -2.118533 1.007823 2.187558 -1.938552 0.91562 2.110527 -2.172647 1.084045 2.082841 -2.144961 1.06466 2.211976 -1.96297 1.007823 2.238404 -1.989398 1.064661 2.407511 -2.158505 0.9523913 2.26609 -2.017084 1.084045 2.251948 -2.314068 -0.3159566 2.294374 -2.045368 -0.3159553 2.407511 -2.158505 -0.3159559 1.912535 -1.974654 -17.11595 3.12876 -3.190878 -15.11596 2.294373 -2.045365 -15.11595 3.12876 -3.190877 -17.11596 3.284323 -3.035314 -15.11596 3.284323 -3.035314 -17.11596 2.068099 -1.81909 -17.11595 1.728688 -1.47968 -14.71595 1.728689 -1.479682 -0.3159517 1.445846 -1.196839 -0.3159498 1.65798 -1.720102 19.88405 1.488274 -1.550397 19.88405 1.445847 -1.196843 18.48405 1.643837 -1.394833 19.88405 1.813543 -1.564539 19.88405 2.011533 -1.762528 18.48404 1.954963 -1.705957 0.8840466 2.011532 -1.762525 1.576867 4.953237 5.41051 -0.3159261 2.829182 3.085798 -0.3159329 2.795005 3.068428 -0.315933 2.795005 3.068428 0.7640669 2.568731 2.68659 -0.3159341 2.777635 3.034251 -0.3159331 2.777635 3.034251 0.7640668 2.295182 2.752453 -0.3159334 2.866933 3.079845 -0.3159331 2.829182 3.085798 0.7640669 2.894103 3.052675 -0.3159332 2.866933 3.079844 0.7640668 3.055456 2.859524 -0.3159342 2.900056 3.014924 -0.3159334 2.894103 3.052675 0.7640667 3.093207 2.853571 -0.3159343 3.011936 3.073129 -0.3159333 3.032593 3.150453 -0.3159331 3.011936 3.114639 -0.3159332 3.021279 2.842154 -0.3159342 2.882686 2.980747 -0.3159335 2.900056 3.014924 0.7640665 3.003909 2.807977 -0.3159343 2.84851 2.963377 -0.3159335 2.882686 2.980747 0.7640665 3.009863 2.770226 -0.3159345 2.810759 2.96933 -0.3159334 2.84851 2.963377 0.7640665 2.866573 2.724316 -0.3159344 2.783589 2.9965 -0.3159332 2.810759 2.96933 0.7640665 2.800662 2.805385 -0.315934 2.783589 2.9965 0.7640666 2.845917 2.760129 -0.3159343 2.687525 2.805384 -0.3159338 2.723338 2.826041 -0.3159338 2.764848 2.826041 -0.3159339 4.611091 4.867707 -0.3159281 4.576913 4.850337 -0.3159282 4.576913 4.850337 0.7640718 3.895263 4.013123 -0.3159307 4.559544 4.81616 -0.3159282 4.559544 4.81616 0.7640717 4.648841 4.861754 -0.3159282 4.611091 4.867707 0.7640718 4.676012 4.834584 -0.3159283 4.648841 4.861754 0.7640717 4.837365 4.641433 -0.3159294 4.681965 4.796833 -0.3159285 4.676012 4.834584 0.7640716 4.875116 4.63548 -0.3159295 4.80233 4.863523 -0.3159285 4.80233 4.905034 -0.3159283 4.803188 4.624063 -0.3159294 4.664595 4.762656 -0.3159286 4.681965 4.796833 0.7640714 4.785818 4.589886 -0.3159295 4.630418 4.745286 -0.3159286 4.664595 4.762656 0.7640713 4.79177 4.552135 -0.3159297 4.592667 4.751239 -0.3159285 4.630418 4.745286 0.7640713 4.654138 4.511882 -0.3159296 4.565496 4.778409 -0.3159284 4.592667 4.751239 0.7640714 4.588227 4.59295 -0.3159291 4.565496 4.778409 0.7640715 4.633482 4.547695 -0.3159294 4.47509 4.59295 -0.3159289 4.510904 4.613606 -0.3159289 4.552413 4.613606 -0.315929 4.803188 4.624063 0.7640706 4.785818 4.589886 0.7640705 4.837365 4.641433 0.7640706 4.902286 4.60831 -0.3159296 4.875116 4.63548 0.7640705 4.904055 4.761798 -0.315929 4.908239 4.570559 -0.3159298 4.902286 4.60831 0.7640703 4.822987 4.82771 -0.3159286 4.868242 4.782454 -0.3159288 5.207653 5.008729 -0.3159285 4.890869 4.536382 -0.3159299 4.908239 4.570559 0.7640702 4.981379 4.782455 -0.3159291 4.945565 4.761799 -0.3159291 2.792985 2.25465 -0.3159366 4.856692 4.519012 -0.3159299 4.890869 4.536382 0.76407 5.451041 4.912706 -0.3159293 4.818941 4.524965 -0.3159298 4.856692 4.519012 0.76407 4.818941 4.524965 0.7640701 4.79177 4.552135 0.7640703 4.633482 4.434558 -0.3159298 4.654139 4.470372 -0.3159297 3.021279 2.842154 0.7640657 3.003909 2.807977 0.7640656 3.055456 2.859524 0.7640657 3.120377 2.8264 -0.3159344 3.093207 2.85357 0.7640656 3.113662 2.971404 -0.3159338 3.12633 2.78865 -0.3159346 3.120377 2.8264 0.7640655 3.032593 3.037316 -0.3159335 3.077848 2.992061 -0.3159337 3.770812 3.571888 -0.3159322 3.108961 2.754473 -0.3159347 3.12633 2.78865 0.7640653 3.190985 2.992061 -0.3159339 3.155171 2.971405 -0.3159339 3.074784 2.737103 -0.3159347 3.108961 2.754472 0.7640652 3.037033 2.743056 -0.3159346 3.074784 2.737103 0.7640652 3.037033 2.743056 0.7640653 3.009863 2.770226 0.7640654 2.866573 2.682806 -0.3159346 5.541859 6.490765 -0.3159221 5.908894 6.148413 -0.3159244 5.87799 6.123131 -0.3159245 5.87799 6.12313 0.7640754 5.852708 6.092226 -0.3159245 5.852708 6.092226 0.7640753 5.655942 6.577658 -0.315922 5.943442 6.166858 -0.3159244 5.908894 6.148412 0.7640755 5.981503 6.178422 -0.3159244 5.943442 6.166857 0.7640755 6.020825 6.18225 -0.3159245 5.981503 6.178421 0.7640755 6.060148 6.178422 -0.3159245 6.020825 6.182249 0.7640754 5.963786 6.331302 -0.3159238 6.098209 6.166857 -0.3159247 6.060148 6.178421 0.7640753 6.132977 6.148252 -0.3159248 6.098209 6.166856 0.7640752 6.163661 6.123131 -0.315925 6.132977 6.148252 0.7640751 6.618188 5.615413 -0.3159281 6.188783 6.092446 -0.3159251 6.163661 6.12313 0.764075 5.991832 6.303255 -0.3159239 6.343786 5.951302 -0.3159263 6.207387 6.057678 -0.3159253 6.188783 6.092446 0.7640748 6.218953 6.019618 -0.3159258 6.207388 6.057677 0.7640746 6.22278 5.980295 -0.315926 6.218953 6.019617 0.7640745 6.531296 5.501329 -0.3159288 6.218953 5.940973 -0.3159261 6.22278 5.980295 0.7640743 6.207388 5.902912 -0.3159263 6.218953 5.940973 0.7640742 6.188943 5.868364 -0.3159264 6.207388 5.902912 0.764074 6.163661 5.837459 -0.3159264 6.188943 5.868363 0.7640736 6.422968 5.407341 -0.3159289 6.132757 5.812177 -0.3159265 6.163661 5.837459 0.7640735 6.098208 5.793733 -0.3159265 6.132757 5.812177 0.7640734 6.060148 5.782168 -0.3159265 6.098208 5.793732 0.7640734 6.020826 5.778341 -0.3159264 6.060148 5.782168 0.7640734 6.297753 5.337402 -0.315929 5.981503 5.782167 -0.3159264 6.020826 5.77834 0.7640734 6.077866 5.629288 -0.3159271 5.943442 5.793733 -0.3159263 5.981503 5.782167 0.7640736 5.908674 5.812337 -0.3159261 5.943443 5.793732 0.7640737 5.87799 5.837459 -0.315926 5.908674 5.812337 0.7640742 5.697865 6.009288 -0.3159247 5.852869 5.868143 -0.3159258 5.87799 5.837459 0.7640743 6.049818 5.657335 -0.315927 5.447873 6.382436 -0.3159224 5.834264 5.902912 -0.3159257 5.852869 5.868143 0.7640745 5.822699 5.940972 -0.3159251 5.834264 5.902911 0.7640747 5.818871 5.980295 -0.315925 5.822699 5.940971 0.7640748 5.822699 6.019617 -0.3159248 5.818871 5.980295 0.764075 5.834263 6.057678 -0.3159247 5.822699 6.019617 0.7640752 5.834263 6.057677 0.7640753 5.377932 6.257221 -0.3159232 5.63085 6.04348 -0.3159244 5.59557 6.025549 -0.3159244 5.59557 6.025549 0.7640755 5.577641 5.99027 -0.3159245 5.577641 5.99027 0.7640755 5.669818 6.037335 -0.3159245 5.63085 6.043479 0.7640755 5.669818 6.037334 0.7640755 6.01085 5.66348 -0.3159269 5.70401 5.970319 -0.3159248 5.697865 6.009287 0.7640753 5.975571 5.64555 -0.3159269 5.686081 5.93504 -0.3159249 5.70401 5.970319 0.7640751 5.957641 5.61027 -0.315927 5.650801 5.91711 -0.3159249 5.686081 5.935039 0.7640751 5.963786 5.571302 -0.3159272 5.611833 5.923255 -0.3159248 5.650801 5.917109 0.7640751 6.160881 5.294449 -0.3159289 5.583786 5.951302 -0.3159247 5.611833 5.923255 0.7640751 5.583786 5.951302 0.7640752 5.33498 6.120349 -0.3159236 5.975571 5.64555 0.764073 5.957641 5.61027 0.7640729 6.01085 5.663479 0.764073 6.049818 5.657334 0.764073 6.084011 5.59032 -0.3159273 6.077866 5.629287 0.7640728 6.066081 5.55504 -0.3159274 6.084011 5.590319 0.7640726 6.030801 5.53711 -0.3159274 6.066081 5.55504 0.7640725 5.991833 5.543255 -0.3159273 6.030801 5.53711 0.7640725 5.991833 5.543255 0.7640725 5.963786 5.571301 0.7640727 6.08401 6.350319 -0.3159239 6.39085 6.04348 -0.315926 6.35557 6.02555 -0.315926 6.35557 6.02555 0.7640743 6.066081 6.31504 -0.3159241 6.337641 5.990271 -0.3159261 6.337641 5.99027 0.7640742 6.077865 6.389288 -0.3159238 6.429818 6.037335 -0.3159261 6.39085 6.043479 0.7640743 5.924588 6.673624 -0.315922 6.457865 6.009288 -0.3159263 6.429818 6.037334 0.7640738 6.680004 5.744799 -0.3159276 6.464011 5.970319 -0.3159264 6.457865 6.009287 0.7640737 6.446081 5.93504 -0.3159265 6.464011 5.970319 0.7640734 6.410801 5.91711 -0.3159265 6.446081 5.93504 0.7640734 6.371833 5.923255 -0.3159264 6.410801 5.917109 0.7640734 6.371833 5.923255 0.7640734 6.030801 6.29711 -0.3159241 6.343786 5.951302 0.7640736 5.78533 6.639473 -0.3159219 6.01085 6.42348 -0.3159235 5.97557 6.40555 -0.3159235 5.97557 6.405549 0.7640764 5.957641 6.370271 -0.3159236 5.957641 6.37027 0.7640763 6.049818 6.417335 -0.3159236 6.01085 6.42348 0.7640764 6.049818 6.417334 0.7640764 6.077865 6.389287 0.7640762 6.08401 6.350319 0.764076 6.066081 6.31504 0.7640759 6.030801 6.29711 0.7640759 5.991832 6.303255 0.7640759 5.963786 6.331302 0.7640761 5.279489 5.923412 -0.3159243 5.533853 5.702389 -0.315926 5.48201 5.667753 -0.315926 5.48201 5.667753 0.7640739 5.447375 5.61591 -0.3159261 5.447375 5.61591 0.7640737 5.595147 5.71458 -0.315926 5.533853 5.702389 0.7640744 5.656441 5.702388 -0.3159261 5.595147 5.71458 0.7640743 5.708284 5.667754 -0.3159264 5.656441 5.702388 0.7640737 5.74292 5.61591 -0.3159266 5.708284 5.667753 0.7640735 5.963944 5.238958 -0.3159288 5.755111 5.554617 -0.3159269 5.74292 5.61591 0.7640733 5.74292 5.493323 -0.3159271 5.755111 5.554616 0.764073 5.708284 5.441479 -0.3159273 5.74292 5.493322 0.7640728 5.777919 5.155723 -0.3159289 5.656441 5.406844 -0.3159273 5.708284 5.441479 0.7640727 5.595147 5.394653 -0.3159273 5.656441 5.406844 0.7640725 5.533854 5.406844 -0.3159271 5.595147 5.394652 0.7640726 5.48201 5.441479 -0.3159269 5.533854 5.406844 0.7640728 5.196253 5.737386 -0.3159249 5.447376 5.493322 -0.3159266 5.48201 5.441479 0.764073 5.605914 5.046413 -0.3159291 5.435184 5.554616 -0.3159264 5.447376 5.493322 0.7640733 5.435184 5.554616 0.7640735 1.170074 1.980898 -0.315935 1.330116 1.869574 -0.3159357 1.295939 1.852204 -0.3159357 1.295939 1.852204 0.7640643 1.278569 1.818028 -0.3159358 1.278569 1.818028 0.7640641 1.599995 2.410819 -0.3159336 1.367866 1.863621 -0.3159357 1.330116 1.869574 0.7640643 1.395037 1.836451 -0.3159359 1.367866 1.863621 0.7640641 1.797985 1.915844 -0.3159363 1.40099 1.7987 -0.3159361 1.395037 1.836451 0.764064 1.288868 1.406727 -0.3159378 1.38362 1.764523 -0.3159362 1.40099 1.7987 0.7640638 1.349443 1.747153 -0.3159362 1.38362 1.764523 0.7640637 1.311692 1.753106 -0.3159361 1.349443 1.747153 0.7640637 1.284522 1.780277 -0.315936 1.311692 1.753106 0.7640638 1.14513 1.950471 -0.3159351 1.284522 1.780276 0.764064 1.126739 1.916005 -0.3159351 1.956377 1.757452 -0.3159371 1.839233 1.360457 -0.3159389 1.805056 1.343088 -0.3159389 1.805056 1.343088 0.764061 1.787686 1.308911 -0.315939 1.787686 1.308911 0.7640609 1.876984 1.354504 -0.315939 1.839233 1.360457 0.764061 1.904154 1.327334 -0.3159391 1.876984 1.354504 0.7640609 2.02143 1.129541 -0.3159405 1.910107 1.289583 -0.3159393 1.904154 1.327334 0.7640607 1.892737 1.255406 -0.3159394 1.910107 1.289583 0.7640606 1.991003 1.104597 -0.3159405 1.85856 1.238037 -0.3159394 1.892737 1.255406 0.7640605 1.820809 1.24399 -0.3159393 1.85856 1.238037 0.7640605 1.956538 1.086207 -0.3159405 1.793639 1.27116 -0.3159391 1.820809 1.243989 0.7640606 1.707475 1.070963 -0.3159398 1.793639 1.27116 0.7640607 1.880009 1.070963 -0.3159404 1.919163 1.07484 -0.3159405 1.668321 1.07484 -0.3159397 1.75438 2.293838 -0.3159343 1.720203 2.276468 -0.3159343 1.720203 2.276468 0.7640656 1.702833 2.242292 -0.3159344 1.702833 2.242291 0.7640655 1.702346 2.492887 -0.3159334 1.79213 2.287885 -0.3159344 1.75438 2.293838 0.7640656 1.819301 2.260715 -0.315935 1.79213 2.287885 0.7640655 1.946477 2.064337 -0.3159359 1.825254 2.222964 -0.3159351 1.819301 2.260715 0.7640654 1.807884 2.188787 -0.3159352 1.825254 2.222964 0.7640652 2.21195 1.733175 -0.315938 1.773707 2.171417 -0.3159352 1.807884 2.188787 0.7640651 2.22932 1.767352 -0.3159379 2.217903 1.695424 -0.3159382 1.735956 2.177371 -0.3159351 1.773707 2.171417 0.7640651 1.708786 2.204541 -0.315935 1.735956 2.17737 0.7640652 1.708786 2.20454 0.7640653 2.104869 1.905945 -0.3159368 2.263496 1.784722 -0.3159379 2.22932 1.767352 0.7640619 2.21195 1.733175 0.7640619 2.393368 2.194444 -0.3159362 2.301248 1.778768 -0.315938 2.263496 1.784721 0.764062 2.328418 1.751598 -0.3159381 2.301248 1.778768 0.7640619 2.451351 1.559462 -0.3159391 2.334371 1.713847 -0.3159383 2.328418 1.751598 0.7640618 2.533419 1.661813 -0.3159388 2.317001 1.679671 -0.3159384 2.334371 1.713847 0.7640616 2.282824 1.662301 -0.3159384 2.317001 1.67967 0.7640615 2.245073 1.668254 -0.3159384 2.282824 1.6623 0.7640615 2.245073 1.668254 0.7640616 2.217903 1.695424 0.7640617 2.434972 2.50196 -0.3159346 2.414582 2.487186 -0.3159346 2.414582 2.487186 0.7640652 2.399808 2.466796 -0.3159347 2.399808 2.466796 0.7640652 2.45868 2.509599 -0.3159346 2.434972 2.50196 0.7640653 2.48362 2.509599 -0.3159347 2.45868 2.509599 0.7640653 2.507392 2.501918 -0.3159347 2.48362 2.509599 0.7640653 2.527719 2.487186 -0.3159352 2.507392 2.501918 0.7640652 2.54245 2.46686 -0.3159353 2.527719 2.487186 0.764065 2.710918 2.152299 -0.3159368 2.550131 2.443088 -0.3159354 2.54245 2.466859 0.764065 2.550131 2.418148 -0.3159355 2.550131 2.443088 0.7640649 2.542492 2.394439 -0.3159356 2.550131 2.418148 0.7640648 2.527719 2.374049 -0.3159356 2.542492 2.394439 0.7640647 2.507328 2.359276 -0.3159357 2.527719 2.374049 0.7640643 2.48362 2.351637 -0.3159357 2.507328 2.359276 0.7640646 2.653057 2.034559 -0.3159372 2.45868 2.351637 -0.3159356 2.48362 2.351637 0.7640647 2.434908 2.359318 -0.3159356 2.45868 2.351637 0.7640647 2.414582 2.374049 -0.3159354 2.434908 2.359318 0.7640647 2.192831 2.670385 -0.3159335 2.39985 2.394376 -0.3159353 2.414582 2.374049 0.7640648 2.392169 2.418148 -0.3159353 2.39985 2.394376 0.7640649 2.392169 2.443088 -0.3159351 2.392169 2.418148 0.764065 2.392169 2.443088 0.7640652 1.596481 1.104597 -0.3159395 1.566054 1.129541 -0.3159394 1.566054 1.129541 0.7640605 1.44726 1.248335 -0.3159387 1.630947 1.086207 -0.3159396 1.596481 1.104597 0.7640604 1.630947 1.086207 0.7640603 1.668321 1.07484 0.7640602 1.880009 1.070963 0.7640598 1.707475 1.070963 0.7640601 1.919163 1.07484 0.7640598 1.956538 1.086207 0.7640597 1.991003 1.104597 0.7640598 2.02143 1.129541 0.7640598 2.451351 1.559462 0.7640607 2.59128 1.779554 -0.3159385 2.533419 1.661813 0.764061 2.622168 1.907056 -0.315938 2.59128 1.779554 0.7640615 2.075091 2.612524 -0.3159336 2.622168 1.907056 0.7640619 2.653057 2.034558 0.7640628 2.710918 2.152299 0.7640631 2.792985 2.25465 0.7640634 2.568731 2.573453 -0.3159345 4.053655 3.854731 -0.3159315 4.017841 3.834074 -0.3159316 3.976331 3.834074 -0.3159315 2.845916 2.646993 -0.3159347 2.727123 2.528199 -0.3159354 2.691309 2.507543 -0.3159354 2.649799 2.507543 -0.3159353 2.613986 2.528199 -0.3159352 5.086945 5.565381 -0.3159258 5.451041 4.912706 0.7640706 5.207653 5.121866 -0.3159277 5.228309 5.086052 -0.3159283 5.228309 5.044543 -0.3159284 5.605914 5.046413 0.7640709 5.777919 5.155722 0.7640711 5.963944 5.238958 0.7640711 6.160881 5.294448 0.764071 6.297753 5.337402 0.7640709 6.422968 5.407341 0.764071 6.531296 5.501329 0.7640712 6.618188 5.615412 0.7640718 6.714155 5.884058 -0.3159272 6.680004 5.744798 0.7640723 6.067877 6.678684 -0.3159222 6.719214 6.027347 -0.3159266 6.714155 5.884057 0.7640728 6.209185 6.654444 -0.3159225 6.694974 6.168654 -0.315926 6.719214 6.027346 0.7640733 6.342586 6.601924 -0.3159233 6.642455 6.302055 -0.315925 6.694974 6.168653 0.7640743 6.462486 6.523329 -0.3159239 6.563859 6.421956 -0.3159244 6.642455 6.302054 0.7640749 6.563859 6.421955 0.7640755 6.462486 6.523329 0.7640761 6.342586 6.601923 0.7640766 6.209185 6.654443 0.764077 6.067877 6.678683 0.7640777 5.924588 6.673624 0.7640779 5.78533 6.639472 0.764078 5.655942 6.577657 0.7640779 5.541859 6.490765 0.7640778 5.447873 6.382436 0.7640771 5.377932 6.257221 0.7640768 5.33498 6.120349 0.7640763 5.279489 5.923412 0.7640756 5.196253 5.737386 0.7640751 5.086945 5.565381 0.7640742 4.953237 5.41051 0.7640737 4.822987 4.940846 -0.3159282 5.049261 5.167121 -0.3159273 5.085074 5.187778 -0.3159272 5.126584 5.187778 -0.3159273 5.162397 5.167121 -0.3159275 3.689743 3.750936 -0.3159313 3.61242 3.73028 -0.3159313 3.648233 3.750936 -0.3159313 2.295182 2.752453 0.7640665 2.548075 2.609267 -0.3159344 2.548075 2.650777 -0.3159342 2.192831 2.670385 0.7640663 2.234977 2.352836 -0.3159353 1.947588 2.581636 -0.3159335 2.075091 2.612524 0.7640663 1.820086 2.550748 -0.3159334 1.947588 2.581636 0.7640664 1.820086 2.550747 0.7640665 1.702346 2.492886 0.7640665 1.599995 2.410819 0.7640663 1.170074 1.980898 0.7640653 1.14513 1.950471 0.7640652 1.115372 1.87863 -0.3159353 1.126739 1.916005 0.7640651 1.111495 1.839476 -0.3159354 1.115372 1.87863 0.764065 1.111495 1.666942 -0.3159361 1.111495 1.666942 0.7640638 1.111495 1.839476 0.7640649 1.115372 1.627789 -0.3159363 1.12674 1.590414 -0.3159365 1.115372 1.627789 0.7640637 1.14513 1.555948 -0.3159366 1.12674 1.590414 0.7640635 1.170074 1.525521 -0.3159368 1.14513 1.555948 0.7640633 1.288868 1.406727 0.7640621 1.170074 1.525521 0.7640631 1.797985 1.915844 0.7640637 1.956377 1.757452 0.7640624 1.44726 1.248335 0.7640612 4.822987 4.827709 0.7640713 4.904055 4.761798 0.7640709 4.868242 4.782454 0.7640711 4.80233 4.863523 0.7640715 4.80233 4.905034 0.7640717 4.822987 4.940846 0.7640718 5.049261 5.167121 0.7640727 5.085074 5.187778 0.7640727 5.126584 5.187778 0.7640722 5.207653 5.121866 0.7640719 5.162398 5.167121 0.7640721 5.228309 5.086052 0.7640717 5.228309 5.044543 0.7640715 5.207653 5.008729 0.7640714 4.981379 4.782455 0.7640709 4.945565 4.761799 0.7640709 4.633482 4.547695 0.7640705 4.654138 4.511882 0.7640703 4.654139 4.470372 0.7640702 4.633482 4.434558 0.76407 4.053655 3.854731 0.7640684 4.017841 3.834074 0.7640684 3.940518 3.854731 -0.3159313 3.976331 3.834074 0.7640684 3.791468 3.607702 -0.3159321 3.895262 3.899986 -0.3159311 3.895263 3.899985 0.7640688 3.940518 3.85473 0.7640686 3.770812 3.685025 -0.3159317 3.874606 3.935799 -0.3159309 3.791468 3.649211 -0.3159319 3.874606 3.977309 -0.3159307 3.874606 3.935798 0.764069 3.725557 3.73028 -0.3159315 3.874606 3.977309 0.7640695 3.895263 4.013123 0.7640696 4.47509 4.59295 0.7640709 4.510904 4.613606 0.7640709 4.552413 4.613606 0.7640709 4.588227 4.59295 0.7640708 3.032593 3.037315 0.7640665 3.113662 2.971404 0.764066 3.077848 2.99206 0.7640662 3.011936 3.073129 0.7640666 3.011936 3.114639 0.7640668 3.032593 3.150452 0.7640669 3.61242 3.73028 0.7640686 3.648233 3.750936 0.7640686 3.689743 3.750936 0.7640686 3.770812 3.685025 0.7640682 3.725557 3.73028 0.7640684 3.791468 3.649211 0.764068 3.791468 3.607701 0.7640678 3.770812 3.571888 0.7640678 3.190985 2.992061 0.764066 3.155171 2.971404 0.7640659 2.845917 2.760129 0.7640656 2.866573 2.724316 0.7640655 2.866573 2.682806 0.7640653 2.727123 2.528198 0.7640649 2.845916 2.646992 0.7640652 2.691309 2.507542 0.7640649 2.649799 2.507542 0.764065 2.568731 2.573453 0.7640653 2.613986 2.528198 0.7640651 2.548075 2.609266 0.7640655 2.548075 2.650777 0.7640657 2.687525 2.805384 0.7640661 2.568731 2.68659 0.7640658 2.723338 2.826041 0.7640661 2.764848 2.82604 0.7640661 2.800662 2.805384 0.7640659 2.393368 2.194444 0.7640638 2.234977 2.352836 0.764065 2.104869 1.905944 0.7640631 1.946477 2.064336 0.764064 -5.317066 4.912703 -0.3159096 -2.992356 2.788648 -0.3159236 -2.974986 2.754472 -0.3159237 -2.974986 2.754471 0.7640762 -2.593148 2.528198 -0.3159253 -2.940809 2.737102 -0.3159238 -2.940809 2.737102 0.7640761 -2.65901 2.254649 -0.3159266 -2.986402 2.8264 -0.3159235 -2.992356 2.788648 0.7640763 -2.959232 2.85357 -0.3159233 -2.986402 2.826399 0.7640765 -2.766082 3.014922 -0.315923 -2.921481 2.859523 -0.3159234 -2.959232 2.853569 0.764077 -2.760128 3.052674 -0.3159229 -2.979686 2.971403 -0.3159229 -3.05701 2.99206 -0.3159223 -3.021197 2.971403 -0.3159228 -2.748711 2.980746 -0.3159232 -2.887305 2.842153 -0.3159235 -2.921481 2.859523 0.7640769 -2.714535 2.963376 -0.3159233 -2.869935 2.807976 -0.3159237 -2.887305 2.842152 0.7640764 -2.676784 2.969329 -0.3159234 -2.875888 2.770225 -0.3159238 -2.869935 2.807976 0.7640762 -2.630873 2.82604 -0.315924 -2.903058 2.743055 -0.3159239 -2.875888 2.770225 0.7640761 -2.711942 2.760128 -0.3159241 -2.903058 2.743055 0.764076 -2.666687 2.805383 -0.315924 -2.711942 2.646991 -0.3159246 -2.732599 2.682805 -0.3159244 -2.732598 2.724315 -0.3159242 -4.774264 4.570557 -0.3159122 -4.756894 4.53638 -0.3159124 -4.756894 4.53638 0.7640876 -3.91968 3.854729 -0.3159167 -4.722718 4.519011 -0.3159124 -4.722718 4.519011 0.7640874 -4.768311 4.608308 -0.315912 -4.774264 4.570557 0.7640877 -4.741141 4.635478 -0.315912 -4.768311 4.608308 0.7640879 -4.54799 4.796831 -0.3159117 -4.70339 4.641431 -0.315912 -4.741141 4.635478 0.7640883 -4.542037 4.834582 -0.3159111 -4.770081 4.761796 -0.3159111 -4.811591 4.761797 -0.315911 -4.530621 4.762654 -0.3159118 -4.669214 4.624061 -0.3159121 -4.70339 4.641431 0.7640883 -4.496444 4.745285 -0.315912 -4.651844 4.589885 -0.3159123 -4.669214 4.624061 0.7640882 -4.458693 4.751237 -0.315912 -4.657796 4.552133 -0.3159124 -4.651844 4.589885 0.764088 -4.418439 4.613605 -0.3159126 -4.684967 4.524963 -0.3159125 -4.657796 4.552133 0.7640875 -4.499508 4.547694 -0.3159127 -4.684967 4.524963 0.7640874 -4.454253 4.592948 -0.3159126 -4.499508 4.434556 -0.3159132 -4.520164 4.47037 -0.315913 -4.520164 4.51188 -0.3159128 -4.530621 4.762654 0.7640885 -4.496444 4.745285 0.7640883 -4.54799 4.796831 0.7640886 -4.514867 4.861752 -0.3159111 -4.542037 4.834582 0.7640888 -4.668356 4.863522 -0.3159108 -4.477116 4.867705 -0.3159111 -4.514867 4.861752 0.7640888 -4.734267 4.782453 -0.315911 -4.689012 4.827708 -0.3159109 -4.915287 5.16712 -0.3159092 -4.44294 4.850336 -0.3159112 -4.477116 4.867705 0.7640888 -4.689012 4.940845 -0.3159105 -4.668356 4.905032 -0.3159106 -2.161207 2.752452 -0.3159251 -4.42557 4.816159 -0.3159118 -4.44294 4.850336 0.7640887 -4.819263 5.410507 -0.315908 -4.431522 4.778407 -0.3159119 -4.42557 4.816159 0.7640885 -4.431522 4.778407 0.7640883 -4.458693 4.751237 0.7640879 -4.341116 4.592948 -0.3159128 -4.376929 4.613605 -0.3159127 -2.748711 2.980746 0.7640767 -2.714535 2.963376 0.7640766 -2.766082 3.014922 0.7640773 -2.732958 3.079844 -0.3159224 -2.760128 3.052673 0.7640774 -2.877962 3.073128 -0.3159223 -2.695207 3.085797 -0.3159229 -2.732958 3.079843 0.7640774 -2.943873 2.992059 -0.3159229 -2.898618 3.037314 -0.3159224 -3.478446 3.730278 -0.3159183 -2.661031 3.068427 -0.315923 -2.695207 3.085797 0.7640774 -2.898618 3.150451 -0.3159219 -2.877962 3.114638 -0.3159221 -2.643661 3.03425 -0.3159232 -2.661031 3.068427 0.7640773 -2.649614 2.996499 -0.3159233 -2.643661 3.03425 0.7640771 -2.649614 2.996499 0.764077 -2.676784 2.969329 0.7640765 -2.589364 2.82604 -0.3159241 -6.397322 5.501327 -0.3159047 -6.054969 5.868361 -0.3159039 -6.029686 5.837457 -0.315904 -6.029686 5.837456 0.7640959 -5.998782 5.812175 -0.3159042 -5.998782 5.812174 0.7640957 -6.484213 5.61541 -0.3159042 -6.073413 5.90291 -0.3159037 -6.054969 5.86836 0.764096 -6.084978 5.94097 -0.3159035 -6.073413 5.902909 0.7640962 -6.088805 5.980292 -0.3159034 -6.084978 5.94097 0.7640963 -6.084979 6.019615 -0.3159028 -6.088805 5.980292 0.7640969 -6.237858 5.923253 -0.3159034 -6.073413 6.057676 -0.3159027 -6.084979 6.019614 0.7640971 -6.054809 6.092444 -0.3159026 -6.073413 6.057675 0.7640972 -6.029687 6.123128 -0.3159025 -6.054809 6.092443 0.7640973 -5.521969 6.577655 -0.3159016 -5.999003 6.14825 -0.3159025 -6.029687 6.123127 0.7640974 -6.209811 5.9513 -0.3159033 -5.857859 6.303253 -0.3159021 -5.964235 6.166854 -0.3159025 -5.999003 6.148249 0.7640975 -5.926174 6.17842 -0.3159025 -5.964235 6.166854 0.7640975 -5.886851 6.182247 -0.3159025 -5.926174 6.178419 0.7640975 -5.407886 6.490763 -0.3159021 -5.847529 6.178419 -0.3159026 -5.886851 6.182246 0.7640974 -5.809469 6.166855 -0.3159027 -5.847529 6.178419 0.7640973 -5.77492 6.14841 -0.3159028 -5.809469 6.166854 0.7640972 -5.744016 6.123128 -0.315903 -5.77492 6.148409 0.7640971 -5.313898 6.382435 -0.3159027 -5.718734 6.092224 -0.3159035 -5.744016 6.123127 0.7640969 -5.700289 6.057675 -0.3159037 -5.718734 6.092223 0.7640963 -5.688724 6.019614 -0.3159039 -5.700289 6.057675 0.7640962 -5.684896 5.980292 -0.315904 -5.688724 6.019614 0.7640961 -5.243959 6.257219 -0.3159037 -5.688724 5.94097 -0.3159042 -5.684896 5.980292 0.7640959 -5.535844 6.037332 -0.315904 -5.700289 5.902909 -0.3159043 -5.688724 5.940969 0.7640957 -5.718893 5.868141 -0.3159044 -5.700289 5.902908 0.7640956 -5.744015 5.837457 -0.3159045 -5.718893 5.86814 0.7640955 -5.915844 5.657332 -0.3159049 -5.774699 5.812335 -0.3159045 -5.744015 5.837456 0.7640954 -5.563891 6.009285 -0.3159041 -6.288993 5.40734 -0.3159053 -5.809467 5.79373 -0.3159046 -5.774699 5.812335 0.7640954 -5.847528 5.782165 -0.3159045 -5.809467 5.79373 0.7640954 -5.886851 5.778338 -0.3159045 -5.847528 5.782165 0.7640954 -5.926173 5.782166 -0.3159044 -5.886851 5.778337 0.7640954 -5.964234 5.79373 -0.3159043 -5.926173 5.782165 0.7640955 -5.964234 5.793729 0.7640956 -6.163778 5.3374 -0.3159062 -5.950036 5.590317 -0.3159051 -5.932106 5.555037 -0.3159053 -5.932106 5.555037 0.7640946 -5.896827 5.537107 -0.3159054 -5.896827 5.537107 0.7640945 -5.943891 5.629285 -0.315905 -5.950036 5.590316 0.7640948 -5.943891 5.629285 0.7640949 -5.570036 5.970317 -0.3159042 -5.876875 5.663477 -0.315905 -5.915844 5.657331 0.764095 -5.552106 5.935037 -0.3159044 -5.841596 5.645547 -0.3159051 -5.876875 5.663476 0.764095 -5.516827 5.917108 -0.3159045 -5.823666 5.610268 -0.3159053 -5.841596 5.645547 0.7640948 -5.477858 5.923253 -0.3159046 -5.829811 5.5713 -0.3159054 -5.823666 5.610268 0.7640947 -5.201005 6.120347 -0.3159043 -5.857858 5.543252 -0.3159055 -5.829811 5.571299 0.7640945 -5.857858 5.543252 0.7640944 -6.026906 5.294446 -0.3159065 -5.552106 5.935037 0.7640955 -5.516827 5.917107 0.7640954 -5.570036 5.970316 0.7640956 -5.563891 6.009285 0.7640958 -5.496876 6.043477 -0.3159041 -5.535844 6.037332 0.7640959 -5.461597 6.025547 -0.3159042 -5.496876 6.043477 0.7640958 -5.443666 5.990268 -0.3159044 -5.461597 6.025547 0.7640957 -5.449811 5.9513 -0.3159045 -5.443666 5.990267 0.7640956 -5.449811 5.951299 0.7640954 -5.477858 5.923252 0.7640953 -6.256876 6.043477 -0.3159025 -5.950036 6.350317 -0.3159018 -5.932106 6.315037 -0.3159019 -5.932106 6.315037 0.764098 -6.221596 6.025547 -0.3159026 -5.896827 6.297108 -0.3159021 -5.896827 6.297107 0.7640979 -6.295845 6.037332 -0.3159024 -5.943891 6.389285 -0.3159016 -5.950036 6.350317 0.7640982 -6.58018 5.884055 -0.3159026 -5.915844 6.417332 -0.3159016 -5.943891 6.389285 0.7640983 -5.651355 6.639471 -0.3159011 -5.876876 6.423477 -0.3159016 -5.915844 6.417332 0.7640984 -5.841597 6.405548 -0.3159017 -5.876876 6.423477 0.7640984 -5.823667 6.370268 -0.3159019 -5.841597 6.405547 0.7640982 -5.829812 6.331299 -0.315902 -5.823667 6.370267 0.7640981 -5.829812 6.331299 0.7640979 -6.203666 5.990268 -0.3159028 -5.857859 6.303252 0.7640978 -6.546029 5.744796 -0.3159036 -6.330036 5.970317 -0.3159026 -6.312106 5.935037 -0.3159028 -6.312106 5.935037 0.7640967 -6.276826 5.917108 -0.3159033 -6.276826 5.917107 0.7640966 -6.323891 6.009285 -0.3159025 -6.330036 5.970316 0.7640973 -6.323891 6.009285 0.7640975 -6.295845 6.037332 0.7640975 -6.256876 6.043477 0.7640975 -6.221596 6.025547 0.7640969 -6.203666 5.990267 0.7640967 -6.209811 5.951299 0.7640966 -6.237858 5.923252 0.7640965 -5.829968 5.238956 -0.3159071 -5.608945 5.49332 -0.3159064 -5.574309 5.441477 -0.3159067 -5.574309 5.441477 0.7640932 -5.522466 5.406842 -0.3159069 -5.522466 5.406842 0.764093 -5.621136 5.554614 -0.3159062 -5.608945 5.49332 0.7640938 -5.608944 5.615908 -0.3159056 -5.621136 5.554614 0.7640941 -5.574309 5.667751 -0.3159054 -5.608944 5.615908 0.7640943 -5.522466 5.702386 -0.3159054 -5.574309 5.667751 0.7640944 -5.145514 5.92341 -0.3159051 -5.461173 5.714578 -0.3159054 -5.522466 5.702386 0.7640945 -5.399879 5.702386 -0.3159056 -5.461173 5.714577 0.7640945 -5.348035 5.667751 -0.3159062 -5.399879 5.702386 0.7640944 -5.062279 5.737385 -0.3159064 -5.3134 5.615908 -0.3159064 -5.348035 5.667751 0.7640941 -5.301209 5.554614 -0.3159067 -5.3134 5.615908 0.7640935 -5.313401 5.493321 -0.3159069 -5.301209 5.554613 0.7640932 -5.348036 5.441477 -0.3159071 -5.313401 5.49332 0.764093 -5.643943 5.15572 -0.3159077 -5.399879 5.406843 -0.3159071 -5.348036 5.441477 0.7640929 -4.95297 5.56538 -0.3159072 -5.461172 5.39465 -0.3159071 -5.399879 5.406842 0.7640928 -5.461172 5.39465 0.7640928 -1.887455 1.129541 -0.315933 -1.776132 1.289583 -0.3159326 -1.758762 1.255406 -0.3159327 -1.758762 1.255406 0.7640672 -1.724585 1.238036 -0.3159328 -1.724585 1.238036 0.7640671 -2.317376 1.559462 -0.3159302 -1.770179 1.327334 -0.3159324 -1.776132 1.289582 0.7640674 -1.743008 1.354504 -0.3159323 -1.770179 1.327333 0.7640675 -1.822402 1.757451 -0.3159303 -1.705257 1.360457 -0.3159323 -1.743008 1.354503 0.7640675 -1.313285 1.248335 -0.3159335 -1.671081 1.343087 -0.3159325 -1.705257 1.360457 0.7640675 -1.653711 1.30891 -0.3159326 -1.671081 1.343087 0.7640674 -1.659664 1.271159 -0.3159328 -1.653711 1.30891 0.7640672 -1.686834 1.243989 -0.3159329 -1.659664 1.271159 0.7640671 -1.857028 1.104596 -0.3159331 -1.686834 1.243989 0.7640671 -1.822562 1.086207 -0.3159332 -1.66401 1.915843 -0.3159299 -1.267015 1.798699 -0.315931 -1.249645 1.764523 -0.3159315 -1.249645 1.764522 0.7640684 -1.215469 1.747153 -0.3159316 -1.215469 1.747153 0.7640683 -1.261062 1.83645 -0.3159309 -1.267015 1.798699 0.7640685 -1.233892 1.863621 -0.3159308 -1.261062 1.83645 0.7640687 -1.036099 1.980897 -0.3159307 -1.196141 1.869574 -0.3159308 -1.233892 1.863621 0.7640687 -1.161964 1.852204 -0.315931 -1.196141 1.869574 0.7640687 -1.011155 1.95047 -0.3159308 -1.144594 1.818027 -0.3159315 -1.161964 1.852204 0.7640686 -1.150547 1.780276 -0.3159316 -1.144594 1.818027 0.7640684 -0.9927648 1.916004 -0.315931 -1.177717 1.753106 -0.3159317 -1.150547 1.780276 0.7640683 -0.9775202 1.666942 -0.3159323 -1.177717 1.753106 0.7640682 -0.9775203 1.839476 -0.3159317 -0.9813973 1.87863 -0.3159312 -0.9813972 1.627788 -0.3159325 -2.200396 1.713846 -0.3159298 -2.183026 1.67967 -0.31593 -2.183026 1.679669 0.7640699 -2.148849 1.6623 -0.3159301 -2.148849 1.6623 0.7640698 -2.399444 1.661812 -0.3159297 -2.194443 1.751597 -0.3159297 -2.200396 1.713846 0.7640702 -2.167273 1.778768 -0.3159296 -2.194443 1.751597 0.7640703 -1.970894 1.905944 -0.3159294 -2.129522 1.784721 -0.3159296 -2.167273 1.778767 0.7640703 -2.095345 1.767351 -0.3159298 -2.129522 1.784721 0.7640703 -1.639733 2.171417 -0.3159289 -2.077975 1.733174 -0.3159299 -2.095345 1.767351 0.7640702 -1.673909 2.188786 -0.3159288 -1.601981 2.17737 -0.3159289 -2.083928 1.695423 -0.3159301 -2.077975 1.733174 0.76407 -2.111098 1.668253 -0.3159301 -2.083928 1.695423 0.7640699 -2.111098 1.668253 0.7640698 -1.812502 2.064336 -0.3159291 -1.691279 2.222963 -0.3159286 -1.673909 2.188786 0.7640715 -1.639733 2.171417 0.7640714 -2.101001 2.352835 -0.3159271 -1.685326 2.260714 -0.3159281 -1.691279 2.222963 0.7640717 -1.658156 2.287884 -0.3159281 -1.685326 2.260714 0.7640718 -1.46602 2.410818 -0.3159279 -1.620405 2.293838 -0.3159281 -1.658156 2.287884 0.7640718 -1.568371 2.492886 -0.3159274 -1.586228 2.276468 -0.3159286 -1.620405 2.293838 0.7640718 -1.568858 2.242291 -0.3159288 -1.586228 2.276468 0.7640717 -1.574811 2.20454 -0.3159289 -1.568858 2.242291 0.7640715 -1.574811 2.20454 0.7640714 -1.601981 2.17737 0.7640714 -2.408517 2.394439 -0.3159264 -2.393744 2.374048 -0.3159266 -2.393744 2.374048 0.7640734 -2.373354 2.359275 -0.3159266 -2.373354 2.359275 0.7640733 -2.416157 2.418147 -0.3159263 -2.408517 2.394438 0.7640734 -2.416157 2.443087 -0.3159263 -2.416157 2.418147 0.7640736 -2.408475 2.466859 -0.3159261 -2.416157 2.443086 0.7640737 -2.393744 2.487185 -0.3159261 -2.408475 2.466858 0.7640737 -2.373417 2.501917 -0.3159261 -2.393744 2.487185 0.7640738 -2.058857 2.670384 -0.3159259 -2.349645 2.509598 -0.3159261 -2.373417 2.501917 0.7640738 -2.324706 2.509598 -0.3159261 -2.349645 2.509598 0.7640739 -2.300997 2.501959 -0.3159262 -2.324706 2.509598 0.7640738 -2.280607 2.487185 -0.3159263 -2.300997 2.501959 0.7640737 -2.265833 2.466795 -0.3159264 -2.280607 2.487185 0.7640736 -2.258194 2.443087 -0.3159265 -2.265833 2.466795 0.7640736 -1.941116 2.612523 -0.3159264 -2.258194 2.418147 -0.3159266 -2.258194 2.443086 0.7640734 -2.265875 2.394375 -0.3159267 -2.258194 2.418147 0.7640733 -2.280607 2.374048 -0.3159267 -2.265875 2.394375 0.7640733 -2.576943 2.152298 -0.3159271 -2.300934 2.359317 -0.3159267 -2.280607 2.374048 0.7640732 -2.324706 2.351636 -0.3159267 -2.300934 2.359317 0.7640731 -2.349645 2.351636 -0.3159267 -2.324706 2.351635 0.7640732 -2.349645 2.351636 0.7640733 -1.011155 1.555948 -0.3159328 -1.036099 1.525521 -0.3159328 -1.036099 1.525521 0.7640671 -1.154893 1.406727 -0.3159331 -0.9927644 1.590414 -0.3159326 -1.011155 1.555948 0.7640671 -0.9927643 1.590414 0.7640673 -0.9813972 1.627788 0.7640674 -0.9775202 1.839476 0.7640683 -0.9775202 1.666942 0.7640676 -0.9813972 1.878629 0.7640684 -0.9927647 1.916004 0.764069 -1.011155 1.95047 0.7640691 -1.036099 1.980897 0.7640693 -1.46602 2.410818 0.764072 -1.686112 2.550747 -0.315927 -1.568371 2.492886 0.7640725 -1.813614 2.581635 -0.3159267 -1.686112 2.550747 0.764073 -2.519082 2.034557 -0.3159277 -1.813614 2.581635 0.7640733 -1.941116 2.612523 0.7640736 -2.058857 2.670384 0.764074 -2.161207 2.752452 0.7640749 -2.480011 2.528198 -0.3159258 -3.761289 4.013121 -0.3159164 -3.740632 3.977308 -0.3159165 -3.740632 3.935797 -0.3159167 -2.55355 2.805383 -0.3159242 -2.434756 2.686589 -0.3159249 -2.4141 2.650776 -0.3159251 -2.4141 2.609266 -0.3159252 -2.434756 2.573452 -0.3159253 -5.471938 5.046411 -0.3159084 -4.819263 5.410507 0.7640919 -5.028423 5.16712 -0.315909 -4.99261 5.187776 -0.315909 -4.9511 5.187776 -0.3159091 -4.95297 5.56538 0.7640928 -5.062279 5.737385 0.7640939 -5.145514 5.92341 0.7640948 -5.201005 6.120347 0.7640956 -5.243959 6.257219 0.7640962 -5.313898 6.382434 0.7640972 -5.407886 6.490762 0.7640979 -5.521969 6.577654 0.7640984 -5.790615 6.673622 -0.3159008 -5.651355 6.63947 0.7640991 -6.58524 6.027343 -0.315902 -5.933903 6.678682 -0.3159002 -5.790615 6.673621 0.7640995 -6.561 6.168651 -0.3159015 -6.07521 6.654441 -0.3159 -5.933903 6.678681 0.7640998 -6.508481 6.302052 -0.3159011 -6.208611 6.601922 -0.3159 -6.07521 6.654441 0.7640999 -6.429885 6.421953 -0.3159007 -6.328512 6.523326 -0.3159005 -6.208611 6.601922 0.7641 -6.328512 6.523326 0.7640998 -6.429885 6.421953 0.7640996 -6.508481 6.302052 0.7640989 -6.561 6.168651 0.7640984 -6.58524 6.027343 0.7640979 -6.58018 5.884055 0.764097 -6.546029 5.744796 0.7640964 -6.484213 5.61541 0.7640957 -6.397322 5.501327 0.7640952 -6.288993 5.407339 0.7640946 -6.163778 5.337399 0.7640941 -6.026906 5.294446 0.7640934 -5.829968 5.238956 0.7640928 -5.643943 5.15572 0.7640922 -5.471938 5.046411 0.7640911 -5.317066 4.912703 0.7640903 -4.847404 4.782454 -0.3159108 -5.073678 5.008728 -0.3159096 -5.094335 5.044541 -0.3159094 -5.094335 5.08605 -0.3159093 -5.073678 5.121864 -0.3159092 -3.657494 3.64921 -0.3159183 -3.636837 3.571887 -0.3159187 -3.657494 3.6077 -0.3159185 -2.65901 2.254649 0.7640733 -2.515825 2.507541 -0.3159258 -2.557334 2.507541 -0.3159257 -2.576943 2.152298 0.7640728 -2.259393 2.194443 -0.3159275 -2.488193 1.907055 -0.3159286 -2.519082 2.034557 0.7640722 -2.457305 1.779553 -0.3159291 -2.488193 1.907055 0.7640714 -2.457305 1.779553 0.7640708 -2.399444 1.661812 0.7640702 -2.317376 1.559461 0.7640697 -1.887455 1.129541 0.7640669 -1.857028 1.104596 0.7640668 -1.785187 1.074839 -0.3159334 -1.822562 1.086206 0.7640666 -1.746034 1.070962 -0.3159338 -1.785187 1.074839 0.7640665 -1.5735 1.070962 -0.3159341 -1.5735 1.070962 0.7640662 -1.746034 1.070962 0.7640664 -1.534346 1.074839 -0.3159342 -1.496971 1.086207 -0.3159342 -1.534346 1.074839 0.7640662 -1.462506 1.104596 -0.3159342 -1.496971 1.086206 0.7640661 -1.432079 1.129541 -0.3159341 -1.462506 1.104596 0.7640662 -1.313285 1.248335 0.7640665 -1.432079 1.129541 0.7640662 -1.822402 1.757451 0.7640696 -1.66401 1.915843 0.76407 -1.154893 1.406727 0.7640668 -4.734267 4.782453 0.7640889 -4.668356 4.863522 0.7640891 -4.689012 4.827708 0.7640889 -4.770081 4.761796 0.7640889 -4.811591 4.761797 0.7640889 -4.847404 4.782454 0.7640891 -5.073678 5.008727 0.7640903 -5.094335 5.04454 0.7640904 -5.094335 5.08605 0.7640906 -5.028423 5.167119 0.7640909 -5.073678 5.121863 0.7640908 -4.99261 5.187776 0.7640909 -4.9511 5.187776 0.7640908 -4.915287 5.16712 0.7640907 -4.689012 4.940845 0.7640894 -4.668356 4.905032 0.7640892 -4.454253 4.592948 0.7640873 -4.418439 4.613605 0.7640873 -4.376929 4.613605 0.7640873 -4.341116 4.592948 0.7640872 -3.761289 4.013121 0.7640836 -3.740632 3.977308 0.7640834 -3.761288 3.899984 -0.3159168 -3.740632 3.935797 0.7640833 -3.514259 3.750935 -0.3159182 -3.806543 3.854729 -0.3159173 -3.806543 3.854729 0.764083 -3.761288 3.899984 0.7640831 -3.591583 3.730278 -0.3159182 -3.842357 3.834073 -0.3159173 -3.555769 3.750935 -0.3159181 -3.883867 3.834073 -0.3159173 -3.842357 3.834073 0.764083 -3.636838 3.685023 -0.3159182 -3.883867 3.834073 0.764083 -3.91968 3.854729 0.7640832 -4.499508 4.434556 0.7640867 -4.520164 4.47037 0.764087 -4.520164 4.51188 0.7640871 -4.499508 4.547694 0.7640872 -2.943873 2.992059 0.7640775 -2.877962 3.073128 0.7640777 -2.898618 3.037314 0.7640776 -2.979686 2.971403 0.7640774 -3.021197 2.971403 0.7640775 -3.05701 2.992059 0.7640777 -3.636837 3.571887 0.7640812 -3.657494 3.6077 0.7640814 -3.657494 3.64921 0.7640815 -3.591583 3.730278 0.7640818 -3.636838 3.685023 0.7640817 -3.555769 3.750935 0.7640818 -3.514259 3.750935 0.7640817 -3.478446 3.730278 0.7640815 -2.898618 3.150451 0.764078 -2.877962 3.114638 0.7640779 -2.666687 2.805383 0.7640758 -2.630873 2.82604 0.7640759 -2.589364 2.82604 0.7640758 -2.434756 2.686589 0.7640751 -2.55355 2.805383 0.7640756 -2.4141 2.650776 0.7640745 -2.4141 2.609266 0.7640743 -2.480011 2.528197 0.7640741 -2.434756 2.573452 0.7640742 -2.515825 2.507541 0.7640741 -2.557334 2.507541 0.7640742 -2.711942 2.646991 0.7640753 -2.593148 2.528197 0.7640746 -2.732599 2.682805 0.7640755 -2.732598 2.724315 0.7640756 -2.711942 2.760128 0.7640758 -2.101001 2.352835 0.7640728 -2.259393 2.194443 0.7640724 -1.812502 2.064336 0.7640709 -1.970894 1.905944 0.7640705 -4.819261 -5.357599 -0.3159574 -2.695206 -3.032889 -0.3159507 -2.661029 -3.015519 -0.3159506 -2.661029 -3.01552 0.7640492 -2.434755 -2.633681 -0.3159492 -2.643659 -2.981342 -0.3159505 -2.643659 -2.981343 0.7640494 -2.161207 -2.699544 -0.3159502 -2.732957 -3.026936 -0.3159506 -2.695206 -3.032889 0.7640492 -2.760127 -2.999765 -0.3159504 -2.732957 -3.026936 0.7640493 -2.92148 -2.806615 -0.3159494 -2.76608 -2.962015 -0.3159503 -2.760127 -2.999766 0.7640495 -2.959231 -2.800662 -0.3159489 -2.877961 -3.02022 -0.3159503 -2.898617 -3.097543 -0.3159506 -2.877961 -3.06173 -0.3159505 -2.887303 -2.789245 -0.315949 -2.74871 -2.927838 -0.3159502 -2.76608 -2.962015 0.7640496 -2.869933 -2.755068 -0.3159489 -2.714534 -2.910468 -0.3159502 -2.74871 -2.927838 0.7640498 -2.875887 -2.717317 -0.3159487 -2.676783 -2.916421 -0.3159502 -2.714534 -2.910468 0.7640498 -2.732597 -2.671407 -0.3159488 -2.649613 -2.943591 -0.3159504 -2.676783 -2.916421 0.7640497 -2.666686 -2.752475 -0.3159496 -2.649613 -2.943591 0.7640495 -2.711941 -2.70722 -0.315949 -2.553549 -2.752475 -0.3159498 -2.589362 -2.773132 -0.3159498 -2.630872 -2.773132 -0.3159497 -4.477115 -4.814798 -0.3159555 -4.442938 -4.797428 -0.3159555 -4.442938 -4.797428 0.7640445 -3.761287 -3.960214 -0.315953 -4.425568 -4.763251 -0.3159554 -4.425568 -4.763251 0.7640445 -4.514866 -4.808845 -0.3159554 -4.477115 -4.814798 0.7640445 -4.542036 -4.781675 -0.3159552 -4.514866 -4.808845 0.7640445 -4.703389 -4.588524 -0.3159543 -4.547989 -4.743924 -0.3159551 -4.542036 -4.781675 0.7640447 -4.741139 -4.582571 -0.3159542 -4.668354 -4.810615 -0.3159552 -4.668354 -4.852125 -0.3159554 -4.669212 -4.571154 -0.3159542 -4.530619 -4.709747 -0.315955 -4.547989 -4.743924 0.7640448 -4.651842 -4.536977 -0.3159537 -4.496442 -4.692377 -0.315955 -4.530619 -4.709747 0.764045 -4.657795 -4.499226 -0.3159536 -4.458691 -4.69833 -0.3159551 -4.496442 -4.692377 0.764045 -4.520163 -4.458973 -0.3159537 -4.431521 -4.7255 -0.3159552 -4.458691 -4.69833 0.7640448 -4.454251 -4.540041 -0.3159545 -4.431521 -4.7255 0.7640447 -4.499506 -4.494786 -0.3159539 -4.341114 -4.540041 -0.3159546 -4.376928 -4.560698 -0.3159546 -4.418437 -4.560698 -0.3159546 -4.669212 -4.571154 0.7640461 -4.651842 -4.536977 0.7640461 -4.703389 -4.588524 0.764046 -4.76831 -4.555401 -0.3159537 -4.741139 -4.582571 0.7640461 -4.770079 -4.708889 -0.3159546 -4.774263 -4.51765 -0.3159535 -4.76831 -4.555401 0.7640463 -4.689011 -4.774801 -0.315955 -4.734266 -4.729546 -0.3159548 -5.073676 -4.95582 -0.3159551 -4.756893 -4.483473 -0.3159534 -4.774263 -4.51765 0.7640464 -4.847403 -4.729546 -0.3159546 -4.811589 -4.70889 -0.3159546 -2.65901 -2.201741 -0.3159471 -4.722716 -4.466103 -0.3159534 -4.756893 -4.483473 0.7640465 -5.317064 -4.859797 -0.3159543 -4.684965 -4.472056 -0.3159535 -4.722716 -4.466103 0.7640466 -4.684965 -4.472056 0.7640464 -4.657795 -4.499226 0.7640463 -4.499505 -4.381649 -0.3159534 -4.520163 -4.417463 -0.3159535 -2.887303 -2.789245 0.7640509 -2.869933 -2.755069 0.764051 -2.92148 -2.806615 0.7640509 -2.986401 -2.773491 -0.3159488 -2.959231 -2.800662 0.764051 -2.979686 -2.918495 -0.3159497 -2.992354 -2.73574 -0.3159486 -2.986401 -2.773492 0.7640511 -2.898617 -2.984407 -0.3159502 -2.943872 -2.939152 -0.3159499 -3.636836 -3.518979 -0.315951 -2.974985 -2.701564 -0.3159485 -2.992354 -2.735741 0.7640513 -3.057009 -2.939152 -0.3159497 -3.021196 -2.918495 -0.3159497 -2.940808 -2.684194 -0.3159485 -2.974985 -2.701564 0.7640514 -2.903057 -2.690147 -0.3159486 -2.940808 -2.684194 0.7640514 -2.903057 -2.690147 0.7640513 -2.875887 -2.717317 0.7640511 -2.732597 -2.629897 -0.3159487 -5.407883 -6.437855 -0.3159611 -5.774917 -6.095502 -0.3159592 -5.744012 -6.07022 -0.3159587 -5.744012 -6.07022 0.7640411 -5.71873 -6.039316 -0.3159587 -5.71873 -6.039316 0.7640412 -5.521966 -6.524747 -0.3159613 -5.809465 -6.113947 -0.3159592 -5.774917 -6.095502 0.7640411 -5.847527 -6.125511 -0.3159592 -5.809465 -6.113947 0.7640411 -5.886848 -6.129339 -0.3159592 -5.847527 -6.125512 0.7640411 -5.926171 -6.125512 -0.3159587 -5.886848 -6.129339 0.7640411 -5.829809 -6.278391 -0.3159598 -5.964231 -6.113946 -0.3159586 -5.926171 -6.125512 0.7640412 -5.999 -6.095342 -0.3159584 -5.964231 -6.113947 0.7640413 -6.029684 -6.07022 -0.3159583 -5.999 -6.095342 0.7640414 -6.484211 -5.562503 -0.3159552 -6.054805 -6.039536 -0.3159582 -6.029684 -6.07022 0.7640416 -5.857855 -6.250345 -0.3159596 -6.209809 -5.898391 -0.3159573 -6.07341 -6.004768 -0.315958 -6.054805 -6.039536 0.7640417 -6.084976 -5.966707 -0.3159578 -6.07341 -6.004768 0.7640419 -6.088803 -5.927384 -0.3159576 -6.084976 -5.966708 0.7640421 -6.397319 -5.448419 -0.3159549 -6.084976 -5.888062 -0.3159575 -6.088803 -5.927385 0.7640422 -6.073411 -5.850001 -0.3159574 -6.084976 -5.888063 0.7640424 -6.054966 -5.815453 -0.3159573 -6.073411 -5.850002 0.7640426 -6.029685 -5.784549 -0.3159571 -6.054966 -5.815454 0.7640426 -6.288991 -5.354431 -0.3159547 -5.99878 -5.759267 -0.3159571 -6.029685 -5.784549 0.7640427 -5.964231 -5.740822 -0.3159571 -5.99878 -5.759267 0.7640428 -5.926171 -5.729258 -0.3159571 -5.964231 -5.740822 0.7640428 -5.886849 -5.72543 -0.3159571 -5.926171 -5.729258 0.7640428 -6.163775 -5.284492 -0.3159546 -5.847526 -5.729257 -0.3159573 -5.886849 -5.72543 0.7640427 -5.943889 -5.576377 -0.3159561 -5.809465 -5.740822 -0.3159573 -5.847526 -5.729258 0.7640427 -5.774697 -5.759427 -0.3159575 -5.809465 -5.740823 0.7640426 -5.744013 -5.784549 -0.3159576 -5.774697 -5.759427 0.7640424 -5.563889 -5.956377 -0.3159586 -5.718892 -5.815232 -0.3159578 -5.744013 -5.784549 0.7640423 -5.915842 -5.604424 -0.3159567 -5.313895 -6.329526 -0.3159608 -5.700287 -5.850001 -0.315958 -5.718892 -5.815233 0.7640421 -5.688721 -5.888062 -0.3159582 -5.700286 -5.850002 0.764042 -5.684895 -5.927384 -0.3159583 -5.688721 -5.888062 0.7640418 -5.688722 -5.966706 -0.3159584 -5.684895 -5.927385 0.7640416 -5.700286 -6.004767 -0.3159586 -5.688722 -5.966707 0.7640415 -5.700286 -6.004768 0.7640413 -5.243956 -6.204311 -0.3159605 -5.496873 -5.990569 -0.3159588 -5.461594 -5.972639 -0.3159588 -5.461594 -5.97264 0.7640411 -5.443664 -5.93736 -0.3159587 -5.443664 -5.93736 0.7640412 -5.535841 -5.984424 -0.3159587 -5.496873 -5.99057 0.764041 -5.535841 -5.984425 0.7640411 -5.876873 -5.610569 -0.3159567 -5.570034 -5.917409 -0.3159584 -5.563889 -5.956378 0.7640413 -5.841594 -5.592639 -0.3159567 -5.552104 -5.882129 -0.3159583 -5.570034 -5.917409 0.7640414 -5.823664 -5.55736 -0.3159566 -5.516824 -5.8642 -0.3159583 -5.552104 -5.88213 0.7640416 -5.829809 -5.518392 -0.3159561 -5.477856 -5.870345 -0.3159584 -5.516824 -5.8642 0.7640416 -6.026904 -5.241539 -0.3159547 -5.449809 -5.898391 -0.3159586 -5.477856 -5.870345 0.7640415 -5.449809 -5.898392 0.7640413 -5.201002 -6.067439 -0.31596 -5.841594 -5.59264 0.7640432 -5.823664 -5.557361 0.7640433 -5.876873 -5.610569 0.7640432 -5.915842 -5.604424 0.7640433 -5.950034 -5.537409 -0.3159559 -5.943889 -5.576378 0.7640434 -5.932104 -5.50213 -0.3159558 -5.950034 -5.537409 0.7640436 -5.896824 -5.4842 -0.3159558 -5.932104 -5.50213 0.7640441 -5.857856 -5.490345 -0.3159559 -5.896824 -5.4842 0.7640441 -5.857856 -5.490345 0.764044 -5.829809 -5.518392 0.7640438 -5.950033 -6.297409 -0.3159597 -6.256873 -5.990569 -0.3159576 -6.221594 -5.97264 -0.3159576 -6.221594 -5.97264 0.7640423 -5.932104 -6.262129 -0.3159596 -6.203664 -5.93736 -0.3159575 -6.203664 -5.93736 0.7640424 -5.943888 -6.336377 -0.3159599 -6.295842 -5.984424 -0.3159575 -6.256873 -5.99057 0.7640423 -5.790611 -6.620713 -0.3159612 -6.323889 -5.956377 -0.3159574 -6.295842 -5.984425 0.7640424 -6.546027 -5.691889 -0.3159556 -6.330034 -5.917409 -0.3159572 -6.323889 -5.956378 0.7640426 -6.312104 -5.88213 -0.3159571 -6.330034 -5.917409 0.7640427 -6.276824 -5.8642 -0.3159571 -6.312104 -5.88213 0.7640427 -6.237856 -5.870345 -0.3159572 -6.276824 -5.8642 0.7640428 -6.237856 -5.870345 0.7640427 -5.896824 -6.2442 -0.3159596 -6.209809 -5.898392 0.7640426 -5.651353 -6.586562 -0.3159613 -5.876873 -6.370569 -0.3159601 -5.841593 -6.352639 -0.3159601 -5.841593 -6.352639 0.7640399 -5.823663 -6.31736 -0.31596 -5.823663 -6.31736 0.7640399 -5.915841 -6.364424 -0.31596 -5.876873 -6.37057 0.7640398 -5.915841 -6.364425 0.7640399 -5.943888 -6.336378 0.7640401 -5.950033 -6.297409 0.7640406 -5.932104 -6.26213 0.7640407 -5.896824 -6.2442 0.7640407 -5.857855 -6.250345 0.7640402 -5.829809 -6.278392 0.7640401 -5.145513 -5.870502 -0.3159589 -5.399877 -5.649478 -0.3159577 -5.348033 -5.614843 -0.3159576 -5.348033 -5.614843 0.7640423 -5.313398 -5.563 -0.3159574 -5.313398 -5.563 0.7640424 -5.461171 -5.66167 -0.3159576 -5.399877 -5.649479 0.7640423 -5.522465 -5.649478 -0.3159574 -5.461171 -5.66167 0.7640423 -5.574308 -5.614843 -0.3159573 -5.522465 -5.649478 0.7640424 -5.608943 -5.563 -0.315957 -5.574308 -5.614843 0.7640426 -5.829967 -5.186048 -0.3159548 -5.621134 -5.501706 -0.3159567 -5.608943 -5.563 0.7640429 -5.608943 -5.440412 -0.3159561 -5.621134 -5.501707 0.7640432 -5.574308 -5.388568 -0.3159559 -5.608943 -5.440413 0.7640433 -5.643942 -5.102813 -0.3159548 -5.522465 -5.353933 -0.3159559 -5.574308 -5.388569 0.7640439 -5.46117 -5.341742 -0.3159559 -5.522465 -5.353934 0.764044 -5.399878 -5.353934 -0.3159561 -5.46117 -5.341743 0.7640439 -5.348033 -5.388569 -0.3159563 -5.399878 -5.353935 0.7640434 -5.062277 -5.684476 -0.3159583 -5.313399 -5.440412 -0.315957 -5.348033 -5.388569 0.7640432 -5.471937 -4.993504 -0.3159546 -5.301207 -5.501706 -0.3159573 -5.313399 -5.440413 0.7640429 -5.301207 -5.501706 0.7640426 -1.036098 -1.927989 -0.3159486 -1.19614 -1.816665 -0.315948 -1.161963 -1.799295 -0.3159479 -1.161963 -1.799295 0.764052 -1.144594 -1.765118 -0.3159478 -1.144594 -1.765119 0.7640521 -1.466019 -2.35791 -0.31595 -1.233891 -1.810712 -0.3159478 -1.19614 -1.816665 0.764052 -1.261061 -1.783542 -0.3159477 -1.233891 -1.810712 0.7640521 -1.664009 -1.862935 -0.3159474 -1.267014 -1.74579 -0.3159475 -1.261061 -1.783542 0.7640522 -1.154892 -1.353818 -0.3159458 -1.249644 -1.711614 -0.3159474 -1.267014 -1.745791 0.7640523 -1.215468 -1.694244 -0.3159474 -1.249644 -1.711614 0.7640525 -1.177717 -1.700197 -0.3159475 -1.215468 -1.694244 0.7640525 -1.150546 -1.727367 -0.3159477 -1.177717 -1.700197 0.7640524 -1.011154 -1.897561 -0.3159486 -1.150546 -1.727367 0.7640522 -0.9927638 -1.863095 -0.3159484 -1.822401 -1.704543 -0.3159461 -1.705257 -1.307548 -0.3159447 -1.67108 -1.290178 -0.3159447 -1.67108 -1.290179 0.7640556 -1.65371 -1.256002 -0.3159446 -1.65371 -1.256002 0.7640557 -1.743008 -1.301595 -0.3159446 -1.705257 -1.307548 0.7640556 -1.770178 -1.274425 -0.3159445 -1.743008 -1.301595 0.7640556 -1.887455 -1.076632 -0.3159431 -1.776131 -1.236674 -0.315944 -1.770178 -1.274425 0.7640558 -1.758761 -1.202497 -0.3159438 -1.776131 -1.236674 0.764056 -1.857028 -1.051688 -0.3159431 -1.724585 -1.185127 -0.3159438 -1.758761 -1.202497 0.7640561 -1.686834 -1.19108 -0.3159439 -1.724585 -1.185128 0.7640561 -1.822562 -1.033298 -0.3159431 -1.659664 -1.21825 -0.3159441 -1.686834 -1.19108 0.764056 -1.5735 -1.018053 -0.3159434 -1.659664 -1.218251 0.7640559 -1.746033 -1.018053 -0.3159431 -1.785187 -1.02193 -0.3159431 -1.534346 -1.02193 -0.3159435 -1.620404 -2.240929 -0.3159489 -1.586227 -2.223559 -0.3159489 -1.586227 -2.223559 0.764051 -1.568857 -2.189383 -0.3159488 -1.568857 -2.189383 0.7640511 -1.56837 -2.439977 -0.3159502 -1.658155 -2.234976 -0.3159489 -1.620404 -2.240929 0.764051 -1.685325 -2.207806 -0.3159487 -1.658155 -2.234976 0.7640511 -1.812501 -2.011427 -0.3159477 -1.691278 -2.170055 -0.3159485 -1.685325 -2.207806 0.7640513 -1.673908 -2.135878 -0.3159484 -1.691278 -2.170055 0.7640514 -2.077974 -1.680266 -0.3159456 -1.639732 -2.118508 -0.3159484 -1.673908 -2.135878 0.7640515 -2.095344 -1.714442 -0.3159457 -2.083927 -1.642515 -0.3159455 -1.601981 -2.124461 -0.3159485 -1.639732 -2.118508 0.7640516 -1.57481 -2.151632 -0.3159486 -1.601981 -2.124461 0.7640514 -1.57481 -2.151632 0.7640513 -1.970893 -1.853035 -0.3159465 -2.129521 -1.731812 -0.3159457 -2.095344 -1.714443 0.7640542 -2.077974 -1.680266 0.7640543 -2.259393 -2.141535 -0.3159475 -2.167272 -1.725859 -0.3159456 -2.129521 -1.731812 0.7640542 -2.194442 -1.698689 -0.3159455 -2.167272 -1.725859 0.7640543 -2.317375 -1.506553 -0.3159445 -2.200395 -1.660938 -0.3159453 -2.194442 -1.698689 0.7640544 -2.399443 -1.608904 -0.3159448 -2.183025 -1.626761 -0.3159452 -2.200395 -1.660938 0.7640546 -2.148849 -1.609391 -0.3159452 -2.183025 -1.626761 0.7640547 -2.111098 -1.615345 -0.3159453 -2.148849 -1.609391 0.7640547 -2.111098 -1.615345 0.7640546 -2.083927 -1.642515 0.7640545 -2.300996 -2.449051 -0.3159486 -2.280606 -2.434277 -0.3159486 -2.280606 -2.434278 0.7640513 -2.265832 -2.413887 -0.3159486 -2.265832 -2.413887 0.7640514 -2.324705 -2.45669 -0.3159486 -2.300996 -2.449051 0.7640513 -2.349644 -2.45669 -0.3159486 -2.324705 -2.45669 0.7640513 -2.373416 -2.449008 -0.3159485 -2.349644 -2.45669 0.7640514 -2.393743 -2.434277 -0.3159484 -2.373416 -2.449009 0.7640514 -2.408474 -2.41395 -0.3159483 -2.393743 -2.434277 0.7640515 -2.576942 -2.09939 -0.3159464 -2.416156 -2.390178 -0.3159482 -2.408474 -2.41395 0.7640516 -2.416155 -2.365239 -0.3159481 -2.416156 -2.390178 0.7640517 -2.408517 -2.34153 -0.315948 -2.416155 -2.365239 0.7640519 -2.393743 -2.32114 -0.315948 -2.408517 -2.34153 0.7640519 -2.373353 -2.306366 -0.315948 -2.393743 -2.321141 0.7640519 -2.349644 -2.298727 -0.315948 -2.373353 -2.306367 0.7640519 -2.519081 -1.981649 -0.3159461 -2.324705 -2.298727 -0.315948 -2.349644 -2.298728 0.764052 -2.300933 -2.306409 -0.3159481 -2.324705 -2.298728 0.7640519 -2.280606 -2.32114 -0.3159481 -2.300933 -2.306409 0.7640518 -2.058856 -2.617476 -0.31595 -2.265875 -2.341467 -0.3159483 -2.280606 -2.32114 0.7640517 -2.258193 -2.365239 -0.3159484 -2.265875 -2.341467 0.7640517 -2.258193 -2.390178 -0.3159484 -2.258193 -2.365239 0.7640516 -2.258193 -2.390178 0.7640514 -1.462505 -1.051688 -0.3159437 -1.432078 -1.076632 -0.3159438 -1.432078 -1.076632 0.764056 -1.313284 -1.195426 -0.3159449 -1.496971 -1.033298 -0.3159436 -1.462505 -1.051688 0.7640562 -1.496971 -1.033298 0.7640563 -1.534346 -1.02193 0.7640565 -1.746033 -1.018054 0.7640568 -1.5735 -1.018054 0.7640565 -1.785187 -1.02193 0.7640568 -1.822562 -1.033298 0.7640569 -1.857028 -1.051688 0.7640568 -1.887455 -1.076632 0.7640568 -2.317375 -1.506553 0.7640558 -2.457304 -1.726645 -0.3159452 -2.399443 -1.608904 0.7640555 -2.488193 -1.854147 -0.3159456 -2.457304 -1.726645 0.7640548 -1.941115 -2.559615 -0.31595 -2.488193 -1.854147 0.7640543 -2.519081 -1.981649 0.7640538 -2.576942 -2.09939 0.7640531 -2.65901 -2.201741 0.7640528 -2.434755 -2.520544 -0.3159487 -3.919679 -3.801822 -0.3159521 -3.883865 -3.781166 -0.3159521 -3.842355 -3.781165 -0.3159521 -2.711941 -2.594084 -0.3159486 -2.593147 -2.475289 -0.3159483 -2.557334 -2.454633 -0.3159483 -2.515823 -2.454633 -0.3159483 -2.48001 -2.475289 -0.3159484 -4.952969 -5.512471 -0.3159579 -5.317064 -4.859797 0.7640456 -5.073676 -5.068957 -0.3159555 -5.094332 -5.033143 -0.3159554 -5.094332 -4.991634 -0.3159552 -5.471937 -4.993505 0.7640454 -5.643942 -5.102813 0.7640452 -5.829967 -5.186048 0.7640451 -6.026904 -5.241539 0.7640453 -6.163775 -5.284492 0.7640453 -6.288991 -5.354431 0.7640452 -6.397319 -5.44842 0.7640451 -6.484211 -5.562503 0.7640447 -6.580178 -5.831148 -0.3159565 -6.546027 -5.691889 0.7640444 -5.9339 -6.625773 -0.315961 -6.585238 -5.974437 -0.315957 -6.580178 -5.831148 0.7640435 -6.075208 -6.601533 -0.3159607 -6.560997 -6.115744 -0.3159576 -6.585238 -5.974437 0.7640429 -6.208609 -6.549014 -0.3159603 -6.508478 -6.249145 -0.3159582 -6.560997 -6.115744 0.7640423 -6.328509 -6.470418 -0.3159598 -6.429883 -6.369046 -0.3159592 -6.508478 -6.249145 0.7640417 -6.429883 -6.369046 0.7640407 -6.328509 -6.470419 0.7640402 -6.208609 -6.549014 0.7640397 -6.075208 -6.601533 0.7640392 -5.9339 -6.625774 0.7640389 -5.790611 -6.620714 0.7640383 -5.651353 -6.586563 0.7640386 -5.521966 -6.524747 0.7640386 -5.407883 -6.437855 0.7640388 -5.313895 -6.329526 0.764039 -5.243956 -6.204312 0.7640394 -5.201002 -6.06744 0.7640399 -5.145513 -5.870502 0.764041 -5.062277 -5.684477 0.7640415 -4.952969 -5.512471 0.7640421 -4.819261 -5.357599 0.7640424 -4.689011 -4.887938 -0.3159554 -4.915285 -5.114212 -0.3159559 -4.951098 -5.134868 -0.315956 -4.992608 -5.134868 -0.3159559 -5.028422 -5.114212 -0.3159558 -3.555768 -3.698027 -0.3159523 -3.478444 -3.677371 -0.3159523 -3.514258 -3.698027 -0.3159523 -2.161207 -2.699544 0.7640501 -2.414099 -2.556358 -0.3159489 -2.414099 -2.597868 -0.315949 -2.058856 -2.617477 0.7640503 -2.101001 -2.299927 -0.3159484 -1.813613 -2.528727 -0.3159501 -1.941115 -2.559615 0.7640499 -1.686111 -2.497838 -0.3159502 -1.813613 -2.528727 0.7640502 -1.686111 -2.497838 0.7640497 -1.56837 -2.439977 0.7640502 -1.466019 -2.35791 0.7640503 -1.036098 -1.927989 0.7640513 -1.011154 -1.897562 0.7640513 -0.9813965 -1.825721 -0.3159483 -0.9927638 -1.863096 0.7640515 -0.9775195 -1.786567 -0.3159482 -0.9813964 -1.825721 0.7640516 -0.9775196 -1.614033 -0.3159475 -0.9775195 -1.614033 0.7640525 -0.9775195 -1.786567 0.7640518 -0.9813964 -1.57488 -0.3159469 -0.992764 -1.537505 -0.3159468 -0.9813963 -1.57488 0.7640526 -1.011154 -1.503039 -0.3159466 -0.9927639 -1.537505 0.7640531 -1.036098 -1.472612 -0.3159465 -1.011154 -1.503039 0.7640532 -1.154892 -1.353818 0.7640541 -1.036098 -1.472612 0.7640534 -1.664009 -1.862935 0.7640526 -1.822401 -1.704543 0.7640538 -1.313284 -1.195426 0.7640554 -4.689011 -4.774801 0.7640449 -4.770079 -4.708889 0.7640454 -4.734265 -4.729546 0.7640452 -4.668354 -4.810615 0.7640448 -4.668354 -4.852125 0.7640446 -4.689011 -4.887938 0.7640445 -4.915285 -5.114212 0.7640439 -4.951098 -5.134868 0.7640439 -4.992608 -5.134868 0.7640441 -5.073676 -5.068958 0.7640444 -5.028422 -5.114212 0.7640442 -5.094332 -5.033144 0.7640445 -5.094332 -4.991634 0.7640447 -5.073676 -4.955821 0.7640448 -4.847403 -4.729546 0.7640457 -4.811589 -4.70889 0.7640458 -4.499505 -4.494786 0.7640461 -4.520163 -4.458973 0.7640463 -4.520163 -4.417463 0.7640464 -4.499505 -4.381649 0.7640465 -3.919679 -3.801822 0.7640478 -3.883865 -3.781166 0.7640479 -3.806542 -3.801822 -0.3159523 -3.842355 -3.781166 0.7640478 -3.657492 -3.554793 -0.3159511 -3.761287 -3.847077 -0.3159525 -3.761287 -3.847077 0.7640474 -3.806541 -3.801822 0.7640476 -3.636836 -3.632116 -0.3159515 -3.74063 -3.88289 -0.3159527 -3.657492 -3.596302 -0.3159513 -3.740631 -3.9244 -0.3159528 -3.74063 -3.88289 0.7640473 -3.591581 -3.677371 -0.3159521 -3.740631 -3.9244 0.7640471 -3.761287 -3.960214 0.764047 -4.341114 -4.540041 0.7640453 -4.376928 -4.560698 0.7640452 -4.418437 -4.560698 0.7640457 -4.454251 -4.540041 0.7640458 -2.898617 -2.984407 0.7640498 -2.979686 -2.918495 0.7640501 -2.943872 -2.939152 0.76405 -2.877961 -3.02022 0.7640496 -2.877961 -3.06173 0.7640494 -2.898617 -3.097544 0.7640493 -3.478444 -3.677371 0.7640476 -3.514258 -3.698027 0.7640476 -3.555768 -3.698027 0.7640477 -3.636836 -3.632117 0.764048 -3.591581 -3.677371 0.7640478 -3.657492 -3.596303 0.7640482 -3.657492 -3.554793 0.7640487 -3.636836 -3.518979 0.7640489 -3.057009 -2.939152 0.7640506 -3.021196 -2.918496 0.7640506 -2.711941 -2.707221 0.764051 -2.732597 -2.671407 0.7640511 -2.732597 -2.629897 0.7640513 -2.593147 -2.47529 0.7640516 -2.711941 -2.594084 0.7640514 -2.557334 -2.454633 0.7640517 -2.515823 -2.454633 0.7640516 -2.434755 -2.520544 0.7640512 -2.48001 -2.47529 0.7640514 -2.414099 -2.556358 0.7640511 -2.414099 -2.597868 0.7640509 -2.553549 -2.752475 0.7640505 -2.434755 -2.633682 0.7640508 -2.589362 -2.773132 0.7640501 -2.630872 -2.773132 0.7640506 -2.666686 -2.752476 0.7640507 -2.259393 -2.141535 0.7640524 -2.101001 -2.299927 0.7640516 -1.970893 -1.853036 0.7640535 -1.812501 -2.011427 0.7640522 5.451043 -4.859795 -0.3159741 3.126331 -2.735739 -0.3159601 3.108961 -2.701562 -0.3159599 3.108961 -2.701562 0.76404 2.727123 -2.475288 -0.315958 3.074785 -2.684193 -0.3159598 3.074785 -2.684193 0.7640401 2.792986 -2.20174 -0.315957 3.120378 -2.77349 -0.3159602 3.126331 -2.735739 0.7640398 3.093208 -2.80066 -0.3159602 3.120378 -2.773491 0.7640397 2.900057 -2.962013 -0.3159606 3.055457 -2.806613 -0.3159602 3.093208 -2.800661 0.7640396 2.894104 -2.999764 -0.3159607 3.113662 -2.918494 -0.3159608 3.190986 -2.939151 -0.315961 3.155173 -2.918494 -0.3159608 2.882687 -2.927837 -0.3159604 3.02128 -2.789243 -0.3159601 3.055457 -2.806614 0.7640397 2.84851 -2.910467 -0.3159603 3.00391 -2.755067 -0.3159599 3.02128 -2.789244 0.7640398 2.81076 -2.91642 -0.3159602 3.009863 -2.717316 -0.3159598 3.00391 -2.755067 0.7640399 2.764849 -2.773131 -0.3159596 3.037034 -2.690146 -0.3159598 3.009863 -2.717316 0.7640401 2.845918 -2.707219 -0.3159595 3.037034 -2.690146 0.7640402 2.800663 -2.752474 -0.3159596 2.845917 -2.594082 -0.3159587 2.866574 -2.629896 -0.3159589 2.866574 -2.671406 -0.3159594 4.90824 -4.517648 -0.3159714 4.890871 -4.483471 -0.3159713 4.890871 -4.483471 0.7640286 4.053656 -3.80182 -0.3159665 4.856694 -4.466102 -0.3159711 4.856694 -4.466102 0.7640288 4.902287 -4.555399 -0.3159716 4.90824 -4.517648 0.7640285 4.875117 -4.582569 -0.3159716 4.902287 -4.555399 0.7640284 4.681966 -4.743922 -0.3159719 4.837366 -4.588522 -0.3159716 4.875117 -4.582569 0.7640283 4.676013 -4.781673 -0.3159721 4.904057 -4.708888 -0.3159722 4.945567 -4.708888 -0.3159723 4.664597 -4.709745 -0.3159718 4.803189 -4.571152 -0.3159715 4.837366 -4.588522 0.7640283 4.63042 -4.692376 -0.3159717 4.78582 -4.536976 -0.3159713 4.803189 -4.571152 0.7640285 4.592669 -4.698328 -0.3159716 4.791772 -4.499224 -0.3159711 4.78582 -4.536976 0.7640286 4.552415 -4.560696 -0.315971 4.818943 -4.472054 -0.3159711 4.791772 -4.499224 0.7640287 4.633484 -4.494784 -0.3159709 4.818943 -4.472054 0.7640288 4.588229 -4.54004 -0.315971 4.633484 -4.381648 -0.3159701 4.65414 -4.417461 -0.3159707 4.65414 -4.458971 -0.3159708 4.664597 -4.709745 0.7640281 4.63042 -4.692376 0.7640283 4.681966 -4.743922 0.764028 4.648843 -4.808844 -0.3159722 4.676013 -4.781673 0.7640278 4.802332 -4.810613 -0.3159724 4.611092 -4.814796 -0.3159721 4.648843 -4.808844 0.7640278 4.868243 -4.729544 -0.3159722 4.822988 -4.774799 -0.3159723 5.049263 -5.11421 -0.3159744 4.576915 -4.797427 -0.315972 4.611092 -4.814796 0.7640278 4.822988 -4.887936 -0.3159731 4.802332 -4.852123 -0.3159726 2.295183 -2.699543 -0.3159582 4.559545 -4.76325 -0.3159719 4.576915 -4.797427 0.764028 4.953239 -5.357597 -0.3159752 4.565498 -4.725498 -0.3159717 4.559545 -4.76325 0.7640281 4.565498 -4.725498 0.7640282 4.592669 -4.698328 0.7640283 4.475092 -4.54004 -0.3159708 4.510905 -4.560696 -0.315971 2.882687 -2.927837 0.7640395 2.84851 -2.910467 0.7640396 2.900057 -2.962013 0.7640393 2.866934 -3.026935 -0.3159608 2.894104 -2.999765 0.7640392 3.011938 -3.020219 -0.315961 2.829183 -3.032888 -0.3159608 2.866934 -3.026935 0.7640391 3.077849 -2.93915 -0.3159608 3.032594 -2.984405 -0.3159609 3.612422 -3.677369 -0.3159653 2.795006 -3.015518 -0.3159606 2.829183 -3.032888 0.7640392 3.032594 -3.097542 -0.3159613 3.011938 -3.061729 -0.3159611 2.777636 -2.981341 -0.3159605 2.795006 -3.015518 0.7640393 2.783589 -2.94359 -0.3159603 2.777636 -2.981341 0.7640395 2.783589 -2.94359 0.7640396 2.81076 -2.91642 0.7640396 2.723339 -2.773131 -0.3159595 6.531299 -5.448416 -0.3159785 6.188946 -5.815451 -0.3159797 6.163664 -5.784546 -0.3159796 6.163664 -5.784546 0.7640203 6.132759 -5.759264 -0.3159794 6.132759 -5.759264 0.7640209 6.618191 -5.5625 -0.3159795 6.20739 -5.849999 -0.3159799 6.188946 -5.815451 0.7640202 6.218955 -5.88806 -0.3159801 6.20739 -5.849999 0.76402 6.222782 -5.927381 -0.3159803 6.218955 -5.88806 0.7640198 6.218955 -5.966704 -0.3159804 6.222782 -5.927382 0.7640197 6.371835 -5.870342 -0.3159803 6.20739 -6.004765 -0.3159805 6.218955 -5.966705 0.7640195 6.188786 -6.039533 -0.3159806 6.20739 -6.004765 0.7640193 6.163664 -6.070218 -0.3159807 6.188786 -6.039534 0.7640193 5.655946 -6.524744 -0.3159821 6.13298 -6.095339 -0.3159807 6.163664 -6.070218 0.7640192 6.343788 -5.898389 -0.3159803 5.991836 -6.250342 -0.3159811 6.098212 -6.113944 -0.3159808 6.13298 -6.095339 0.7640191 6.060151 -6.125509 -0.3159807 6.098212 -6.113944 0.7640191 6.020828 -6.129336 -0.3159807 6.060151 -6.12551 0.7640191 5.541862 -6.437853 -0.3159815 5.981506 -6.125509 -0.3159806 6.020828 -6.129336 0.7640191 5.943446 -6.113944 -0.3159806 5.981506 -6.125509 0.7640193 5.908897 -6.095499 -0.3159804 5.943446 -6.113945 0.7640194 5.877993 -6.070218 -0.3159803 5.908897 -6.0955 0.7640195 5.447875 -6.329524 -0.3159806 5.852711 -6.039313 -0.3159801 5.877993 -6.070218 0.7640196 5.834266 -6.004765 -0.3159799 5.852711 -6.039313 0.7640198 5.822701 -5.966703 -0.3159797 5.834266 -6.004765 0.76402 5.818873 -5.927381 -0.3159796 5.822701 -5.966704 0.7640202 5.377935 -6.204309 -0.31598 5.8227 -5.888059 -0.3159794 5.818873 -5.927382 0.7640203 5.669821 -5.984422 -0.3159795 5.834266 -5.849998 -0.3159793 5.8227 -5.88806 0.7640209 5.85287 -5.81523 -0.3159792 5.834266 -5.849999 0.764021 5.877992 -5.784546 -0.3159791 5.85287 -5.815231 0.7640211 6.049821 -5.604422 -0.3159784 5.908676 -5.759425 -0.3159791 5.877992 -5.784546 0.7640212 5.697868 -5.956375 -0.3159795 6.42297 -5.354429 -0.3159779 5.943445 -5.74082 -0.3159791 5.908676 -5.759425 0.7640213 5.981505 -5.729254 -0.3159791 5.943445 -5.74082 0.7640213 6.020828 -5.725427 -0.3159791 5.981505 -5.729255 0.7640213 6.06015 -5.729255 -0.3159792 6.020828 -5.725428 0.7640208 6.098211 -5.740819 -0.3159793 6.06015 -5.729255 0.7640211 6.098211 -5.74082 0.764021 6.297755 -5.284489 -0.3159775 6.084013 -5.537406 -0.3159781 6.066082 -5.502127 -0.3159779 6.066082 -5.502127 0.7640219 6.030804 -5.484197 -0.3159778 6.030804 -5.484198 0.7640221 6.077868 -5.576375 -0.3159782 6.084013 -5.537406 0.7640218 6.077868 -5.576375 0.7640217 5.704013 -5.917406 -0.3159794 6.010852 -5.610567 -0.3159783 6.049821 -5.604422 0.7640216 5.686083 -5.882127 -0.3159792 5.975573 -5.592637 -0.3159782 6.010852 -5.610567 0.7640216 5.650804 -5.864197 -0.3159791 5.957643 -5.557357 -0.315978 5.975573 -5.592638 0.7640218 5.611835 -5.870342 -0.3159791 5.963788 -5.518389 -0.3159778 5.957643 -5.557358 0.7640219 5.334982 -6.067437 -0.3159794 5.991835 -5.490342 -0.3159778 5.963788 -5.518389 0.7640221 5.991835 -5.490343 0.7640221 6.160883 -5.241536 -0.3159771 5.686083 -5.882127 0.7640207 5.650804 -5.864197 0.7640209 5.704013 -5.917407 0.7640205 5.697868 -5.956375 0.7640204 5.630852 -5.990567 -0.3159795 5.669821 -5.984422 0.7640203 5.595573 -5.972637 -0.3159794 5.630852 -5.990567 0.7640203 5.577643 -5.937358 -0.3159793 5.595573 -5.972637 0.7640205 5.583788 -5.898389 -0.3159791 5.577643 -5.937358 0.7640207 5.583788 -5.898389 0.7640212 5.611835 -5.870342 0.7640213 6.390852 -5.990567 -0.3159807 6.084013 -6.297406 -0.3159819 6.066083 -6.262126 -0.3159817 6.066083 -6.262127 0.7640182 6.355573 -5.972637 -0.3159806 6.030804 -6.244197 -0.3159812 6.030804 -6.244197 0.7640184 6.429821 -5.984422 -0.3159808 6.077868 -6.336375 -0.315982 6.084013 -6.297407 0.7640181 6.714157 -5.831144 -0.3159807 6.049821 -6.364421 -0.3159821 6.077868 -6.336375 0.7640179 5.785332 -6.58656 -0.3159825 6.010853 -6.370566 -0.3159821 6.049821 -6.364422 0.7640179 5.975574 -6.352637 -0.3159819 6.010853 -6.370567 0.7640179 5.957643 -6.317358 -0.3159818 5.975574 -6.352637 0.7640181 5.963788 -6.278389 -0.3159812 5.957643 -6.317358 0.7640182 5.963788 -6.278389 0.7640183 6.337643 -5.937357 -0.3159804 5.991836 -6.250342 0.7640184 6.680006 -5.691886 -0.3159801 6.464013 -5.917406 -0.3159806 6.446083 -5.882127 -0.3159804 6.446083 -5.882127 0.7640194 6.410803 -5.864197 -0.3159803 6.410803 -5.864197 0.7640196 6.457868 -5.956375 -0.3159807 6.464013 -5.917407 0.7640193 6.457868 -5.956375 0.7640192 6.429821 -5.984422 0.7640191 6.390852 -5.990567 0.7640191 6.355573 -5.972637 0.7640193 6.337643 -5.937358 0.7640194 6.343788 -5.898389 0.7640196 6.371835 -5.870342 0.7640196 5.963946 -5.186046 -0.3159766 5.742922 -5.44041 -0.3159772 5.708286 -5.388566 -0.3159769 5.708286 -5.388567 0.764023 5.656443 -5.353931 -0.3159767 5.656443 -5.353932 0.7640232 5.755113 -5.501704 -0.3159775 5.742922 -5.44041 0.7640227 5.742921 -5.562997 -0.3159776 5.755113 -5.501704 0.7640225 5.708286 -5.614841 -0.3159778 5.742921 -5.562998 0.7640222 5.656443 -5.649476 -0.3159778 5.708286 -5.614841 0.7640221 5.279491 -5.870501 -0.3159781 5.595149 -5.661667 -0.3159778 5.656443 -5.649477 0.7640221 5.533855 -5.649477 -0.3159776 5.595149 -5.661667 0.7640221 5.482012 -5.614841 -0.3159775 5.533855 -5.649477 0.7640223 5.196255 -5.684475 -0.3159772 5.447377 -5.562998 -0.3159772 5.482012 -5.614841 0.7640225 5.435186 -5.501704 -0.3159769 5.447377 -5.562998 0.7640227 5.447377 -5.440411 -0.3159767 5.435186 -5.501704 0.764023 5.482012 -5.388567 -0.3159766 5.447377 -5.440411 0.7640232 5.77792 -5.10281 -0.3159756 5.533855 -5.353932 -0.3159765 5.482012 -5.388567 0.7640234 5.086946 -5.51247 -0.3159764 5.595149 -5.34174 -0.3159766 5.533855 -5.353932 0.7640234 5.595149 -5.34174 0.7640234 2.021431 -1.076631 -0.3159502 1.910107 -1.236673 -0.3159511 1.892737 -1.202496 -0.3159509 1.892737 -1.202496 0.7640494 1.858561 -1.185127 -0.3159504 1.858561 -1.185127 0.7640495 2.451352 -1.506552 -0.315953 1.904154 -1.274424 -0.3159512 1.910107 -1.236673 0.7640492 1.876984 -1.301594 -0.3159513 1.904154 -1.274424 0.7640491 1.956377 -1.704542 -0.315953 1.839233 -1.307547 -0.3159512 1.876984 -1.301594 0.764049 1.44726 -1.195425 -0.3159498 1.805056 -1.290178 -0.3159511 1.839233 -1.307548 0.7640491 1.787687 -1.256001 -0.3159509 1.805056 -1.290178 0.7640492 1.79364 -1.21825 -0.3159504 1.787687 -1.256001 0.7640493 1.82081 -1.19108 -0.3159504 1.79364 -1.21825 0.7640495 1.991004 -1.051687 -0.3159501 1.82081 -1.19108 0.7640496 1.956538 -1.033297 -0.31595 1.797985 -1.862934 -0.3159537 1.40099 -1.74579 -0.3159523 1.383621 -1.711613 -0.3159521 1.383621 -1.711613 0.7640478 1.349444 -1.694244 -0.315952 1.349444 -1.694244 0.7640479 1.395038 -1.783541 -0.3159524 1.40099 -1.74579 0.7640476 1.367868 -1.810711 -0.3159524 1.395038 -1.783541 0.7640475 1.170075 -1.927988 -0.3159526 1.330116 -1.816664 -0.3159524 1.367868 -1.810712 0.7640475 1.29594 -1.799294 -0.3159523 1.330116 -1.816665 0.7640475 1.14513 -1.897561 -0.3159524 1.27857 -1.765118 -0.3159521 1.29594 -1.799295 0.7640476 1.284523 -1.727367 -0.315952 1.27857 -1.765118 0.7640478 1.12674 -1.863095 -0.3159523 1.311693 -1.700196 -0.3159519 1.284523 -1.727367 0.7640479 1.111496 -1.614033 -0.3159512 1.311693 -1.700197 0.7640479 1.111496 -1.786567 -0.315952 1.115373 -1.82572 -0.3159521 1.115373 -1.574879 -0.3159511 2.334372 -1.660937 -0.3159534 2.317002 -1.62676 -0.3159533 2.317002 -1.626761 0.7640463 2.282825 -1.60939 -0.3159531 2.282825 -1.609391 0.7640464 2.53342 -1.608903 -0.3159539 2.328418 -1.698688 -0.3159539 2.334372 -1.660937 0.7640461 2.301248 -1.725858 -0.315954 2.328418 -1.698688 0.764046 2.10487 -1.853034 -0.3159542 2.263497 -1.731811 -0.315954 2.301248 -1.725858 0.7640459 2.229321 -1.714442 -0.3159539 2.263497 -1.731812 0.764046 1.773708 -2.118507 -0.3159547 2.211951 -1.680265 -0.3159533 2.229321 -1.714442 0.764046 1.807885 -2.135877 -0.3159548 1.735957 -2.124461 -0.3159546 2.217904 -1.642514 -0.3159531 2.211951 -1.680265 0.7640463 2.245074 -1.615344 -0.3159531 2.217904 -1.642514 0.7640464 2.245074 -1.615344 0.7640464 1.946478 -2.011426 -0.3159546 1.825255 -2.170054 -0.315955 1.807885 -2.135877 0.7640451 1.773708 -2.118508 0.7640452 2.234977 -2.299926 -0.3159565 1.819302 -2.207805 -0.3159551 1.825255 -2.170054 0.7640449 1.792132 -2.234975 -0.3159552 1.819302 -2.207805 0.7640448 1.599996 -2.357909 -0.3159554 1.75438 -2.240928 -0.3159552 1.792132 -2.234976 0.7640447 1.702346 -2.439976 -0.3159562 1.720204 -2.223558 -0.315955 1.75438 -2.240929 0.7640448 1.702834 -2.189382 -0.3159549 1.720204 -2.223559 0.7640449 1.708787 -2.151631 -0.3159548 1.702834 -2.189382 0.7640451 1.708787 -2.151631 0.7640452 1.735957 -2.124461 0.7640452 2.542493 -2.341529 -0.3159572 2.527719 -2.321139 -0.3159571 2.527719 -2.321139 0.7640428 2.507329 -2.306366 -0.315957 2.507329 -2.306366 0.7640429 2.550132 -2.365238 -0.3159573 2.542493 -2.341529 0.7640427 2.550132 -2.390177 -0.3159574 2.550132 -2.365238 0.7640427 2.542451 -2.413949 -0.3159574 2.550132 -2.390177 0.7640426 2.527719 -2.434276 -0.3159575 2.542451 -2.413949 0.7640424 2.507393 -2.449007 -0.3159576 2.527719 -2.434276 0.7640424 2.192832 -2.617475 -0.3159577 2.483621 -2.456689 -0.3159576 2.507393 -2.449007 0.7640424 2.458681 -2.456689 -0.3159575 2.483621 -2.456689 0.7640424 2.434973 -2.44905 -0.3159574 2.458681 -2.456689 0.7640424 2.414582 -2.434276 -0.3159573 2.434973 -2.44905 0.7640425 2.399809 -2.413886 -0.3159572 2.414582 -2.434276 0.7640426 2.39217 -2.390177 -0.3159571 2.399809 -2.413886 0.7640427 2.075091 -2.559614 -0.3159573 2.39217 -2.365238 -0.315957 2.39217 -2.390177 0.7640428 2.399851 -2.341466 -0.315957 2.39217 -2.365238 0.7640429 2.414582 -2.321139 -0.3159569 2.399851 -2.341466 0.764043 2.710919 -2.099389 -0.3159565 2.434909 -2.306408 -0.3159568 2.414582 -2.321139 0.764043 2.458682 -2.298727 -0.3159569 2.434909 -2.306408 0.764043 2.483621 -2.298727 -0.3159569 2.458682 -2.298727 0.764043 2.483621 -2.298727 0.764043 1.14513 -1.503038 -0.3159509 1.170075 -1.472611 -0.3159508 1.170075 -1.472612 0.7640495 1.288869 -1.353817 -0.3159502 1.12674 -1.537504 -0.315951 1.14513 -1.503039 0.7640494 1.12674 -1.537505 0.7640493 1.115373 -1.574879 0.7640492 1.111496 -1.786567 0.764048 1.111496 -1.614033 0.7640491 1.115373 -1.82572 0.7640478 1.12674 -1.863095 0.7640476 1.14513 -1.897561 0.7640475 1.170075 -1.927988 0.7640473 1.599996 -2.357909 0.7640446 1.820087 -2.497838 -0.3159566 1.702346 -2.439977 0.7640441 1.947589 -2.528726 -0.315957 1.820087 -2.497838 0.7640433 2.653058 -1.981648 -0.3159556 1.947589 -2.528726 0.764043 2.075091 -2.559614 0.7640427 2.192832 -2.617475 0.7640422 2.295183 -2.699543 0.7640418 2.613987 -2.475288 -0.3159578 3.895264 -3.960212 -0.3159669 3.874608 -3.924399 -0.3159667 3.874608 -3.882889 -0.3159665 2.687526 -2.752474 -0.3159594 2.568732 -2.63368 -0.3159584 2.548076 -2.597867 -0.3159582 2.548075 -2.556357 -0.315958 2.568732 -2.520543 -0.3159579 5.605915 -4.993502 -0.3159748 4.953239 -5.357597 0.7640247 5.162399 -5.11421 -0.3159745 5.126586 -5.134866 -0.3159746 5.085076 -5.134866 -0.3159745 5.086946 -5.51247 0.7640236 5.196255 -5.684475 0.7640227 5.279491 -5.870501 0.7640218 5.334982 -6.067437 0.7640205 5.377935 -6.204309 0.7640199 5.447875 -6.329524 0.7640193 5.541862 -6.437853 0.7640184 5.655946 -6.524745 0.7640178 5.924592 -6.620711 -0.3159829 5.785332 -6.586561 0.7640174 6.719217 -5.974433 -0.3159812 6.067881 -6.625771 -0.3159831 5.924592 -6.620712 0.7640171 6.694977 -6.115741 -0.3159822 6.209187 -6.601531 -0.3159832 6.067881 -6.625771 0.7640168 6.642457 -6.249142 -0.3159826 6.342588 -6.549011 -0.3159833 6.209187 -6.601531 0.7640166 6.563862 -6.369042 -0.3159829 6.462489 -6.470416 -0.3159831 6.342588 -6.549012 0.7640167 6.462489 -6.470416 0.7640168 6.563862 -6.369043 0.764017 6.642457 -6.249143 0.7640174 6.694977 -6.115742 0.7640178 6.719217 -5.974433 0.7640183 6.714157 -5.831145 0.7640193 6.680006 -5.691886 0.7640199 6.618191 -5.5625 0.7640204 6.531299 -5.448417 0.7640215 6.42297 -5.354429 0.764022 6.297755 -5.28449 0.7640225 6.160883 -5.241536 0.7640229 5.963946 -5.186046 0.7640234 5.77792 -5.10281 0.764024 5.605915 -4.993503 0.7640251 5.451043 -4.859795 0.7640259 4.98138 -4.729544 -0.3159724 5.207654 -4.955819 -0.315974 5.228311 -4.991632 -0.3159742 5.228311 -5.033142 -0.3159744 5.207654 -5.068955 -0.3159745 3.79147 -3.596301 -0.3159653 3.770813 -3.518978 -0.3159645 3.79147 -3.554791 -0.3159651 2.792986 -2.20174 0.7640429 2.6498 -2.454632 -0.3159578 2.69131 -2.454632 -0.3159579 2.710919 -2.099389 0.7640438 2.393369 -2.141534 -0.3159558 2.622169 -1.854146 -0.3159551 2.653058 -1.981648 0.7640444 2.591281 -1.726644 -0.3159545 2.622169 -1.854146 0.7640449 2.591281 -1.726644 0.7640455 2.53342 -1.608903 0.764046 2.451352 -1.506552 0.7640469 2.021431 -1.076631 0.7640497 1.991004 -1.051687 0.7640498 1.919163 -1.02193 -0.3159499 1.956538 -1.033297 0.76405 1.88001 -1.018053 -0.3159498 1.919163 -1.02193 0.7640501 1.707476 -1.018053 -0.3159495 1.707476 -1.018053 0.7640504 1.88001 -1.018053 0.7640501 1.668322 -1.021929 -0.3159494 1.630947 -1.033297 -0.3159494 1.668322 -1.02193 0.7640505 1.596481 -1.051687 -0.3159494 1.630947 -1.033297 0.7640505 1.566054 -1.076631 -0.3159495 1.596481 -1.051687 0.7640505 1.44726 -1.195425 0.7640501 1.566054 -1.076631 0.7640504 1.956377 -1.704542 0.7640466 1.797985 -1.862934 0.7640462 1.288869 -1.353818 0.7640498 4.868243 -4.729544 0.7640277 4.802332 -4.810613 0.7640275 4.822988 -4.774799 0.7640276 4.904057 -4.708888 0.7640278 4.945567 -4.708888 0.7640277 4.98138 -4.729544 0.7640275 5.207654 -4.955819 0.7640259 5.228311 -4.991632 0.7640257 5.228311 -5.033142 0.7640255 5.162399 -5.11421 0.7640253 5.207654 -5.068955 0.7640255 5.126586 -5.134866 0.7640253 5.085076 -5.134866 0.7640254 5.049263 -5.11421 0.7640255 4.822988 -4.887936 0.7640272 4.802332 -4.852123 0.7640274 4.588229 -4.54004 0.7640289 4.552415 -4.560696 0.7640289 4.510905 -4.560696 0.7640289 4.475092 -4.54004 0.7640291 3.895264 -3.960212 0.764033 3.874608 -3.924399 0.7640332 3.895264 -3.847075 -0.3159664 3.874608 -3.882889 0.7640334 3.648235 -3.698026 -0.3159654 3.940519 -3.80182 -0.3159663 3.940519 -3.80182 0.7640336 3.895264 -3.847075 0.7640334 3.725558 -3.677369 -0.3159655 3.976332 -3.781164 -0.3159663 3.689745 -3.698026 -0.3159655 4.017843 -3.781164 -0.3159664 3.976332 -3.781164 0.7640336 3.770814 -3.632114 -0.3159654 4.017843 -3.781164 0.7640336 4.053656 -3.80182 0.7640334 4.633484 -4.381648 0.7640295 4.65414 -4.417461 0.7640293 4.65414 -4.458971 0.7640292 4.633484 -4.494784 0.764029 3.077849 -2.93915 0.7640391 3.011938 -3.020219 0.7640389 3.032594 -2.984405 0.764039 3.113662 -2.918494 0.7640391 3.155173 -2.918494 0.764039 3.190986 -2.939151 0.7640389 3.770813 -3.518978 0.764035 3.79147 -3.554791 0.7640348 3.79147 -3.596301 0.7640346 3.725558 -3.67737 0.7640344 3.770814 -3.632115 0.7640345 3.689745 -3.698026 0.7640344 3.648235 -3.698026 0.7640345 3.612422 -3.67737 0.7640346 3.032594 -3.097543 0.7640386 3.011938 -3.061729 0.7640388 2.800663 -2.752474 0.7640403 2.764849 -2.773131 0.7640403 2.723339 -2.773131 0.7640404 2.568732 -2.63368 0.7640416 2.687526 -2.752474 0.7640405 2.548076 -2.597867 0.7640417 2.548075 -2.556357 0.7640419 2.613987 -2.475288 0.7640421 2.568732 -2.520543 0.764042 2.6498 -2.454632 0.7640421 2.69131 -2.454632 0.7640421 2.845917 -2.594082 0.7640409 2.727123 -2.475288 0.7640419 2.866574 -2.629896 0.7640407 2.866574 -2.671406 0.7640405 2.845918 -2.707219 0.7640404 2.234977 -2.299926 0.7640438 2.393369 -2.141534 0.7640441 1.946478 -2.011427 0.7640454 2.10487 -1.853035 0.7640457 -0.57261 -1.197944 -14.11594 -1.157414 -0.6131401 -14.11594 -1.116444 -0.5912889 -14.11594 -1.116444 -0.591289 -13.87594 -0.5507588 -1.156974 -14.11594 -0.5552669 -0.03011137 -14.11594 -0.5552669 -0.03011143 -13.87594 -0.5681007 -1.244157 -14.11594 -1.203627 -0.6086308 -14.11594 -1.157414 -0.6131401 -13.87594 -0.5386114 -1.280024 -14.11594 -1.239494 -0.5791416 -14.11594 -1.203627 -0.6086308 -13.87594 -1.613013 -0.1299825 -14.11594 -1.253013 -0.5347204 -14.11594 -1.239494 -0.5791417 -13.87594 -0.3221038 -1.653543 -14.11595 -1.626167 -0.3622751 -14.11594 -1.253013 0.5876344 -14.11594 -1.253013 -0.5347205 -13.87594 -1.613013 1.50581 -14.11593 -1.239494 0.6320556 -14.11593 -1.253013 0.5876343 -13.87594 -1.203628 0.6615448 -14.11593 -1.239494 0.6320555 -13.87594 -1.157415 0.666054 -14.11593 -1.203628 0.6615447 -13.87594 -1.116445 0.6442029 -14.11593 -1.157415 0.666054 -13.87594 -0.5552669 0.08302563 -14.11594 -1.116445 0.6442028 -13.87594 0.08774197 -0.5751404 -14.11594 -0.5346106 0.04721212 -14.11594 -0.5552669 0.08302557 -13.87594 0.1235555 -0.5957967 -14.11594 0.04623198 -0.5751404 -14.11594 -0.5346106 0.005702078 -14.11594 -0.5346106 0.04721206 -13.87594 0.01041841 -0.5957967 -14.11594 -0.5346106 0.005702078 -13.87594 1.746987 -1.45273 -14.11595 -0.5507593 1.209888 -14.11593 0.01041817 0.6487111 -14.11594 0.01041817 0.648711 -13.87594 0.6892408 -0.03011113 -14.11594 0.04623168 0.6280548 -14.11594 0.04623174 0.6280548 -13.87594 -1.550824 2.311777 -14.11593 -0.5726104 1.250858 -14.11593 -0.5507593 1.209888 -13.87593 -1.779839 2.131031 -14.11593 -0.5681011 1.297072 -14.11593 -0.5726104 1.250858 -13.87593 -1.377268 2.156822 -14.11593 -0.538612 1.332938 -14.11593 -0.5681011 1.297072 -13.87593 -1.189183 2.023366 -14.11593 -0.4941908 1.346457 -14.11593 -0.538612 1.332938 -13.87593 -0.08945304 1.706457 -14.11593 0.6281641 1.346457 -14.11594 -0.4941908 1.346457 -13.87593 -0.3217455 1.719611 -14.11593 -0.5491088 1.758239 -14.11593 -0.772238 1.822553 -14.11593 -0.98593 1.911067 -14.11593 1.546339 1.706457 -14.11594 0.6725852 1.332938 -14.11594 0.6281641 1.346457 -13.87594 1.337601 0.6615453 -14.11594 0.7020745 1.297072 -14.11594 0.6725852 1.332938 -13.87594 1.373468 0.6320561 -14.11594 1.291388 0.6660545 -14.11594 0.7065837 1.250859 -14.11594 0.7020745 1.297072 -13.87594 1.250418 0.6442034 -14.11594 0.6847326 1.209889 -14.11594 0.7065837 1.250859 -13.87594 0.6892408 0.08302587 -14.11594 0.1235553 0.6487111 -14.11594 0.6847326 1.209889 -13.87594 0.6685845 0.04721236 -14.11594 0.08774173 0.6280548 -14.11594 0.1235553 0.6487111 -13.87594 0.6685845 0.005702316 -14.11594 0.08774179 0.6280548 -13.87594 0.6892408 -0.03011119 -13.87594 1.250418 -0.5912884 -14.11595 1.250418 -0.5912885 -13.87595 0.6685845 0.005702316 -13.87594 0.6685845 0.0472123 -13.87594 0.6892408 0.08302587 -13.87594 1.250418 0.6442034 -13.87594 1.291388 0.6660544 -13.87594 1.337601 0.6615452 -13.87594 1.746987 0.1828971 -14.11594 1.386986 0.5876349 -14.11594 1.373468 0.6320561 -13.87594 1.76014 0.4151896 -14.11594 1.386987 -0.5347199 -14.11595 1.386986 0.5876349 -13.87594 1.373468 -0.5791411 -14.11595 1.386987 -0.53472 -13.87595 1.337601 -0.6086302 -14.11595 1.373468 -0.5791411 -13.87595 1.291388 -0.6131395 -14.11595 1.337601 -0.6086303 -13.87595 1.291388 -0.6131396 -13.87595 0.684733 -1.156974 -14.11595 0.1235555 -0.5957967 -13.87594 0.08774197 -0.5751404 -13.87594 1.684798 -2.258862 -14.11595 0.7065841 -1.197944 -14.11595 0.684733 -1.156974 -13.87595 1.913812 -2.078117 -14.11595 0.702075 -1.244157 -14.11595 0.7065841 -1.197944 -13.87595 0.6725858 -1.280023 -14.11595 0.702075 -1.244157 -13.87595 1.424351 -2.10138 -14.11595 0.6281646 -1.293542 -14.11595 0.6725858 -1.280023 -13.87595 -0.0180158 -1.666335 -14.11595 -0.4941903 -1.293543 -14.11594 0.6281646 -1.293542 -13.87595 0.2824648 -1.704257 -14.11595 0.5798563 -1.767426 -14.11595 0.870293 -1.855027 -14.11595 1.153015 -1.966832 -14.11595 -0.4941902 -1.293543 -13.87594 -0.5386114 -1.280024 -13.87594 -0.5681007 -1.244157 -13.87594 -0.57261 -1.197944 -13.87594 -0.5507588 -1.156974 -13.87594 0.01041847 -0.5957967 -13.87594 0.04623198 -0.5751404 -13.87594 -1.609762 -2.215977 -14.11595 -1.789936 -1.632477 -14.11595 -1.408099 -2.014314 -14.11595 -1.408099 -2.014314 -13.87595 -1.609762 -2.215977 -13.87595 -1.929922 -1.229713 -14.11594 -1.611684 -1.454224 -14.11594 -1.789936 -1.632477 -13.87595 -2.063378 -1.417798 -14.11594 -1.817623 -1.026459 -14.11594 -1.412366 -1.653543 -14.11595 -1.611684 -1.454224 -13.87594 -1.412366 -1.653543 -13.87595 -1.664795 -0.5896384 -14.11594 -1.729109 -0.8127675 -14.11594 -0.3221037 -1.653543 -13.87595 -0.0180158 -1.666335 -13.87595 0.2824649 -1.704257 -13.87595 0.5798563 -1.767426 -13.87595 0.870293 -1.855027 -13.87595 1.153015 -1.966832 -13.87595 1.424351 -2.10138 -13.87595 1.684798 -2.258862 -13.87595 1.725838 -1.830383 -14.11595 2.122776 -1.874523 -14.11595 1.913812 -2.078117 -13.87595 1.547586 -1.652131 -14.11595 2.107758 -1.448628 -14.11595 2.309422 -1.650291 -14.11595 2.122776 -1.874523 -13.87595 2.309422 -1.650291 -13.87595 2.107758 -1.448628 -13.87595 1.725838 -1.830383 -13.87595 -1.413695 1.705128 -14.11593 1.547586 -1.652131 -13.87595 1.746987 -1.45273 -13.87595 1.746987 0.1828971 -13.87594 1.798769 0.6425529 -14.11594 1.76014 0.4151896 -13.87594 1.863083 0.8656821 -14.11594 1.798769 0.6425528 -13.87594 1.951597 1.079374 -14.11594 1.863083 0.8656821 -13.87594 1.745658 1.507139 -14.11594 2.063896 1.282627 -14.11594 1.951597 1.079374 -13.87594 1.92391 1.685391 -14.11594 2.197352 1.470712 -14.11594 2.063896 1.282627 -13.87594 1.743735 2.268892 -14.11593 2.352306 1.644269 -14.11594 2.197352 1.470712 -13.87594 2.171561 1.873283 -14.11594 2.352306 1.644269 -13.87594 1.967967 2.082247 -14.11593 2.171561 1.873283 -13.87594 1.967967 2.082247 -13.87593 1.542072 2.067229 -14.11593 1.743735 2.268892 -13.87593 1.542072 2.067229 -13.87594 1.92391 1.685391 -13.87594 1.745658 1.507139 -13.87594 1.546339 1.706457 -13.87594 -0.08945304 1.706457 -13.87593 -0.3217455 1.719611 -13.87593 -0.5491088 1.758239 -13.87593 -0.772238 1.822553 -13.87593 -0.98593 1.911067 -13.87593 -1.189183 2.023366 -13.87593 -1.377268 2.156822 -13.87593 -1.550824 2.311776 -13.87593 -1.591947 1.88338 -14.11593 -1.988803 1.927438 -14.11593 -1.779839 2.131031 -13.87593 -1.973785 1.501543 -14.11593 -2.175448 1.703206 -14.11593 -1.988803 1.927438 -13.87593 -2.175448 1.703206 -13.87593 -1.973785 1.501542 -13.87593 -1.591947 1.88338 -13.87593 -1.413695 1.705128 -13.87593 -1.613013 1.50581 -13.87593 -1.613013 -0.1299826 -13.87594 -1.626167 -0.3622751 -13.87594 -1.664795 -0.5896385 -13.87594 -1.729109 -0.8127676 -13.87594 -1.817623 -1.02646 -13.87594 -1.929922 -1.229713 -13.87594 -2.218332 -1.591354 -14.11595 -2.063378 -1.417798 -13.87594 -2.037587 -1.820368 -14.11595 -2.218332 -1.591354 -13.87595 -1.833994 -2.029333 -14.11595 -2.037587 -1.820369 -13.87595 -1.833994 -2.029333 -13.87595 -0.5726093 -1.197945 -6.615946 -1.157414 -0.6131414 -6.615942 -1.116444 -0.5912903 -6.615942 -1.116444 -0.5912904 -6.375942 -0.5507583 -1.156975 -6.615946 -0.5552664 -0.03011274 -6.61594 -0.5552664 -0.0301128 -6.37594 -0.5681 -1.244159 -6.615946 -1.203627 -0.6086322 -6.615942 -1.157414 -0.6131415 -6.375942 -0.5386109 -1.280025 -6.615946 -1.239493 -0.579143 -6.615942 -1.203627 -0.6086322 -6.375942 -1.613013 -0.129984 -6.615939 -1.253012 -0.5347218 -6.615942 -1.239493 -0.5791431 -6.375942 -0.3221032 -1.653544 -6.615948 -1.626166 -0.3622765 -6.615941 -1.253013 0.587633 -6.615936 -1.253012 -0.5347219 -6.375941 -1.613013 1.505808 -6.615932 -1.239494 0.6320542 -6.615936 -1.253013 0.5876329 -6.375936 -1.203627 0.6615434 -6.615936 -1.239494 0.6320541 -6.375936 -1.157414 0.6660526 -6.615936 -1.203627 0.6615433 -6.375936 -1.116444 0.6442015 -6.615936 -1.157414 0.6660525 -6.375936 -0.5552664 0.08302426 -6.615939 -1.116444 0.6442015 -6.375936 0.0877425 -0.5751417 -6.615944 -0.5346102 0.04721075 -6.61594 -0.5552664 0.0830242 -6.375939 0.123556 -0.595798 -6.615944 0.04623246 -0.5751418 -6.615944 -0.5346102 0.005700707 -6.61594 -0.5346102 0.04721069 -6.37594 0.01041895 -0.595798 -6.615944 -0.5346102 0.005700647 -6.37594 1.746987 -1.452732 -6.615952 -0.5507587 1.209887 -6.615935 0.01041871 0.6487097 -6.615938 0.01041877 0.6487097 -6.375938 0.6892414 -0.0301125 -6.615943 0.04623228 0.6280534 -6.615938 0.04623228 0.6280534 -6.375938 -1.550824 2.311775 -6.615929 -0.5726099 1.250857 -6.615935 -0.5507587 1.209887 -6.375935 -1.779838 2.13103 -6.615928 -0.5681006 1.29707 -6.615934 -0.5726099 1.250857 -6.375935 -1.377267 2.156821 -6.61593 -0.5386114 1.332937 -6.615934 -0.5681006 1.29707 -6.375935 -1.189183 2.023365 -6.615931 -0.4941903 1.346456 -6.615934 -0.5386114 1.332937 -6.375935 -0.0894525 1.706456 -6.615934 0.6281646 1.346456 -6.615936 -0.4941903 1.346456 -6.375935 -0.321745 1.719609 -6.615933 -0.5491083 1.758238 -6.615933 -0.7722374 1.822552 -6.615932 -0.9859294 1.911066 -6.615931 1.54634 1.706456 -6.615936 0.6725858 1.332937 -6.615936 0.6281646 1.346456 -6.375936 1.337602 0.6615439 -6.615942 0.702075 1.297071 -6.615936 0.6725858 1.332937 -6.375936 1.373468 0.6320547 -6.615942 1.291388 0.6660531 -6.615942 0.7065842 1.250857 -6.615937 0.702075 1.297071 -6.375936 1.250418 0.644202 -6.615942 0.6847331 1.209887 -6.615937 0.7065842 1.250857 -6.375937 0.6892414 0.0830245 -6.615942 0.1235558 0.6487098 -6.615938 0.6847331 1.209887 -6.375937 0.668585 0.04721099 -6.615943 0.08774226 0.6280535 -6.615938 0.1235558 0.6487097 -6.375938 0.6685851 0.005700945 -6.615943 0.08774232 0.6280534 -6.375938 0.6892414 -0.03011256 -6.375942 1.250419 -0.5912898 -6.615946 1.250419 -0.5912899 -6.375946 0.6685851 0.005700886 -6.375942 0.668585 0.04721093 -6.375942 0.6892414 0.0830245 -6.375942 1.250419 0.6442019 -6.375941 1.291388 0.6660531 -6.375941 1.337602 0.6615438 -6.375941 1.746987 0.1828957 -6.615944 1.386987 0.5876335 -6.615942 1.373468 0.6320547 -6.375941 1.760141 0.4151882 -6.615943 1.386987 -0.5347213 -6.615946 1.386987 0.5876335 -6.375941 1.373468 -0.5791425 -6.615947 1.386987 -0.5347213 -6.375946 1.337602 -0.6086317 -6.615947 1.373468 -0.5791425 -6.375947 1.291389 -0.613141 -6.615946 1.337602 -0.6086317 -6.375947 1.291389 -0.613141 -6.375946 0.6847336 -1.156975 -6.615948 0.1235561 -0.5957981 -6.375944 0.08774256 -0.5751418 -6.375944 1.684799 -2.258863 -6.615955 0.7065847 -1.197945 -6.615948 0.6847336 -1.156975 -6.375948 1.913813 -2.078118 -6.615954 0.7020754 -1.244158 -6.615948 0.7065847 -1.197945 -6.375948 0.6725863 -1.280025 -6.615948 0.7020754 -1.244158 -6.375948 1.424352 -2.101381 -6.615954 0.6281651 -1.293544 -6.615948 0.6725863 -1.280025 -6.375948 -0.01801526 -1.666336 -6.615949 -0.4941897 -1.293544 -6.615946 0.6281651 -1.293544 -6.375948 0.2824654 -1.704259 -6.615949 0.5798569 -1.767427 -6.615952 0.8702937 -1.855028 -6.615952 1.153016 -1.966833 -6.615953 -0.4941897 -1.293544 -6.375946 -0.5386109 -1.280025 -6.375946 -0.5681 -1.244159 -6.375946 -0.5726093 -1.197945 -6.375946 -0.5507583 -1.156975 -6.375946 0.01041901 -0.595798 -6.375944 0.04623252 -0.5751418 -6.375944 -1.609761 -2.215979 -6.615948 -1.789936 -1.632478 -6.615945 -1.408098 -2.014316 -6.615948 -1.408098 -2.014316 -6.375948 -1.609761 -2.215979 -6.375948 -1.929922 -1.229714 -6.615943 -1.611684 -1.454226 -6.615945 -1.789936 -1.632478 -6.375946 -2.063377 -1.417799 -6.615944 -1.817623 -1.026461 -6.615943 -1.412365 -1.653544 -6.615946 -1.611684 -1.454226 -6.375946 -1.412365 -1.653544 -6.375946 -1.664795 -0.5896398 -6.615942 -1.729109 -0.8127689 -6.615942 -0.3221032 -1.653544 -6.375948 -0.01801526 -1.666336 -6.375949 0.2824654 -1.704259 -6.375949 0.5798569 -1.767427 -6.375951 0.8702937 -1.855029 -6.375952 1.153016 -1.966833 -6.375953 1.424352 -2.101381 -6.375954 1.684799 -2.258863 -6.375955 1.725839 -1.830385 -6.615953 2.122777 -1.874525 -6.615954 1.913813 -2.078118 -6.375954 1.547587 -1.652132 -6.615952 2.107759 -1.448629 -6.615952 2.309422 -1.650293 -6.615954 2.122777 -1.874525 -6.375954 2.309422 -1.650293 -6.375954 2.107759 -1.44863 -6.375952 1.725839 -1.830385 -6.375953 -1.413694 1.705127 -6.615931 1.547587 -1.652132 -6.375952 1.746988 -1.452732 -6.375952 1.746987 0.1828957 -6.375943 1.798769 0.6425514 -6.615942 1.760141 0.4151881 -6.375943 1.863083 0.8656807 -6.61594 1.798769 0.6425514 -6.375942 1.951598 1.079373 -6.61594 1.863084 0.8656806 -6.37594 1.745658 1.507138 -6.615938 2.063896 1.282626 -6.615939 1.951598 1.079373 -6.37594 1.92391 1.68539 -6.615937 2.197352 1.47071 -6.615938 2.063896 1.282626 -6.375939 1.743736 2.26889 -6.615934 2.352307 1.644267 -6.615938 2.197352 1.47071 -6.375938 2.171561 1.873281 -6.615937 2.352307 1.644267 -6.375938 1.967968 2.082245 -6.615936 2.171561 1.873281 -6.375937 1.967968 2.082245 -6.375936 1.542073 2.067227 -6.615935 1.743736 2.26889 -6.375934 1.542073 2.067227 -6.375934 1.92391 1.68539 -6.375937 1.745658 1.507138 -6.375938 1.54634 1.706456 -6.375936 -0.08945244 1.706456 -6.375933 -0.321745 1.719609 -6.375933 -0.5491083 1.758238 -6.375932 -0.7722374 1.822552 -6.375931 -0.9859294 1.911066 -6.375931 -1.189183 2.023365 -6.37593 -1.377267 2.156821 -6.375929 -1.550824 2.311775 -6.375928 -1.591946 1.883379 -6.615931 -1.988802 1.927436 -6.615928 -1.779838 2.13103 -6.375928 -1.973784 1.501541 -6.615931 -2.175447 1.703204 -6.615931 -1.988802 1.927436 -6.375928 -2.175447 1.703204 -6.37593 -1.973784 1.501541 -6.375931 -1.591946 1.883379 -6.37593 -1.413694 1.705127 -6.375931 -1.613013 1.505808 -6.375932 -1.613012 -0.129984 -6.375939 -1.626166 -0.3622765 -6.37594 -1.664795 -0.5896399 -6.375941 -1.729108 -0.812769 -6.375942 -1.817623 -1.026461 -6.375942 -1.929922 -1.229714 -6.375943 -2.218332 -1.591356 -6.615944 -2.063377 -1.417799 -6.375944 -2.037587 -1.82037 -6.615946 -2.218332 -1.591356 -6.375944 -1.833993 -2.029334 -6.615947 -2.037587 -1.82037 -6.375946 -1.833993 -2.029334 -6.375947 0.4669891 -2.053547 11.94405 0.3669405 -1.967529 11.94405 0.3910307 -1.957589 11.94405 0.3910307 -1.957589 12.18405 0.4009713 -1.933499 11.94405 0.4009891 -1.933546 12.18405 0.296989 -2.053547 11.94405 0.3429699 -1.957566 11.94405 0.3669874 -1.967547 12.18405 0.3330069 -1.933596 11.94405 0.3429475 -1.957589 12.18405 0.2969891 -1.813547 11.94405 0.3429474 -1.909505 11.94405 0.3329891 -1.933549 12.18405 0.3670376 -1.899565 11.94405 0.3429474 -1.909506 12.18405 0.3910083 -1.909528 11.94405 0.3669909 -1.899547 12.18405 0.3910307 -1.909506 12.18405 0.165984 -1.607609 11.94405 0.1914398 -1.597065 11.94405 0.2019841 -1.571609 11.94405 0.1405282 -1.597065 11.94405 0.07668793 -1.53385 11.94405 0.4669891 -1.832579 11.94405 0.03884166 -1.527856 11.94405 0.01174658 -1.500761 11.94405 -0.1630108 -2.053547 11.94405 -0.2330594 -1.96753 11.94405 -0.2089692 -1.957589 11.94405 -0.2089692 -1.957589 12.18405 -0.1990286 -1.933499 11.94405 -0.1990108 -1.933545 12.18405 -0.2570299 -1.957567 11.94405 -0.2330126 -1.967547 12.18405 -0.3330109 -1.832579 11.94405 -0.2669929 -1.933596 11.94405 -0.2570525 -1.957589 12.18405 -0.3330109 -2.053547 11.94405 -0.2570525 -1.909506 11.94405 -0.2670108 -1.933549 12.18405 -0.3406235 -1.798536 11.94405 -0.2329622 -1.899565 11.94405 -0.2570525 -1.909506 12.18405 -1.748446 -0.2732084 11.94406 -0.2089917 -1.909528 11.94405 -0.233009 -1.899547 12.18405 -0.3619518 -1.771001 11.94405 -0.1630108 -1.813547 11.94405 -0.2089691 -1.909506 12.18405 0.1405279 -0.4091253 11.94405 1.408554 -1.77642 11.94405 1.419393 -1.792641 11.94405 1.419393 -1.792641 12.18405 1.480153 -1.913384 11.94404 1.435614 -1.80348 11.94405 1.43557 -1.803454 12.18405 -1.454683 1.060916 11.94406 1.404748 -1.757286 11.94405 1.40858 -1.776464 12.18405 1.408554 -1.738152 11.94405 1.404745 -1.757268 12.18405 1.419393 -1.721931 11.94405 1.408572 -1.738203 12.18405 1.435614 -1.711092 11.94405 1.419388 -1.721926 12.18405 0.7599536 -1.013639 11.94405 1.454748 -1.707286 11.94405 1.435665 -1.71111 12.18405 0.7344977 -1.003095 11.94405 0.7854094 -1.003095 11.94405 1.473882 -1.711092 11.94405 1.454731 -1.707283 12.18405 1.490103 -1.721931 11.94405 1.473926 -1.711118 12.18405 1.673662 -1.75641 11.94405 1.500942 -1.738152 11.94405 1.490103 -1.721931 12.18405 0.7959536 -0.9776389 11.94405 0.7854093 -0.952183 11.94405 1.504748 -1.757286 11.94405 1.500917 -1.738108 12.18405 1.500942 -1.77642 11.94405 1.504751 -1.757304 12.18405 1.490103 -1.792641 11.94405 1.500924 -1.776369 12.18405 1.473882 -1.80348 11.94405 1.490109 -1.792647 12.18405 1.454748 -1.807286 11.94405 1.473831 -1.803462 12.18405 1.454766 -1.807289 12.18405 1.849852 -1.58022 11.94405 1.804534 -1.38044 11.94405 1.815372 -1.396661 11.94405 1.815372 -1.396661 12.18405 1.831593 -1.4075 11.94405 1.83155 -1.407474 12.18405 1.452977 -1.52924 11.94405 1.800728 -1.361306 11.94405 1.80456 -1.380484 12.18405 1.792388 -1.189829 11.94405 1.804534 -1.342172 11.94405 1.800725 -1.361289 12.18405 1.815372 -1.325951 11.94405 1.804552 -1.342224 12.18405 1.831593 -1.315112 11.94405 1.815367 -1.325946 12.18405 1.850728 -1.311306 11.94405 1.831645 -1.31513 12.18405 1.869862 -1.315112 11.94405 1.85071 -1.311303 12.18405 1.886083 -1.325951 11.94405 1.869905 -1.315138 12.18405 2.006825 -1.386711 11.94405 1.896921 -1.342172 11.94405 1.886083 -1.325951 12.18405 1.900728 -1.361306 11.94405 1.896896 -1.342128 12.18405 1.896921 -1.38044 11.94405 1.900731 -1.361324 12.18405 1.886083 -1.396661 11.94405 1.896904 -1.380389 12.18405 1.869862 -1.4075 11.94405 1.886088 -1.396667 12.18405 1.850728 -1.411306 11.94405 1.86981 -1.407482 12.18405 1.850746 -1.411309 12.18405 -1.507467 -0.9257496 11.94406 -1.735884 -1.315113 11.94405 -1.752105 -1.325951 11.94405 -1.752105 -1.325952 12.18405 -1.762944 -1.342173 11.94405 -1.762918 -1.342129 12.18405 -1.71675 -1.311307 11.94405 -1.735927 -1.315139 12.18405 -1.697616 -1.315113 11.94405 -1.716732 -1.311304 12.18405 -1.681394 -1.325952 11.94405 -1.697667 -1.315131 12.18405 -1.301636 -1.711093 11.94405 -1.670556 -1.342173 11.94405 -1.681389 -1.325946 12.18405 -1.285415 -1.721931 11.94405 -1.488705 -1.359536 11.94405 -1.32077 -1.707287 11.94405 -1.66675 -1.361307 11.94405 -1.670574 -1.342224 12.18405 -1.339904 -1.711093 11.94405 -1.670556 -1.380441 11.94405 -1.666747 -1.361289 12.18405 -1.356125 -1.721931 11.94405 -1.681394 -1.396662 11.94405 -1.670581 -1.380485 12.18405 -1.366964 -1.738152 11.94405 -1.697615 -1.407501 11.94405 -1.681394 -1.396662 12.18405 -1.37077 -1.757287 11.94405 -1.71675 -1.411307 11.94405 -1.697572 -1.407475 12.18405 -1.366964 -1.776421 11.94405 -1.735884 -1.407501 11.94405 -1.716768 -1.41131 12.18405 -1.356125 -1.792642 11.94405 -1.752105 -1.396662 11.94405 -1.735832 -1.407483 12.18405 -1.864755 -1.283038 11.94405 -1.762944 -1.380441 11.94405 -1.75211 -1.396667 12.18405 -1.274346 -1.924783 11.94405 -1.76675 -1.361307 11.94405 -1.762926 -1.38039 12.18405 -1.766753 -1.361325 12.18405 -1.356125 -1.721931 12.18405 -1.366938 -1.738109 12.18405 -1.339948 -1.711118 12.18405 -1.320752 -1.707283 12.18405 -1.301687 -1.711111 12.18405 -1.149293 -1.812084 11.94405 -1.274576 -1.738152 11.94405 -1.285409 -1.721926 12.18405 -1.27077 -1.757287 11.94405 -1.274594 -1.738204 12.18405 -1.242501 -1.905292 11.94405 -1.274576 -1.776421 11.94405 -1.270767 -1.757269 12.18405 -1.285415 -1.792642 11.94405 -1.274602 -1.776464 12.18405 -1.301636 -1.80348 11.94405 -1.285415 -1.792642 12.18405 -1.32077 -1.807287 11.94405 -1.301592 -1.803455 12.18405 -1.339904 -1.80348 11.94405 -1.320787 -1.80729 12.18405 -1.339852 -1.803463 12.18405 -1.35613 -1.792647 12.18405 -1.366946 -1.776369 12.18405 -1.370773 -1.757304 12.18405 1.096536 -0.641056 11.94405 -1.274591 1.829351 11.94407 -1.285415 1.845546 11.94407 -1.285415 1.845546 12.18407 -1.346176 1.966289 11.94407 -1.301611 1.856371 11.94407 -1.301593 1.856359 12.18407 1.588596 -1.008106 11.94405 -1.27078 1.810225 11.94407 -1.274602 1.829369 12.18407 -1.274583 1.791082 11.94407 -1.270767 1.810174 12.18407 -1.285428 1.774848 11.94407 -1.274594 1.791109 12.18407 -1.301662 1.764003 11.94407 -1.28541 1.774831 12.18407 0.4771106 -0.03654235 11.94406 -1.320804 1.760201 11.94407 -1.301688 1.764015 12.18407 0.5025666 -0.04708647 11.94406 0.4516549 -0.04708653 11.94406 -1.33993 1.764011 11.94407 -1.320754 1.760188 12.18407 -1.356126 1.774836 11.94407 -1.339948 1.764023 12.18407 -1.539685 1.809315 11.94407 -1.36695 1.791031 11.94407 -1.356126 1.774836 12.18407 0.4411107 -0.0725423 11.94406 0.4516549 -0.0979982 11.94406 -1.370761 1.810157 11.94407 -1.366939 1.791013 12.18407 -1.366959 1.8293 11.94407 -1.370773 1.810207 12.18407 -1.356114 1.845534 11.94407 -1.366947 1.829273 12.18407 -1.339879 1.856379 11.94407 -1.356131 1.845551 12.18407 -1.320737 1.860181 11.94407 -1.339853 1.856367 12.18407 -1.320787 1.860194 12.18407 -1.715875 1.633125 11.94407 -1.67057 1.433371 11.94407 -1.681395 1.449566 11.94407 -1.681395 1.449566 12.18407 -1.69759 1.460391 11.94407 -1.697572 1.460379 12.18407 -1.318999 1.582145 11.94407 -1.66676 1.414245 11.94407 -1.670582 1.433389 12.18407 -1.65841 1.242734 11.94407 -1.670562 1.395102 11.94407 -1.666747 1.414194 12.18407 -1.681407 1.378868 11.94407 -1.670574 1.395129 12.18407 -1.697641 1.368023 11.94407 -1.68139 1.37885 12.18407 -1.716784 1.364221 11.94407 -1.697668 1.368035 12.18407 -1.73591 1.368031 11.94407 -1.716734 1.364208 12.18407 -1.752105 1.378856 11.94407 -1.735928 1.368043 12.18407 -1.872848 1.439616 11.94407 -1.76293 1.395051 11.94407 -1.752105 1.378856 12.18407 -1.76674 1.414177 11.94407 -1.762919 1.395033 12.18407 -1.762938 1.43332 11.94407 -1.766753 1.414227 12.18407 -1.752093 1.449554 11.94407 -1.762926 1.433293 12.18407 -1.735859 1.460399 11.94407 -1.75211 1.449571 12.18407 -1.716717 1.464201 11.94407 -1.735832 1.460387 12.18407 -1.716766 1.464214 12.18407 1.641444 0.9786547 11.94406 1.869887 1.368032 11.94406 1.886082 1.378856 11.94406 1.886083 1.378856 12.18406 1.896907 1.395052 11.94406 1.896896 1.395034 12.18406 1.850761 1.364221 11.94406 1.869905 1.368044 12.18406 1.831618 1.368024 11.94406 1.850711 1.364209 12.18406 1.815384 1.378869 11.94406 1.831645 1.368035 12.18406 1.435638 1.764003 11.94406 1.804539 1.395103 11.94406 1.815367 1.378851 12.18406 1.419404 1.774848 11.94406 1.622682 1.41244 11.94406 1.454781 1.760201 11.94406 1.800737 1.414245 11.94406 1.804551 1.395129 12.18406 1.473907 1.764011 11.94406 1.804547 1.433371 11.94406 1.800724 1.414195 12.18406 1.490103 1.774836 11.94406 1.815372 1.449567 11.94406 1.804559 1.43339 12.18406 1.500927 1.791031 11.94406 1.831567 1.460391 11.94406 1.815372 1.449567 12.18406 1.504737 1.810158 11.94406 1.850694 1.464202 11.94406 1.831549 1.46038 12.18406 1.500935 1.8293 11.94406 1.869836 1.4604 11.94406 1.850743 1.464215 12.18406 1.49009 1.845534 11.94406 1.88607 1.449555 11.94406 1.86981 1.460388 12.18406 1.998733 1.335943 11.94406 1.896915 1.433321 11.94406 1.886088 1.449572 12.18406 1.408323 1.977688 11.94406 1.900717 1.414178 11.94406 1.896903 1.433294 12.18406 1.90073 1.414228 12.18406 1.490103 1.774836 12.18406 1.500916 1.791013 12.18406 1.473925 1.764023 12.18406 1.454731 1.760188 12.18406 1.435665 1.764015 12.18406 1.28327 1.864989 11.94406 1.408559 1.791083 11.94406 1.419387 1.774831 12.18406 1.404757 1.810225 11.94406 1.408571 1.791109 12.18406 1.376478 1.958197 11.94406 1.408567 1.829351 11.94406 1.404744 1.810175 12.18406 1.419392 1.845547 11.94406 1.408579 1.829369 12.18406 1.435587 1.856371 11.94406 1.419392 1.845547 12.18406 1.454714 1.860182 11.94406 1.435569 1.85636 12.18406 1.473856 1.856379 11.94406 1.454764 1.860194 12.18406 1.47383 1.856368 12.18406 1.490108 1.845552 12.18406 1.500924 1.829274 12.18406 1.50475 1.810208 12.18406 -0.01786398 0.02645248 11.94406 -1.054996 1.098562 11.94406 -1.021956 1.115397 11.94406 -1.021956 1.115397 12.18406 -1.005121 1.148437 11.94406 -1.005121 1.148437 12.18406 -1.091622 1.104363 11.94406 -1.054996 1.098562 12.18406 -1.117843 1.130584 11.94406 -1.091621 1.104363 12.18406 -1.31166 1.245029 11.94406 -1.123643 1.167209 11.94406 -1.117843 1.130584 12.18406 -1.146465 1.409611 11.94407 -1.106809 1.200249 11.94406 -1.123643 1.167209 12.18406 -1.073768 1.217084 11.94406 -1.106809 1.200249 12.18406 -1.037143 1.211283 11.94406 -1.073768 1.217084 12.18406 -1.010922 1.185062 11.94406 -1.037143 1.211283 12.18406 -1.010922 1.185062 12.18406 0.0669887 0.1113052 11.94406 1.707185 -0.8074263 11.94405 1.172515 -0.2900326 11.94405 1.240786 -0.2422478 11.94405 1.240786 -0.2422478 12.18405 1.288571 -0.1739768 11.94405 1.288571 -0.1739768 12.18405 1.091954 -0.3116298 11.94405 1.172515 -0.2900326 12.18405 1.009008 -0.3043607 11.94405 1.091954 -0.3116298 12.18405 0.9333828 -0.2691 11.94405 1.009008 -0.3043608 12.18405 0.8745225 -0.2102399 11.94405 0.9333828 -0.2691001 12.18405 -1.274346 1.977687 11.94407 0.8392618 -0.1346144 11.94405 0.8745225 -0.21024 12.18405 -1.311692 1.980602 11.94407 -0.8852134 1.600908 11.94407 0.8319928 -0.05166834 11.94406 0.8392618 -0.1346144 12.18405 -1.242502 1.958196 11.94407 -0.6784594 1.708685 11.94407 0.8535899 0.02889233 11.94406 0.8319928 -0.05166846 12.18406 0.9013746 0.09716331 11.94405 0.8535899 0.02889227 12.18406 0.9696457 0.1449481 11.94406 0.9013746 0.09716325 12.18406 -0.4597612 1.789443 11.94407 1.050206 0.1665453 11.94406 0.9696457 0.144948 12.18406 1.133152 0.1592763 11.94406 1.050206 0.1665452 12.18406 1.208778 0.1240156 11.94406 1.133152 0.1592762 12.18406 0.01174604 1.497371 11.94406 1.267638 0.06515544 11.94405 1.208778 0.1240155 12.18406 1.799452 -0.593362 11.94405 1.302899 -0.01047003 11.94405 1.267638 0.06515538 12.18405 1.863915 -0.3693467 11.94405 1.310168 -0.09341603 11.94405 1.302899 -0.01047009 12.18405 1.310168 -0.09341603 12.18405 0.6973456 -1.702203 11.94405 0.2674186 -1.195129 11.94405 0.3356896 -1.147344 11.94405 0.3356896 -1.147345 12.18405 0.8619466 -1.632958 11.94405 0.3834742 -1.079074 11.94405 0.3834742 -1.079074 12.18405 0.1868578 -1.216727 11.94405 0.2674186 -1.195129 12.18405 0.5269891 -1.75512 11.94405 0.1039119 -1.209457 11.94405 0.1868578 -1.216727 12.18405 0.02828633 -1.174197 11.94405 0.1039119 -1.209457 12.18405 -0.03057384 -1.115337 11.94405 0.02828633 -1.174197 12.18405 -1.665528 0.6461184 11.94406 -0.06583452 -1.039711 11.94405 -0.03057384 -1.115337 12.18405 -0.0731036 -0.9567652 11.94405 -0.06583452 -1.039711 12.18405 -0.05150645 -0.8762043 11.94405 -0.0731036 -0.9567653 12.18405 -1.573274 0.8602023 11.94406 -0.003721654 -0.8079333 11.94405 -0.05150645 -0.8762044 12.18405 0.06454926 -0.7601485 11.94405 -0.003721654 -0.8079335 12.18406 0.14511 -0.7385514 11.94405 0.06454926 -0.7601487 12.18406 0.228056 -0.7458205 11.94405 0.14511 -0.7385516 12.18406 0.3036815 -0.7810811 11.94405 0.228056 -0.7458206 12.18405 0.3625417 -0.8399413 11.94405 0.3036815 -0.7810811 12.18405 1.408324 -1.924782 11.94405 0.3978024 -0.9155668 11.94405 0.3625417 -0.8399413 12.18405 1.44567 -1.927697 11.94405 1.019191 -1.548003 11.94405 0.4050714 -0.9985128 11.94405 0.3978024 -0.9155669 12.18405 1.376479 -1.905291 11.94405 0.4050714 -0.9985128 12.18405 0.1518415 0.02645248 11.94406 0.06698876 0.1113052 12.18406 -0.01786398 0.02645242 12.18406 1.280443 -1.356706 11.94405 0.06698876 -0.05840027 11.94406 0.1518416 0.02645242 12.18406 1.445585 -1.192182 11.94405 0.06698882 -0.05840033 12.18406 1.66505 -0.1085421 11.94405 1.690506 -0.09799796 11.94405 1.690506 -0.09799802 12.18405 1.70105 -0.07254213 11.94405 1.70105 -0.07254213 12.18405 1.639594 -0.0979979 11.94405 1.66505 -0.1085422 12.18405 1.575754 -0.03478384 11.94405 1.62905 -0.07254201 11.94405 1.639594 -0.0979979 12.18405 1.609895 -0.01738774 11.94405 1.639594 -0.04708623 11.94405 1.62905 -0.07254207 12.18405 1.627292 0.01675385 11.94405 1.66505 -0.03654205 11.94405 1.639594 -0.04708629 12.18405 1.690506 -0.04708623 11.94405 1.66505 -0.03654205 12.18405 1.690506 -0.04708629 12.18405 1.621297 0.05460017 11.94405 1.899537 -0.1389737 11.94405 1.504818 0.03615164 11.94405 1.07108 0.4854273 11.94406 1.096536 0.4959715 11.94406 1.096536 0.4959715 12.18406 1.522214 0.07029336 11.94405 1.10708 0.5214273 11.94406 1.10708 0.5214273 12.18406 1.045624 0.4959716 11.94406 1.07108 0.4854273 12.18406 0.1108291 1.481678 11.94406 1.03508 0.5214275 11.94406 1.045624 0.4959715 12.18406 0.07668745 1.464282 11.94406 1.510812 -0.00169456 11.94405 1.045624 0.5468832 11.94406 1.03508 0.5214274 12.18406 0.1282252 1.51582 11.94406 1.07108 0.5574274 11.94406 1.045624 0.5468831 12.18406 1.096536 0.5468832 11.94406 1.07108 0.5574274 12.18406 1.096536 0.5468832 12.18406 0.1222308 1.553666 11.94406 1.556356 0.08768945 11.94405 1.07108 -0.7025119 11.94405 1.096536 -0.6919677 11.94405 1.096536 -0.6919677 12.18405 1.10708 -0.6665119 11.94405 1.10708 -0.666512 12.18405 1.045624 -0.6919677 11.94405 1.07108 -0.7025119 12.18405 0.4771107 -0.1085423 11.94406 1.03508 -0.6665118 11.94405 1.045625 -0.6919677 12.18405 0.5025666 -0.0979982 11.94406 1.045624 -0.641056 11.94405 1.03508 -0.6665118 12.18405 0.5131107 -0.07254236 11.94406 1.07108 -0.6305118 11.94405 1.045625 -0.641056 12.18405 1.07108 -0.6305118 12.18405 1.096536 -0.641056 12.18405 0.5025666 -0.0979982 12.18406 0.5131107 -0.07254236 12.18406 0.4771107 -0.1085424 12.18406 0.4516549 -0.0979982 12.18406 0.4411107 -0.07254236 12.18406 0.4516549 -0.04708653 12.18406 0.4771106 -0.03654235 12.18406 0.5025666 -0.04708653 12.18406 0.7854094 -1.003095 12.18405 0.7959536 -0.9776389 12.18405 0.7599536 -1.013639 12.18405 0.1659838 -0.4196694 11.94405 0.7239535 -0.9776388 11.94405 0.7344977 -1.003095 12.18405 0.1914396 -0.4091252 11.94405 0.7344977 -0.952183 11.94405 0.7239535 -0.9776389 12.18405 0.2019838 -0.3836694 11.94405 0.7599535 -0.9416388 11.94405 0.7344977 -0.9521831 12.18405 0.1914396 -0.3582136 11.94406 0.7599535 -0.9416389 12.18405 0.7854093 -0.952183 12.18405 0.1914399 -1.597065 12.18405 0.2019841 -1.571609 12.18405 0.165984 -1.607609 12.18405 0.129984 -1.571609 11.94405 0.1405282 -1.597065 12.18405 0.1108297 -1.516454 11.94405 0.1405281 -1.546153 11.94405 0.129984 -1.571609 12.18405 0.1282257 -1.482313 11.94405 0.165984 -1.535609 11.94405 0.1405281 -1.546153 12.18405 0.1914398 -1.546153 11.94405 0.165984 -1.535609 12.18405 0.1914398 -1.546153 12.18405 0.4746018 -1.798536 11.94405 0.005752265 -1.462915 11.94405 -0.4279857 -1.013639 11.94405 -0.4025299 -1.003095 11.94405 -0.4025299 -1.003095 12.18406 0.02314841 -1.428773 11.94405 -0.3919857 -0.9776391 11.94405 -0.3919857 -0.9776392 12.18406 -0.4534415 -1.003095 11.94405 -0.4279857 -1.013639 12.18406 -1.388237 -0.01738834 11.94406 -0.4639858 -0.9776391 11.94405 -0.4534415 -1.003095 12.18406 -1.422379 -0.03478443 11.94406 -0.4534416 -0.9521832 11.94405 -0.4639858 -0.9776391 12.18406 -1.370841 0.01675331 11.94406 -0.4279857 -0.9416391 11.94405 -0.4534416 -0.9521833 12.18406 -0.4025299 -0.9521833 11.94405 -0.4279857 -0.9416391 12.18406 -0.4025299 -0.9521834 12.18406 0.05729001 -1.411377 11.94405 -1.376835 0.05459958 11.94406 0.1914396 -0.4091252 12.18406 0.2019838 -0.3836694 12.18406 0.1659838 -0.4196694 12.18406 0.1299838 -0.3836694 11.94405 0.140528 -0.4091253 12.18406 0.1405279 -0.3582136 11.94406 0.1299838 -0.3836694 12.18406 0.1659838 -0.3476694 11.94406 0.140528 -0.3582136 12.18406 0.1659838 -0.3476694 12.18406 0.1914396 -0.3582136 12.18406 0.1108291 1.481678 12.18406 0.1282252 1.51582 12.18406 0.03884106 1.470276 11.94406 0.07668745 1.464282 12.18406 0.03884106 1.470276 12.18406 -0.2326272 1.841894 11.94407 0.005751729 1.535218 11.94406 0.01174604 1.497371 12.18406 0.02314782 1.569359 11.94406 0.005751788 1.535218 12.18406 0.05728954 1.586755 11.94406 0.02314788 1.569359 12.18406 -6.9815e-4 1.865207 11.94407 0.0951358 1.580761 11.94406 0.05728954 1.586755 12.18406 0.09513586 1.580761 12.18406 0.1222309 1.553666 12.18406 1.594202 0.08169519 11.94405 1.609895 -0.0173878 12.18405 1.627292 0.01675385 12.18405 1.537907 -0.02878957 11.94405 1.575754 -0.03478389 12.18405 1.537908 -0.02878963 12.18405 1.510812 -0.001694619 12.18405 1.504818 0.03615164 12.18405 1.522215 0.07029336 12.18405 1.556356 0.08768945 12.18405 1.594202 0.08169519 12.18405 1.621297 0.05460011 12.18405 0.1108297 -1.516454 12.18405 0.1282257 -1.482313 12.18405 0.07668799 -1.53385 12.18405 0.03884166 -1.527856 12.18405 0.01174664 -1.500761 12.18405 -1.460225 -0.02879017 11.94406 0.005752265 -1.462915 12.18405 0.02314841 -1.428773 12.18405 0.0951364 -1.417371 11.94405 0.05729007 -1.411377 12.18405 -1.729971 0.4220986 11.94406 0.1222314 -1.444466 11.94405 0.09513646 -1.417371 12.18405 0.1222315 -1.444466 12.18405 -1.388237 -0.0173884 12.18406 -1.370841 0.01675325 12.18406 -1.422379 -0.03478449 12.18406 -1.48732 -0.001695156 11.94406 -1.460225 -0.02879023 12.18406 -1.493314 0.03615111 11.94406 -1.48732 -0.001695215 12.18406 -1.765573 0.1917352 11.94406 -1.475918 0.07029277 11.94406 -1.493314 0.03615105 12.18406 -1.441777 0.08768886 11.94406 -1.475918 0.07029277 12.18406 -1.40393 0.0816946 11.94406 -1.441776 0.08768886 12.18406 -1.40393 0.0816946 12.18406 -1.376835 0.05459958 12.18406 0.4669891 -2.053547 12.18405 0.296989 -2.053547 12.18405 0.4669891 -1.832579 12.18405 0.4959301 -1.771001 11.94405 0.4746018 -1.798536 12.18405 0.4959301 -1.771001 12.18405 0.5269891 -1.75512 12.18405 0.6973456 -1.702203 12.18405 0.8619466 -1.632958 12.18405 1.019191 -1.548003 12.18405 1.376479 -1.905291 12.18405 1.408364 -1.924818 12.18405 1.445624 -1.927726 12.18405 1.480153 -1.913384 12.18405 1.673662 -1.75641 12.18405 1.849852 -1.58022 12.18405 1.828202 -1.169173 11.94405 2.021139 -1.352228 11.94405 2.006825 -1.386711 12.18405 1.869711 -1.169173 11.94405 2.018224 -1.314882 11.94405 2.021168 -1.352182 12.18405 1.905525 -1.189829 11.94405 1.998733 -1.283037 11.94405 2.01826 -1.314922 12.18405 1.998733 -1.283037 12.18405 1.905525 -1.189829 12.18405 1.869654 -1.169124 12.18405 1.828259 -1.169124 12.18405 1.792388 -1.189829 12.18405 1.452977 -1.529241 12.18405 1.280443 -1.356706 12.18405 1.445585 -1.192182 12.18405 1.588596 -1.008106 12.18405 1.707185 -0.8074264 12.18405 1.799452 -0.593362 12.18405 1.863915 -0.3693468 12.18405 1.905746 0.09406149 11.94405 1.899537 -0.1389738 12.18405 0.2323094 1.85901 11.94407 1.882439 0.3260204 11.94405 1.905746 0.09406143 12.18406 0.4626628 1.823406 11.94406 1.829985 0.5531803 11.94406 1.882439 0.3260203 12.18406 0.6866714 1.758963 11.94406 1.749227 0.771888 11.94406 1.829985 0.5531803 12.18406 0.9007454 1.666711 11.94406 1.749227 0.771888 12.18406 1.641444 0.9786546 12.18406 1.450148 1.239906 11.94406 1.101452 1.548124 11.94406 2.018223 1.367787 11.94406 1.998733 1.335943 12.18406 1.445669 1.980603 11.94406 2.021138 1.405133 11.94406 2.018259 1.367828 12.18406 1.480152 1.966289 11.94406 2.006825 1.439617 11.94406 2.021167 1.405088 12.18406 1.673661 1.809316 11.94406 1.849851 1.633126 11.94406 2.006825 1.439617 12.18406 1.849852 1.633126 12.18406 1.673661 1.809316 12.18406 1.480152 1.966289 12.18406 1.445623 1.980632 12.18406 1.408364 1.977723 12.18406 1.376479 1.958196 12.18406 1.262571 1.829092 11.94406 1.28327 1.864989 12.18406 1.262571 1.787748 11.94406 1.262565 1.829118 12.18406 1.28327 1.751852 11.94406 1.262565 1.787722 12.18406 1.28327 1.751852 12.18406 1.622682 1.41244 12.18406 1.28556 1.405105 11.94406 1.450148 1.239906 12.18406 1.28556 1.405105 12.18406 1.101453 1.548124 12.18406 0.9007454 1.666711 12.18406 0.6866714 1.758963 12.18406 0.4626628 1.823406 12.18406 0.2323095 1.85901 12.18407 -6.98134e-4 1.865207 12.18407 -0.2326272 1.841894 12.18407 -0.4597612 1.789443 12.18407 -0.6784594 1.708685 12.18407 -0.8852134 1.600908 12.18407 -1.242502 1.958196 12.18407 -1.274387 1.977723 12.18407 -1.311646 1.980631 12.18407 -1.346176 1.966289 12.18407 -1.539684 1.809315 12.18407 -1.715875 1.633125 12.18407 -1.694307 1.222035 11.94407 -1.887161 1.405133 11.94407 -1.872848 1.439616 12.18407 -1.735651 1.222035 11.94407 -1.884246 1.367787 11.94407 -1.88719 1.405087 12.18407 -1.771548 1.242734 11.94407 -1.864755 1.335942 11.94407 -1.884282 1.367827 12.18407 -1.864755 1.335942 12.18407 -1.771547 1.242734 12.18407 -1.735676 1.222029 12.18407 -1.694281 1.222029 12.18407 -1.65841 1.242734 12.18407 -1.318999 1.582145 12.18407 -1.146465 1.409611 12.18407 -1.311659 1.245029 12.18406 -1.454682 1.060916 12.18406 -1.573274 0.8602023 12.18406 -1.665528 0.6461184 12.18406 -1.729971 0.4220986 12.18406 -1.771764 -0.04127871 11.94406 -1.765573 0.1917352 12.18406 -1.771764 -0.04127871 12.18406 -0.3930107 -1.75512 11.94405 -1.69599 -0.5003358 11.94406 -1.748446 -0.2732084 12.18406 -0.60206 -1.687599 11.94405 -1.615234 -0.7190187 11.94406 -1.69599 -0.5003358 12.18406 -0.8018169 -1.595514 11.94405 -1.615233 -0.7190188 12.18406 -1.507467 -0.9257497 12.18406 -1.31617 -1.187001 11.94405 -0.9891707 -1.480241 11.94405 -1.884246 -1.314883 11.94405 -1.864755 -1.283038 12.18405 -1.311691 -1.927698 11.94405 -1.887161 -1.352229 11.94405 -1.884282 -1.314923 12.18405 -1.346175 -1.913384 11.94405 -1.872848 -1.386712 11.94405 -1.88719 -1.352183 12.18405 -1.539684 -1.756411 11.94405 -1.715874 -1.580221 11.94405 -1.872848 -1.386712 12.18405 -1.715874 -1.580221 12.18405 -1.539684 -1.756411 12.18405 -1.346175 -1.913384 12.18405 -1.311646 -1.927727 12.18405 -1.274386 -1.924818 12.18405 -1.242501 -1.905292 12.18405 -1.128593 -1.776187 11.94405 -1.149293 -1.812084 12.18405 -1.128593 -1.734843 11.94405 -1.128587 -1.776213 12.18405 -1.149293 -1.698947 11.94405 -1.128587 -1.734817 12.18405 -1.149293 -1.698947 12.18405 -1.488704 -1.359536 12.18405 -1.161435 -1.343429 11.94405 -1.31617 -1.187001 12.18405 -1.161435 -1.343429 12.18405 -0.9891707 -1.480241 12.18405 -0.8018169 -1.595514 12.18405 -0.60206 -1.687599 12.18405 -0.3930107 -1.75512 12.18405 -0.3619518 -1.771001 12.18405 -0.3406235 -1.798536 12.18405 -0.3330109 -1.832579 12.18405 -0.3330109 -2.053547 12.18405 -0.1630107 -2.053547 12.18405 -0.1630108 -1.813547 12.18405 0.2969891 -1.813547 12.18405 0.8589472 0.5921404 -1.515941 0.861261 0.1929081 -1.515942 0.830663 0.1678764 -1.515942 0.8306631 0.1678762 -0.3159423 0.6326731 0.3658663 -1.515941 0.8056313 0.1372784 -1.515942 0.8056315 0.1372782 -0.3159428 0.8954674 0.2111702 -1.515942 0.8612611 0.1929079 -0.3159423 0.9331513 0.2226202 -1.515942 0.8954675 0.21117 -0.3159422 0.9720844 0.2264098 -1.515942 0.9331514 0.22262 -0.3159423 1.011017 0.2226203 -1.515942 0.9720845 0.2264096 -0.3159423 1.048701 0.2111702 -1.515942 1.011018 0.22262 -0.3159424 1.083125 0.1927499 -1.515943 1.048701 0.21117 -0.3159428 1.113506 0.1678765 -1.515943 1.083125 0.1927496 -0.315943 1.138379 0.1374963 -1.515943 1.113506 0.1678763 -0.3159431 1.47476 -0.3922511 -1.515946 1.156799 0.1030722 -1.515943 1.138379 0.1374961 -0.3159433 1.440125 -0.3404077 -1.515946 1.168249 0.06538826 -1.515943 1.1568 0.1030719 -0.3159434 1.172039 0.02645516 -1.515943 1.168249 0.06538802 -0.3159436 1.168249 -0.01247793 -1.515944 1.172039 0.02645492 -0.3159438 1.156799 -0.05016177 -1.515944 1.168249 -0.01247811 -0.3159439 1.388281 -0.3057727 -1.515946 1.138537 -0.08436816 -1.515944 1.1568 -0.05016201 -0.3159441 1.326987 -0.2935811 -1.515945 1.113506 -0.1149661 -1.515944 1.138537 -0.08436834 -0.3159441 1.265694 -0.3057727 -1.515945 1.082908 -0.1399978 -1.515944 1.113506 -0.1149663 -0.3159442 1.213851 -0.3404077 -1.515945 1.048701 -0.1582599 -1.515944 1.082908 -0.139998 -0.3159443 1.011017 -0.1697099 -1.515944 1.048701 -0.1582601 -0.3159443 1.179216 -0.3922511 -1.515946 0.9720844 -0.1734995 -1.515944 1.011018 -0.1697102 -0.3159443 0.9331513 -0.1697099 -1.515944 0.9720845 -0.1734998 -0.3159443 1.167024 -0.4535449 -1.515946 0.8954674 -0.1582599 -1.515944 0.9331514 -0.1697101 -0.3159441 0.8610432 -0.1398396 -1.515944 0.8954675 -0.1582602 -0.3159441 0.830663 -0.1149662 -1.515944 0.8610433 -0.1398398 -0.3159439 -0.04405349 0.7652568 -1.515938 0.8057897 -0.08458602 -1.515944 0.8306631 -0.1149664 -0.3159438 -0.07443362 0.7901301 -1.515938 -0.009629309 0.7468365 -1.515938 0.7873693 -0.05016183 -1.515944 0.8057898 -0.08458626 -0.3159436 0.02805453 0.7353864 -1.515938 0.7759192 -0.01247793 -1.515943 0.7873694 -0.05016207 -0.3159435 0.06698769 0.7315968 -1.515938 0.7721297 0.02645504 -1.515943 0.7759193 -0.01247817 -0.3159433 0.1059207 0.7353864 -1.515938 0.7759192 0.06538814 -1.515943 0.7721298 0.0264548 -0.3159431 0.519536 0.3658663 -1.515941 0.7873693 0.1030721 -1.515943 0.7759193 0.06538796 -0.315943 0.1436046 0.7468366 -1.515938 0.4063989 0.4790033 -1.51594 0.5968596 0.34521 -1.515941 0.7873694 0.1030718 -0.3159428 0.5553495 0.34521 -1.515941 -0.2530486 1.286455 -1.515936 -0.04383575 1.098004 -1.515936 -0.07443374 1.072973 -1.515937 -0.07443368 1.072973 -0.3159365 -0.2652404 1.225161 -1.515936 -0.09946542 1.042375 -1.515937 -0.09946537 1.042375 -0.3159366 -0.2998754 1.399592 -1.515935 -0.009629368 1.116267 -1.515936 -0.04383569 1.098004 -0.3159365 -0.2652404 1.347748 -1.515935 0.4338504 1.399592 -1.515936 0.02805447 1.127717 -1.515936 -0.009629309 1.116266 -0.3159365 0.4856938 1.434227 -1.515936 0.06698757 1.131506 -1.515937 0.02805453 1.127716 -0.3159365 0.1059207 1.127717 -1.515937 0.06698763 1.131506 -0.3159365 0.1436045 1.116267 -1.515937 0.1059207 1.127716 -0.3159366 0.1780287 1.097846 -1.515937 0.1436046 1.116266 -0.3159367 0.2084089 1.072973 -1.515937 0.1780288 1.097846 -0.3159372 0.632673 0.8184145 -1.515939 0.2332823 1.042593 -1.515937 0.208409 1.072973 -0.3159373 0.3992154 1.347748 -1.515936 0.3870238 1.286455 -1.515936 0.3992154 1.225161 -1.515937 0.2517027 1.008169 -1.515937 0.2332824 1.042593 -0.3159375 0.4063989 0.5921404 -1.51594 0.2631527 0.9704847 -1.515938 0.2517027 1.008168 -0.3159377 0.2669423 0.9315516 -1.515938 0.2631528 0.9704844 -0.3159378 0.2631527 0.8926185 -1.515938 0.2669424 0.9315513 -0.3159381 0.2517027 0.8549346 -1.515938 0.2631527 0.8926182 -0.3159382 0.2334406 0.8207283 -1.515938 0.2517028 0.8549343 -0.3159383 0.2084089 0.7901302 -1.515938 0.2334406 0.820728 -0.3159384 0.3857426 0.5563269 -1.51594 0.1778109 0.7650986 -1.515938 0.208409 0.79013 -0.3159385 0.3857426 0.5148168 -1.51594 0.177811 0.7650984 -0.3159385 0.1436047 0.7468363 -0.3159385 0.1059207 0.7353862 -0.3159385 0.06698775 0.7315967 -0.3159385 0.02805465 0.7353862 -0.3159384 -0.009629189 0.7468362 -0.3159383 -0.04405337 0.7652565 -0.3159382 -0.4130123 1.126491 -1.515936 -0.09930706 0.8205104 -1.515938 -0.07443356 0.79013 -0.315938 -0.3517188 1.138683 -1.515936 -0.1177274 0.8549345 -1.515937 -0.099307 0.8205102 -0.3159379 -0.1291775 0.8926184 -1.515937 -0.1177273 0.8549343 -0.3159377 -0.1329671 0.9315515 -1.515937 -0.1291773 0.8926182 -0.3159375 -0.2998754 1.173318 -1.515936 -0.1291775 0.9704846 -1.515937 -0.1329669 0.9315513 -0.3159374 -0.1177275 1.008169 -1.515937 -0.1291774 0.9704844 -0.3159372 -0.1177274 1.008168 -0.3159368 -1.131718 0.3586825 -1.515938 -0.9489322 0.1929077 -1.515939 -0.9795301 0.1678761 -1.515939 -0.97953 0.1678758 -0.3159394 -1.193012 0.3464909 -1.515938 -1.004562 0.137278 -1.515939 -1.004562 0.1372779 -0.3159394 -1.079875 0.3933175 -1.515938 -0.9147258 0.2111698 -1.515939 -0.9489321 0.1929075 -0.315939 -0.877042 0.2226198 -1.515939 -0.9147257 0.2111696 -0.3159389 -1.04524 0.445161 -1.515938 -0.8381088 0.2264094 -1.515939 -0.8770419 0.2226196 -0.315939 -0.7991757 0.2226198 -1.515939 -0.8381087 0.2264093 -0.315939 -1.033049 0.5064547 -1.515937 -0.7614917 0.2111698 -1.515939 -0.7991756 0.2226196 -0.3159395 -0.7270676 0.1927495 -1.515939 -0.7614916 0.2111697 -0.3159396 -0.6966874 0.1678761 -1.515939 -0.7270675 0.1927493 -0.3159397 0.1780291 -0.7123469 -1.515945 -0.671814 0.1374959 -1.51594 -0.6966872 0.1678759 -0.3159399 0.2084093 -0.7372203 -1.515945 0.1436049 -0.6939265 -1.515945 -0.6533938 0.1030718 -1.51594 -0.6718139 0.1374957 -0.31594 0.105921 -0.6824765 -1.515945 -0.6419436 0.06538784 -1.51594 -0.6533936 0.1030716 -0.3159402 0.06698793 -0.6786869 -1.515945 -0.6381541 0.0264548 -1.51594 -0.6419435 0.0653876 -0.3159403 0.02805489 -0.6824765 -1.515945 -0.6419436 -0.01247823 -1.515941 -0.638154 0.02645456 -0.3159405 -0.3855605 -0.3129564 -1.515942 -0.6533937 -0.05016213 -1.515941 -0.6419435 -0.01247847 -0.3159406 -0.009629011 -0.6939265 -1.515945 -0.2724233 -0.4260934 -1.515943 -0.4628839 -0.2923001 -1.515942 -0.671656 -0.08436852 -1.515941 -0.6533936 -0.05016237 -0.3159408 -0.4213739 -0.2923001 -1.515942 -0.4986975 -0.3129564 -1.515942 -0.6966874 -0.1149665 -1.515941 -0.6716557 -0.0843687 -0.3159409 -0.7249716 -0.5392305 -1.515943 -0.7272855 -0.1399981 -1.515941 -0.6966872 -0.1149668 -0.3159409 -0.7614917 -0.1582602 -1.515941 -0.7272854 -0.1399984 -0.315941 -0.7991757 -0.1697103 -1.515941 -0.7614916 -0.1582605 -0.315941 -0.8381088 -0.1734999 -1.515941 -0.7991756 -0.1697105 -0.315941 -0.877042 -0.1697103 -1.515941 -0.8381087 -0.1735001 -0.3159409 -0.9147257 -0.1582603 -1.515941 -0.8770419 -0.1697105 -0.3159409 -0.9491499 -0.13984 -1.515941 -0.9147256 -0.1582605 -0.3159407 -0.9795301 -0.1149666 -1.515941 -0.9491497 -0.1398402 -0.3159406 -1.004403 -0.08458638 -1.51594 -0.97953 -0.1149668 -0.3159405 -1.340784 0.4451609 -1.515937 -1.022824 -0.05016225 -1.51594 -1.004403 -0.08458662 -0.3159403 -1.306149 0.3933175 -1.515937 -1.034274 -0.01247835 -1.51594 -1.022824 -0.05016243 -0.3159402 -1.038063 0.02645474 -1.51594 -1.034274 -0.01247853 -0.31594 -1.034274 0.06538784 -1.515939 -1.038063 0.0264545 -0.3159399 -1.022824 0.1030717 -1.515939 -1.034274 0.0653876 -0.3159397 -1.254306 0.3586825 -1.515937 -1.022824 0.1030715 -0.3159396 -0.251767 -0.503417 -1.515944 -0.0438354 -0.7121886 -1.515945 -0.07443338 -0.7372203 -1.515945 -0.07443332 -0.7372205 -0.3159452 -0.2724232 -0.5392305 -1.515944 -0.09946507 -0.7678183 -1.515945 -0.09946489 -0.7678185 -0.3159452 -0.251767 -0.4619069 -1.515944 -0.04383522 -0.7121889 -0.3159451 -0.009628951 -0.6939268 -0.315945 0.02805495 -0.6824766 -0.3159451 0.06698799 -0.6786872 -0.3159452 0.1059211 -0.6824766 -0.3159452 0.143605 -0.6939267 -0.3159453 0.1780291 -0.712347 -0.3159455 0.546988 -1.073581 -1.515947 0.2332826 -0.7676005 -1.515945 0.2084093 -0.7372205 -0.3159456 0.4856944 -1.085773 -1.515948 0.251703 -0.8020247 -1.515946 0.2332828 -0.7676007 -0.3159458 0.263153 -0.8397085 -1.515946 0.2517031 -0.8020249 -0.3159459 0.2669426 -0.8786415 -1.515946 0.2631531 -0.8397087 -0.3159461 0.433851 -1.120408 -1.515948 0.2631531 -0.9175746 -1.515946 0.2669427 -0.8786418 -0.3159462 0.2517031 -0.9552586 -1.515946 0.2631532 -0.917575 -0.3159464 0.3992159 -1.172251 -1.515948 0.2334409 -0.9894649 -1.515947 0.2517032 -0.9552588 -0.3159465 0.2084093 -1.020063 -1.515947 0.233441 -0.9894652 -0.3159466 0.3870242 -1.233545 -1.515948 0.1778113 -1.045095 -1.515947 0.2084094 -1.020063 -0.3159467 0.433851 -1.346682 -1.515948 0.143605 -1.063357 -1.515947 0.1778114 -1.045095 -0.3159468 0.3992159 -1.294839 -1.515948 -0.2998748 -1.346682 -1.515947 0.1059211 -1.074807 -1.515947 0.1436051 -1.063357 -0.3159468 -0.3517181 -1.381317 -1.515947 0.06698799 -1.078596 -1.515947 0.1059212 -1.074807 -0.3159468 0.02805489 -1.074807 -1.515947 0.06698805 -1.078597 -0.3159467 -0.009628951 -1.063357 -1.515947 0.02805495 -1.074807 -0.3159466 -0.04405307 -1.044936 -1.515946 -0.009628832 -1.063357 -0.3159465 -0.07443326 -1.020063 -1.515946 -0.04405301 -1.044937 -0.3159464 -0.4986975 -0.7655047 -1.515944 -0.0993067 -0.9896827 -1.515946 -0.0744332 -1.020063 -0.3159462 -0.2530481 -1.233545 -1.515947 -0.2652398 -1.172251 -1.515947 -0.2652398 -1.294839 -1.515947 -0.1177271 -0.9552586 -1.515946 -0.09930664 -0.9896829 -0.3159461 -0.1291771 -0.9175747 -1.515946 -0.117727 -0.9552589 -0.3159459 -0.1329667 -0.8786416 -1.515946 -0.129177 -0.917575 -0.3159458 -0.1291771 -0.8397085 -1.515945 -0.1329666 -0.8786418 -0.3159456 -0.1177271 -0.8020247 -1.515945 -0.129177 -0.8397087 -0.3159455 -0.1177271 -0.8020249 -0.3159453 0.4338505 1.399592 -0.3159361 0.3992155 1.347748 -0.3159362 0.730175 1.566455 -1.515936 0.5469875 1.446419 -1.515936 0.4856939 1.434227 -0.315936 0.6082811 1.434227 -1.515936 0.5469877 1.446418 -0.3159361 0.6601245 1.399592 -1.515936 0.6082813 1.434227 -0.3159362 1.388281 0.6542273 -1.515941 0.6947596 1.347749 -1.515937 0.6601247 1.399592 -0.3159365 1.440124 0.6195923 -1.515942 1.326987 0.6664189 -1.515941 0.7069513 1.286455 -1.515937 0.6947597 1.347748 -0.3159367 1.265694 0.6542271 -1.515941 0.6947596 1.225161 -1.515937 0.7069514 1.286455 -0.3159369 1.21385 0.6195922 -1.515941 0.6601246 1.173318 -1.515937 0.6947597 1.225161 -0.3159376 1.179215 0.5677487 -1.515941 0.6082812 1.138683 -1.515937 0.6601247 1.173318 -0.3159377 1.167024 0.5064551 -1.515941 0.5469876 1.126491 -1.515937 0.6082813 1.138683 -0.3159378 1.179215 0.4451615 -1.515942 0.4856939 1.138683 -1.515937 0.5469877 1.126491 -0.3159377 1.21385 0.3933181 -1.515942 0.4338504 1.173318 -1.515937 0.4856939 1.138683 -0.3159375 0.4338505 1.173318 -0.3159373 0.8589472 0.7052775 -1.51594 0.6684864 0.8390709 -1.515939 0.7099965 0.8390709 -1.515939 0.74581 0.8184145 -1.515939 0.3992155 1.225161 -0.3159367 0.3870238 1.286455 -0.3159365 -1.420757 2.375447 -1.515928 -0.4743061 1.434227 -1.515934 -0.5261495 1.399592 -1.515934 -0.5261494 1.399591 -0.3159345 -1.565614 2.435449 -1.515928 -0.5607845 1.347748 -1.515934 -0.5607844 1.347748 -0.3159347 -0.5962001 1.566455 -1.515933 -0.4130125 1.446419 -1.515934 -0.4743061 1.434226 -0.3159345 -0.9913473 1.961602 -1.515931 -0.3517188 1.434227 -1.515935 -0.4130124 1.446418 -0.3159345 -0.3517187 1.434226 -0.3159347 -0.2998753 1.399591 -0.3159349 -0.2652403 1.347748 -0.3159351 -0.2530485 1.286455 -0.3159354 -0.2652403 1.225161 -0.3159356 -0.2998753 1.173317 -0.3159358 -0.3517187 1.138682 -0.3159358 1.179216 -0.5148385 -1.515946 -0.4743061 1.138683 -1.515936 -0.4130123 1.126491 -0.3159358 1.213851 -0.5666819 -1.515947 -0.5261495 1.173318 -1.515935 -0.474306 1.138682 -0.3159356 -2.0498 2.774561 -1.515925 -0.5607845 1.225161 -1.515935 -0.5261493 1.173317 -0.3159354 2.828725 -2.19386 -1.515957 -2.153328 2.788191 -1.515925 -0.5729762 1.286455 -1.515935 -0.5607843 1.225161 -0.3159351 -1.953328 2.734601 -1.515925 -0.5729761 1.286455 -0.3159349 -1.699278 2.517301 -1.515927 -1.818799 2.619347 -1.515926 -1.870485 2.671033 -1.515926 0.433851 -1.120408 -0.3159475 0.399216 -1.172251 -0.315948 0.4856944 -1.085773 -0.3159474 -1.04524 0.5677483 -1.515937 0.6082816 -1.085773 -1.515948 0.5469881 -1.073581 -0.3159475 -1.079875 0.6195917 -1.515937 0.660125 -1.120408 -1.515948 0.6082817 -1.085773 -0.315948 2.183776 -2.721652 -1.515958 0.69476 -1.172251 -1.515948 0.6601251 -1.120408 -0.3159482 -2.694749 2.246769 -1.515926 2.287303 -2.735281 -1.515958 0.7069518 -1.233545 -1.515949 0.6947602 -1.172251 -0.3159485 2.087303 -2.681691 -1.515958 0.6947601 -1.294838 -1.515949 0.7069519 -1.233545 -0.3159487 1.69959 -2.382539 -1.515956 0.6601251 -1.346682 -1.515949 0.6947602 -1.294839 -0.315949 1.833253 -2.464391 -1.515957 1.952775 -2.566438 -1.515957 2.004461 -2.618124 -1.515957 1.554732 -2.322537 -1.515955 0.6082817 -1.381317 -1.515949 0.6601252 -1.346682 -0.3159491 0.7301757 -1.513545 -1.51595 0.5469881 -1.393509 -1.515949 0.6082818 -1.381317 -0.3159492 1.125323 -1.908692 -1.515952 -0.5961995 -1.513545 -1.515947 0.4856944 -1.381317 -1.515949 0.5469882 -1.393509 -0.3159491 0.4856945 -1.381317 -0.315949 0.433851 -1.346682 -0.3159487 0.399216 -1.294839 -0.3159485 0.3870243 -1.233545 -0.3159482 -1.04524 -0.5148389 -1.515942 -0.4743055 -1.085773 -1.515946 -0.5261491 -1.120408 -1.515946 -0.5261489 -1.120408 -0.3159459 -1.079875 -0.5666823 -1.515942 -0.5607839 -1.172251 -1.515946 -0.5607838 -1.172252 -0.3159461 -1.033048 -0.4535452 -1.515942 -0.413012 -1.073581 -1.515946 -0.4743055 -1.085773 -0.3159459 -1.04524 -0.3922516 -1.515941 -0.3517182 -1.085773 -1.515946 -0.413012 -1.073581 -0.3159459 -1.079875 -0.3404082 -1.515941 -0.2998748 -1.120408 -1.515946 -0.3517181 -1.085773 -0.3159461 -0.2998747 -1.120408 -0.3159463 -0.7249716 -0.6523676 -1.515943 -0.6118345 -0.7655047 -1.515944 -0.5345109 -0.786161 -1.515944 -0.576021 -0.786161 -1.515944 -0.2652397 -1.172252 -0.3159465 -0.2530481 -1.233545 -0.3159468 -0.2652397 -1.294839 -0.315947 -0.2998747 -1.346682 -0.3159472 -0.4130119 -1.393509 -1.515947 -0.3517181 -1.381317 -0.3159472 -0.4743055 -1.381317 -1.515947 -0.4130118 -1.393509 -0.3159472 -0.5261489 -1.346682 -1.515947 -0.4743054 -1.381317 -0.315947 -1.254306 -0.6013174 -1.515942 -0.5607839 -1.294839 -1.515947 -0.5261487 -1.346682 -0.3159468 -1.306149 -0.5666823 -1.515942 -1.193012 -0.6135089 -1.515942 -0.5729757 -1.233545 -1.515946 -0.5607838 -1.294839 -0.3159465 -1.131718 -0.6013173 -1.515942 -0.5729756 -1.233545 -0.3159463 1.21385 0.619592 -0.3159412 1.179215 0.5677486 -0.3159413 1.265694 0.6542269 -0.3159411 1.326987 0.6664186 -0.3159412 1.388281 0.654227 -0.3159413 1.606987 0.6896429 -1.515941 1.47476 0.5677489 -1.515942 1.440125 0.619592 -0.3159415 1.486951 0.5064553 -1.515942 1.47476 0.5677486 -0.3159418 1.606988 -0.6367322 -1.515948 1.47476 0.4451615 -1.515942 1.486951 0.506455 -0.3159421 1.440125 0.3933181 -1.515942 1.47476 0.4451613 -0.3159422 1.388281 0.3586831 -1.515942 1.440125 0.3933179 -0.3159424 1.326987 0.3464913 -1.515942 1.388281 0.3586829 -0.3159425 1.265694 0.3586831 -1.515942 1.326988 0.3464911 -0.3159424 1.265694 0.3586829 -0.3159423 1.213851 0.3933179 -0.3159421 0.8796034 0.669464 -1.51594 1.179216 0.4451612 -0.3159418 1.167024 0.5064549 -0.3159415 1.213851 -0.3404079 -0.3159457 1.179216 -0.3922514 -0.3159458 1.265694 -0.3057729 -0.3159456 1.326988 -0.2935813 -0.3159457 1.388281 -0.3057729 -0.3159458 1.440125 -0.3404079 -0.3159461 1.486951 -0.4535448 -1.515947 1.47476 -0.3922513 -0.3159463 0.8796035 0.627954 -1.515941 1.47476 -0.5148384 -1.515947 1.486952 -0.453545 -0.3159466 2.415981 -1.461289 -1.515953 1.440125 -0.5666818 -1.515947 1.47476 -0.5148386 -0.3159468 2.659881 -1.859331 -1.515955 1.388281 -0.6013168 -1.515947 1.440125 -0.566682 -0.3159469 2.557835 -1.73981 -1.515954 2.475982 -1.606146 -1.515954 2.815095 -2.090332 -1.515956 1.326988 -0.6135085 -1.515947 1.388282 -0.601317 -0.3159469 2.775135 -1.99386 -1.515956 1.265694 -0.6013168 -1.515947 1.326988 -0.6135088 -0.3159469 1.265694 -0.6013171 -0.3159468 1.213851 -0.5666821 -0.3159465 1.179216 -0.5148386 -0.3159463 1.167024 -0.453545 -0.3159461 -1.473012 0.6896421 -1.515936 -1.254306 -0.3057732 -1.515941 -1.306149 -0.3404082 -1.515941 -1.306149 -0.3404085 -0.3159409 -1.340784 -0.3922516 -1.515941 -1.340784 -0.3922519 -0.315941 -1.193012 -0.2935815 -1.515941 -1.254306 -0.3057734 -0.3159408 -1.131718 -0.3057732 -1.515941 -1.193012 -0.2935817 -0.3159409 -1.131718 -0.3057734 -0.315941 -1.079875 -0.3404085 -0.3159412 -0.7456279 -0.6165541 -1.515943 -1.04524 -0.3922519 -0.3159415 -1.033048 -0.4535454 -0.3159418 -1.04524 -0.5148391 -0.3159423 -1.079875 -0.5666825 -0.3159424 -1.131718 -0.6013175 -0.3159425 -1.193012 -0.6135093 -0.3159425 -1.254306 -0.6013176 -0.3159423 -1.473012 -0.6367329 -1.515942 -1.340784 -0.5148389 -1.515941 -1.306149 -0.5666826 -0.3159421 -1.352976 -0.4535453 -1.515941 -1.340784 -0.5148392 -0.3159415 -1.352976 -0.4535456 -0.3159412 -2.525905 1.912241 -1.515928 -1.254306 0.6542266 -1.515936 -1.306149 0.6195916 -1.515936 -1.306149 0.6195914 -0.3159363 -2.282005 1.514199 -1.515931 -1.340784 0.5677482 -1.515936 -1.340784 0.567748 -0.3159368 -2.423859 1.792719 -1.515929 -2.342007 1.659056 -1.51593 -2.681119 2.143242 -1.515927 -1.193012 0.6664184 -1.515936 -1.254306 0.6542264 -0.3159363 -2.641159 2.046769 -1.515927 -1.131719 0.6542267 -1.515937 -1.193012 0.6664182 -0.3159363 -1.131718 0.6542265 -0.3159369 -1.079875 0.6195915 -0.3159371 -1.04524 0.5677481 -0.3159373 -1.033048 0.5064545 -0.3159376 -1.04524 0.4451608 -0.3159378 -1.079875 0.3933174 -0.3159379 -1.131718 0.3586823 -0.315938 -1.193012 0.3464907 -0.3159379 -1.254306 0.3586823 -0.3159378 -1.306149 0.3933173 -0.3159376 -1.352976 0.5064546 -1.515937 -1.340784 0.4451608 -0.3159373 -0.7456279 -0.5750442 -1.515943 -1.352976 0.5064544 -0.3159371 2.487303 -2.681691 -1.515959 -0.1592863 -0.03011363 -1.515941 0.0104193 -0.1998192 -1.515942 -0.1592862 -0.03011381 -0.3159415 0.04623281 -0.2204754 -1.515943 0.04623287 -0.2204757 -0.315943 0.01041936 -0.1998194 -0.3159428 -2.252323 2.176059 -1.515928 -0.1799426 0.005699872 -1.515941 -2.641159 2.446769 -1.515926 -0.4986976 0.365866 -1.515939 -0.1799426 0.04720991 -1.515941 -0.1799425 0.005699634 -0.3159413 -0.7249717 0.5921401 -1.515938 -0.4628841 0.3452097 -1.515939 -0.1592864 0.08302342 -1.515941 -0.1799425 0.04720968 -0.3159412 -0.2517672 0.5148167 -1.515939 0.01041918 0.2527291 -1.515941 0.01041924 0.2527289 -0.3159407 -0.2724235 0.4790031 -1.515939 -0.3855605 0.3658661 -1.515939 -0.421374 0.3452098 -1.515939 -0.1592862 0.08302319 -0.315941 -0.2517672 0.5563267 -1.515939 0.0462327 0.2733854 -1.515941 -0.2724235 0.5921402 -1.515938 0.08774274 0.2733854 -1.515941 0.04623281 0.2733852 -0.3159406 -2.353327 2.734601 -1.515925 0.1235563 0.2527291 -1.515941 0.0877428 0.2733852 -0.3159407 0.2932619 0.08302348 -1.515942 0.293262 0.0830233 -0.3159418 0.1235563 0.2527289 -0.3159409 2.386298 -2.123149 -1.515956 0.3139182 0.04720997 -1.515942 2.775135 -2.39386 -1.515958 0.6326733 -0.3129562 -1.515944 0.3139182 0.005699932 -1.515942 0.3139183 0.04720979 -0.3159419 0.8589473 -0.5392303 -1.515946 0.5968598 -0.2922999 -1.515944 0.293262 -0.03011351 -1.515942 0.3139183 0.005699753 -0.3159421 0.3857428 -0.4619067 -1.515944 0.1235563 -0.1998192 -1.515943 0.1235564 -0.1998194 -0.315943 0.4063991 -0.4260932 -1.515944 0.5195362 -0.3129562 -1.515944 0.5553497 -0.2922999 -1.515944 0.293262 -0.03011375 -0.3159426 0.3857428 -0.5034168 -1.515945 0.0877428 -0.2204754 -1.515943 0.4063991 -0.5392304 -1.515945 0.08774292 -0.2204757 -0.315943 -0.5962 1.566454 -0.3159334 0.7301751 1.566455 -0.3159359 -1.268364 2.338811 -1.515928 -1.020578 2.009347 -1.515931 -0.9913472 1.961601 -0.3159308 -1.024991 2.065297 -1.51593 -1.020578 2.009347 -0.3159306 -1.003608 2.11692 -1.51593 -1.024991 2.065297 -0.3159303 -1.111692 2.326454 -1.515929 -0.9609256 2.153363 -1.51593 -1.003608 2.11692 -0.3159301 -0.9064944 2.166455 -1.51593 -0.9609255 2.153362 -0.3159301 1.245667 2.326455 -1.515933 1.040469 2.166455 -1.515934 -0.9064943 2.166454 -0.3159301 1.0949 2.153363 -1.515934 1.040469 2.166455 -0.3159337 1.137583 2.116921 -1.515934 1.0949 2.153363 -0.3159338 1.158966 2.065298 -1.515934 1.137583 2.116921 -0.315934 1.254927 1.3841 -1.515938 1.154553 2.009348 -1.515935 1.158966 2.065297 -0.3159343 1.125322 1.961602 -1.515935 1.154553 2.009348 -0.3159348 1.125322 1.961602 -0.315935 2.366988 -1.152224 -1.515951 2.206988 -0.9470266 -1.51595 2.206988 0.9999371 -1.515941 2.206988 0.9999369 -0.3159413 2.366987 1.205135 -1.51594 2.193896 1.054368 -1.515941 2.193896 1.054368 -0.315941 2.193896 -1.001457 -1.51595 2.206988 -0.9470267 -0.31595 2.379344 -1.308896 -1.515952 2.157454 -1.04414 -1.51595 2.193896 -1.001458 -0.3159502 2.105831 -1.065523 -1.51595 2.157454 -1.04414 -0.3159503 2.049881 -1.061111 -1.51595 2.105831 -1.065523 -0.3159503 2.002135 -1.031879 -1.51595 2.049881 -1.061111 -0.3159502 2.002135 -1.03188 -0.31595 1.606988 -0.6367324 -0.3159475 1.424632 1.214394 -1.515939 2.002134 1.08479 -1.51594 1.606987 0.6896426 -0.3159415 2.386297 2.17606 -1.515936 2.04988 1.114021 -1.51594 2.002134 1.08479 -0.3159406 2.10583 1.118434 -1.51594 2.04988 1.114021 -0.3159406 2.157453 1.097051 -1.515941 2.10583 1.118434 -0.3159406 2.157453 1.097051 -0.3159408 -1.111692 2.326454 -0.3159292 1.245667 2.326455 -0.3159334 -1.268364 2.338811 -0.3159289 -1.420757 2.375447 -0.3159281 -1.565614 2.435448 -0.3159276 -1.699278 2.517301 -0.3159271 -1.870485 2.671033 -0.3159262 -1.818799 2.619347 -0.3159265 -1.953328 2.734601 -0.3159255 -2.0498 2.774561 -0.3159251 2.815095 -2.297387 -1.515957 -2.256855 2.774561 -1.515925 -2.153328 2.78819 -0.315925 -2.256855 2.774561 -0.3159248 -2.082617 2.345764 -1.515927 -2.436171 2.671033 -1.515925 -2.353327 2.734601 -0.3159248 -1.120952 1.384099 -1.515933 -0.5345113 0.8390706 -1.515937 -0.4986976 0.8184143 -1.515937 -2.577592 2.529612 -1.515925 -2.577592 2.529612 -0.3159253 -2.436171 2.671033 -0.315925 2.390831 -2.721652 -1.515958 -2.681119 2.350297 -1.515926 -2.641159 2.446769 -0.3159258 -2.681119 2.350297 -0.3159261 -2.694749 2.246769 -0.3159266 -2.681119 2.143242 -0.315927 -2.577592 1.963927 -1.515928 -2.641159 2.046769 -0.3159275 -2.525905 1.91224 -0.3159285 -2.577592 1.963927 -0.3159279 -2.423859 1.792719 -0.3159291 -2.342007 1.659055 -0.3159298 -1.971855 1.118433 -1.515933 -2.245369 1.361806 -1.515931 -2.282005 1.514199 -0.3159304 -1.915905 1.11402 -1.515933 -1.868159 1.084789 -1.515933 -2.059921 1.054367 -1.515933 -2.233012 1.205134 -1.515932 -2.245369 1.361806 -0.3159315 -2.023478 1.09705 -1.515933 -2.073012 -0.9470272 -1.515942 -2.233011 -1.152225 -1.515943 -2.233012 1.205134 -0.3159322 -2.073012 0.9999364 -1.515933 -2.252321 -2.12315 -1.515947 -2.245368 -1.308897 -1.515944 -2.233011 -1.152225 -0.3159429 -2.05992 -1.001458 -1.515942 -2.023478 -1.044141 -1.515942 -2.282004 -1.46129 -1.515944 -2.245368 -1.308897 -0.3159435 -2.342006 -1.606147 -1.515945 -2.282004 -1.46129 -0.3159444 -2.423858 -1.739811 -1.515945 -2.342006 -1.606147 -0.3159449 -2.525905 -1.859332 -1.515946 -2.423858 -1.739811 -0.3159453 -1.870484 -2.618125 -1.51595 -2.577591 -1.911018 -1.515946 -2.577591 -1.911018 -0.3159457 -1.818798 -2.566438 -1.51595 -2.525905 -1.859332 -0.3159456 -1.953327 -2.681692 -1.51595 -2.641158 -1.993861 -1.515946 -2.049799 -2.721652 -1.51595 -2.681118 -2.090333 -1.515946 -2.641158 -1.993861 -0.3159459 -2.153327 -2.735282 -1.51595 -2.694748 -2.193861 -1.515947 -2.681118 -2.090333 -0.3159462 -2.256855 -2.721652 -1.51595 -2.681118 -2.297388 -1.515947 -2.694748 -2.193861 -0.315947 -2.353327 -2.681692 -1.515949 -2.641158 -2.393861 -1.515948 -2.681118 -2.297389 -0.3159474 -2.436169 -2.618125 -1.515949 -2.577591 -2.476703 -1.515948 -2.641158 -2.393861 -0.3159479 -2.436169 -2.618125 -0.3159491 -2.577591 -2.476704 -0.3159483 -2.353327 -2.681692 -0.3159498 -2.256854 -2.721653 -0.3159502 -2.153327 -2.735282 -0.3159503 -2.049799 -2.721653 -0.3159505 -1.953327 -2.681692 -0.3159505 -1.818798 -2.566439 -0.3159502 -1.870484 -2.618125 -0.3159503 -2.082616 -2.292855 -1.515948 -1.699277 -2.464392 -1.51595 -1.120951 -1.33119 -1.515946 -1.565613 -2.38254 -1.51595 -1.699277 -2.464392 -0.31595 -1.420756 -2.322538 -1.51595 -1.565613 -2.38254 -0.3159499 -1.268363 -2.285902 -1.51595 -1.420756 -2.322538 -0.3159499 -1.111691 -2.273545 -1.51595 -1.268363 -2.285902 -0.31595 1.04047 -2.113544 -1.515953 1.245668 -2.273545 -1.515954 -1.111691 -2.273545 -0.3159503 -0.9064937 -2.113545 -1.51595 -0.9609245 -2.100453 -1.515949 -1.003607 -2.064011 -1.515949 -1.02499 -2.012388 -1.515949 1.137583 -2.064011 -1.515953 1.40234 -2.285901 -1.515955 1.245668 -2.273545 -0.3159545 1.094901 -2.100453 -1.515953 1.40234 -2.285901 -0.3159548 1.154554 -1.956438 -1.515953 1.158967 -2.012387 -1.515953 1.554733 -2.322537 -0.3159551 1.69959 -2.382539 -0.3159556 1.833253 -2.464391 -0.3159565 2.004461 -2.618124 -0.3159574 1.952775 -2.566438 -0.3159571 2.087303 -2.681692 -0.3159577 2.183776 -2.721652 -0.3159581 2.287303 -2.735281 -0.3159583 2.390831 -2.721652 -0.3159584 2.216593 -2.292855 -1.515956 2.570146 -2.618124 -1.515958 2.487303 -2.681692 -0.3159584 1.254927 -1.33119 -1.51595 0.6684868 -0.7861607 -1.515947 0.6326733 -0.7655044 -1.515946 2.711568 -2.476702 -1.515958 2.711568 -2.476702 -0.315958 2.570146 -2.618124 -0.3159583 2.775135 -2.39386 -0.3159578 2.815095 -2.297387 -0.3159574 2.828725 -2.19386 -0.3159571 2.815095 -2.090332 -0.3159567 2.711568 -1.911017 -1.515955 2.775135 -1.99386 -0.3159558 2.659881 -1.859331 -0.3159551 2.711568 -1.911017 -0.3159554 2.557835 -1.73981 -0.3159545 2.475982 -1.606146 -0.3159534 2.415981 -1.461289 -0.3159528 2.379344 -1.308896 -0.3159521 2.366988 -1.152224 -0.3159515 2.379343 1.361807 -1.51594 2.366987 1.205135 -0.3159407 2.41598 1.5142 -1.515939 2.379343 1.361807 -0.3159397 2.475981 1.659057 -1.515939 2.41598 1.514199 -0.3159392 2.557834 1.792721 -1.515938 2.475981 1.659057 -0.3159387 2.65988 1.912242 -1.515938 2.557834 1.79272 -0.3159384 2.00446 2.671034 -1.515933 2.711566 1.963928 -1.515938 2.711566 1.963928 -0.3159375 1.952774 2.619348 -1.515933 2.65988 1.912242 -0.3159381 2.087302 2.734601 -1.515933 2.775134 2.04677 -1.515937 2.183775 2.774562 -1.515933 2.815094 2.143243 -1.515937 2.775134 2.04677 -0.3159373 2.287302 2.788192 -1.515933 2.828724 2.24677 -1.515937 2.815094 2.143243 -0.315937 2.39083 2.774562 -1.515933 2.815094 2.350298 -1.515936 2.828724 2.24677 -0.3159366 2.487303 2.734601 -1.515934 2.775134 2.44677 -1.515936 2.815094 2.350298 -0.3159362 2.570145 2.671034 -1.515934 2.711566 2.529613 -1.515935 2.775134 2.44677 -0.3159357 2.570145 2.671034 -0.3159342 2.711566 2.529613 -0.3159353 2.487303 2.734601 -0.3159338 2.39083 2.774562 -0.3159335 2.287302 2.788191 -0.3159332 2.183775 2.774562 -0.3159331 2.087302 2.734601 -0.3159331 1.952774 2.619348 -0.3159334 2.00446 2.671034 -0.3159332 2.216592 2.345765 -1.515935 1.833252 2.517302 -1.515934 1.699589 2.43545 -1.515934 1.833252 2.517302 -0.3159336 1.554732 2.375448 -1.515934 1.699589 2.435449 -0.3159337 1.402339 2.338811 -1.515934 1.554732 2.375447 -0.3159337 1.402339 2.338811 -0.3159336 -2.073012 -0.9470274 -0.3159423 -2.05992 -1.001459 -0.3159426 -2.073012 0.9999362 -0.3159332 -2.059921 1.054367 -0.315933 -2.023478 1.097049 -0.3159329 -1.971855 1.118433 -0.3159329 -1.915905 1.11402 -0.315933 -1.868159 1.084789 -0.3159332 -1.473012 0.689642 -0.3159357 -1.290657 -1.161484 -1.515944 -1.868159 -1.03188 -1.515943 -1.473012 -0.6367331 -0.3159421 -1.915905 -1.061111 -1.515943 -1.868159 -1.03188 -0.315943 -1.971855 -1.065524 -1.515943 -1.915905 -1.061111 -0.315943 -1.971854 -1.065524 -0.315943 -2.023478 -1.044141 -0.3159428 0.7301758 -1.513545 -0.3159499 -0.5961993 -1.513545 -0.3159477 1.125323 -1.908692 -0.3159524 1.154554 -1.956438 -0.3159527 1.158967 -2.012387 -0.3159529 1.137583 -2.064011 -0.3159531 1.094901 -2.100453 -0.3159535 1.04047 -2.113545 -0.3159535 -0.9064936 -2.113545 -0.3159496 -0.9609244 -2.100453 -0.3159494 -1.003607 -2.064011 -0.3159492 -1.020578 -1.956438 -1.515949 -1.02499 -2.012388 -0.315949 -0.9913465 -1.908692 -1.515949 -1.020578 -1.956438 -0.3159488 -0.9913464 -1.908693 -0.3159486 2.386297 2.176059 -0.3159362 1.254927 1.3841 -0.3159378 1.424632 1.214394 -0.3159388 2.216592 2.345765 -0.3159353 2.216593 -2.292855 -0.3159564 0.8796037 -0.5750437 -1.515946 1.424633 -1.161484 -1.51595 1.424633 -1.161484 -0.3159496 2.386298 -2.123149 -0.3159557 0.8796036 -0.6165537 -1.515946 0.7099969 -0.7861607 -1.515947 0.7458104 -0.7655044 -1.515947 0.8589473 -0.6523674 -1.515946 1.254927 -1.33119 -0.31595 -2.252323 2.176059 -0.3159276 -0.7456282 0.6279535 -1.515937 -1.290657 1.214394 -1.515934 -1.290657 1.214394 -0.315934 -2.082617 2.345764 -0.3159272 -0.7456282 0.6694635 -1.515937 -0.6118348 0.8184143 -1.515937 -0.7249717 0.7052773 -1.515937 -0.5760214 0.8390706 -1.515937 -1.120952 1.384099 -0.3159332 -1.120951 -1.33119 -0.3159458 -2.252321 -2.12315 -0.3159474 -2.082616 -2.292856 -0.3159484 -1.290657 -1.161485 -0.3159449 0.406399 0.4790031 -0.3159404 0.5553497 0.3452097 -0.3159412 0.5195361 0.365866 -0.315941 0.3857427 0.5148166 -0.3159402 0.3857427 0.5563267 -0.3159401 0.406399 0.5921401 -0.31594 0.6326731 0.8184143 -0.315939 0.6684865 0.8390707 -0.315939 0.7099966 0.8390706 -0.3159391 0.8589473 0.7052773 -0.3159403 0.7458102 0.8184143 -0.3159393 0.8796036 0.6694638 -0.3159404 0.8796036 0.6279538 -0.3159406 0.8589473 0.5921403 -0.3159407 0.6326732 0.365866 -0.3159412 0.5968597 0.3452098 -0.3159412 -0.7249715 -0.6523678 -0.3159434 -0.7456278 -0.6165543 -0.3159432 -0.7456278 -0.5750443 -0.315943 -0.7249715 -0.5392308 -0.315943 -0.4986975 -0.3129566 -0.3159424 -0.4628838 -0.2923003 -0.3159424 -0.4213739 -0.2923003 -0.3159424 -0.2724233 -0.4260936 -0.3159432 -0.3855603 -0.3129566 -0.3159426 -0.251767 -0.4619071 -0.3159434 -0.251767 -0.5034173 -0.3159435 -0.2724232 -0.5392307 -0.3159437 -0.4986974 -0.7655048 -0.3159442 -0.5345108 -0.7861612 -0.3159442 -0.5760208 -0.7861611 -0.3159441 -0.6118344 -0.7655048 -0.315944 -0.6118347 0.8184142 -0.3159371 -0.7456281 0.6694633 -0.3159374 -0.7249716 0.705277 -0.3159373 -0.5760213 0.8390704 -0.3159371 -0.5345112 0.8390704 -0.3159371 -0.4986976 0.8184142 -0.3159372 -0.2724235 0.59214 -0.3159385 -0.2517672 0.5563265 -0.3159387 -0.2517672 0.5148164 -0.3159388 -0.3855605 0.3658658 -0.3159396 -0.2724235 0.4790029 -0.3159389 -0.4213739 0.3452095 -0.3159396 -0.4628841 0.3452095 -0.3159391 -0.4986975 0.3658658 -0.315939 -0.7249716 0.5921399 -0.3159378 -0.7456281 0.6279534 -0.3159375 0.7458105 -0.7655046 -0.3159466 0.7099971 -0.7861609 -0.3159466 0.668487 -0.7861609 -0.3159465 0.6326735 -0.7655046 -0.3159464 0.4063992 -0.5392306 -0.3159452 0.3857429 -0.503417 -0.3159446 0.3857429 -0.461907 -0.3159444 0.5195363 -0.3129564 -0.315944 0.4063992 -0.4260935 -0.3159443 0.5553498 -0.2923001 -0.315944 0.5968599 -0.2923001 -0.3159441 0.6326734 -0.3129564 -0.3159442 0.8589475 -0.5392305 -0.3159459 0.8796038 -0.5750439 -0.3159461 0.8796038 -0.6165539 -0.3159462 0.8589475 -0.6523675 -0.3159464 -6.182838 6.358169 0.7640986 -5.508975 5.684305 0.7640945 -5.547439 5.640881 0.7640944 -5.490871 5.584312 1.764093 -6.226263 6.319703 0.7640985 -5.590864 5.602415 0.7640942 -5.588912 5.506127 1.764093 -6.135161 6.391067 0.7640987 -5.476075 5.731982 0.7640946 -5.412686 5.682353 1.764094 -6.083861 6.417993 0.7640987 -5.44915 5.783283 0.7640947 -6.029682 6.438546 0.7640987 -5.428597 5.837461 0.7640949 -5.358276 5.795335 1.764094 -5.973388 6.452427 0.7640986 -5.414716 5.893755 0.7640951 -5.915814 6.459416 0.7640985 -5.407727 5.951329 0.7640953 -5.330372 5.917592 1.764095 -5.857857 6.459411 0.7640984 -5.407732 6.009286 0.7640956 -5.80034 6.452425 0.7640984 -5.414718 6.066803 0.7640958 -5.330372 6.042992 1.764095 -5.744078 6.438563 0.7640982 -5.428581 6.123065 0.764096 -5.689871 6.418012 0.7640981 -5.449131 6.177272 0.7640963 -5.358277 6.165248 1.764096 -5.638514 6.391057 0.7640978 -5.476087 6.22863 0.7640969 -5.590813 6.358124 0.7640976 -5.509019 6.27633 0.7640972 -5.412686 6.27823 1.764097 -5.547444 6.319699 0.7640974 -5.490872 6.376272 1.764097 -5.588914 6.454457 1.764098 -5.701895 6.508866 1.764098 -5.824152 6.536771 1.764099 -5.949552 6.536771 1.764099 -6.071808 6.508867 1.764099 -6.18479 6.454457 1.764099 -6.264728 6.276279 0.7640984 -6.282831 6.376272 1.764099 -5.63854 5.569516 0.7640942 -6.297627 6.228602 0.7640982 -6.361016 6.27823 1.764098 -5.689841 5.542592 0.7640942 -6.324552 6.177302 0.7640981 -5.744021 5.522038 0.7640942 -6.345105 6.123122 0.7640979 -6.415426 6.165248 1.764098 -5.800314 5.508158 0.7640942 -6.358986 6.066829 0.7640978 -5.857888 5.501168 0.7640942 -6.365975 6.009255 0.7640975 -6.44333 6.042993 1.764097 -5.915846 5.501173 0.7640944 -6.36597 5.951297 0.7640973 -5.973362 5.508158 0.7640945 -6.358985 5.893781 0.7640966 -6.44333 5.917593 1.764097 -6.029624 5.52202 0.7640947 -6.345122 5.837518 0.7640964 -6.083831 5.542573 0.7640948 -6.32457 5.783312 0.7640962 -6.415425 5.795336 1.764096 -6.135188 5.569527 0.764095 -6.297615 5.731954 0.7640959 -6.18289 5.60246 0.7640952 -6.264683 5.684253 0.7640957 -6.361017 5.682354 1.764096 -6.226258 5.640884 0.7640954 -6.282831 5.584312 1.764095 -6.184789 5.506126 1.764094 -6.071807 5.451718 1.764094 -5.949551 5.423813 1.764093 -5.82415 5.423814 1.764093 -5.701894 5.451717 1.764093 -6.175056 6.196016 7.164097 -6.102576 6.268496 7.164097 -6.141409 6.234849 7.164097 -6.282831 6.376271 6.164098 -6.361017 6.278229 6.164099 -6.202822 6.152804 7.164097 -6.059364 6.296263 7.164098 -6.184789 6.454456 6.164099 -6.224155 6.106081 7.164097 -6.012641 6.317595 7.164097 -6.238622 6.056802 7.164097 -5.963362 6.332062 7.164097 -6.071807 6.508866 6.164099 -6.245929 6.005969 7.164096 -5.912528 6.339369 7.164097 -5.949552 6.53677 6.164099 -6.245928 5.954613 7.164096 -5.861173 6.339369 7.164097 -6.238622 5.90378 7.164096 -5.81034 6.332063 7.164097 -5.824151 6.53677 6.164099 -6.224155 5.854501 7.164096 -5.761061 6.317595 7.164097 -5.701895 6.508866 6.164098 -6.202822 5.807778 7.164096 -5.714338 6.296262 7.164097 -5.912745 6.076875 7.164096 -5.671121 6.268494 7.164096 -5.588913 6.454457 6.164098 -5.957561 6.051002 7.164096 -5.816141 6.051002 7.164096 -5.632293 6.234849 7.164096 -5.860956 6.076875 7.164096 -5.790266 6.006186 7.164096 -5.598649 6.196021 7.164096 -5.490871 6.376271 6.164097 -5.816139 5.909581 7.164096 -5.57088 6.152804 7.164096 -5.412685 6.278229 6.164097 -5.790266 5.954397 7.164096 -6.01264 5.642986 7.164094 -5.549546 6.106081 7.164096 -6.059363 5.66432 7.164095 -5.963361 5.62852 7.164094 -5.535079 6.056802 7.164096 -5.358277 6.165248 6.164096 -5.912528 5.621213 7.164094 -5.527772 6.005969 7.164095 -5.330373 6.042992 6.164096 -5.861173 5.621213 7.164094 -5.527772 5.954614 7.164095 -5.810339 5.62852 7.164094 -5.535079 5.90378 7.164095 -5.330371 5.917592 6.164094 -5.761061 5.642986 7.164094 -5.549546 5.854501 7.164095 -5.358275 5.795335 6.164094 -5.714337 5.66432 7.164094 -5.570879 5.807778 7.164095 -5.671125 5.692085 7.164094 -5.598645 5.764566 7.164094 -5.412685 5.682354 6.164093 -5.632292 5.725733 7.164094 -5.490871 5.584312 6.164093 -5.588913 5.506126 6.164093 -5.701894 5.451716 6.164093 -5.82415 5.423812 6.164093 -5.949551 5.423813 6.164094 -6.071806 5.451716 6.164095 -5.860956 5.883707 7.164095 -6.10258 5.692089 7.164095 -6.184788 5.506125 6.164095 -5.957561 5.909581 7.164096 -6.141408 5.725732 7.164095 -5.912745 5.883707 7.164095 -5.983435 5.954396 7.164096 -6.175052 5.764562 7.164095 -6.28283 5.584311 6.164095 -6.361016 5.682353 6.164096 -5.983435 6.006185 7.164096 -6.415425 5.795334 6.164097 -6.443329 5.917591 6.164097 -6.44333 6.042991 6.164098 -6.415426 6.165247 6.164098 -5.957561 6.051001 12.76409 -5.912753 6.076874 12.76409 -5.983435 6.006191 12.76409 -5.983441 5.954426 12.76409 -5.957555 5.909584 12.76409 -5.912713 5.883698 12.76409 -5.860948 5.883705 12.76409 -5.816139 5.909579 12.76409 -5.790266 5.954387 12.76409 -5.790259 6.006153 12.76409 -5.816145 6.050994 12.76409 -5.860987 6.07688 12.76409 -6.264725 -6.223372 0.7640414 -5.590862 -5.549508 0.7640429 -5.547438 -5.587973 0.7640427 -5.490869 -5.531405 1.764043 -6.226259 -6.266796 0.7640411 -5.508972 -5.631398 0.7640425 -5.412684 -5.629446 1.764042 -6.297624 -6.175695 0.7640416 -5.638539 -5.516609 0.7640431 -5.588911 -5.45322 1.764043 -6.324549 -6.124395 0.7640419 -5.689839 -5.489684 0.7640433 -6.345102 -6.070215 0.7640421 -5.744019 -5.469131 0.7640435 -5.701892 -5.39881 1.764044 -6.358983 -6.013921 0.7640424 -5.800312 -5.45525 0.7640441 -6.365973 -5.956348 0.7640426 -5.857886 -5.448261 0.7640442 -5.824149 -5.370906 1.764044 -6.365968 -5.89839 0.7640428 -5.915843 -5.448266 0.7640443 -6.358983 -5.840874 0.764043 -5.97336 -5.455251 0.7640444 -5.949548 -5.370906 1.764044 -6.34512 -5.784612 0.7640432 -6.029622 -5.469114 0.7640444 -6.324568 -5.730404 0.7640434 -6.083829 -5.489665 0.7640444 -6.071805 -5.398811 1.764045 -6.297614 -5.679048 0.7640436 -6.135187 -5.516621 0.7640444 -6.264681 -5.631346 0.7640441 -6.182888 -5.549553 0.7640443 -6.184786 -5.453219 1.764045 -6.226256 -5.587977 0.7640442 -6.282828 -5.531405 1.764044 -6.361014 -5.629447 1.764044 -6.415423 -5.742429 1.764043 -6.443327 -5.864685 1.764043 -6.443327 -5.990086 1.764042 -6.415423 -6.112341 1.764042 -6.361013 -6.225323 1.764041 -6.182835 -6.305262 0.764041 -6.282828 -6.323364 1.76404 -5.476073 -5.679074 0.7640423 -6.135158 -6.33816 0.7640404 -6.184786 -6.40155 1.76404 -5.449149 -5.730375 0.764042 -6.083858 -6.365086 0.7640402 -5.428595 -5.784554 0.7640417 -6.029678 -6.385639 0.76404 -6.071805 -6.45596 1.764039 -5.414714 -5.840848 0.7640415 -5.973385 -6.399519 0.7640398 -5.407725 -5.898422 0.7640413 -5.915811 -6.406509 0.7640398 -5.949549 -6.483864 1.764039 -5.40773 -5.956379 0.7640411 -5.857853 -6.406504 0.7640396 -5.414714 -6.013896 0.7640408 -5.800337 -6.399518 0.7640396 -5.824149 -6.483864 1.764039 -5.428577 -6.070158 0.7640402 -5.744075 -6.385656 0.7640395 -5.449129 -6.124365 0.7640401 -5.689868 -6.365104 0.7640396 -5.701892 -6.455959 1.764039 -5.476084 -6.175723 0.7640399 -5.63851 -6.33815 0.7640396 -5.509016 -6.223423 0.7640398 -5.590809 -6.305217 0.7640396 -5.588911 -6.40155 1.764039 -5.547441 -6.266792 0.7640397 -5.490869 -6.323364 1.764039 -5.412683 -6.225322 1.764039 -5.358274 -6.112341 1.76404 -5.33037 -5.990085 1.76404 -5.33037 -5.864684 1.764041 -5.358274 -5.742428 1.764041 -6.102573 -6.215591 7.164041 -6.175054 -6.143112 7.164041 -6.141407 -6.181944 7.164041 -6.282827 -6.323365 6.16404 -6.184785 -6.401551 6.16404 -6.059361 -6.243357 7.164041 -6.202819 -6.099899 7.164041 -6.361013 -6.225324 6.164041 -6.012638 -6.26469 7.164041 -6.224153 -6.053175 7.164041 -5.963359 -6.279157 7.16404 -6.238619 -6.003897 7.164042 -6.415422 -6.112342 6.164041 -5.912525 -6.286464 7.16404 -6.245927 -5.953063 7.164042 -6.443327 -5.990087 6.164042 -5.86117 -6.286464 7.16404 -6.245927 -5.901708 7.164042 -5.810337 -6.279157 7.16404 -6.23862 -5.850875 7.164042 -6.443326 -5.864686 6.164042 -5.761058 -6.264691 7.164041 -6.224153 -5.801596 7.164042 -6.415422 -5.74243 6.164043 -5.714334 -6.243358 7.16404 -6.202819 -5.754873 7.164043 -5.983432 -5.95328 7.164041 -6.175051 -5.711657 7.164043 -6.361014 -5.629448 6.164044 -5.957559 -5.998096 7.164041 -5.957559 -5.856675 7.164042 -6.141407 -5.672828 7.164043 -5.983432 -5.901492 7.164042 -5.912743 -5.830802 7.164042 -6.102578 -5.639184 7.164043 -6.282828 -5.531406 6.164044 -5.816138 -5.856675 7.164042 -6.059361 -5.611415 7.164043 -6.184786 -5.45322 6.164044 -5.860954 -5.830802 7.164042 -5.549543 -6.053176 7.164041 -6.012638 -5.590081 7.164043 -5.570876 -6.099899 7.164041 -5.535077 -6.003896 7.164041 -5.963359 -5.575614 7.164043 -6.071805 -5.398812 6.164045 -5.52777 -5.953063 7.164041 -5.912527 -5.568308 7.164043 -5.949548 -5.370908 6.164044 -5.52777 -5.901708 7.164041 -5.861171 -5.568308 7.164043 -5.535078 -5.850874 7.164041 -5.810338 -5.575614 7.164043 -5.824148 -5.370906 6.164044 -5.549543 -5.801596 7.164041 -5.761058 -5.590081 7.164043 -5.701891 -5.39881 6.164044 -5.570877 -5.754872 7.164042 -5.714335 -5.611414 7.164042 -5.598643 -5.711661 7.164042 -5.671123 -5.639181 7.164042 -5.588911 -5.45322 6.164043 -5.63229 -5.672827 7.164042 -5.490869 -5.531406 6.164043 -5.412683 -5.629448 6.164042 -5.358273 -5.742429 6.164042 -5.330369 -5.864685 6.164041 -5.33037 -5.990086 6.164041 -5.358273 -6.112342 6.164041 -5.790264 -5.901492 7.164042 -5.598646 -6.143115 7.164041 -5.412682 -6.225323 6.16404 -5.816138 -5.998097 7.164041 -5.632289 -6.181944 7.16404 -5.790264 -5.95328 7.164041 -5.860953 -6.02397 7.164041 -5.671118 -6.215588 7.16404 -5.490868 -6.323365 6.16404 -5.58891 -6.401551 6.16404 -5.912741 -6.02397 7.164041 -5.701891 -6.45596 6.164039 -5.824148 -6.483864 6.164039 -5.949548 -6.483865 6.164039 -6.071805 -6.455961 6.16404 -5.957559 -5.998098 12.76404 -5.983432 -5.953289 12.76404 -5.912749 -6.023971 12.76404 -5.860984 -6.023978 12.76404 -5.816143 -5.998092 12.76404 -5.790256 -5.95325 12.76404 -5.790263 -5.901484 12.76404 -5.816137 -5.856676 12.76404 -5.860946 -5.830803 12.76404 -5.912711 -5.830796 12.76404 -5.957553 -5.856682 12.76404 -5.983438 -5.901524 12.76404 6.316815 -6.305259 0.7640177 5.642951 -5.631395 0.7640222 5.681416 -5.587971 0.7640223 5.624848 -5.531403 1.764022 6.360239 -6.266793 0.7640177 5.724841 -5.549506 0.7640224 5.72289 -5.453217 1.764022 6.269138 -6.338158 0.7640177 5.610052 -5.679072 0.7640221 5.546663 -5.629444 1.764022 6.217838 -6.365083 0.7640176 5.583127 -5.730373 0.7640218 6.163659 -6.385636 0.7640176 5.562573 -5.784552 0.7640217 5.492252 -5.742425 1.764021 6.107365 -6.399517 0.7640176 5.548693 -5.840846 0.7640215 6.049791 -6.406507 0.7640177 5.541703 -5.898419 0.7640212 5.464348 -5.864682 1.764021 5.991834 -6.406501 0.7640178 5.541708 -5.956377 0.7640206 5.934317 -6.399516 0.7640179 5.548695 -6.013894 0.7640204 5.464348 -5.990082 1.76402 5.878055 -6.385653 0.764018 5.562557 -6.070156 0.7640202 5.823848 -6.365102 0.7640182 5.583109 -6.124363 0.7640199 5.492254 -6.112338 1.76402 5.772491 -6.338147 0.7640184 5.610064 -6.17572 0.7640197 5.72479 -6.305214 0.7640187 5.642996 -6.223421 0.7640194 5.546662 -6.22532 1.764019 5.68142 -6.266789 0.7640188 5.624848 -6.323362 1.764019 5.72289 -6.401548 1.764018 5.835872 -6.455956 1.764018 5.958129 -6.483861 1.764017 6.083529 -6.483861 1.764017 6.205785 -6.455957 1.764017 6.318767 -6.401547 1.764017 6.398705 -6.223369 0.7640178 6.416808 -6.323362 1.764017 5.772517 -5.516606 0.7640224 6.431604 -6.175692 0.7640179 6.494994 -6.22532 1.764017 5.823818 -5.489682 0.7640224 6.458529 -6.124392 0.7640185 5.877998 -5.469129 0.7640224 6.479082 -6.070212 0.7640187 6.549403 -6.112339 1.764018 5.934291 -5.455248 0.7640224 6.492963 -6.013919 0.7640189 5.991865 -5.448258 0.7640223 6.499952 -5.956345 0.7640191 6.577307 -5.990083 1.764019 6.049823 -5.448263 0.7640222 6.499947 -5.898387 0.7640193 6.107339 -5.455248 0.7640221 6.492962 -5.840871 0.7640196 6.577307 -5.864683 1.764019 6.163601 -5.469111 0.764022 6.479099 -5.784609 0.7640198 6.217808 -5.489663 0.7640218 6.458547 -5.730402 0.76402 6.549402 -5.742426 1.76402 6.269165 -5.516617 0.7640216 6.431592 -5.679044 0.7640207 6.316867 -5.54955 0.7640213 6.39866 -5.631343 0.7640209 6.494994 -5.629445 1.76402 6.360235 -5.587975 0.7640212 6.416808 -5.531403 1.764021 6.318766 -5.453217 1.764021 6.205784 -5.398808 1.764022 6.083528 -5.370903 1.764022 5.958127 -5.370904 1.764022 5.835871 -5.398808 1.764022 6.309034 -6.143108 7.164019 6.236554 -6.215589 7.164018 6.275387 -6.181942 7.164018 6.416809 -6.323362 6.164018 6.494995 -6.22532 6.164018 6.3368 -6.099896 7.164018 6.193342 -6.243355 7.164018 6.318767 -6.401548 6.164018 6.358134 -6.053173 7.164018 6.146619 -6.264688 7.164018 6.3726 -6.003894 7.164019 6.09734 -6.279154 7.164018 6.205786 -6.455957 6.164018 6.379906 -5.953061 7.164019 6.046506 -6.286461 7.164018 6.08353 -6.483862 6.164018 6.379906 -5.901706 7.164019 5.995151 -6.286461 7.164018 6.3726 -5.850872 7.164019 5.944318 -6.279155 7.164018 5.958129 -6.483861 6.164018 6.358133 -5.801593 7.164019 5.895039 -6.264688 7.164019 5.835873 -6.455958 6.164018 6.3368 -5.75487 7.16402 5.848316 -6.243354 7.164019 6.046723 -6.023967 7.164019 5.805099 -6.215586 7.164019 5.722891 -6.401549 6.164019 6.091539 -5.998094 7.164019 5.950118 -5.998094 7.16402 5.766271 -6.181942 7.164019 5.994934 -6.023968 7.16402 5.924244 -5.953278 7.16402 5.732626 -6.143113 7.16402 5.624849 -6.323363 6.164019 5.950118 -5.856673 7.16402 5.704857 -6.099896 7.16402 5.546663 -6.225321 6.16402 5.924244 -5.901489 7.16402 6.146618 -5.590078 7.164021 5.683524 -6.053173 7.16402 6.193341 -5.611412 7.164021 6.097339 -5.575612 7.164021 5.669056 -6.003894 7.16402 5.492255 -6.11234 6.16402 6.046506 -5.568305 7.164021 5.66175 -5.953061 7.16402 5.46435 -5.990083 6.164021 5.995151 -5.568305 7.164021 5.66175 -5.901706 7.164021 5.944317 -5.575613 7.164021 5.669057 -5.850872 7.164021 5.464349 -5.864684 6.164021 5.895039 -5.590078 7.164021 5.683524 -5.801593 7.164021 5.492253 -5.742426 6.164022 5.848315 -5.611412 7.164021 5.704857 -5.75487 7.164021 5.805103 -5.639178 7.164021 5.732623 -5.711658 7.164021 5.546662 -5.629446 6.164022 5.76627 -5.672825 7.164021 5.624848 -5.531404 6.164023 5.72289 -5.453217 6.164023 5.835872 -5.398808 6.164023 5.958127 -5.370904 6.164023 6.083528 -5.370905 6.164022 6.205784 -5.398808 6.164022 5.994934 -5.830799 7.16402 6.236558 -5.639181 7.164021 6.318766 -5.453217 6.164021 6.091539 -5.856673 7.16402 6.275386 -5.672824 7.16402 6.046723 -5.830799 7.16402 6.117413 -5.901488 7.16402 6.309031 -5.711654 7.16402 6.416808 -5.531403 6.164021 6.494994 -5.629445 6.164021 6.117412 -5.953277 7.164019 6.549403 -5.742426 6.16402 6.577307 -5.864683 6.16402 6.577307 -5.990083 6.164019 6.549404 -6.112339 6.164019 6.091539 -5.998096 12.76402 6.046731 -6.023969 12.76402 6.117413 -5.953287 12.76402 6.11742 -5.901521 12.76402 6.091534 -5.85668 12.76402 6.046692 -5.830793 12.76402 5.994927 -5.8308 12.76402 5.950118 -5.856674 12.76402 5.924244 -5.901483 12.76402 5.924237 -5.953248 12.76402 5.950124 -5.99809 12.76402 5.994966 -6.023976 12.76402 6.398702 6.276281 0.7640752 5.724838 5.602418 0.7640733 5.681414 5.640883 0.7640735 5.624845 5.584315 1.764073 6.360236 6.319705 0.7640754 5.642949 5.684308 0.7640737 5.546661 5.682356 1.764074 6.431601 6.228604 0.7640749 5.772516 5.569518 0.764073 5.722887 5.50613 1.764073 6.458526 6.177304 0.7640748 5.823816 5.542594 0.7640728 6.479079 6.123125 0.7640745 5.877995 5.522041 0.7640727 5.835869 5.45172 1.764072 6.49296 6.066831 0.7640743 5.934289 5.50816 0.7640725 6.499949 6.009257 0.7640736 5.991863 5.501171 0.7640724 5.958126 5.423816 1.764072 6.499945 5.9513 0.7640733 6.04982 5.501175 0.7640723 6.492959 5.893783 0.7640731 6.107337 5.508161 0.7640719 6.083525 5.423816 1.764072 6.479097 5.837521 0.764073 6.163599 5.522023 0.7640722 6.458546 5.783314 0.7640728 6.217806 5.542575 0.7640722 6.205782 5.45172 1.764071 6.431591 5.731956 0.7640726 6.269164 5.56953 0.7640722 6.398658 5.684256 0.7640725 6.316864 5.602462 0.7640722 6.318763 5.506129 1.764071 6.360233 5.640887 0.7640724 6.416805 5.584315 1.764072 6.494991 5.682357 1.764072 6.5494 5.795339 1.764072 6.577305 5.917595 1.764073 6.577304 6.042995 1.764073 6.5494 6.165251 1.764074 6.49499 6.278233 1.764075 6.316812 6.358171 0.7640756 6.416805 6.376274 1.764075 5.610049 5.731984 0.7640744 6.269135 6.39107 0.7640759 6.318764 6.45446 1.764076 5.583126 5.783285 0.7640746 6.217835 6.417995 0.7640761 5.562572 5.837464 0.7640749 6.163656 6.438548 0.7640762 6.205782 6.508869 1.764076 5.548691 5.893758 0.7640751 6.107362 6.452429 0.7640764 5.541701 5.951332 0.7640753 6.049788 6.459419 0.7640765 6.083526 6.536773 1.764076 5.541706 6.009289 0.7640755 5.99183 6.459414 0.7640765 5.548692 6.066806 0.7640758 5.934314 6.452428 0.7640767 5.958126 6.536773 1.764077 5.562554 6.123067 0.7640759 5.878052 6.438565 0.7640767 5.583106 6.177275 0.7640761 5.823845 6.418014 0.7640767 5.835869 6.508869 1.764077 5.61006 6.228632 0.7640763 5.772487 6.391059 0.7640767 5.642993 6.276333 0.7640764 5.724786 6.358127 0.7640767 5.722887 6.45446 1.764077 5.681417 6.319702 0.7640765 5.624845 6.376274 1.764077 5.546659 6.278232 1.764076 5.492251 6.165251 1.764076 5.464346 6.042994 1.764075 5.464347 5.917594 1.764075 5.49225 5.795338 1.764074 6.236551 6.268498 7.164076 6.309031 6.196019 7.164076 6.275384 6.234852 7.164076 6.416805 6.376274 6.164075 6.318763 6.454459 6.164076 6.193339 6.296265 7.164076 6.336798 6.152806 7.164075 6.494991 6.278232 6.164075 6.146615 6.317598 7.164076 6.35813 6.106083 7.164075 6.097337 6.332065 7.164076 6.372597 6.056805 7.164075 6.549401 6.165251 6.164075 6.046503 6.339371 7.164076 6.379904 6.00597 7.164074 6.577305 6.042994 6.164074 5.995148 6.339371 7.164077 6.379905 5.954616 7.164074 5.944315 6.332064 7.164075 6.372598 5.903782 7.164072 6.577304 5.917593 6.164074 5.895036 6.317598 7.164075 6.358131 5.854503 7.164072 6.549401 5.795337 6.164073 5.848313 6.296265 7.164075 6.336798 5.80778 7.164072 6.11741 6.006187 7.164073 6.309029 5.764564 7.164072 6.494992 5.682356 6.164072 6.091537 6.051004 7.164074 6.091536 5.909583 7.164073 6.275385 5.725735 7.164072 6.117411 5.954399 7.164073 6.046721 5.883709 7.164073 6.236556 5.692091 7.164072 6.416806 5.584314 6.164072 5.950116 5.909583 7.164074 6.19334 5.664322 7.164072 6.318764 5.506128 6.164072 5.994933 5.883709 7.164073 5.683521 6.106083 7.164075 6.146616 5.642988 7.164072 5.704854 6.152806 7.164075 5.669054 6.056804 7.164075 6.097338 5.628522 7.164072 6.205783 5.451719 6.164072 5.661747 6.00597 7.164074 6.046504 5.621215 7.164072 6.083527 5.423815 6.164072 5.661748 5.954616 7.164074 5.99515 5.621215 7.164072 5.669055 5.903782 7.164074 5.944315 5.628522 7.164072 5.958127 5.423814 6.164072 5.683522 5.854504 7.164074 5.895037 5.642989 7.164072 5.83587 5.451719 6.164072 5.704854 5.80778 7.164074 5.848313 5.664322 7.164073 5.732621 5.764568 7.164073 5.805101 5.692088 7.164073 5.722888 5.506128 6.164073 5.766268 5.725735 7.164073 5.624846 5.584314 6.164073 5.54666 5.682355 6.164074 5.492251 5.795337 6.164074 5.464348 5.917593 6.164075 5.464347 6.042994 6.164075 5.492251 6.16525 6.164076 5.924242 5.9544 7.164074 5.732624 6.196022 7.164075 5.546659 6.278231 6.164076 5.950115 6.051004 7.164074 5.766268 6.234852 7.164075 5.924242 6.006188 7.164074 5.994932 6.076878 7.164074 5.805097 6.268495 7.164075 5.624845 6.376273 6.164076 5.722887 6.454459 6.164077 6.04672 6.076878 7.164074 5.83587 6.508868 6.164077 5.958126 6.536772 6.164077 6.083527 6.536772 6.164077 6.205782 6.508869 6.164076 6.091537 6.051002 12.76407 6.117411 6.006195 12.76407 6.046729 6.076877 12.76407 5.994963 6.076883 12.76407 5.950121 6.050998 12.76407 5.924236 6.006155 12.76407 5.924242 5.95439 12.76407 5.950116 5.909581 12.76407 5.994925 5.883708 12.76407 6.04669 5.883701 12.76407 6.091532 5.909587 12.76407 6.117418 5.954429 12.76407 1.776524 -1.743834 6.348187 -1.823476 -1.743837 6.34819 -1.823478 1.856164 6.348198 1.776522 1.856166 6.348196 1.776524 -1.743834 6.748188 -1.823475 -1.743837 6.74819 -1.823478 1.856164 6.748199 1.776522 1.856166 6.748195 3.335893 2.736333 -0.2074436 2.770206 3.302017 -0.2074441 3.788437 4.320254 -0.2074452 4.354124 3.75457 -0.2074443 3.335893 2.736333 1.392556 2.770206 3.302017 1.392556 3.788437 4.320254 1.392555 4.354124 3.75457 1.392555 -4.187838 3.719156 -0.2074556 -3.622154 4.284843 -0.2074552 -2.603918 3.266612 -0.2074562 -3.169602 2.700925 -0.2074562 -4.187838 3.719157 1.392544 -3.622154 4.284844 1.392545 -2.603918 3.266612 1.392544 -3.169602 2.700926 1.392544 -5.983441 6.006175 9.764099 -6.077171 6.069044 9.7641 -6.035341 6.128784 9.7641 -6.035341 6.128784 10.55126 -5.95756 6.051003 9.7641 -5.975601 6.170614 9.7641 -5.99158 6.162312 10.87748 -6.025292 6.138195 10.52622 -6.003364 6.155004 10.69203 -6.014785 6.146822 10.5016 -5.868554 5.77109 9.764098 -6.096051 5.998587 9.764099 -6.077171 6.069043 11.7641 -5.95756 5.909582 9.764099 -5.983442 5.95441 9.764099 -6.071579 6.080164 10.72659 -6.069597 6.083765 10.6722 -6.064267 6.092642 10.63499 -6.05091 6.11138 10.59369 -5.941194 5.777448 9.764098 -6.089694 5.925948 9.764099 -6.096051 5.998586 11.7641 -6.007308 5.808277 9.764098 -6.058865 5.859834 9.764099 -6.089694 5.925947 11.7641 -6.058865 5.859832 11.7641 -6.007308 5.808275 11.7641 -5.941194 5.777447 11.7641 -5.912732 5.883699 9.764099 -5.798098 5.78997 9.764098 -5.868554 5.77109 11.7641 -5.816138 5.909582 9.764099 -5.738357 5.831799 9.764099 -5.782118 5.798272 10.87748 -5.860967 5.883699 9.764099 -5.798098 5.789969 11.7641 -5.790256 5.95441 9.764099 -5.696528 5.89154 9.764099 -5.738357 5.831799 10.55126 -5.770335 5.80558 10.69203 -5.758913 5.813762 10.5016 -5.748405 5.822389 10.52622 -5.905144 6.189494 9.7641 -5.677649 5.961997 9.764099 -5.696528 5.891539 11.7641 -5.816139 6.051002 9.7641 -5.790256 6.006174 9.764099 -5.702119 5.880418 10.72659 -5.722788 5.849204 10.59369 -5.704102 5.876817 10.6722 -5.709431 5.86794 10.63499 -5.832505 6.183137 9.7641 -5.684004 6.034636 9.7641 -5.677649 5.961996 11.7641 -5.76639 6.152308 9.7641 -5.714833 6.100751 9.7641 -5.684004 6.034635 11.7641 -5.714833 6.10075 11.7641 -5.76639 6.152307 11.7641 -5.832505 6.183135 11.7641 -5.860967 6.076884 9.7641 -5.905144 6.189492 11.7641 -5.912731 6.076885 9.7641 -5.975601 6.170612 11.7641 -5.95756 6.051002 11.7641 -5.983441 6.006173 11.7641 -5.912731 6.076884 11.7641 -5.860967 6.076883 11.7641 -5.816139 6.051001 11.7641 -5.790256 6.006173 11.7641 -5.790256 5.954409 11.7641 -5.816138 5.90958 11.7641 -5.860967 5.883698 11.7641 -5.912732 5.883698 11.7641 -5.95756 5.90958 11.7641 -5.983442 5.954409 11.7641 -6.035341 6.128783 11.7641 -6.035341 6.128784 10.97693 -6.06698 6.088239 10.84969 -6.061992 6.096158 10.97506 -6.055791 6.105022 11.01171 -6.047487 6.115551 11.00959 -6.041584 6.122267 10.99335 -6.014381 6.147131 10.92635 -5.738357 5.831799 11.7641 -5.738357 5.831799 10.97693 -5.732115 5.838315 10.99335 -5.706718 5.872344 10.84969 -5.711706 5.864426 10.97506 -5.717907 5.855561 11.01171 -5.726211 5.845031 11.00959 -5.759316 5.813452 10.92635 -6.155297 6.218906 10.58966 -6.164844 6.212761 10.64105 -6.160861 6.215183 10.60971 -6.074923 6.085015 10.74122 -6.166633 6.212014 10.67888 -6.066265 6.09786 10.9501 -6.075939 6.088186 10.76217 -6.153264 6.225384 10.9386 -6.064611 6.097653 10.96415 -6.156297 6.22274 10.90526 -6.14225 6.233794 10.97128 -6.148332 6.229272 10.96183 -6.135949 6.238254 10.96553 -5.996697 6.167428 10.87748 -6.270633 6.547391 10.74104 -5.777001 5.793155 10.87748 -5.637749 5.72233 10.96553 -5.427279 5.308075 10.70329 -5.757654 5.812502 10.5016 -5.618401 5.741677 10.58965 -6.016045 6.148081 10.5016 -5.608853 5.747823 10.64106 -5.614554 5.744279 10.60158 -5.611296 5.746376 10.61911 -5.698774 5.875568 10.74121 -5.607015 5.748417 10.69196 -5.607393 5.748519 10.6659 -5.707434 5.862722 10.9501 -5.69776 5.872396 10.76216 -5.621897 5.734014 10.94768 -5.709087 5.86293 10.96415 -5.619182 5.736249 10.92835 -5.629346 5.728327 10.96979 -5.625364 5.731312 10.96182 -5.633573 5.725262 10.97105 -5.491933 5.398224 10.73174 -5.56881 5.634194 10.94083 -5.50078 5.560491 10.93353 -5.434363 5.499868 10.94098 -5.370323 5.451225 10.96079 -5.309268 5.413348 10.99062 -5.233667 5.029487 10.59394 -5.340808 5.160031 10.59288 -5.586257 5.566571 10.48123 -5.593561 5.573354 10.51142 -5.603236 5.56367 10.69944 -5.599185 5.554859 10.72275 -5.530457 5.452693 10.74273 -5.552515 5.484359 10.74524 -5.564296 5.501501 10.74474 -5.567468 5.506155 10.7443 -5.5804 5.525372 10.7406 -5.591095 5.541742 10.73375 -5.546901 5.616777 10.94298 -5.448492 5.518656 10.94335 -5.337231 5.435719 10.9798 -5.250811 5.384595 11.02884 -5.192128 5.362465 11.07588 -5.213248 5.375224 11.06149 -5.131218 5.344714 11.13142 -5.070726 5.330409 11.19085 -5.081584 5.338097 11.18315 -5.012544 5.318262 11.25009 -4.954716 5.306348 11.30918 -5.042879 4.776514 10.51392 -4.894751 5.292639 11.3687 -4.948296 5.310227 11.3188 -4.836091 5.276331 11.4232 -4.78096 5.25666 11.46883 -4.816511 5.275338 11.44349 -4.725022 5.231368 11.50827 -4.663929 5.197764 11.54364 -4.691222 5.219341 11.53266 -4.596553 5.154113 11.57417 -4.855121 4.548399 10.46198 -4.525303 5.101537 11.5982 -4.574783 5.144983 11.58681 -4.45929 5.048303 11.61464 -4.465369 5.059956 11.61819 -4.39858 4.996844 11.62655 -4.671595 4.34098 10.43124 -4.33685 4.942993 11.63669 -4.359797 4.969951 11.63822 -4.267704 4.880968 11.64585 -4.189486 4.808635 11.65342 -4.256314 4.877492 11.65241 -4.492665 4.152153 10.4185 -4.101826 4.724856 11.65841 -4.154788 4.782858 11.66128 -4.003142 4.627184 11.65972 -4.055125 4.686247 11.6652 -4.318681 3.980345 10.4213 -3.891727 4.512775 11.65586 -3.957219 4.587848 11.66457 -3.76632 4.379047 11.64515 -3.860948 4.487849 11.65977 -4.150522 3.823045 10.43527 -3.628224 4.226271 11.62626 -3.672763 4.283777 11.63932 -3.766177 4.386434 11.65122 -3.988487 3.678383 10.45762 -3.479063 4.055637 11.59863 -3.580551 4.18005 11.6245 -3.832859 3.544808 10.486 -3.318272 3.866611 11.56229 -3.399078 3.970048 11.58779 -3.48938 4.075419 11.60718 -3.541478 3.303903 10.55095 -3.141823 3.655269 11.51739 -3.309469 3.864097 11.56676 -3.683834 3.420249 10.51748 -3.277046 3.09228 10.61891 -2.946984 3.420937 11.46657 -3.131641 3.651043 11.52143 -3.405895 3.194906 10.58516 -3.220384 3.757711 11.5445 -3.153697 2.994662 10.65202 -2.750807 3.185291 11.41578 -2.865481 3.330967 11.45205 -2.954287 3.43759 11.47498 -3.043007 3.544284 11.49811 -2.915084 2.805904 10.71617 -2.576485 2.972107 11.36577 -2.688203 3.117468 11.40544 -3.034682 2.900605 10.68414 -2.776676 3.224348 11.42912 -2.662049 2.607937 10.78703 -2.428186 2.78339 11.31376 -2.513825 2.901683 11.35215 -2.792205 2.709105 10.74973 -2.600471 3.009999 11.38004 -2.520258 2.503006 10.83447 -2.300713 2.612523 11.25791 -2.345058 2.681646 11.28617 -2.428582 2.792298 11.32108 -2.28468 2.393075 10.99615 -2.191207 2.457011 11.19871 -2.263546 2.569568 11.24684 -2.303467 2.384135 10.96047 -2.324751 2.381223 10.92934 -2.346337 2.384799 10.90616 -2.365984 2.394333 10.89315 -2.275047 2.383012 10.96443 -2.184448 2.45572 11.20246 -2.305778 2.370349 10.90859 -2.339764 2.370875 10.86553 -2.371723 2.384508 10.84195 -2.701957 2.624527 10.72586 -3.022771 2.876823 10.63769 -3.342774 3.130066 10.55178 -3.660486 3.386419 10.47283 -3.972698 3.649767 10.40995 -4.275826 3.923862 10.37259 -4.566041 4.211795 10.36965 -4.840895 4.514389 10.40535 -5.099458 4.830759 10.47974 -5.552966 5.657662 10.56574 -5.527891 5.635804 10.57351 -5.427787 5.530077 10.56264 -5.407958 5.327458 10.32742 -5.481539 5.428886 10.36909 -5.489483 5.587938 10.55771 -5.573958 5.551729 10.45752 -5.557451 5.530657 10.43484 -5.547257 5.517333 10.42329 -5.54054 5.508468 10.41636 -5.520328 5.481495 10.39788 -4.816078 5.295449 11.04788 -5.148431 4.959003 10.18725 -5.324151 5.176338 10.27197 -4.88791 5.315001 10.98061 -4.972631 5.333417 10.89528 -5.06003 5.351709 10.80635 -5.136023 5.370613 10.73289 -5.200798 5.391644 10.6766 -5.257431 5.415838 10.63486 -5.311895 5.44542 10.60284 -5.368521 5.48301 10.57834 -4.474785 5.096189 11.23066 -4.882318 4.622961 10.09726 -5.08279 4.847091 10.15888 -4.538184 5.145391 11.21238 -4.599038 5.188295 11.18929 -4.65374 5.222514 11.16293 -4.70443 5.250071 11.13316 -4.756578 5.273944 11.09678 -4.190154 4.846716 11.27589 -4.62191 4.327229 10.05181 -4.824244 4.530716 10.08446 -4.27269 4.922351 11.26701 -4.345049 4.986551 11.25652 -4.410808 5.043158 11.24474 -3.992681 4.655493 11.28393 -4.37395 4.071901 10.04232 -4.549365 4.228174 10.04886 -4.097263 4.75855 11.28197 -3.740585 4.391453 11.26856 -4.137749 3.848373 10.05863 -4.259179 3.940229 10.05174 -3.874448 4.534297 11.28012 -3.588474 4.222598 11.24702 -3.914632 3.65061 10.09125 -3.956057 3.666174 10.08914 -3.414983 4.02286 11.21324 -3.704956 3.473114 10.13266 -3.213743 3.78427 11.16517 -3.508297 3.312029 10.17844 -3.643868 3.402848 10.15202 -2.986712 3.511143 11.10586 -3.324032 3.164299 10.22545 -2.766281 3.24643 11.04887 -3.151503 3.027582 10.27153 -3.326178 3.146517 10.23098 -2.990554 2.900365 10.31494 -3.006196 2.893303 10.3169 -2.577803 3.017072 10.99626 -2.837791 2.779405 10.35587 -2.685545 2.660372 10.39861 -2.419399 2.816484 10.94198 -2.524636 2.539375 10.44996 -2.685415 2.641011 10.40503 -2.286645 2.639149 10.88461 -2.346636 2.413681 10.51727 -2.171859 2.476359 10.82284 -2.326989 2.404146 10.53028 -2.355208 2.401022 10.52112 -2.305404 2.40057 10.55346 -2.32325 2.387389 10.5447 -2.28412 2.403482 10.58459 -2.289264 2.386863 10.58776 -2.265332 2.412422 10.62027 -2.165399 2.47477 10.83239 -2.258533 2.399526 10.6436 -2.155789 2.471476 10.86203 -2.159318 2.472864 10.84819 -2.244529 2.588587 10.87737 -2.326043 2.700667 10.9167 -2.494811 2.920708 10.98268 -2.409567 2.811321 10.95161 -2.581461 3.029024 11.01056 -2.846455 3.350015 11.08262 -2.669195 3.136494 11.03596 -2.75766 3.243385 11.05967 -3.024023 3.563305 11.12859 -2.935298 3.456612 11.10547 -3.290472 3.883139 11.19729 -3.112639 3.670083 11.15196 -3.20138 3.776755 11.17504 -3.470386 4.094466 11.23772 -3.380083 3.989092 11.21832 -3.653774 4.302826 11.26985 -3.561559 4.199098 11.25504 -3.74719 4.405485 11.28175 -3.938236 4.606902 11.29509 -3.841963 4.506902 11.2903 -4.036145 4.705302 11.29573 -4.135809 4.801915 11.2918 -4.237339 4.896549 11.28293 -4.340823 4.989011 11.26875 -4.446398 5.079014 11.24871 -4.555815 5.164037 11.21732 -4.672247 5.238385 11.16316 -4.797532 5.294373 11.07399 -4.929323 5.329255 10.94929 -5.062615 5.357126 10.81362 -5.194283 5.394258 10.69198 -5.318246 5.454756 10.6103 -5.429491 5.537688 10.57387 -5.617401 5.737844 10.90526 -5.607731 5.747523 10.71732 -5.551043 5.674093 10.69578 -5.545408 5.646264 10.88005 -5.533212 5.62867 10.90054 -2.249034 2.607679 10.99893 -2.274719 2.620248 11.19489 -2.159589 2.455984 11.13166 -2.161902 2.454873 11.1557 -2.149915 2.465658 10.94372 -2.268224 2.381677 10.89624 -2.360524 2.759117 11.05034 -2.409884 2.801602 11.25432 -2.32314 2.682466 11.24008 -2.241435 2.569701 11.20011 -2.49005 2.926584 11.09916 -2.459697 2.865972 11.27306 -2.406878 2.793756 11.27553 -2.512481 2.933012 11.2914 -2.492353 2.903723 11.30705 -2.537906 2.986685 11.11492 -2.56852 3.003067 11.30944 -2.588306 3.049174 11.13047 -2.627671 3.075981 11.32715 -2.579243 3.012561 11.33529 -2.641316 3.11416 11.14589 -2.690189 3.152148 11.34471 -2.667224 3.120493 11.36097 -2.696895 3.181657 11.16122 -2.756826 3.232606 11.3625 -2.755952 3.227772 11.38484 -2.755396 3.252196 11.17671 -2.808525 3.294705 11.37588 -2.81747 3.326704 11.19272 -2.860516 3.357027 11.38918 -2.845016 3.334721 11.40786 -2.865872 3.384714 11.20508 -2.913251 3.420258 11.40269 -2.914994 3.443638 11.21769 -2.96668 3.48447 11.41656 -2.934066 3.441628 11.43084 -2.964613 3.5033 11.23062 -3.019437 3.548005 11.43043 -3.015489 3.564578 11.244 -3.07039 3.609411 11.44389 -3.023025 3.548597 11.45401 -3.0665 3.626056 11.25747 -3.120141 3.669342 11.45698 -3.111912 3.655656 11.4774 -3.116384 3.686138 11.2706 -3.168789 3.727849 11.46967 -3.212914 3.802042 11.29553 -3.231681 3.803248 11.48577 -3.20091 3.762661 11.50057 -3.164995 3.744585 11.28325 -3.274889 3.876024 11.31098 -3.292115 3.875335 11.50076 -3.290255 3.869412 11.52297 -3.333831 3.945939 11.3251 -3.350551 3.944591 11.51469 -3.390076 4.012158 11.33794 -3.407535 4.011606 11.5276 -3.380134 3.975755 11.54416 -3.444092 4.075215 11.34957 -3.462944 4.0762 11.53941 -3.495994 4.135247 11.36003 -3.516893 4.138478 11.55013 -3.470715 4.081543 11.56373 -3.545707 4.192176 11.36932 -3.569512 4.198577 11.55976 -3.562179 4.186614 11.58124 -3.684067 4.347313 11.39091 -3.620732 4.256418 11.56828 -3.670565 4.312019 11.5757 -3.654698 4.290803 11.59625 -3.811441 4.46528 11.59164 -3.748437 4.393942 11.60835 -3.918359 4.597018 11.41074 -3.936919 4.596459 11.59898 -3.843551 4.495859 11.61711 -3.807638 4.481207 11.40419 -4.017756 4.697402 11.41202 -4.047183 4.707258 11.59967 -3.940187 4.596373 11.6221 -4.107099 4.784613 11.40927 -4.144363 4.801281 11.59561 -4.138559 4.792452 11.61915 -4.038482 4.6953 11.62291 -4.187708 4.860782 11.40356 -4.230386 4.881595 11.58826 -4.260314 4.92731 11.39574 -4.30615 4.950032 11.57883 -4.240527 4.887632 11.61042 -4.325042 4.984945 11.38661 -4.372838 5.008474 11.56822 -4.34448 4.980642 11.59633 -4.383928 5.036002 11.37654 -4.43726 5.063282 11.55585 -4.496935 5.12911 11.35093 -4.507446 5.12009 11.53863 -4.45059 5.071254 11.57639 -4.440567 5.083745 11.36509 -4.552713 5.170961 11.33301 -4.583879 5.176438 11.51279 -4.560951 5.157324 11.54513 -4.605646 5.207183 11.31151 -4.656182 5.222805 11.47941 -4.699296 5.261389 11.26075 -4.721579 5.25796 11.4405 -4.679003 5.23317 11.49082 -4.653873 5.236773 11.28752 -4.745877 5.283152 11.22881 -4.781892 5.284173 11.39662 -4.797645 5.303049 11.1878 -4.842753 5.304562 11.34454 -4.806815 5.290844 11.40057 -4.857942 5.321157 11.13351 -4.907238 5.321316 11.28312 -4.928194 5.337855 11.0646 -4.970206 5.334997 11.21969 -4.940541 5.326581 11.27447 -5.005391 5.353835 10.98582 -5.031254 5.347494 11.15721 -5.079756 5.369854 10.91074 -5.09352 5.361139 11.09465 -5.074108 5.354496 11.13851 -5.143661 5.386422 10.84982 -5.157335 5.377923 11.03412 -5.198733 5.404522 10.80225 -5.219002 5.398881 10.98174 -5.204424 5.390998 11.01779 -5.247313 5.424843 10.76588 -5.27864 5.425839 10.93969 -5.293456 5.448818 10.73736 -5.340567 5.462057 10.90661 -5.326134 5.450084 10.93721 -5.390601 5.514867 10.69734 -5.406125 5.509865 10.88376 -5.340919 5.478402 10.71435 -5.4424 5.559096 10.6876 -5.474702 5.570814 10.87395 -5.435823 5.531663 10.90103 -5.496029 5.611922 10.68657 -5.521051 5.640846 10.66415 -5.423672 5.543846 10.66464 -5.313999 5.462271 10.7008 -5.192304 5.403182 10.78136 -5.061988 5.366674 10.90207 -4.928418 5.338759 11.03804 -4.79468 5.30303 11.16416 -4.666879 5.245364 11.25441 -4.548833 5.169527 11.30872 -4.438471 5.083464 11.33999 -4.332357 4.992853 11.35994 -4.228402 4.899839 11.37402 -4.126431 4.804658 11.38276 -4.026353 4.707506 11.38652 -3.928055 4.608576 11.38571 -3.831417 4.508061 11.38072 -3.7363 4.406144 11.37197 -3.64256 4.303003 11.35987 -3.550038 4.198812 11.34485 -3.458571 4.093739 11.32734 -3.367989 3.987949 11.30777 -3.278108 3.881604 11.28658 -3.188757 3.774854 11.26419 -3.099762 3.667845 11.24101 -3.010894 3.560765 11.21758 -2.921921 3.453798 11.19442 -2.832837 3.346917 11.17152 -2.743788 3.239958 11.14847 -2.655067 3.132669 11.12457 -2.567082 3.024736 11.0989 -2.48019 2.915897 11.07066 -2.310975 2.694637 11.00369 -2.394714 2.805928 11.03914 -2.229268 2.58187 10.96372 -2.25855 2.39135 10.7083 -2.149643 2.467133 10.91752 -2.300979 2.36818 10.83673 -2.17092 2.454296 11.19044 -2.164701 2.45444 11.17152 -5.521323 5.640811 10.63806 -5.424868 5.542501 10.6136 -5.522628 5.639914 10.61315 -2.291305 2.377853 10.64879 -2.327529 2.378414 10.60289 -2.337203 2.36874 10.79083 -2.371267 2.383272 10.7657 -2.361593 2.392946 10.57776 -2.532799 2.496579 10.70364 -2.548081 2.524525 10.5071 -5.467164 5.371326 10.4141 -5.403427 5.250399 10.55335 -5.336034 5.175451 10.33079 -5.201943 4.964924 10.44526 -5.058382 4.799011 10.20366 -5.001671 4.705979 10.36976 -4.780032 4.464231 10.13105 -4.806818 4.474074 10.32208 -4.616598 4.264161 10.29674 -4.514063 4.176675 10.10327 -4.431271 4.073459 10.28982 -4.260594 3.927341 10.10859 -4.251848 3.900367 10.29796 -4.021006 3.709303 10.13631 -4.078903 3.742389 10.31722 -3.913044 3.597332 10.34399 -3.79604 3.515842 10.17685 -3.754224 3.463069 10.37559 -3.585652 3.341899 10.22375 -3.602706 3.338239 10.40993 -3.458518 3.221652 10.44545 -3.389173 3.18355 10.27282 -3.321804 3.112498 10.48091 -3.205721 3.037809 10.32134 -3.191608 3.009321 10.51568 -3.035294 2.903138 10.36736 -3.066996 2.910867 10.54934 -2.942456 2.812381 10.58287 -2.874698 2.776072 10.4105 -2.815121 2.711765 10.61725 -2.715737 2.651395 10.45462 -2.679992 2.60674 10.65599 -6.236301 6.499262 10.75412 -6.207453 6.32942 10.94023 -6.277005 6.40415 10.93357 -6.344871 6.465299 10.94221 -6.410176 6.513975 10.96361 -6.382136 6.726867 10.65357 -6.407343 6.777181 10.61316 -6.198937 6.406796 10.45044 -6.180137 6.38723 10.51143 -6.170462 6.396905 10.69939 -6.174328 6.406227 10.72886 -6.187669 6.393614 10.47545 -6.188997 6.395083 10.47183 -6.22613 6.484758 10.75605 -6.213026 6.465836 10.75665 -6.196535 6.441475 10.75307 -6.194553 6.438488 10.75216 -6.183565 6.421538 10.74409 -6.17563 6.408516 10.73205 -6.231516 6.345177 10.94282 -6.333199 6.445412 10.94468 -6.472243 6.551489 10.99521 -6.448446 6.529109 10.98528 -6.531775 6.579707 11.0355 -6.514822 6.921606 10.57372 -6.592469 6.601583 11.08545 -6.576837 6.588345 11.07428 -6.655164 6.619044 11.14366 -6.716404 6.63302 11.20448 -6.712644 6.624256 11.20282 -6.77556 6.645209 11.26492 -6.834765 6.657599 11.32517 -6.671919 7.131663 10.50557 -6.897136 6.672517 11.38623 -6.849918 6.653026 11.34245 -6.965439 6.693584 11.44702 -7.039731 6.72493 11.50228 -6.985133 6.692645 11.46543 -7.117404 6.767653 11.54725 -7.112471 6.755638 11.54826 -6.850467 7.34986 10.45455 -7.197589 6.821213 11.58152 -7.282064 6.885965 11.6069 -7.230496 6.8359 11.59686 -7.369501 6.958774 11.62572 -7.341958 6.925377 11.62516 -7.03975 7.5625 10.4245 -7.459253 7.036732 11.6409 -7.450341 7.018612 11.64464 -7.556984 7.124602 11.65359 -7.556845 7.114023 11.65892 -7.222396 7.752733 10.41474 -7.665711 7.226168 11.66281 -7.66148 7.211503 11.66813 -7.783592 7.340811 11.66697 -7.7643 7.31091 11.67252 -7.392544 7.919838 10.41865 -7.910256 7.469242 11.6647 -7.865364 7.412104 11.67235 -7.54988 8.067317 10.43134 -8.046071 7.612876 11.65464 -7.964742 7.514947 11.6679 -7.695661 8.198869 10.44965 -8.191633 7.773385 11.63541 -8.06252 7.619304 11.65943 -7.831165 8.317482 10.47138 -8.347671 7.952522 11.60568 -8.253651 7.832015 11.63166 -8.158788 7.725037 11.64726 -8.074663 8.523585 10.51951 -8.514873 8.151818 11.56439 -8.439596 8.049195 11.59147 -7.95729 8.425231 10.49503 -8.347214 7.940109 11.61297 -8.28525 8.696474 10.56802 -8.694146 8.372634 11.51093 -8.530915 8.159148 11.5675 -8.183975 8.613832 10.54404 -8.542 8.902918 10.63276 -8.887201 8.616648 11.44535 -8.710876 8.381184 11.51335 -8.463813 8.840414 10.61258 -8.378469 8.771859 10.59097 -8.621299 8.269848 11.54135 -8.821998 9.12558 10.70654 -9.096691 8.885684 11.36873 -8.976104 8.71788 11.42139 -8.753174 9.070913 10.68832 -8.684581 9.016424 10.67018 -8.614878 8.960991 10.65181 -8.888143 8.605308 11.45306 -8.799779 8.493041 11.48382 -9.099732 9.343512 10.7835 -9.326237 9.181205 11.28383 -9.151365 8.943518 11.35656 -9.031374 9.290748 10.76343 -8.961584 9.236114 10.74393 -8.891562 9.180783 10.72502 -9.063798 8.830652 11.38912 -9.489018 9.567508 10.9962 -9.581194 9.504458 11.19595 -9.414662 9.281657 11.26026 -9.470232 9.576448 10.96052 -9.448948 9.57936 10.92938 -9.427362 9.575784 10.90621 -9.407715 9.566249 10.8932 -9.318617 9.504842 10.85756 -9.240006 9.448512 10.82889 -9.168292 9.395463 10.80487 -9.32666 9.169123 11.29182 -9.23894 9.056376 11.32403 -9.498651 9.57757 10.96448 -9.591913 9.505957 11.20028 -9.503079 9.393873 11.22963 -9.46792 9.590233 10.90864 -9.433935 9.589708 10.86558 -9.404211 9.571966 10.87323 -9.125907 9.371855 10.77261 -8.855534 9.160739 10.69635 -8.586954 8.947298 10.6254 -8.319291 8.73266 10.55716 -8.053964 8.515055 10.49575 -7.792469 8.292739 10.44533 -7.536444 8.064025 10.41018 -7.287686 7.827333 10.39466 -7.048184 7.581252 10.40312 -6.8201 7.324634 10.43984 -6.605721 7.05671 10.50874 -9.600543 9.485111 10.82007 -9.44671 9.556437 10.53033 -9.427062 9.546902 10.51732 -9.422821 9.553355 10.51166 -9.514093 9.37589 10.84938 -9.314863 9.469199 10.47293 -9.144515 9.353241 10.41104 -9.468296 9.560012 10.55351 -9.450448 9.573194 10.54475 -9.418492 9.559561 10.52117 -9.489579 9.5571 10.58464 -9.484435 9.573719 10.58781 -9.508366 9.54816 10.62032 -9.610575 9.487293 10.83771 -9.515165 9.561057 10.64365 -9.617262 9.489363 10.86027 -9.521688 9.375259 10.86806 -9.430294 9.269598 10.87832 -9.219339 9.39974 10.43939 -9.349143 9.166235 10.9069 -9.433267 9.263038 10.89869 -9.132811 9.334652 10.4118 -9.270746 9.065804 10.93525 -9.345264 9.150503 10.93025 -8.96315 9.202765 10.36319 -9.195129 8.968304 10.96341 -9.257541 9.037753 10.96246 -9.048513 9.269683 10.38692 -8.877662 9.135077 10.34028 -9.103866 8.85054 10.99751 -9.169964 8.924892 10.99499 -8.792956 9.067795 10.31786 -9.015719 8.737222 11.0299 -9.082395 8.812023 11.02755 -8.709074 9.001162 10.29566 -8.930943 8.62844 11.06079 -8.994699 8.699249 11.05982 -8.533528 8.861356 10.24967 -8.849593 8.524779 11.08951 -8.906736 8.586673 11.09149 -8.623807 8.933352 10.2732 -8.43457 8.782077 10.22435 -8.771727 8.426352 11.11596 -8.818368 8.474402 11.12225 -8.324415 8.693203 10.19696 -8.697224 8.332983 11.14024 -8.729464 8.362544 11.15179 -8.626008 8.2447 11.1622 -8.639883 8.251205 11.17979 -8.202426 8.593767 10.16794 -8.558159 8.161576 11.18186 -7.9228 8.360169 10.1087 -8.314 7.871493 11.24095 -8.549497 8.140501 11.20593 -8.068678 8.483168 10.13815 -7.763927 8.222717 10.08114 -8.107246 7.638983 11.2741 -8.272224 7.813362 11.2701 -8.458174 8.030547 11.22991 -8.365791 7.921459 11.2514 -7.590607 8.067608 10.0577 -7.931066 7.451399 11.28877 -8.081088 7.600646 11.29787 -8.177359 7.706381 11.28569 -7.399487 7.888775 10.04189 -7.780565 7.299363 11.29074 -7.883925 7.393443 11.31078 -7.983306 7.496288 11.30633 -7.18851 7.679326 10.03992 -7.651632 7.17516 11.28465 -7.782858 7.292247 11.31095 -6.964401 7.438953 10.06085 -7.540709 7.07286 11.27356 -7.575397 7.09536 11.29734 -7.680036 7.19284 11.30655 -7.446228 6.98897 11.25993 -7.468894 6.999943 11.28308 -7.364242 6.918613 11.24496 -6.748615 7.18468 10.11037 -7.284807 6.853369 11.2267 -7.36049 6.906729 11.26353 -7.205958 6.794028 11.2016 -7.24904 6.81724 11.23527 -7.133657 6.746405 11.16984 -6.56394 6.943497 10.18309 -7.069416 6.710691 11.13313 -7.131024 6.736989 11.18667 -7.002534 6.680801 11.08553 -6.920235 6.654225 11.01382 -7.003717 6.67399 11.10392 -6.815742 6.630169 10.91031 -6.868497 6.634406 10.98085 -6.413024 6.724927 10.27015 -6.704638 6.606801 10.79741 -6.731218 6.605638 10.84121 -6.611837 6.582253 10.70958 -6.535323 6.55362 10.64797 -6.595411 6.569715 10.71268 -6.289981 6.528043 10.36517 -6.466227 6.51783 10.60511 -6.394153 6.469454 10.57461 -6.467029 6.51048 10.6237 -6.317837 6.405359 10.55888 -6.351796 6.426789 10.58311 -6.238055 6.323022 10.56217 -6.250121 6.326559 10.58125 -6.254829 6.479806 10.3868 -6.21106 6.421953 10.43125 -6.21314 6.42461 10.42841 -6.230584 6.447335 10.40804 -6.24469 6.466127 10.3949 -6.425947 6.75856 10.2516 -6.624321 7.038085 10.14717 -6.838697 7.306007 10.07827 -7.06678 7.562624 10.04155 -7.306283 7.808708 10.03308 -7.55504 8.045403 10.04861 -7.811069 8.274119 10.08376 -8.072565 8.496436 10.13417 -8.337895 8.714042 10.19559 -8.605558 8.928681 10.26382 -8.874141 9.142124 10.33478 -6.165967 6.21306 10.71732 -6.229105 6.315272 10.87988 -6.241998 6.336076 10.91035 -6.244607 6.312321 10.69079 -9.563425 9.419294 10.96342 -9.55883 9.435355 11.14968 -9.614109 9.504599 11.13171 -9.61002 9.506086 11.16592 -9.623784 9.494925 10.94377 -9.505475 9.578906 10.89629 -9.504799 9.367213 11.16784 -9.520739 9.393836 11.19473 -9.504515 9.344934 10.9833 -9.451972 9.3002 11.18609 -9.446996 9.271884 11.00329 -9.400307 9.234344 11.20435 -9.432104 9.28142 11.22534 -9.390817 9.200175 11.02327 -9.349785 9.169692 11.22253 -9.335934 9.129842 11.04315 -9.288216 9.090639 11.24503 -9.343888 9.168668 11.25691 -9.282343 9.060967 11.06282 -9.22824 9.013434 11.2672 -9.255958 9.055683 11.28915 -9.229978 8.993536 11.08221 -9.169679 8.937952 11.28898 -9.168174 8.942568 11.32175 -9.170316 8.916625 11.1044 -9.112527 8.864268 11.31025 -9.112065 8.841532 11.12608 -9.056738 8.792404 11.33093 -9.080401 8.829427 11.35439 -9.055113 8.76819 11.14717 -9.002177 8.722249 11.351 -8.999475 8.696685 11.16758 -8.94876 8.653751 11.37041 -8.9925 8.716362 11.38677 -8.94521 8.627158 11.18722 -8.896524 8.587008 11.38907 -8.90433 8.603482 11.41857 -8.892387 8.559735 11.20601 -8.845372 8.521932 11.40699 -8.830929 8.48169 11.22735 -8.795197 8.458423 11.42415 -8.815755 8.490889 11.44948 -8.771475 8.40668 11.24737 -8.746035 8.396552 11.4405 -8.713985 8.334677 11.26605 -8.697846 8.336288 11.45604 -8.726637 8.378691 11.47917 -8.658463 8.2657 11.28336 -8.634938 8.258255 11.4755 -8.636842 8.267001 11.50735 -8.605017 8.199871 11.2993 -8.573544 8.182867 11.49351 -8.540773 8.121553 11.3174 -8.513636 8.1101 11.51006 -8.546233 8.155931 11.53368 -8.478989 8.047138 11.33366 -8.455093 8.039813 11.52517 -8.454682 8.045597 11.55785 -8.419873 7.976823 11.34807 -8.397954 7.972046 11.53885 -8.363079 7.910137 11.3608 -8.342137 7.906684 11.55113 -8.362061 7.936118 11.57954 -8.2907 7.826446 11.37536 -8.28762 7.84368 11.56205 -8.234414 7.783018 11.57164 -8.268246 7.827619 11.59843 -8.222144 7.74857 11.38735 -8.182419 7.724553 11.57997 -8.095186 7.608134 11.40469 -8.033752 7.562013 11.59782 -8.173123 7.720225 11.61422 -8.156972 7.675855 11.39705 -7.980598 7.485779 11.41468 -7.89533 7.417092 11.60618 -7.978513 7.509284 11.63524 -8.036386 7.544817 11.4105 -8.07658 7.614069 11.62659 -7.828979 7.330533 11.41935 -7.766595 7.288042 11.60659 -7.878831 7.406006 11.63986 -7.698546 7.203163 11.41541 -7.647098 7.173263 11.60052 -7.674292 7.204526 11.63593 -7.777449 7.304374 11.64019 -7.5858 7.097708 11.40602 -7.538048 7.072736 11.58955 -7.569304 7.106606 11.62683 -7.488561 7.010204 11.3935 -7.440507 6.986212 11.57537 -7.462428 7.010756 11.61264 -7.405438 6.937913 11.37956 -7.348952 6.9079 11.55833 -7.353648 6.917076 11.59321 -7.328327 6.873071 11.36377 -7.258976 6.835135 11.53618 -7.251141 6.812113 11.34288 -7.17264 6.772717 11.5054 -7.241557 6.826884 11.56503 -7.109282 6.717962 11.28149 -7.089535 6.722045 11.46366 -7.122413 6.745495 11.51644 -7.175961 6.758821 11.31472 -7.046434 6.685759 11.24206 -7.008716 6.683167 11.40969 -6.975689 6.657397 11.18752 -6.933247 6.656661 11.34668 -6.993232 6.681119 11.43303 -6.887374 6.6322 11.1063 -6.865464 6.638976 11.28222 -6.781212 6.60932 10.99913 -6.802995 6.625419 11.21927 -6.856217 6.640611 11.30886 -6.742177 6.612977 11.15702 -6.67815 6.586923 10.89532 -6.680109 6.599384 11.09464 -6.718475 6.611713 11.1688 -6.616439 6.582658 11.03423 -6.594474 6.562973 10.81847 -6.554773 6.561725 10.98182 -6.583523 6.576215 11.04082 -6.525365 6.535265 10.76519 -6.495309 6.534882 10.93984 -6.46069 6.500205 10.72708 -6.433512 6.498791 10.90676 -6.456888 6.518063 10.95269 -6.392528 6.453099 10.69998 -6.36807 6.451137 10.88387 -6.32023 6.3912 10.6866 -6.299618 6.390389 10.87396 -6.342888 6.435441 10.91231 -6.255361 6.3227 10.65063 -6.356243 6.422061 10.65258 -6.47023 6.504677 10.69295 -6.596856 6.562829 10.78107 -6.731808 6.598338 10.90904 -6.869553 6.627233 11.04911 -7.006574 6.667706 11.17335 -7.135725 6.732088 11.2567 -7.254859 6.813466 11.30528 -7.366939 6.903675 11.33343 -7.475738 6.997329 11.35292 -7.582613 7.093184 11.3671 -7.687606 7.191104 11.3762 -7.790764 7.290952 11.38046 -7.892151 7.392587 11.38014 -7.991836 7.495867 11.37552 -8.089905 7.600655 11.36687 -8.18645 7.706811 11.3545 -8.281578 7.814206 11.33872 -8.375394 7.922709 11.31982 -8.46802 8.03219 11.29813 -8.559574 8.142527 11.27396 -8.650183 8.2536 11.24763 -8.739982 8.365294 11.21946 -8.829102 8.477493 11.18976 -8.91768 8.590089 11.15885 -9.005851 8.702974 11.12705 -9.093755 8.81604 11.09467 -9.181531 8.929184 11.06203 -9.269317 9.042303 11.02943 -9.35725 9.15529 10.99719 -9.445467 9.268045 10.96561 -9.534106 9.380464 10.93501 -9.623456 9.49265 10.90489 -9.515149 9.569232 10.70835 -9.47272 9.592404 10.83677 -9.60237 9.506552 11.18969 -9.608673 9.506258 11.17202 -9.482394 9.58273 10.64884 -9.446169 9.582169 10.60294 -9.436496 9.591842 10.79088 -9.402432 9.577311 10.76574 -9.401352 9.577954 10.80418 -9.412106 9.567638 10.57781 -9.313108 9.515806 10.72995 -9.116903 9.3732 10.70162 -9.401976 9.576074 10.842 -9.300058 9.490037 10.53348 -9.414721 9.564585 10.54445 -6.284787 6.569013 10.41218 -6.265511 6.562695 10.60834 -6.378567 6.743414 10.52127 -6.3551 6.709271 10.57565 -6.411123 6.768461 10.3181 -6.513056 6.939826 10.44159 -6.56586 6.989565 10.23269 -6.671468 7.150795 10.37396 -6.553771 6.997904 10.45989 -6.754586 7.23279 10.16256 -6.851202 7.369306 10.32406 -6.769626 7.274387 10.38187 -6.972604 7.486465 10.11668 -7.040792 7.581073 10.29552 -7.00023 7.538912 10.33823 -7.195174 7.722712 10.09908 -7.22267 7.770019 10.28643 -7.403241 7.927751 10.10298 -7.392306 7.93622 10.29085 -7.243122 7.792208 10.32484 -7.54918 8.0829 10.30397 -7.495966 8.035437 10.33722 -7.591522 8.103036 10.11971 -7.694392 8.213705 10.32251 -7.762588 8.255586 10.14354 -7.829358 8.331709 10.34434 -7.756614 8.270069 10.37069 -7.919502 8.390995 10.17121 -7.954971 8.438947 10.36798 -8.063607 8.512273 10.20059 -8.071914 8.536904 10.39242 -8.023121 8.497767 10.42064 -8.195745 8.621402 10.2302 -8.180791 8.626749 10.41691 -8.281649 8.70901 10.44084 -8.316221 8.719521 10.25897 -8.374473 8.78405 10.46372 -8.29373 8.720319 10.48248 -8.424976 8.807215 10.28607 -8.459457 8.852306 10.48525 -8.522749 8.885519 10.31112 -8.537301 8.914534 10.50535 -8.612137 8.95679 10.33444 -8.609953 8.972426 10.52434 -8.566832 8.939579 10.55176 -8.696761 9.024086 10.35673 -8.679495 9.027728 10.54267 -8.74792 9.08208 10.56077 -8.780158 9.090327 10.37881 -8.816579 9.136611 10.57896 -8.864408 9.157238 10.40112 -8.886007 9.19172 10.59738 -8.840918 9.157439 10.62412 -8.949448 9.22456 10.42392 -8.955944 9.246973 10.61628 -9.034387 9.291124 10.44757 -9.025653 9.301527 10.63578 -9.118352 9.355807 10.47239 -9.094014 9.354282 10.65586 -9.162616 9.40625 10.67727 -9.204673 9.420705 10.49995 -9.234401 9.459351 10.70131 -9.130262 9.359823 10.4419 -8.854268 9.144054 10.36439 -8.58017 8.926186 10.29203 -8.307059 8.706918 10.22275 -8.03644 8.484356 10.1609 -7.769927 8.256649 10.11096 -7.50927 8.022009 10.07749 -7.256419 7.778769 10.06512 -7.013522 7.52546 10.07851 -6.782917 7.260924 10.12217 -6.567064 6.984433 10.2002 -6.368398 6.695792 10.31598 -6.390841 6.718968 10.28046 -6.374349 6.735512 10.60123 -9.119863 9.373087 10.74017 -8.846002 9.159083 10.66314 -8.573996 8.942894 10.59131 -8.302952 8.725386 10.52242 -8.03434 8.504712 10.46073 -7.769729 8.279059 10.41059 -7.510829 8.046681 10.37646 -7.259526 7.805941 10.36286 -7.017909 7.555397 10.37434 -6.788247 7.29389 10.41532 -6.572932 7.020673 10.48983 -9.600111 9.506515 11.19349 -9.513235 9.394485 11.21882 -6.237282 6.340246 10.93349 -9.424684 9.282145 11.24943 -9.336551 9.169478 11.281 -9.248702 9.056585 11.31322 -9.160999 8.943569 11.3458 -9.073306 8.830534 11.37841 -8.985484 8.717583 11.41074 -8.897397 8.604822 11.44249 -8.808904 8.492355 11.47334 -8.719869 8.38029 11.50298 -8.630158 8.268739 11.53108 -8.539638 8.157812 11.55734 -8.448178 8.047628 11.58143 -8.355649 7.938302 11.60305 -8.261935 7.829962 11.62187 -8.166913 7.72273 11.63758 -8.070478 7.61674 11.64987 -7.972525 7.512122 11.65845 -7.872961 7.409014 11.66301 -7.771704 7.307553 11.66327 -7.668681 7.207879 11.65896 -7.56383 7.11013 11.64982 -7.457101 7.014453 11.6356 -7.348477 6.920948 11.61615 -7.236634 6.831036 11.58792 -7.117935 6.750091 11.53933 -6.989488 6.686262 11.45616 -6.853196 6.646107 11.33247 -6.715641 6.617262 11.19258 -6.580345 6.581601 11.06437 -6.453 6.523015 10.97589 -6.338494 6.439962 10.93541 -8.862507 9.142563 10.34232 -9.136372 9.356569 10.41935 -8.590498 8.926372 10.27049 -8.31945 8.708861 10.2016 -8.050835 8.488183 10.13991 -7.786221 8.262527 10.08978 -7.527317 8.030144 10.05565 -7.276012 7.789402 10.04206 -7.034393 7.538855 10.05355 -6.804731 7.277345 10.09453 -6.58942 7.004129 10.16905 -9.622841 9.49209 10.89676 -9.618916 9.490007 10.86824 -9.529745 9.37797 10.89804 -6.253788 6.323726 10.61271 -9.441189 9.265627 10.92865 -9.353055 9.152956 10.96022 -9.265203 9.04006 10.99245 -9.177498 8.927042 11.02502 -9.089803 8.814004 11.05763 -9.001979 8.701051 11.08997 -8.913888 8.588287 11.12172 -8.825393 8.475816 11.15257 -8.736357 8.363751 11.1822 -8.646644 8.252196 11.21031 -8.55612 8.141265 11.23657 -8.464657 8.031078 11.26066 -8.372127 7.92175 11.28228 -8.278408 7.813407 11.3011 -8.183384 7.706174 11.31681 -8.086945 7.600181 11.3291 -7.988989 7.495561 11.33767 -7.889423 7.392452 11.34223 -7.788163 7.29099 11.34249 -7.685136 7.191314 11.33818 -7.580283 7.093566 11.32904 -7.473554 6.997883 11.31482 -7.36491 6.904403 11.29531 -7.253079 6.814475 11.26712 -7.134388 6.733542 11.21853 -7.005972 6.669707 11.13543 -6.869675 6.629588 11.01166 -6.732116 6.600743 10.87176 -6.59682 6.565071 10.74356 -6.469484 6.506487 10.65509 -6.354992 6.423439 10.61463 -2.177419 2.454763 11.19985 -2.172883 2.454383 11.19411 -2.256651 2.568885 11.24419 -2.250295 2.568534 11.23498 -2.245031 2.568708 11.2199 -5.42379 5.543648 10.63853 -5.53582 5.626299 10.91984 -5.539132 5.623395 10.93391 -5.542913 5.620148 10.94181 -2.326711 2.681388 11.2598 -2.41042 2.792599 11.29519 -2.495864 2.902495 11.32665 -2.582724 3.01127 11.35485 -2.670674 3.119146 11.3805 -2.759371 3.226377 11.40435 -2.848404 3.333287 11.42735 -2.937427 3.440162 11.45033 -3.02636 3.5471 11.4735 -3.115218 3.654125 11.49687 -3.204187 3.761091 11.52004 -3.293502 3.8678 11.54242 -3.383347 3.974097 11.56359 -3.473895 4.079834 11.58314 -3.565323 4.184853 11.60062 -3.657805 4.288986 11.61562 -3.751503 4.392066 11.62769 -3.846575 4.493922 11.63642 -3.943165 4.594373 11.64139 -4.041411 4.693235 11.64219 -4.141434 4.79032 11.6384 -4.243346 4.885432 11.62966 -4.347239 4.978374 11.61556 -4.453279 5.068909 11.59561 -4.563513 5.154845 11.56435 -4.681342 5.230496 11.51007 -4.808803 5.28795 11.41998 -4.94226 5.323576 11.29409 -5.075796 5.351485 11.15817 -5.206312 5.388072 11.0373 -5.328355 5.447356 10.95654 -5.438278 5.529129 10.92031 -2.331931 2.681056 11.27472 -2.415592 2.79212 11.30999 -2.500983 2.901881 11.34135 -2.587786 3.010535 11.36947 -2.67568 3.118304 11.39504 -2.764317 3.225442 11.41885 -2.853291 3.332275 11.44183 -2.942256 3.439084 11.4648 -3.031133 3.545957 11.48796 -3.119932 3.652913 11.51132 -3.208842 3.759801 11.53446 -3.298097 3.866425 11.55681 -3.38788 3.972631 11.57794 -3.478363 4.078273 11.59745 -3.569724 4.183189 11.61489 -3.662136 4.287217 11.62984 -3.75576 4.390186 11.64187 -3.850752 4.491926 11.65055 -3.947259 4.592258 11.65548 -4.045415 4.690999 11.65623 -4.145345 4.78796 11.65241 -4.247155 4.882946 11.64363 -4.35094 4.97576 11.62951 -4.45686 5.066158 11.60954 -4.56688 5.151857 11.57824 -4.684348 5.227171 11.524 -4.811242 5.284242 11.43415 -4.944255 5.319673 11.30857 -5.077723 5.34757 11.17272 -5.208537 5.384297 11.05165 -5.331089 5.443897 10.97064 -5.441362 5.525976 10.93436 -2.338229 2.681199 11.28374 -2.421826 2.792069 11.31884 -2.507148 2.901654 11.35006 -2.593878 3.010149 11.37807 -2.681695 3.117776 11.40356 -2.770256 3.224793 11.42731 -2.85915 3.331525 11.45027 -2.94804 3.438246 11.47321 -3.036843 3.545036 11.49636 -3.125566 3.6519 11.5197 -3.214396 3.758684 11.54281 -3.303572 3.865196 11.56512 -3.393274 3.971282 11.5862 -3.483671 4.076797 11.60566 -3.574944 4.181581 11.62304 -3.667262 4.285467 11.63793 -3.760788 4.38829 11.6499 -3.855677 4.489879 11.65852 -3.952074 4.590054 11.66338 -4.050114 4.688635 11.66408 -4.149919 4.785433 11.66021 -4.251596 4.880255 11.65139 -4.355241 4.972903 11.63724 -4.460999 5.063117 11.61723 -4.57074 5.148505 11.5859 -4.687733 5.223375 11.53169 -4.813886 5.279946 11.44215 -4.946326 5.315122 11.31699 -5.079706 5.343006 11.18123 -5.210909 5.379917 11.0599 -5.33412 5.439931 10.97858 -5.444849 5.522406 10.94222 -2.151086 2.46889 10.89296 -5.314611 5.460426 10.64986 -2.15438 2.470836 10.8691 -5.313884 5.461878 10.67474 -2.230529 2.583213 10.93812 -2.233786 2.585047 10.91422 -2.238601 2.586936 10.89351 -5.524869 5.638207 10.59113 -5.191855 5.402593 10.75548 -5.06134 5.366001 10.87634 -4.927801 5.33809 11.01227 -4.794333 5.302473 11.13818 -4.666882 5.245027 11.22827 -4.549059 5.169385 11.28255 -4.438825 5.083456 11.31382 -4.332779 4.992919 11.33378 -4.228884 4.899976 11.34787 -4.12697 4.804862 11.35662 -4.026944 4.707777 11.36041 -3.928696 4.608913 11.35961 -3.832103 4.50846 11.35465 -3.73703 4.406604 11.34592 -3.643329 4.303522 11.33384 -3.550846 4.199388 11.31885 -3.459415 4.094367 11.30136 -3.368866 3.988627 11.28181 -3.279018 3.882328 11.26064 -3.189697 3.775621 11.23827 -3.100731 3.668651 11.2151 -3.011891 3.561605 11.19167 -2.922946 3.454669 11.16852 -2.83389 3.34782 11.14562 -2.744871 3.240899 11.12258 -2.656181 3.133658 11.09871 -2.568227 3.025781 11.07307 -2.481365 2.917005 11.04487 -2.395919 2.807108 11.01341 -2.312209 2.695895 10.97802 -2.320181 2.699252 10.93307 -2.403779 2.810125 10.96817 -2.489103 2.91971 10.99939 -2.575835 3.028206 11.02739 -2.663656 3.135835 11.05288 -2.752208 3.242862 11.07666 -2.841091 3.349605 11.09964 -2.930017 3.4563 11.12251 -3.018828 3.563088 11.14564 -3.107531 3.669971 11.16904 -3.196361 3.776759 11.19215 -3.285542 3.883271 11.21445 -3.375246 3.989359 11.23553 -3.465646 4.094877 11.25499 -3.55692 4.199661 11.27237 -3.64924 4.303549 11.28726 -3.742769 4.406373 11.29923 -3.83766 4.507964 11.30785 -3.934059 4.608141 11.31271 -4.032101 4.706723 11.3134 -4.131908 4.803522 11.30953 -4.233589 4.898344 11.30071 -4.337234 4.990995 11.28656 -4.442996 5.081209 11.26655 -4.55274 5.166592 11.23521 -4.669727 5.241451 11.181 -4.795873 5.298014 11.09145 -4.92832 5.333181 10.96627 -5.061705 5.361066 10.83051 -5.192908 5.397983 10.70918 -5.316103 5.458 10.62788 -5.426815 5.54047 10.59154 -2.315423 2.69757 10.95396 -2.399084 2.808636 10.98923 -2.484477 2.918398 11.02059 -2.571284 3.027052 11.0487 -2.65918 3.134822 11.07428 -2.74781 3.241971 11.09811 -2.836771 3.348815 11.12112 -2.92577 3.455597 11.14401 -3.014658 3.562469 11.16715 -3.103439 3.669445 11.19056 -3.192346 3.776337 11.21371 -3.281606 3.88296 11.23605 -3.371393 3.989168 11.25719 -3.461877 4.094812 11.27669 -3.553241 4.199731 11.29414 -3.645654 4.303759 11.30909 -3.73928 4.40673 11.32111 -3.834274 4.508471 11.32979 -3.930783 4.608805 11.33472 -4.028943 4.707547 11.33547 -4.128874 4.804508 11.33165 -4.230687 4.899497 11.32286 -4.334475 4.992314 11.30875 -4.440398 5.082711 11.28877 -4.550419 5.168404 11.25746 -4.667881 5.243708 11.20321 -4.794766 5.300771 11.11336 -4.92779 5.336192 10.98777 -5.06126 5.364092 10.85191 -5.192075 5.400824 10.73085 5.924235 6.006174 9.764079 5.830506 6.069043 9.76408 5.872335 6.128784 9.76408 5.872335 6.128784 10.55124 5.950117 6.051002 9.76408 5.932076 6.170613 9.76408 5.916096 6.162311 10.87746 5.882383 6.138194 10.5262 5.904313 6.155003 10.69201 5.892891 6.146821 10.50158 6.039122 5.77109 9.764078 5.811625 5.998586 9.764079 5.830506 6.069042 11.76408 5.950117 5.909581 9.764079 5.924235 5.954409 9.764079 5.836098 6.080164 10.72657 5.83808 6.083765 10.67218 5.84341 6.092643 10.63497 5.856766 6.111379 10.59367 5.966484 5.777446 9.764078 5.817983 5.925947 9.764079 5.811625 5.998585 11.76408 5.90037 5.808276 9.764078 5.848813 5.859833 9.764079 5.817983 5.925946 11.76408 5.848813 5.859832 11.76408 5.90037 5.808275 11.76408 5.966484 5.777446 11.76408 5.994945 5.883698 9.764079 6.109579 5.78997 9.764078 6.039122 5.77109 11.76408 6.091538 5.909581 9.764079 6.16932 5.831799 9.764078 6.125559 5.798271 10.87746 6.046709 5.883698 9.764079 6.109579 5.789969 11.76408 6.11742 5.954409 9.764079 6.211149 5.89154 9.764078 6.16932 5.831799 10.55124 6.137342 5.805579 10.69201 6.148764 5.813761 10.50158 6.159271 5.822388 10.5262 6.002533 6.189493 9.76408 6.230029 5.961997 9.764078 6.211149 5.89154 11.76408 6.091539 6.051002 9.76408 6.117421 6.006173 9.764079 6.205558 5.880417 10.72657 6.184888 5.849203 10.59367 6.203576 5.876816 10.67217 6.198246 5.86794 10.63497 6.075172 6.183136 9.76408 6.223673 6.034636 9.764079 6.230029 5.961997 11.76408 6.141287 6.152307 9.76408 6.192844 6.100749 9.764079 6.223673 6.034635 11.76408 6.192844 6.100749 11.76408 6.141287 6.152306 11.76408 6.075173 6.183135 11.76408 6.04671 6.076884 9.76408 6.002533 6.189492 11.76408 5.994946 6.076884 9.76408 5.932076 6.170612 11.76408 5.950117 6.051002 11.76408 5.924235 6.006173 11.76408 5.994946 6.076884 11.76408 6.04671 6.076884 11.76408 6.091539 6.051001 11.76408 6.117421 6.006173 11.76408 6.11742 5.954409 11.76408 6.091538 5.90958 11.76408 6.046709 5.883698 11.76408 5.994945 5.883697 11.76408 5.950117 5.90958 11.76408 5.924235 5.954409 11.76408 5.872335 6.128783 11.76408 5.872335 6.128783 10.97691 5.840696 6.088239 10.84967 5.845685 6.096157 10.97504 5.851886 6.105021 11.01169 5.86019 6.115551 11.00957 5.866093 6.122267 10.99333 5.893295 6.14713 10.92633 6.16932 5.831799 11.76408 6.16932 5.831799 10.97691 6.175562 5.838315 10.99333 6.200958 5.872343 10.84967 6.195971 5.864425 10.97504 6.189769 5.85556 11.01169 6.181466 5.84503 11.00957 6.14836 5.813452 10.92633 5.75238 6.218905 10.58964 5.742833 6.21276 10.64103 5.746817 6.215182 10.60969 5.832753 6.085014 10.74119 5.741044 6.212014 10.67886 5.841412 6.097859 10.95008 5.831737 6.088185 10.76214 5.754413 6.225382 10.93858 5.843065 6.097652 10.96413 5.751379 6.222739 10.90524 5.765427 6.233793 10.97126 5.759345 6.229271 10.96181 5.771728 6.238252 10.96551 5.91098 6.167428 10.87746 5.637043 6.54739 10.74102 6.130675 5.793154 10.87746 6.269929 5.722329 10.96551 6.480397 5.308074 10.70327 6.150023 5.812502 10.50158 6.289276 5.741677 10.58963 5.891632 6.14808 10.50158 6.298823 5.747822 10.64103 6.293122 5.744279 10.60156 6.29638 5.746376 10.61909 6.208903 5.875568 10.74119 6.300662 5.748417 10.69194 6.300284 5.748519 10.66588 6.200243 5.862722 10.95008 6.209917 5.872396 10.76214 6.285779 5.734014 10.94766 6.19859 5.862929 10.96413 6.288495 5.736249 10.92833 6.27833 5.728326 10.96977 6.282313 5.731311 10.9618 6.274105 5.725261 10.97103 6.415744 5.398224 10.73172 6.338866 5.634194 10.9408 6.406898 5.560491 10.9335 6.473313 5.499868 10.94096 6.537353 5.451224 10.96077 6.598409 5.413347 10.9906 6.67401 5.029486 10.59392 6.566868 5.16003 10.59286 6.321419 5.56657 10.48121 6.314115 5.573353 10.5114 6.304441 5.563669 10.69942 6.308492 5.554857 10.72273 6.37722 5.452693 10.74271 6.355161 5.484358 10.74522 6.343381 5.501501 10.74472 6.340209 5.506155 10.74428 6.327277 5.525371 10.74058 6.316582 5.541741 10.73373 6.360775 5.616776 10.94296 6.459185 5.518655 10.94333 6.570446 5.435719 10.97978 6.656866 5.384593 11.02882 6.715549 5.362464 11.07586 6.694428 5.375223 11.06147 6.776458 5.344713 11.1314 6.836951 5.330409 11.19083 6.826092 5.338096 11.18313 6.895134 5.318261 11.25007 6.952961 5.306348 11.30916 6.864799 4.776513 10.5139 7.012926 5.292639 11.36868 6.959382 5.310226 11.31878 7.071586 5.276331 11.42318 7.126717 5.256659 11.46881 7.091166 5.275338 11.44347 7.182656 5.231367 11.50825 7.243748 5.197764 11.54362 7.216455 5.219341 11.53264 7.311124 5.154113 11.57415 7.052556 4.5484 10.46196 7.382374 5.101536 11.59818 7.332894 5.144982 11.58679 7.448388 5.048303 11.61462 7.442308 5.059955 11.61817 7.509098 4.996843 11.62653 7.236083 4.34098 10.43122 7.570828 4.942993 11.63667 7.547881 4.96995 11.6382 7.639974 4.880967 11.64583 7.718191 4.808634 11.6534 7.651363 4.877491 11.65239 7.415013 4.152152 10.41848 7.805851 4.724857 11.65839 7.75289 4.782858 11.66126 7.904536 4.627184 11.6597 7.852552 4.686246 11.66518 7.588996 3.980345 10.42128 8.015952 4.512775 11.65584 7.950458 4.587847 11.66455 8.14136 4.379047 11.64514 8.04673 4.487849 11.65975 7.757155 3.823044 10.43525 8.279454 4.226271 11.62624 8.234915 4.283776 11.6393 8.141501 4.386433 11.6512 7.91919 3.678382 10.45761 8.428616 4.055637 11.59861 8.327128 4.18005 11.62448 8.074818 3.544807 10.48598 8.589406 3.866611 11.56227 8.5086 3.970048 11.58777 8.418299 4.075419 11.60717 8.366199 3.303902 10.55093 8.765854 3.655268 11.51737 8.598209 3.864097 11.56674 8.223845 3.420248 10.51746 8.630632 3.09228 10.61889 8.960694 3.420936 11.46655 8.776037 3.651043 11.52141 8.501782 3.194905 10.58514 8.687294 3.757711 11.54448 8.753981 2.994661 10.652 9.15687 3.185291 11.41576 9.042196 3.330966 11.45203 8.953391 3.43759 11.47496 8.864671 3.544284 11.49809 8.992594 2.805903 10.71615 9.331193 2.972107 11.36575 9.219474 3.117468 11.40542 8.872996 2.900605 10.68412 9.131002 3.224348 11.4291 9.245629 2.607936 10.78701 9.479492 2.78339 11.31374 9.393853 2.901683 11.35213 9.115472 2.709105 10.74971 9.307207 3.009998 11.38002 9.38742 2.503005 10.83445 9.606965 2.612523 11.25789 9.56262 2.681645 11.28615 9.479095 2.792298 11.32106 9.622998 2.393074 10.99613 9.716471 2.457011 11.19869 9.644132 2.569567 11.24682 9.60421 2.384134 10.96045 9.582926 2.381222 10.92931 9.561342 2.384799 10.90614 9.541694 2.394333 10.89313 9.632631 2.383012 10.96441 9.723229 2.45572 11.20244 9.6019 2.370348 10.90857 9.567914 2.370875 10.86551 9.535955 2.384507 10.84193 9.20572 2.624526 10.72584 8.884906 2.876823 10.63767 8.564903 3.130065 10.55176 8.247191 3.386419 10.47281 7.93498 3.649767 10.40993 7.631851 3.923861 10.37257 7.341635 4.211794 10.36963 7.066782 4.514388 10.40533 6.80822 4.830758 10.47972 6.354711 5.657661 10.56572 6.379786 5.635803 10.57349 6.47989 5.530076 10.56262 6.499719 5.327457 10.3274 6.426138 5.428886 10.36907 6.418193 5.587937 10.55769 6.333718 5.551729 10.4575 6.350225 5.530655 10.43482 6.36042 5.517332 10.42327 6.367137 5.508468 10.41634 6.387348 5.481495 10.39786 7.091599 5.295449 11.04786 6.759246 4.959003 10.18723 6.583526 5.176337 10.27195 7.019766 5.315001 10.98059 6.935046 5.333416 10.89526 6.847647 5.351708 10.80633 6.771653 5.370612 10.73287 6.70688 5.391643 10.67658 6.650246 5.415837 10.63484 6.595783 5.445419 10.60282 6.539155 5.48301 10.57832 7.432893 5.096189 11.23064 7.02536 4.622961 10.09724 6.824887 4.84709 10.15886 7.369493 5.14539 11.21236 7.30864 5.188295 11.18927 7.253938 5.222514 11.16291 7.203248 5.25007 11.13314 7.1511 5.273944 11.09676 7.717523 4.846716 11.27587 7.285768 4.327229 10.05178 7.083434 4.530715 10.08444 7.634987 4.92235 11.26699 7.562629 4.98655 11.2565 7.49687 5.043157 11.24472 7.914997 4.655493 11.28392 7.533726 4.0719 10.0423 7.358313 4.228174 10.04884 7.810415 4.75855 11.28195 8.167095 4.391453 11.26854 7.769929 3.848373 10.05861 7.648499 3.940229 10.05172 8.033231 4.534297 11.2801 8.319206 4.222597 11.247 7.993046 3.650609 10.09123 7.95162 3.666174 10.08913 8.492695 4.022859 11.21322 8.202722 3.473113 10.13264 8.693934 3.784269 11.16515 8.39938 3.312029 10.17842 8.26381 3.402847 10.152 8.920966 3.511143 11.10584 8.583645 3.164299 10.22543 9.141396 3.24643 11.04885 8.756175 3.027581 10.27151 8.581501 3.146517 10.23096 8.917123 2.900364 10.31492 8.901482 2.893302 10.31687 9.329874 3.017071 10.99624 9.069887 2.779405 10.35584 9.222132 2.660372 10.39858 9.488278 2.816484 10.94196 9.383042 2.539375 10.44994 9.222262 2.641011 10.40501 9.621032 2.639148 10.88459 9.561041 2.413681 10.51725 9.735817 2.476359 10.82281 9.580688 2.404146 10.53026 9.55247 2.401022 10.5211 9.602274 2.40057 10.55344 9.584427 2.387389 10.54468 9.623558 2.403481 10.58457 9.618413 2.386862 10.58774 9.642345 2.412422 10.62025 9.742279 2.47477 10.83237 9.649145 2.399525 10.64358 9.751889 2.471476 10.86201 9.748359 2.472864 10.84817 9.663148 2.588587 10.87735 9.581635 2.700667 10.91668 9.412866 2.920707 10.98266 9.49811 2.811321 10.95159 9.326217 3.029024 11.01054 9.061222 3.350014 11.0826 9.238483 3.136493 11.03594 9.150018 3.243384 11.05965 8.883655 3.563304 11.12857 8.97238 3.456611 11.10545 8.617206 3.883139 11.19727 8.795039 3.670082 11.15194 8.706297 3.776754 11.17502 8.437293 4.094465 11.2377 8.527595 3.989092 11.2183 8.253905 4.302826 11.26983 8.346119 4.199098 11.25502 8.160489 4.405484 11.28173 7.969442 4.606901 11.29508 8.065716 4.506902 11.29028 7.871533 4.705302 11.29571 7.771868 4.801914 11.29178 7.670339 4.896549 11.28291 7.566855 4.98901 11.26873 7.461279 5.079014 11.24869 7.351862 5.164036 11.2173 7.23543 5.238385 11.16314 7.110145 5.294373 11.07397 6.978354 5.329254 10.94926 6.845061 5.357125 10.8136 6.713395 5.394257 10.69196 6.589431 5.454755 10.61028 6.478186 5.537687 10.57385 6.290276 5.737843 10.90524 6.299946 5.747521 10.7173 6.356634 5.674092 10.69576 6.362269 5.646264 10.88004 6.374465 5.628669 10.90052 9.658642 2.607678 10.99891 9.632959 2.620248 11.19487 9.748088 2.455984 11.13164 9.745775 2.454873 11.15568 9.757762 2.465658 10.9437 9.639454 2.381676 10.89622 9.547155 2.759116 11.05032 9.497793 2.801601 11.2543 9.584537 2.682465 11.24006 9.666243 2.5697 11.20009 9.417628 2.926583 11.09914 9.447979 2.865972 11.27304 9.5008 2.793755 11.27551 9.395197 2.933011 11.29138 9.415325 2.903722 11.30703 9.369771 2.986685 11.1149 9.339158 3.003066 11.30942 9.319372 3.049174 11.13045 9.280007 3.075981 11.32713 9.328435 3.012561 11.33527 9.266361 3.114159 11.14587 9.217488 3.152148 11.3447 9.240453 3.120493 11.36095 9.210783 3.181656 11.1612 9.150852 3.232606 11.36248 9.151725 3.227772 11.38482 9.152282 3.252196 11.17669 9.099153 3.294704 11.37587 9.090208 3.326704 11.1927 9.047162 3.357027 11.38916 9.062663 3.334721 11.40784 9.041805 3.384714 11.20506 8.994427 3.420258 11.40267 8.992684 3.443637 11.21767 8.940998 3.48447 11.41654 8.973612 3.441628 11.43082 8.943064 3.503299 11.2306 8.888241 3.548004 11.43041 8.892189 3.564578 11.24398 8.837287 3.609411 11.44386 8.884652 3.548596 11.45399 8.841176 3.626055 11.25745 8.787536 3.669342 11.45696 8.795766 3.655656 11.47738 8.791294 3.686138 11.27058 8.738888 3.727848 11.46965 8.694764 3.802041 11.29551 8.675996 3.803248 11.48575 8.706768 3.76266 11.50055 8.742683 3.744585 11.28324 8.632788 3.876024 11.31096 8.615562 3.875335 11.50074 8.617423 3.869412 11.52295 8.573847 3.945939 11.32508 8.557126 3.94459 11.51467 8.517602 4.012157 11.33792 8.500144 4.011607 11.52758 8.527544 3.975754 11.54414 8.463587 4.075215 11.34955 8.444734 4.0762 11.5394 8.411684 4.135246 11.36001 8.390786 4.138477 11.55011 8.436964 4.081542 11.56371 8.361971 4.192176 11.3693 8.338168 4.198577 11.55974 8.3455 4.186614 11.58122 8.223611 4.347313 11.39089 8.286947 4.256417 11.56826 8.237113 4.312018 11.57568 8.25298 4.290802 11.59623 8.096238 4.465279 11.59162 8.159242 4.393941 11.60833 7.989317 4.597018 11.41073 7.970758 4.596458 11.59896 8.064126 4.495858 11.61709 8.10004 4.481206 11.40417 7.889922 4.697401 11.412 7.860495 4.707258 11.59965 7.96749 4.596372 11.62208 7.80058 4.784613 11.40925 7.763315 4.80128 11.59559 7.769118 4.792451 11.61913 7.869195 4.6953 11.62289 7.71997 4.860781 11.40354 7.677292 4.881594 11.58824 7.647364 4.92731 11.39572 7.601527 4.950031 11.57881 7.66715 4.887632 11.61039 7.582636 4.984944 11.38659 7.53484 5.008474 11.5682 7.563198 4.980641 11.59631 7.52375 5.036001 11.37652 7.470417 5.063282 11.55583 7.410743 5.129109 11.35091 7.400231 5.120089 11.53861 7.457087 5.071253 11.57637 7.46711 5.083744 11.36507 7.354965 5.17096 11.33299 7.323798 5.176437 11.51277 7.346727 5.157323 11.54511 7.302031 5.207182 11.31149 7.251495 5.222805 11.47939 7.208381 5.261387 11.26073 7.186098 5.25796 11.44048 7.228674 5.23317 11.4908 7.253805 5.236773 11.28751 7.1618 5.283152 11.22879 7.125785 5.284173 11.3966 7.110033 5.303049 11.18778 7.064925 5.304561 11.34452 7.100862 5.290844 11.40055 7.049736 5.321156 11.13349 7.00044 5.321315 11.28309 6.979483 5.337855 11.06458 6.937471 5.334996 11.21967 6.967137 5.32658 11.27445 6.902287 5.353834 10.9858 6.876423 5.347492 11.15719 6.827921 5.369854 10.91072 6.814157 5.361139 11.09463 6.833569 5.354495 11.13849 6.764016 5.386422 10.8498 6.750341 5.377922 11.0341 6.708944 5.404521 10.80223 6.688675 5.39888 10.98172 6.703252 5.390997 11.01777 6.660365 5.424842 10.76586 6.629036 5.425838 10.93967 6.614221 5.448818 10.73734 6.567111 5.462056 10.90659 6.581543 5.450084 10.93719 6.517076 5.514866 10.69732 6.501552 5.509864 10.88374 6.566758 5.478402 10.71433 6.465277 5.559095 10.68758 6.432975 5.570813 10.87393 6.471854 5.531663 10.90101 6.411647 5.611921 10.68655 6.386626 5.640845 10.66413 6.484004 5.543845 10.66462 6.593677 5.46227 10.70078 6.715373 5.403181 10.78134 6.845689 5.366673 10.90205 6.97926 5.338757 11.03801 7.112997 5.30303 11.16414 7.240798 5.245363 11.25439 7.358844 5.169527 11.3087 7.469205 5.083463 11.33997 7.575321 4.992852 11.35992 7.679276 4.899839 11.374 7.781246 4.804657 11.38274 7.881325 4.707505 11.3865 7.979622 4.608576 11.38569 8.076262 4.50806 11.3807 8.171379 4.406143 11.37194 8.265119 4.303002 11.35985 8.357641 4.198812 11.34483 8.449107 4.093739 11.32732 8.53969 3.987948 11.30775 8.62957 3.881604 11.28656 8.718921 3.774854 11.26417 8.807916 3.667845 11.24099 8.896784 3.560765 11.21756 8.985756 3.453798 11.1944 9.07484 3.346916 11.1715 9.163889 3.239958 11.14845 9.25261 3.132669 11.12456 9.340595 3.024736 11.09888 9.427488 2.915896 11.07064 9.596703 2.694636 11.00367 9.512964 2.805928 11.03912 9.67841 2.581869 10.9637 9.649128 2.39135 10.70828 9.758034 2.467133 10.9175 9.606699 2.368179 10.8367 9.736758 2.454295 11.19042 9.742978 2.45444 11.1715 6.386353 5.640811 10.63804 6.482809 5.5425 10.61358 6.385048 5.639914 10.61313 9.616374 2.377853 10.64877 9.580149 2.378414 10.60287 9.570475 2.36874 10.79081 9.53641 2.383272 10.76568 9.546084 2.392946 10.57774 9.374878 2.496578 10.70362 9.359597 2.524525 10.50708 6.440513 5.371326 10.41408 6.50425 5.250399 10.55333 6.571643 5.17545 10.33077 6.705733 4.964924 10.44524 6.849294 4.799011 10.20364 6.906006 4.705978 10.36974 7.127646 4.46423 10.13102 7.10086 4.474073 10.32206 7.29108 4.264161 10.29672 7.393614 4.176674 10.10324 7.476407 4.073459 10.2898 7.647083 3.927341 10.10857 7.655828 3.900366 10.29794 7.886672 3.709303 10.1363 7.828774 3.742389 10.3172 7.994633 3.597331 10.34397 8.111638 3.515842 10.17683 8.153453 3.463068 10.37557 8.322025 3.341899 10.22373 8.304972 3.338239 10.40991 8.449159 3.221652 10.44543 8.518504 3.18355 10.2728 8.585874 3.112497 10.48089 8.701957 3.037809 10.32132 8.71607 3.009321 10.51566 8.872384 2.903138 10.36733 8.840682 2.910867 10.54932 8.965222 2.812381 10.58285 9.032979 2.776071 10.41048 9.092556 2.711764 10.61723 9.191942 2.651394 10.4546 9.227685 2.606739 10.65597 5.671376 6.499262 10.7541 5.700223 6.329419 10.94021 5.630672 6.404149 10.93355 5.562807 6.465299 10.94219 5.497501 6.513974 10.96359 5.525541 6.726866 10.65355 5.500334 6.77718 10.61314 5.70874 6.406796 10.45042 5.72754 6.387229 10.51141 5.737215 6.396905 10.69937 5.733348 6.406227 10.72884 5.720007 6.393613 10.47542 5.71868 6.395082 10.47181 5.681547 6.484757 10.75603 5.694652 6.465836 10.75663 5.711142 6.441474 10.75304 5.713124 6.438488 10.75214 5.724112 6.421538 10.74407 5.732047 6.408515 10.73202 5.676161 6.345176 10.9428 5.574478 6.445412 10.94466 5.435433 6.551489 10.99519 5.459231 6.529109 10.98526 5.375902 6.579707 11.03548 5.392855 6.921606 10.5737 5.315207 6.601582 11.08543 5.33084 6.588344 11.07426 5.252512 6.619043 11.14364 5.191273 6.633019 11.20446 5.195033 6.624256 11.2028 5.132116 6.645208 11.2649 5.072911 6.657599 11.32514 5.235758 7.131661 10.50555 5.01054 6.672518 11.38621 5.057758 6.653026 11.34243 4.942237 6.693584 11.44699 4.867946 6.72493 11.50226 4.922543 6.692644 11.46541 4.790273 6.767654 11.54723 4.795205 6.755638 11.54824 5.057209 7.34986 10.45453 4.710087 6.821213 11.5815 4.625612 6.885965 11.60688 4.67718 6.8359 11.59684 4.538176 6.958775 11.6257 4.565718 6.925376 11.62514 4.867927 7.562499 10.42448 4.448423 7.036732 11.64088 4.457334 7.018612 11.64462 4.350692 7.124603 11.65357 4.350831 7.114024 11.6589 4.685281 7.752732 10.41472 4.241965 7.226168 11.66279 4.246196 7.211504 11.66811 4.124084 7.340811 11.66695 4.143376 7.31091 11.6725 4.515132 7.919839 10.41863 3.99742 7.469241 11.66468 4.042314 7.412104 11.67233 4.357795 8.067315 10.43132 3.861606 7.612876 11.65462 3.942934 7.514947 11.66788 4.212016 8.198868 10.44963 3.716044 7.773384 11.63539 3.845156 7.619304 11.65941 4.076511 8.317483 10.47137 3.560006 7.952522 11.60566 3.654025 7.832015 11.63164 3.748888 7.725037 11.64723 3.833014 8.523585 10.51949 3.392803 8.151818 11.56437 3.468081 8.049194 11.59145 3.950386 8.425231 10.49501 3.560462 7.94011 11.61295 3.622425 8.696474 10.568 3.213531 8.372634 11.51091 3.376761 8.159147 11.56748 3.723702 8.613831 10.54402 3.365676 8.902917 10.63274 3.020475 8.616648 11.44533 3.1968 8.381183 11.51333 3.443862 8.840414 10.61256 3.529207 8.771858 10.59095 3.286378 8.269848 11.54133 3.085679 9.12558 10.70652 2.810986 8.885683 11.36871 2.931572 8.71788 11.42137 3.154502 9.070913 10.6883 3.223094 9.016423 10.67016 3.292798 8.96099 10.65179 3.019532 8.605307 11.45304 3.107897 8.49304 11.4838 2.807945 9.343511 10.78348 2.581439 9.181204 11.28381 2.756312 8.943517 11.35654 2.876302 9.290748 10.76341 2.946093 9.236114 10.74391 3.016115 9.180784 10.725 2.843878 8.830651 11.3891 2.418658 9.567508 10.99618 2.326482 9.504459 11.19593 2.493015 9.281656 11.26024 2.437445 9.576448 10.9605 2.458729 9.57936 10.92936 2.480315 9.575783 10.90619 2.499962 9.566249 10.89318 2.58906 9.504842 10.85754 2.66767 9.448512 10.82887 2.739386 9.395462 10.80485 2.581017 9.169122 11.2918 2.668737 9.056375 11.32401 2.409025 9.57757 10.96446 2.315764 9.505956 11.20026 2.404597 9.393873 11.22961 2.439756 9.590234 10.90862 2.473742 9.589708 10.86556 2.503466 9.571965 10.87321 2.78177 9.371855 10.77259 3.052143 9.160739 10.69633 3.320723 8.947298 10.62538 3.588385 8.73266 10.55714 3.853714 8.515056 10.49573 4.115207 8.29274 10.44531 4.371232 8.064025 10.41016 4.61999 7.827332 10.39464 4.859492 7.581251 10.4031 5.087576 7.324634 10.43982 5.301955 7.056709 10.50872 2.307134 9.485111 10.82005 2.460967 9.556436 10.53031 2.480614 9.546901 10.5173 2.484855 9.553354 10.51164 2.393583 9.375889 10.84935 2.592815 9.469198 10.47291 2.763161 9.353241 10.41102 2.439382 9.560011 10.55349 2.457227 9.573194 10.54473 2.489186 9.55956 10.52115 2.418098 9.557101 10.58462 2.423242 9.57372 10.58779 2.39931 9.54816 10.6203 2.297101 9.487294 10.83769 2.392511 9.561057 10.64363 2.290414 9.489362 10.86025 2.385989 9.375258 10.86804 2.477383 9.269598 10.8783 2.688338 9.399739 10.43937 2.558534 9.166234 10.90688 2.474409 9.263038 10.89867 2.774866 9.334651 10.41178 2.63693 9.065804 10.93523 2.562414 9.150502 10.93023 2.944526 9.202764 10.36317 2.712547 8.968303 10.96339 2.650136 9.037753 10.96244 2.859163 9.269682 10.3869 3.030014 9.135076 10.34026 2.803811 8.850541 10.99749 2.737712 8.924891 10.99497 3.114721 9.067795 10.31784 2.891958 8.737222 11.02988 2.825281 8.812022 11.02753 3.198604 9.001162 10.29564 2.976734 8.628439 11.06077 2.912978 8.699249 11.0598 3.374148 8.861356 10.24965 3.058084 8.524779 11.08948 3.00094 8.586673 11.09147 3.283869 8.933352 10.27318 3.473106 8.782076 10.22433 3.135949 8.426351 11.11594 3.089307 8.474401 11.12223 3.583262 8.693202 10.19694 3.210452 8.332983 11.14022 3.178212 8.362542 11.15177 3.281668 8.244699 11.16218 3.267793 8.251204 11.17977 3.70525 8.593766 10.16792 3.349517 8.161575 11.18184 3.984876 8.360169 10.10869 3.593677 7.871491 11.24093 3.358179 8.1405 11.20591 3.838998 8.483167 10.13813 4.143749 8.222717 10.08112 3.800431 7.638982 11.27408 3.635453 7.813361 11.27008 3.449502 8.030545 11.22989 3.541886 7.921458 11.25138 4.31707 8.067608 10.05768 3.97661 7.451398 11.28875 3.826589 7.600645 11.29784 3.730317 7.70638 11.28567 4.50819 7.888774 10.04187 4.127111 7.299362 11.29072 4.023752 7.393442 11.31076 3.924371 7.496288 11.30631 4.719166 7.679326 10.0399 4.256044 7.17516 11.28463 4.124818 7.292247 11.31093 4.943275 7.438952 10.06083 4.366967 7.072859 11.27354 4.33228 7.095359 11.29732 4.227641 7.19284 11.30653 4.461449 6.98897 11.25991 4.438782 6.999942 11.28306 4.543434 6.918612 11.24494 5.159061 7.18468 10.11035 4.622869 6.853368 11.22668 4.547186 6.906729 11.26351 4.701718 6.794028 11.20158 4.658636 6.81724 11.23525 4.774019 6.746403 11.16982 5.343737 6.943496 10.18307 4.83826 6.71069 11.13311 4.776652 6.736989 11.18665 4.905142 6.680801 11.08551 4.987441 6.654225 11.0138 4.903958 6.67399 11.1039 5.091935 6.630168 10.91029 5.039178 6.634406 10.98083 5.494652 6.724925 10.27013 5.20304 6.606801 10.79739 5.176457 6.605637 10.84119 5.295839 6.582252 10.70956 5.372354 6.55362 10.64795 5.312266 6.569714 10.71266 5.617695 6.528043 10.36515 5.44145 6.517829 10.60509 5.513524 6.469452 10.57459 5.440647 6.51048 10.62368 5.58984 6.405359 10.55886 5.555881 6.426789 10.58309 5.669622 6.323022 10.56215 5.657556 6.326558 10.58123 5.652847 6.479805 10.38677 5.696617 6.421952 10.43123 5.694538 6.42461 10.42839 5.677092 6.447334 10.40802 5.662987 6.466126 10.39487 5.48173 6.75856 10.25158 5.283355 7.038084 10.14715 5.068979 7.306006 10.07825 4.840897 7.562624 10.04153 4.601394 7.808707 10.03307 4.352635 8.045403 10.04859 4.096608 8.274118 10.08374 3.835112 8.496436 10.13415 3.569782 8.714041 10.19557 3.302118 8.928681 10.2638 3.033535 9.142124 10.33476 5.741709 6.21306 10.7173 5.678571 6.315272 10.87986 5.665679 6.336075 10.91033 5.66307 6.312321 10.69077 2.344252 9.419293 10.9634 2.348846 9.435354 11.14966 2.293567 9.504598 11.13169 2.297656 9.506087 11.1659 2.283893 9.494924 10.94375 2.402202 9.578906 10.89627 2.402877 9.367212 11.16781 2.386938 9.393835 11.19471 2.403162 9.344934 10.98328 2.455705 9.3002 11.18607 2.46068 9.271883 11.00327 2.50737 9.234343 11.20433 2.475572 9.28142 11.22532 2.516859 9.200174 11.02325 2.557891 9.169692 11.22251 2.571742 9.129842 11.04313 2.619461 9.090638 11.24501 2.563788 9.168668 11.25689 2.625333 9.060967 11.0628 2.679437 9.013433 11.26718 2.651719 9.055683 11.28913 2.677698 8.993535 11.08219 2.737997 8.937952 11.28896 2.739502 8.942568 11.32172 2.737361 8.916625 11.10438 2.79515 8.864269 11.31023 2.795612 8.841531 11.12606 2.850938 8.792404 11.33091 2.827275 8.829426 11.35437 2.852563 8.768191 11.14715 2.905499 8.722248 11.35098 2.908202 8.696686 11.16756 2.958918 8.65375 11.37038 2.915177 8.716362 11.38675 2.962466 8.627157 11.1872 3.011152 8.587007 11.38905 3.003347 8.603482 11.41855 3.015289 8.559735 11.20599 3.062304 8.521931 11.40697 3.076747 8.481689 11.22733 3.112479 8.458423 11.42413 3.091921 8.490888 11.44945 3.136201 8.406679 11.24735 3.161641 8.396552 11.44048 3.193691 8.334676 11.26603 3.20983 8.336288 11.45602 3.181038 8.37869 11.47915 3.249213 8.265698 11.28334 3.27274 8.258253 11.47548 3.270834 8.267001 11.50733 3.302659 8.19987 11.29928 3.334133 8.182866 11.49349 3.366904 8.121551 11.31738 3.394041 8.110099 11.51004 3.361443 8.155929 11.53366 3.428688 8.047138 11.33364 3.452584 8.039813 11.52515 3.452994 8.045597 11.55783 3.487804 7.976822 11.34805 3.509722 7.972046 11.53883 3.544598 7.910136 11.36078 3.565539 7.906684 11.55111 3.545616 7.936118 11.57952 3.616975 7.826445 11.37533 3.620056 7.84368 11.56203 3.673262 7.783019 11.57162 3.63943 7.827619 11.59841 3.685533 7.74857 11.38733 3.725257 7.724553 11.57995 3.812491 7.608135 11.40467 3.873925 7.562013 11.5978 3.734554 7.720226 11.6142 3.750704 7.675855 11.39703 3.927079 7.485779 11.41466 4.012345 7.417092 11.60616 3.929163 7.509284 11.63522 3.87129 7.544817 11.41048 3.831097 7.61407 11.62657 4.078696 7.330533 11.41933 4.141082 7.288041 11.60657 4.028845 7.406006 11.63984 4.20913 7.203163 11.41539 4.260578 7.173263 11.60049 4.233383 7.204526 11.63591 4.130228 7.304374 11.64017 4.321877 7.097708 11.406 4.369628 7.072737 11.58952 4.338373 7.106606 11.62681 4.419115 7.010204 11.39348 4.467168 6.986213 11.57534 4.445249 7.010756 11.61262 4.502239 6.937912 11.37954 4.558723 6.9079 11.55831 4.554028 6.917077 11.59319 4.579349 6.873071 11.36375 4.6487 6.835135 11.53616 4.656537 6.812112 11.34286 4.735036 6.772718 11.50538 4.666119 6.826884 11.56501 4.798394 6.717961 11.28147 4.818141 6.722045 11.46364 4.785263 6.745494 11.51642 4.731715 6.75882 11.3147 4.861241 6.685758 11.24204 4.898961 6.683167 11.40967 4.931986 6.657396 11.1875 4.97443 6.656661 11.34666 4.914444 6.681119 11.43301 5.020302 6.6322 11.10628 5.042212 6.638975 11.28219 5.126464 6.609319 10.99911 5.104681 6.625418 11.21925 5.051459 6.64061 11.30884 5.165499 6.612977 11.157 5.229527 6.586923 10.8953 5.227568 6.599383 11.09462 5.189202 6.611713 11.16878 5.291238 6.582658 11.03421 5.313202 6.562972 10.81845 5.352903 6.561725 10.9818 5.324154 6.576215 11.0408 5.382311 6.535264 10.76517 5.412368 6.534882 10.93982 5.446987 6.500204 10.72706 5.474165 6.498791 10.90674 5.450789 6.518062 10.95267 5.515149 6.453098 10.69996 5.539607 6.451136 10.88385 5.587446 6.3912 10.68658 5.608059 6.390388 10.87394 5.564789 6.435441 10.91229 5.652317 6.322699 10.65061 5.551434 6.42206 10.65256 5.437448 6.504676 10.69293 5.310821 6.562828 10.78105 5.175869 6.598337 10.90902 5.038123 6.627232 11.04909 4.901102 6.667706 11.17333 4.771951 6.732087 11.25668 4.652817 6.813465 11.30526 4.540738 6.903674 11.33341 4.431939 6.997328 11.35289 4.325064 7.093183 11.36708 4.22007 7.191104 11.37618 4.116911 7.290953 11.38044 4.015526 7.392587 11.38012 3.915841 7.495867 11.3755 3.817772 7.600653 11.36685 3.721226 7.706812 11.35448 3.626099 7.814207 11.3387 3.532283 7.922708 11.3198 3.439658 8.032189 11.29811 3.348103 8.142525 11.27394 3.257493 8.253599 11.24761 3.167694 8.365292 11.21944 3.078574 8.477493 11.18974 2.989997 8.590088 11.15883 2.901825 8.702973 11.12703 2.813921 8.81604 11.09465 2.726145 8.929184 11.06201 2.638359 9.042302 11.02941 2.550427 9.155289 10.99717 2.462209 9.268045 10.96559 2.373572 9.380463 10.93499 2.28422 9.49265 10.90487 2.392528 9.569231 10.70833 2.434956 9.592403 10.83675 2.305307 9.506552 11.18966 2.299004 9.506258 11.172 2.425282 9.582729 10.64881 2.461507 9.582169 10.60292 2.471181 9.591842 10.79086 2.505244 9.577311 10.76572 2.506325 9.577954 10.80416 2.49557 9.567638 10.57779 2.594569 9.515806 10.72993 2.790774 9.3732 10.7016 2.505701 9.576075 10.84198 2.607619 9.490037 10.53346 2.492955 9.564584 10.54443 5.622889 6.569012 10.41216 5.642165 6.562694 10.60832 5.529109 6.743413 10.52125 5.552577 6.70927 10.57563 5.496554 6.768461 10.31808 5.394621 6.939826 10.44157 5.341817 6.989564 10.23268 5.236208 7.150794 10.37394 5.353906 6.997903 10.45987 5.15309 7.23279 10.16255 5.056473 7.369305 10.32404 5.138051 7.274386 10.38185 4.935072 7.486464 10.11666 4.866885 7.581073 10.2955 4.907448 7.53891 10.33821 4.712502 7.722712 10.09907 4.685008 7.770018 10.28641 4.504436 7.92775 10.10296 4.51537 7.936219 10.29083 4.664555 7.792207 10.32482 4.358495 8.0829 10.30395 4.41171 8.035437 10.33719 4.316155 8.103035 10.11969 4.213284 8.213705 10.32249 4.145087 8.255587 10.14352 4.078318 8.331709 10.34432 4.151062 8.270068 10.37068 3.988175 8.390994 10.17119 3.952704 8.438947 10.36796 3.84407 8.512272 10.20057 3.835762 8.536904 10.3924 3.884555 8.497766 10.42062 3.711931 8.621401 10.23018 3.726885 8.626749 10.41689 3.626027 8.70901 10.44082 3.591454 8.719521 10.25894 3.533204 8.784049 10.4637 3.613946 8.720318 10.48246 3.482701 8.807215 10.28605 3.44822 8.852306 10.48523 3.384927 8.885519 10.3111 3.370376 8.914533 10.50533 3.29554 8.95679 10.33442 3.297723 8.972426 10.52432 3.340844 8.939579 10.55174 3.210915 9.024085 10.35671 3.228181 9.027727 10.54265 3.159757 9.08208 10.56075 3.127518 9.090327 10.37879 3.091096 9.13661 10.57894 3.043269 9.157238 10.4011 3.021669 9.19172 10.59736 3.066759 9.157439 10.6241 2.958228 9.224561 10.4239 2.951734 9.246972 10.61626 2.873289 9.291124 10.44755 2.882024 9.301527 10.63576 2.789324 9.355807 10.47237 2.813663 9.354282 10.65584 2.74506 9.40625 10.67725 2.703003 9.420706 10.49993 2.673275 9.459351 10.70129 2.777415 9.359823 10.44187 3.05341 9.144054 10.36437 3.327506 8.926187 10.29201 3.600617 8.706918 10.22273 3.871235 8.484357 10.16088 4.13775 8.256649 10.11094 4.398405 8.022008 10.07746 4.651257 7.778768 10.0651 4.894155 7.525459 10.07849 5.124759 7.260924 10.12215 5.340611 6.984433 10.20018 5.539278 6.695792 10.31596 5.516836 6.718968 10.28044 5.533329 6.735511 10.60121 2.787814 9.373086 10.74015 3.061675 9.159083 10.66312 3.33368 8.942894 10.59129 3.604724 8.725385 10.5224 3.873336 8.504711 10.46071 4.137947 8.279058 10.41057 4.396848 8.04668 10.37644 4.64815 7.805941 10.36284 4.889768 7.555397 10.37432 5.11943 7.293889 10.4153 5.334744 7.020672 10.4898 2.307565 9.506514 11.19347 2.394442 9.394484 11.21879 5.670394 6.340245 10.93347 2.482993 9.282146 11.2494 2.571126 9.169477 11.28098 2.658975 9.056584 11.3132 2.746678 8.943568 11.34578 2.834371 8.830533 11.37839 2.922193 8.717583 11.41072 3.01028 8.604822 11.44247 3.098773 8.492355 11.47332 3.187807 8.38029 11.50296 3.277518 8.268737 11.53106 3.368038 8.157812 11.55732 3.459499 8.047626 11.58142 3.552027 7.938301 11.60303 3.645743 7.829961 11.62185 3.740763 7.72273 11.63756 3.837199 7.616739 11.64985 3.935152 7.512122 11.65843 4.034715 7.409014 11.66299 4.135972 7.307553 11.66325 4.238995 7.207879 11.65894 4.343846 7.11013 11.6498 4.450575 7.014453 11.63558 4.559199 6.920947 11.61613 4.671041 6.831036 11.5879 4.789741 6.750091 11.53931 4.918188 6.686262 11.45614 5.054481 6.646107 11.33245 5.192037 6.617261 11.19256 5.327332 6.5816 11.06435 5.454677 6.523015 10.97587 5.569181 6.439961 10.93539 3.045169 9.142563 10.3423 2.771304 9.35657 10.41933 3.317178 8.926372 10.27047 3.588226 8.70886 10.20158 3.856841 8.488182 10.13989 4.121456 8.262527 10.08976 4.38036 8.030145 10.05563 4.631665 7.789402 10.04204 4.873283 7.538854 10.05353 5.102945 7.277345 10.09451 5.318257 7.004128 10.16903 2.284835 9.49209 10.89674 2.288761 9.490006 10.86821 2.377933 9.37797 10.89801 5.653889 6.323726 10.61269 2.466487 9.265627 10.92863 2.554622 9.152956 10.9602 2.642474 9.04006 10.99243 2.730178 8.927042 11.025 2.817874 8.814004 11.05761 2.905697 8.70105 11.08995 2.993788 8.588287 11.1217 3.082283 8.475816 11.15255 3.17132 8.363749 11.18218 3.261033 8.252194 11.21029 3.351556 8.141264 11.23655 3.443019 8.031077 11.26064 3.53555 7.921749 11.28226 3.629269 7.813406 11.30107 3.724293 7.706173 11.31678 3.820732 7.600181 11.32908 3.918687 7.495562 11.33765 4.018253 7.392452 11.34221 4.119513 7.29099 11.34247 4.222539 7.191315 11.33816 4.327394 7.093567 11.32901 4.434122 6.997883 11.3148 4.542766 6.904401 11.29529 4.654597 6.814475 11.2671 4.773287 6.733541 11.21851 4.901703 6.669707 11.13541 5.038002 6.629587 11.01164 5.17556 6.600742 10.87174 5.310857 6.565071 10.74354 5.438193 6.506487 10.65507 5.552684 6.423438 10.61461 9.730258 2.454763 11.19983 9.734795 2.454382 11.19409 9.651026 2.568884 11.24417 9.657382 2.568533 11.23496 9.662647 2.568707 11.21988 6.483886 5.543647 10.63851 6.371856 5.626298 10.91982 6.368545 5.623394 10.93389 6.364764 5.620147 10.94178 9.580966 2.681388 11.25978 9.497258 2.792598 11.29517 9.411813 2.902494 11.32663 9.324954 3.011269 11.35483 9.237003 3.119145 11.38048 9.148307 3.226377 11.40433 9.059272 3.333287 11.42733 8.970252 3.440162 11.45031 8.881318 3.5471 11.47348 8.79246 3.654125 11.49685 8.703492 3.76109 11.52002 8.614176 3.867799 11.5424 8.524331 3.974096 11.56357 8.433784 4.079834 11.58312 8.342355 4.184853 11.60061 8.249874 4.288986 11.6156 8.156175 4.392066 11.62767 8.061104 4.493922 11.6364 7.964512 4.594372 11.64137 7.866267 4.693235 11.64217 7.766243 4.790319 11.63839 7.664332 4.885432 11.62964 7.560439 4.978373 11.61555 7.454398 5.068909 11.59559 7.344165 5.154844 11.56433 7.226335 5.230496 11.51005 7.098874 5.28795 11.41997 6.965417 5.323575 11.29407 6.831881 5.351484 11.15815 6.701365 5.388072 11.03728 6.579321 5.447355 10.95652 6.469398 5.529129 10.92029 9.575746 2.681056 11.2747 9.492086 2.79212 11.30997 9.406694 2.90188 11.34133 9.31989 3.010534 11.36945 9.231998 3.118303 11.39503 9.14336 3.225441 11.41883 9.054387 3.332275 11.44182 8.965421 3.439083 11.46478 8.876544 3.545957 11.48794 8.787745 3.652913 11.5113 8.698836 3.759801 11.53444 8.609581 3.866425 11.55679 8.519798 3.972631 11.57792 8.429315 4.078273 11.59743 8.337954 4.18319 11.61487 8.245543 4.287216 11.62982 8.151919 4.390186 11.64185 8.056926 4.491926 11.65053 7.960419 4.592258 11.65546 7.862262 4.690999 11.65621 7.762333 4.78796 11.65239 7.660522 4.882946 11.64361 7.556736 4.97576 11.62949 7.450818 5.066158 11.60952 7.340796 5.151857 11.57822 7.22333 5.227171 11.52398 7.096435 5.284241 11.43413 6.963422 5.319672 11.30855 6.829955 5.347569 11.1727 6.699141 5.384296 11.05163 6.576589 5.443897 10.97062 6.466315 5.525975 10.93434 9.569448 2.681199 11.28372 9.485852 2.792069 11.31882 9.400529 2.901654 11.35004 9.313799 3.010149 11.37805 9.225981 3.117776 11.40354 9.137422 3.224793 11.42729 9.048528 3.331525 11.45025 8.959637 3.438246 11.47319 8.870834 3.545035 11.49634 8.782113 3.651899 11.51968 8.693282 3.758684 11.54279 8.604105 3.865196 11.5651 8.514405 3.971282 11.58618 8.424007 4.076797 11.60564 8.332735 4.181581 11.62302 8.240416 4.285466 11.63791 8.14689 4.388289 11.64987 8.052001 4.489878 11.6585 7.955603 4.590054 11.66336 7.857563 4.688635 11.66406 7.757759 4.785432 11.66019 7.656081 4.880255 11.65137 7.552436 4.972902 11.63722 7.446679 5.063117 11.61722 7.336937 5.148505 11.58588 7.219944 5.223375 11.53167 7.093791 5.279946 11.44213 6.961351 5.315121 11.31697 6.827971 5.343004 11.18121 6.696768 5.379916 11.05988 6.573557 5.43993 10.97856 6.462828 5.522405 10.9422 9.756591 2.46889 10.89294 6.593067 5.460425 10.64984 9.753297 2.470836 10.86908 6.593793 5.461877 10.67472 9.677149 2.583212 10.9381 9.673892 2.585046 10.9142 9.669075 2.586936 10.89349 6.382807 5.638207 10.59111 6.715821 5.402592 10.75546 6.846337 5.366 10.87632 6.979876 5.338089 11.01225 7.113343 5.302473 11.13816 7.240796 5.245026 11.22825 7.358618 5.169384 11.28253 7.468852 5.083455 11.3138 7.574898 4.992919 11.33376 7.678793 4.899975 11.34785 7.780707 4.804862 11.3566 7.880733 4.707776 11.36039 7.978981 4.608912 11.3596 8.075576 4.50846 11.35463 8.170648 4.406604 11.3459 8.264349 4.303522 11.33382 8.356833 4.199388 11.31883 8.448264 4.094367 11.30134 8.538811 3.988626 11.28179 8.628661 3.882328 11.26062 8.71798 3.775621 11.23825 8.806946 3.668651 11.21508 8.895786 3.561605 11.19165 8.984731 3.454668 11.1685 9.073786 3.34782 11.1456 9.162806 3.240899 11.12257 9.251497 3.133658 11.09869 9.33945 3.02578 11.07305 9.426313 2.917005 11.04485 9.511759 2.807107 11.01339 9.595469 2.695895 10.978 9.587496 2.699252 10.93305 9.503899 2.810124 10.96815 9.418576 2.91971 10.99937 9.331842 3.028206 11.02737 9.244022 3.135834 11.05286 9.15547 3.242861 11.07664 9.066586 3.349604 11.09962 8.97766 3.4563 11.12249 8.88885 3.563088 11.14562 8.800146 3.66997 11.16902 8.711318 3.77676 11.19213 8.622137 3.88327 11.21443 8.532432 3.989358 11.23551 8.442033 4.094876 11.25497 8.350758 4.199661 11.27236 8.258439 4.303548 11.28724 8.16491 4.406373 11.2992 8.070019 4.507963 11.30783 7.973618 4.60814 11.31269 7.875577 4.706722 11.31338 7.775769 4.803521 11.30951 7.674089 4.898344 11.30069 7.570443 4.990995 11.28654 7.46468 5.081209 11.26654 7.354937 5.166591 11.23519 7.23795 5.241451 11.18098 7.111805 5.298013 11.09144 6.979356 5.33318 10.96625 6.845973 5.361066 10.83049 6.714768 5.397983 10.70916 6.591574 5.457999 10.62786 6.480861 5.54047 10.59152 9.592254 2.697569 10.95394 9.508592 2.808635 10.98921 9.423201 2.918398 11.02057 9.336394 3.027052 11.04868 9.248498 3.134822 11.07426 9.159867 3.24197 11.09809 9.070906 3.348814 11.1211 8.981906 3.455597 11.14399 8.893019 3.562469 11.16713 8.804239 3.669445 11.19054 8.715332 3.776336 11.21369 8.626071 3.882959 11.23603 8.536286 3.989168 11.25716 8.445802 4.094813 11.27667 8.354438 4.19973 11.29412 8.262025 4.303759 11.30906 8.168398 4.40673 11.32109 8.073405 4.508471 11.32977 7.976893 4.608804 11.3347 7.878735 4.707546 11.33545 7.778803 4.804508 11.33162 7.67699 4.899496 11.32284 7.573203 4.992313 11.30873 7.46728 5.08271 11.28875 7.357257 5.168404 11.25744 7.239796 5.243707 11.20319 7.112911 5.30077 11.11334 6.979887 5.336192 10.98775 6.846417 5.36409 10.85189 6.715602 5.400823 10.73083 5.924234 -5.901503 9.764018 5.830506 -5.838633 9.764018 5.872335 -5.778892 9.764019 5.872335 -5.778892 10.55118 5.950117 -5.856675 9.764018 5.932075 -5.737063 9.764019 5.916096 -5.745366 10.8774 5.882383 -5.769482 10.52614 5.904313 -5.752674 10.69195 5.892891 -5.760856 10.50152 6.039122 -6.136587 9.764017 5.811626 -5.90909 9.764018 5.830506 -5.838634 11.76402 5.950117 -5.998095 9.764018 5.924235 -5.953267 9.764018 5.836097 -5.827512 10.72651 5.83808 -5.823911 10.67211 5.843409 -5.815034 10.63491 5.856766 -5.796298 10.59361 5.966483 -6.13023 9.764017 5.817983 -5.981729 9.764018 5.811626 -5.909091 11.76402 5.900368 -6.099401 9.764017 5.848811 -6.047844 9.764017 5.817983 -5.98173 11.76402 5.848811 -6.047845 11.76402 5.900368 -6.099402 11.76402 5.966483 -6.130231 11.76402 5.994945 -6.023977 9.764017 6.109579 -6.117707 9.764017 6.039122 -6.136587 11.76402 6.091538 -5.998096 9.764018 6.16932 -6.075878 9.764016 6.125558 -6.109406 10.87739 6.046709 -6.023978 9.764017 6.109579 -6.117708 11.76402 6.11742 -5.953268 9.764018 6.211149 -6.016137 9.764017 6.16932 -6.075878 10.55118 6.137342 -6.102097 10.69194 6.148763 -6.093915 10.50152 6.159271 -6.085289 10.52614 6.002532 -5.718183 9.764019 6.230029 -5.94568 9.764017 6.211149 -6.016138 11.76402 6.091538 -5.856675 9.764018 6.11742 -5.901503 9.764018 6.205557 -6.027258 10.72651 6.184888 -6.058473 10.59361 6.203575 -6.030859 10.67211 6.198245 -6.039737 10.63491 6.075171 -5.724541 9.764019 6.223672 -5.873041 9.764017 6.230029 -5.945682 11.76402 6.141286 -5.75537 9.764019 6.192843 -5.806927 9.764018 6.223672 -5.873042 11.76402 6.192843 -5.806928 11.76402 6.141286 -5.755371 11.76402 6.075171 -5.724542 11.76402 6.04671 -5.830792 9.764018 6.002532 -5.718185 11.76402 5.994945 -5.830792 9.764018 5.932075 -5.737064 11.76402 5.950117 -5.856676 11.76402 5.924234 -5.901504 11.76402 5.994945 -5.830794 11.76402 6.04671 -5.830794 11.76402 6.091538 -5.856676 11.76402 6.11742 -5.901504 11.76402 6.11742 -5.953269 11.76402 6.091538 -5.998097 11.76402 6.046709 -6.023979 11.76402 5.994945 -6.023979 11.76402 5.950117 -5.998096 11.76402 5.924235 -5.953268 11.76402 5.872335 -5.778894 11.76402 5.872335 -5.778893 10.97685 5.840696 -5.819438 10.84961 5.845684 -5.81152 10.97498 5.851885 -5.802655 11.01163 5.860189 -5.792126 11.00951 5.866093 -5.78541 10.99327 5.893294 -5.760547 10.92627 6.16932 -6.075879 11.76401 6.16932 -6.075878 10.97685 6.175561 -6.069361 10.99327 6.200958 -6.035333 10.84961 6.19597 -6.043251 10.97498 6.189769 -6.052116 11.01162 6.181466 -6.062645 11.00951 6.148359 -6.094225 10.92627 5.752379 -5.688771 10.58957 5.742832 -5.694916 10.64096 5.746816 -5.692494 10.60962 5.832753 -5.822662 10.74113 5.741043 -5.695662 10.6788 5.841412 -5.809816 10.95002 5.831737 -5.81949 10.76208 5.754412 -5.682294 10.93852 5.843065 -5.810024 10.96407 5.751379 -5.684938 10.90518 5.765427 -5.673883 10.97119 5.759344 -5.678405 10.96174 5.771727 -5.669424 10.96545 5.910979 -5.740249 10.8774 5.637042 -5.360287 10.74096 6.130675 -6.114522 10.87739 6.269927 -6.185348 10.96545 6.480397 -6.599602 10.70321 6.150022 -6.095175 10.50152 6.289275 -6.166 10.58957 5.891632 -5.759596 10.50152 6.298823 -6.159854 10.64097 6.293122 -6.163397 10.6015 6.29638 -6.1613 10.61903 6.208901 -6.03211 10.74113 6.300662 -6.15926 10.69188 6.300284 -6.159158 10.66582 6.200243 -6.044954 10.95002 6.209917 -6.03528 10.76208 6.285779 -6.173662 10.9476 6.198589 -6.044748 10.96407 6.288494 -6.171427 10.92827 6.27833 -6.17935 10.96971 6.282312 -6.176365 10.96173 6.274104 -6.182415 10.97097 6.415743 -6.509453 10.73166 6.338866 -6.273482 10.94074 6.406897 -6.347186 10.93344 6.473313 -6.407808 10.9409 6.537353 -6.456452 10.96071 6.598408 -6.494329 10.99054 6.674009 -6.87819 10.59386 6.566868 -6.747646 10.5928 6.321419 -6.341106 10.48115 6.314115 -6.334324 10.51134 6.304441 -6.344007 10.69936 6.308491 -6.352818 10.72267 6.377219 -6.454984 10.74265 6.355161 -6.423319 10.74516 6.343381 -6.406176 10.74466 6.340208 -6.401521 10.74422 6.327276 -6.382305 10.74052 6.316581 -6.365935 10.73367 6.360774 -6.290901 10.9429 6.459185 -6.389022 10.94327 6.570446 -6.471958 10.97972 6.656866 -6.523083 11.02876 6.715548 -6.545211 11.0758 6.694427 -6.532453 11.06141 6.776458 -6.562963 11.13134 6.836951 -6.577268 11.19077 6.826092 -6.569581 11.18306 6.895133 -6.589416 11.25001 6.952961 -6.60133 11.30909 6.864799 -7.131163 10.51383 7.012926 -6.615038 11.36862 6.959382 -6.59745 11.31872 7.071586 -6.631345 11.42312 7.126716 -6.651017 11.46875 7.091165 -6.63234 11.44341 7.182654 -6.67631 11.50818 7.243748 -6.709913 11.54356 7.216455 -6.688336 11.53258 7.311124 -6.753564 11.57409 7.052556 -7.359276 10.4619 7.382373 -6.80614 11.59812 7.332893 -6.762694 11.58673 7.448388 -6.859374 11.61456 7.442307 -6.847722 11.61811 7.509097 -6.910833 11.62646 7.236083 -7.566697 10.43115 7.570827 -6.964684 11.6366 7.54788 -6.937726 11.63814 7.639973 -7.026709 11.64577 7.71819 -7.099042 11.65334 7.651363 -7.030185 11.65233 7.415012 -7.755523 10.41842 7.805851 -7.182821 11.65833 7.752889 -7.124818 11.66119 7.904534 -7.280493 11.65963 7.852552 -7.22143 11.66512 7.588996 -7.927331 10.42122 8.015951 -7.394901 11.65578 7.950458 -7.319829 11.66448 8.141358 -7.528629 11.64507 8.04673 -7.419827 11.65969 7.757155 -8.084631 10.43519 8.279453 -7.681405 11.62618 8.234914 -7.6239 11.63924 8.141501 -7.521244 11.65113 7.91919 -8.229294 10.45754 8.428615 -7.852039 11.59855 8.327127 -7.727627 11.62442 8.074818 -8.362869 10.48592 8.589406 -8.041066 11.56221 8.5086 -7.937629 11.58771 8.418298 -7.832258 11.6071 8.366199 -8.603774 10.55087 8.765854 -8.252408 11.51731 8.598208 -8.043581 11.56668 8.223844 -8.487428 10.5174 8.630632 -8.815397 10.61883 8.960693 -8.486741 11.46649 8.776038 -8.256633 11.52135 8.501783 -8.712771 10.58508 8.687294 -8.149966 11.54442 8.753981 -8.913015 10.65194 9.15687 -8.722386 11.4157 9.042197 -8.57671 11.45197 8.953391 -8.470088 11.47489 8.864671 -8.363393 11.49802 8.992593 -9.101773 10.71609 9.331193 -8.93557 11.36569 9.219475 -8.790209 11.40535 8.872996 -9.007072 10.68405 9.131003 -8.683328 11.42904 9.24563 -9.299739 10.78695 9.479492 -9.124286 11.31367 9.393853 -9.005993 11.35207 9.115472 -9.198572 10.74965 9.307207 -8.897678 11.37995 9.387419 -9.40467 10.83439 9.606965 -9.295153 11.25783 9.56262 -9.226031 11.28609 9.479095 -9.115379 11.321 9.622997 -9.514601 10.99607 9.716471 -9.450665 11.19863 9.644132 -9.338109 11.24676 9.60421 -9.523541 10.96039 9.582927 -9.526453 10.92925 9.561341 -9.522878 10.90608 9.541694 -9.513343 10.89307 9.63263 -9.524664 10.96435 9.723229 -9.451955 11.20238 9.601899 -9.537327 10.90851 9.567914 -9.536802 10.86545 9.535955 -9.523168 10.84187 9.20572 -9.283149 10.72578 8.884907 -9.030853 10.63761 8.564903 -8.777611 10.5517 8.247191 -8.521257 10.47274 7.934978 -8.257909 10.40987 7.631851 -7.983815 10.37251 7.341635 -7.695881 10.36957 7.066781 -7.393288 10.40527 6.808219 -7.076917 10.47966 6.35471 -6.250016 10.56566 6.379785 -6.271873 10.57343 6.479889 -6.3776 10.56256 6.499719 -6.580219 10.32734 6.426137 -6.478791 10.36901 6.418193 -6.319739 10.55763 6.333718 -6.355948 10.45744 6.350224 -6.37702 10.43476 6.360419 -6.390345 10.42321 6.367136 -6.399209 10.41628 6.387347 -6.426182 10.3978 7.091599 -6.612227 11.0478 6.759245 -6.948673 10.18717 6.583525 -6.731339 10.27189 7.019765 -6.592675 10.98052 6.935046 -6.574261 10.8952 6.847646 -6.555968 10.80627 6.771652 -6.537065 10.73281 6.706879 -6.516034 10.67652 6.650245 -6.491839 10.63477 6.595782 -6.462257 10.60276 6.539155 -6.424668 10.57826 7.432892 -6.811487 11.23057 7.025359 -7.284714 10.09718 6.824886 -7.060585 10.15879 7.369493 -6.762285 11.2123 7.30864 -6.719381 11.18921 7.253937 -6.685163 11.16285 7.203247 -6.657606 11.13308 7.151099 -6.633732 11.09669 7.717522 -7.060959 11.27581 7.285767 -7.580447 10.05172 7.083433 -7.376959 10.08438 7.634987 -6.985326 11.26693 7.562627 -6.921125 11.25643 7.496869 -6.864519 11.24466 7.914996 -7.252183 11.28385 7.533726 -7.835775 10.04224 7.358311 -7.679502 10.04878 7.810414 -7.149126 11.28189 8.167093 -7.516223 11.26848 7.769928 -8.059303 10.05855 7.648499 -7.967447 10.05166 8.03323 -7.373379 11.28004 8.319205 -7.685079 11.24693 7.993046 -8.257067 10.09117 7.951619 -8.241502 10.08906 8.492694 -7.884817 11.21316 8.202722 -8.434562 10.13258 8.693934 -8.123407 11.16509 8.399381 -8.595647 10.17836 8.26381 -8.504829 10.15194 8.920966 -8.396533 11.10577 8.583645 -8.743377 10.22537 9.141397 -8.661247 11.04879 8.756174 -8.880095 10.27145 8.5815 -8.761159 10.2309 8.917123 -9.007312 10.31486 8.901482 -9.014374 10.31681 9.329874 -8.890604 10.99618 9.069887 -9.128272 10.35578 9.222133 -9.247303 10.39852 9.488279 -9.091192 10.9419 9.383042 -9.368301 10.44988 9.222263 -9.266666 10.40495 9.621033 -9.268527 10.88453 9.561041 -9.493995 10.51719 9.735818 -9.431318 10.82275 9.580689 -9.50353 10.5302 9.552469 -9.506653 10.52104 9.602274 -9.507105 10.55338 9.584427 -9.520288 10.54462 9.623558 -9.504194 10.58451 9.618413 -9.520813 10.58768 9.642345 -9.495254 10.62019 9.742279 -9.432908 10.8323 9.649144 -9.508151 10.64352 9.751888 -9.436201 10.86195 9.748359 -9.434813 10.84811 9.663149 -9.319089 10.87728 9.581635 -9.207009 10.91662 9.412866 -8.986969 10.9826 9.49811 -9.096356 10.95153 9.326217 -8.878652 11.01048 9.061223 -8.557662 11.08254 9.238482 -8.771183 11.03588 9.150018 -8.664292 11.05959 8.883655 -8.344372 11.12851 8.972379 -8.451064 11.10539 8.617206 -8.024537 11.19721 8.79504 -8.237595 11.15188 8.706296 -8.130922 11.17496 8.437292 -7.81321 11.23764 8.527594 -7.918583 11.21824 8.253904 -7.604849 11.26977 8.346118 -7.708578 11.25496 8.160488 -7.502192 11.28166 7.969441 -7.300775 11.29501 8.065715 -7.400774 11.29022 7.871532 -7.202374 11.29565 7.771866 -7.105761 11.29172 7.670338 -7.011126 11.28285 7.566854 -6.918665 11.26866 7.461278 -6.828662 11.24863 7.351861 -6.74364 11.21724 7.23543 -6.669291 11.16308 7.110145 -6.613304 11.07391 6.978354 -6.578423 10.9492 6.845061 -6.550551 10.81354 6.713394 -6.513419 10.69189 6.58943 -6.452921 10.61022 6.478185 -6.369989 10.57379 6.290275 -6.169834 10.90518 6.299945 -6.160154 10.71724 6.356633 -6.233585 10.6957 6.362268 -6.261413 10.87997 6.374464 -6.279008 10.90046 9.658643 -9.299998 10.99885 9.632958 -9.287428 11.1948 9.748088 -9.451692 11.13158 9.745776 -9.452804 11.15562 9.757762 -9.442018 10.94364 9.639454 -9.526 10.89616 9.547154 -9.14856 11.05025 9.497794 -9.106074 11.25424 9.584538 -9.225211 11.23999 9.666243 -9.337976 11.20002 9.417628 -8.981093 11.09908 9.44798 -9.041705 11.27297 9.5008 -9.113922 11.27545 9.395196 -8.974664 11.29132 9.415325 -9.003954 11.30697 9.369771 -8.920991 11.11484 9.339158 -8.90461 11.30936 9.319372 -8.858502 11.13039 9.280007 -8.831696 11.32707 9.328434 -8.895115 11.33521 9.266362 -8.793518 11.1458 9.217489 -8.755529 11.34463 9.240453 -8.787184 11.36089 9.210783 -8.726019 11.16114 9.150852 -8.675071 11.36242 9.151725 -8.679904 11.38476 9.152282 -8.655481 11.17663 9.099152 -8.612973 11.3758 9.090208 -8.580972 11.19263 9.047163 -8.55065 11.3891 9.062662 -8.572956 11.40778 9.041806 -8.522962 11.205 8.994427 -8.487419 11.4026 8.992683 -8.464038 11.21761 8.940998 -8.423207 11.41648 8.973612 -8.466049 11.43076 8.943064 -8.404376 11.23053 8.888241 -8.359672 11.43035 8.892189 -8.343098 11.24392 8.837287 -8.298266 11.4438 8.884653 -8.35908 11.45393 8.841177 -8.28162 11.25739 8.787536 -8.238335 11.4569 8.795765 -8.252021 11.47731 8.791294 -8.221539 11.27051 8.738889 -8.179828 11.46959 8.694764 -8.105635 11.29545 8.675997 -8.104429 11.48569 8.706768 -8.145016 11.50049 8.742683 -8.163091 11.28317 8.632788 -8.031652 11.3109 8.615562 -8.032341 11.50068 8.617423 -8.038265 11.52289 8.573847 -7.961737 11.32502 8.557126 -7.963086 11.5146 8.517601 -7.895518 11.33786 8.500144 -7.89607 11.52751 8.527544 -7.931922 11.54407 8.463586 -7.83246 11.34949 8.444733 -7.831477 11.53933 8.411683 -7.772429 11.35995 8.390785 -7.769199 11.55005 8.436963 -7.826133 11.56364 8.361971 -7.715501 11.36924 8.338167 -7.7091 11.55968 8.345499 -7.721062 11.58115 8.22361 -7.560364 11.39083 8.286946 -7.65126 11.5682 8.237112 -7.595659 11.57562 8.252979 -7.616873 11.59617 8.096237 -7.442399 11.59156 8.15924 -7.513734 11.60827 7.989316 -7.310658 11.41066 7.970758 -7.311219 11.5989 8.064126 -7.411818 11.61702 8.10004 -7.426471 11.40411 7.889921 -7.210276 11.41193 7.860494 -7.200417 11.59959 7.967489 -7.311304 11.62201 7.800579 -7.123064 11.40919 7.763314 -7.106396 11.59552 7.769117 -7.115225 11.61907 7.869194 -7.212377 11.62283 7.719969 -7.046895 11.40348 7.677292 -7.026082 11.58818 7.647363 -6.980367 11.39566 7.601526 -6.957645 11.57875 7.66715 -7.020045 11.61033 7.582635 -6.922732 11.38653 7.53484 -6.899202 11.56814 7.563198 -6.927034 11.59625 7.523749 -6.871675 11.37646 7.470417 -6.844395 11.55577 7.410742 -6.778567 11.35085 7.40023 -6.787588 11.53855 7.457087 -6.836423 11.57631 7.46711 -6.823933 11.36501 7.354963 -6.736717 11.33293 7.323798 -6.731239 11.51271 7.346725 -6.750353 11.54505 7.302031 -6.700494 11.31142 7.251494 -6.684872 11.47933 7.208381 -6.646288 11.26067 7.186098 -6.649718 11.44042 7.228673 -6.674508 11.49074 7.253804 -6.670904 11.28744 7.161799 -6.624525 11.22873 7.125785 -6.623505 11.39653 7.110032 -6.604627 11.18772 7.064924 -6.603116 11.34445 7.100862 -6.616833 11.40048 7.049736 -6.586519 11.13343 7.000439 -6.586361 11.28303 6.979483 -6.569822 11.06451 6.93747 -6.572679 11.21961 6.967136 -6.581096 11.27439 6.902286 -6.553842 10.98574 6.876423 -6.560184 11.15713 6.82792 -6.537823 10.91066 6.814157 -6.546538 11.09457 6.833569 -6.553182 11.13843 6.764016 -6.521255 10.84974 6.75034 -6.529754 11.03404 6.708943 -6.503155 10.80216 6.688675 -6.508795 10.98166 6.703252 -6.516679 11.01771 6.660364 -6.482834 10.7658 6.629035 -6.481837 10.93961 6.614221 -6.458859 10.73727 6.56711 -6.44562 10.90652 6.581542 -6.457593 10.93712 6.517075 -6.392811 10.69726 6.501552 -6.397812 10.88368 6.566757 -6.429275 10.71427 6.465276 -6.348581 10.68752 6.432974 -6.336863 10.87387 6.471854 -6.376013 10.90095 6.411647 -6.295756 10.68649 6.386625 -6.266831 10.66407 6.484004 -6.363831 10.66456 6.593677 -6.445407 10.70072 6.715373 -6.504496 10.78128 6.845688 -6.541003 10.90199 6.979259 -6.568919 11.03795 7.112996 -6.604646 11.16407 7.240797 -6.662313 11.25432 7.358843 -6.73815 11.30864 7.469205 -6.824213 11.33991 7.57532 -6.914824 11.35986 7.679276 -7.007838 11.37394 7.781246 -7.10302 11.38267 7.881325 -7.200172 11.38644 7.979621 -7.2991 11.38562 8.076261 -7.399616 11.38064 8.171378 -7.501533 11.37188 8.265118 -7.604674 11.35979 8.35764 -7.708865 11.34477 8.449106 -7.813938 11.32726 8.539689 -7.919727 11.30769 8.62957 -8.026072 11.2865 8.718921 -8.132822 11.26411 8.807915 -8.239831 11.24093 8.896784 -8.346911 11.21749 8.985757 -8.453879 11.19434 9.07484 -8.560759 11.17144 9.163888 -8.667718 11.14839 9.25261 -8.775007 11.12449 9.340596 -8.88294 11.09882 9.427488 -8.99178 11.07058 9.596702 -9.213039 11.0036 9.512964 -9.101749 11.03906 9.67841 -9.325807 10.96364 9.649127 -9.516325 10.70822 9.758035 -9.440544 10.91744 9.606698 -9.539497 10.83664 9.736758 -9.45338 11.19036 9.742977 -9.453236 11.17144 6.386353 -6.266866 10.63798 6.482808 -6.365176 10.61351 6.385048 -6.267763 10.61307 9.616373 -9.529823 10.64871 9.580148 -9.529263 10.60281 9.570475 -9.538936 10.79075 9.536411 -9.524404 10.76562 9.546084 -9.51473 10.57768 9.374878 -9.411098 10.70356 9.359597 -9.383152 10.50702 6.440513 -6.536351 10.41403 6.50425 -6.657278 10.55327 6.571642 -6.732227 10.3307 6.705733 -6.942752 10.44518 6.849294 -7.108665 10.20358 6.906005 -7.201697 10.36968 7.127646 -7.443447 10.13096 7.100859 -7.433603 10.322 7.291079 -7.643515 10.29666 7.393614 -7.731001 10.10318 7.476407 -7.834217 10.28974 7.647082 -7.980334 10.1085 7.655828 -8.00731 10.29788 7.886672 -8.198374 10.13623 7.828773 -8.165287 10.31714 7.994633 -8.310345 10.34391 8.111638 -8.391834 10.17677 8.153453 -8.444607 10.37551 8.322024 -8.565777 10.22367 8.304971 -8.569437 10.40985 8.449159 -8.686024 10.44537 8.518504 -8.724126 10.27273 8.585874 -8.795179 10.48083 8.701956 -8.869867 10.32126 8.716069 -8.898355 10.5156 8.872384 -9.004539 10.36727 8.840682 -8.996809 10.54926 8.965223 -9.095295 10.58279 9.032979 -9.131606 10.41042 9.092557 -9.195911 10.61717 9.191942 -9.256281 10.45454 9.227685 -9.300936 10.6559 5.671375 -5.408414 10.75404 5.700223 -5.578257 10.94015 5.630671 -5.503528 10.93349 5.562806 -5.442378 10.94213 5.4975 -5.393702 10.96353 5.525541 -5.18081 10.65349 5.500334 -5.130496 10.61308 5.708739 -5.500881 10.45036 5.727539 -5.520447 10.51135 5.737214 -5.510771 10.69931 5.733347 -5.50145 10.72878 5.720006 -5.514063 10.47536 5.718679 -5.512594 10.47175 5.681547 -5.422918 10.75597 5.694651 -5.441841 10.75657 5.711142 -5.466202 10.75298 5.713123 -5.469189 10.75208 5.724112 -5.486138 10.74401 5.732047 -5.499161 10.73196 5.676161 -5.5625 10.94274 5.574477 -5.462265 10.9446 5.435432 -5.356188 10.99513 5.459231 -5.378569 10.9852 5.375901 -5.32797 11.03542 5.392854 -4.986071 10.57364 5.315207 -5.306094 11.08537 5.33084 -5.319333 11.0742 5.252512 -5.288634 11.14358 5.191272 -5.274657 11.2044 5.195032 -5.283421 11.20274 5.132116 -5.262468 11.26484 5.07291 -5.250078 11.32508 5.235757 -4.776016 10.50549 5.01054 -5.235159 11.38615 5.057757 -5.254652 11.34237 4.942236 -5.214093 11.44693 4.867946 -5.182747 11.5022 4.922542 -5.215032 11.46535 4.790272 -5.140023 11.54717 4.795204 -5.152039 11.54818 5.057209 -4.557817 10.45447 4.710086 -5.086464 11.58143 4.625611 -5.021712 11.60681 4.67718 -5.071777 11.59678 4.538175 -4.948904 11.62564 4.565717 -4.982301 11.62508 4.867926 -4.345179 10.42442 4.448423 -4.870946 11.64082 4.457334 -4.889065 11.64456 4.350691 -4.783075 11.65351 4.350831 -4.793654 11.65884 4.68528 -4.154945 10.41465 4.241964 -4.681509 11.66272 4.246195 -4.696174 11.66805 4.124084 -4.566866 11.66689 4.143376 -4.596767 11.67244 4.515132 -3.987838 10.41857 3.99742 -4.438436 11.66462 4.042312 -4.495573 11.67227 4.357795 -3.840362 10.43126 3.861606 -4.294802 11.65456 3.942934 -4.39273 11.66782 4.212015 -3.708809 10.44957 3.716043 -4.134294 11.63532 3.845156 -4.288373 11.65935 4.07651 -3.590195 10.47131 3.560005 -3.955155 11.6056 3.654025 -4.075662 11.63158 3.748887 -4.18264 11.64717 3.833014 -3.384093 10.51943 3.392802 -3.75586 11.5643 3.46808 -3.858483 11.59139 3.950386 -3.482447 10.49495 3.560461 -3.967568 11.61288 3.622425 -3.211205 10.56794 3.21353 -3.535044 11.51084 3.376761 -3.748531 11.56741 3.723701 -3.293846 10.54396 3.365676 -3.00476 10.63268 3.020475 -3.291029 11.44527 3.1968 -3.526494 11.51327 3.443862 -3.067265 10.6125 3.529207 -3.13582 10.59089 3.286377 -3.637829 11.54127 3.085678 -2.782099 10.70646 2.810986 -3.021995 11.36865 2.931572 -3.189798 11.42131 3.154502 -2.836765 10.68824 3.223094 -2.891255 10.67009 3.292798 -2.946687 10.65173 3.019532 -3.30237 11.45298 3.107897 -3.414638 11.48374 2.807945 -2.564167 10.78342 2.581439 -2.726473 11.28375 2.756311 -2.96416 11.35648 2.876302 -2.61693 10.76335 2.946092 -2.671564 10.74384 3.016115 -2.726896 10.72494 2.843877 -3.077027 11.38904 2.418658 -2.340171 10.99612 2.326481 -2.40322 11.19587 2.493014 -2.626022 11.26017 2.437445 -2.33123 10.96044 2.458729 -2.328318 10.9293 2.480314 -2.331894 10.90613 2.499961 -2.341429 10.89311 2.58906 -2.402836 10.85748 2.66767 -2.459167 10.82881 2.739385 -2.512216 10.80479 2.581016 -2.738555 11.29174 2.668737 -2.851302 11.32395 2.409025 -2.330107 10.9644 2.315764 -2.401722 11.2002 2.404597 -2.513805 11.22955 2.439756 -2.317444 10.90855 2.473742 -2.31797 10.8655 2.503466 -2.335713 10.87315 2.781769 -2.535824 10.77253 3.052142 -2.746939 10.69627 3.320723 -2.960381 10.62531 3.588384 -3.175019 10.55708 3.853713 -3.392623 10.49567 4.115206 -3.614938 10.44525 4.371232 -3.843652 10.4101 4.61999 -4.080344 10.39457 4.859492 -4.326426 10.40304 5.087576 -4.583044 10.43975 5.301955 -4.850968 10.50866 2.307134 -2.422567 10.81999 2.460966 -2.351242 10.53025 2.480613 -2.360776 10.51724 2.484854 -2.354324 10.51158 2.393583 -2.531788 10.84929 2.592814 -2.43848 10.47285 2.76316 -2.554437 10.41095 2.439381 -2.347666 10.55342 2.457227 -2.334484 10.54467 2.489186 -2.348118 10.52109 2.418097 -2.350578 10.58456 2.423241 -2.333958 10.58773 2.39931 -2.359518 10.62024 2.297101 -2.420385 10.83763 2.39251 -2.346621 10.64356 2.290414 -2.418315 10.86019 2.385988 -2.532419 10.86798 2.477382 -2.63808 10.87824 2.688337 -2.507939 10.43931 2.558533 -2.741443 10.90682 2.474409 -2.644639 10.8986 2.774866 -2.573026 10.41171 2.63693 -2.841875 10.93517 2.562413 -2.757176 10.93017 2.944526 -2.704913 10.3631 2.712547 -2.939375 10.96333 2.650135 -2.869926 10.96238 2.859163 -2.637995 10.38684 3.030014 -2.772601 10.3402 2.80381 -3.057138 10.99743 2.737713 -2.982787 10.99491 3.11472 -2.839884 10.31778 2.891957 -3.170456 11.02982 2.825281 -3.095656 11.02747 3.198603 -2.906516 10.29558 2.976734 -3.279238 11.06071 2.912977 -3.20843 11.05974 3.374147 -3.046322 10.24959 3.058083 -3.382899 11.08942 3.00094 -3.321005 11.09141 3.283869 -2.974326 10.27312 3.473106 -3.125602 10.22426 3.135949 -3.481327 11.11588 3.089307 -3.433276 11.12217 3.583261 -3.214476 10.19688 3.210452 -3.574695 11.14016 3.178212 -3.545135 11.15171 3.281667 -3.662978 11.16212 3.267792 -3.656474 11.17971 3.705249 -3.313913 10.16786 3.349517 -3.746103 11.18178 3.984875 -3.547509 10.10862 3.593677 -4.036185 11.24087 3.358179 -3.767177 11.20585 3.838997 -3.424511 10.13807 4.143749 -3.684962 10.08106 3.800429 -4.268695 11.27401 3.635452 -4.094316 11.27002 3.449501 -3.877132 11.22983 3.541885 -3.98622 11.25132 4.317069 -3.84007 10.05762 3.97661 -4.456279 11.28869 3.826589 -4.307032 11.29778 3.730317 -4.201297 11.28561 4.508189 -4.018903 10.04181 4.127111 -4.608316 11.29066 4.023751 -4.514235 11.3107 3.924369 -4.41139 11.30625 4.719165 -4.228352 10.03984 4.256043 -4.732517 11.28457 4.124817 -4.61543 11.31087 4.943274 -4.468724 10.06077 4.366967 -4.834817 11.27348 4.332279 -4.812318 11.29726 4.22764 -4.714838 11.30647 4.461448 -4.918707 11.25985 4.438781 -4.907735 11.28299 4.543434 -4.989065 11.24488 5.15906 -4.722997 10.11029 4.622869 -5.054309 11.22662 4.547186 -5.000948 11.26345 4.701718 -5.113649 11.20152 4.658636 -5.090437 11.23519 4.774018 -5.161273 11.16976 5.343737 -4.964181 10.18301 4.83826 -5.196987 11.13305 4.776651 -5.170688 11.18659 4.905142 -5.226876 11.08545 4.98744 -5.253452 11.01374 4.903958 -5.233687 11.10383 5.091934 -5.277508 10.91023 5.039178 -5.273271 10.98077 5.494652 -5.182751 10.27007 5.203039 -5.300876 10.79733 5.176457 -5.302039 10.84113 5.295839 -5.325425 10.7095 5.372354 -5.354057 10.64788 5.312265 -5.337963 10.7126 5.617694 -5.379633 10.36508 5.44145 -5.389847 10.60502 5.513524 -5.438224 10.57453 5.440647 -5.397196 10.62362 5.58984 -5.502318 10.5588 5.555881 -5.480888 10.58302 5.669621 -5.584654 10.56209 5.657556 -5.581119 10.58117 5.652847 -5.427871 10.38671 5.696616 -5.485724 10.43117 5.694537 -5.483067 10.42833 5.677092 -5.460343 10.40796 5.662986 -5.441549 10.39481 5.481729 -5.149117 10.25152 5.283355 -4.869593 10.14709 5.068979 -4.601671 10.07819 4.840896 -4.345053 10.04147 4.601393 -4.09897 10.033 4.352634 -3.862276 10.04853 4.096607 -3.63356 10.08368 3.835111 -3.411242 10.13409 3.569781 -3.193636 10.19551 3.302118 -2.978996 10.26374 3.033535 -2.765554 10.3347 5.741709 -5.694616 10.71724 5.678571 -5.592404 10.8798 5.665678 -5.5716 10.91027 5.663069 -5.595355 10.69071 2.344252 -2.488385 10.96334 2.348846 -2.472324 11.1496 2.293566 -2.40308 11.13163 2.297655 -2.401592 11.16584 2.283892 -2.412753 10.94369 2.402201 -2.328772 10.89621 2.402877 -2.540467 11.16775 2.386938 -2.513843 11.19465 2.403162 -2.562745 10.98322 2.455704 -2.607479 11.18601 2.46068 -2.635795 11.00321 2.507369 -2.673334 11.20427 2.475572 -2.626258 11.22525 2.516858 -2.707504 11.02319 2.557891 -2.737986 11.22245 2.571742 -2.777836 11.04307 2.61946 -2.81704 11.24495 2.563787 -2.73901 11.25683 2.625333 -2.846711 11.06274 2.679436 -2.894245 11.26712 2.651719 -2.851995 11.28907 2.677698 -2.914143 11.08213 2.737997 -2.969727 11.28889 2.739502 -2.96511 11.32166 2.73736 -2.991053 11.10432 2.795149 -3.04341 11.31017 2.795611 -3.066147 11.12599 2.850937 -3.115274 11.33085 2.827275 -3.078252 11.35431 2.852562 -3.139488 11.14709 2.905499 -3.185429 11.35092 2.908201 -3.210992 11.1675 2.958917 -3.253928 11.37032 2.915177 -3.191315 11.38669 2.962466 -3.280521 11.18714 3.011152 -3.32067 11.38899 3.003346 -3.304196 11.41848 3.015288 -3.347943 11.20593 3.062304 -3.385746 11.40691 3.076747 -3.425988 11.22727 3.112478 -3.449254 11.42407 3.091921 -3.41679 11.44939 3.1362 -3.500998 11.24729 3.161641 -3.511126 11.44042 3.193691 -3.573001 11.26596 3.20983 -3.571389 11.45596 3.181038 -3.528987 11.47909 3.249212 -3.641979 11.28328 3.272739 -3.649424 11.47542 3.270834 -3.640677 11.50726 3.302659 -3.707808 11.29921 3.334132 -3.724811 11.49343 3.366903 -3.786125 11.31732 3.39404 -3.797577 11.50998 3.361443 -3.751747 11.53359 3.428687 -3.86054 11.33358 3.452584 -3.867865 11.52509 3.452994 -3.862082 11.55776 3.487803 -3.930854 11.34799 3.509721 -3.935631 11.53876 3.544597 -3.997541 11.36072 3.565538 -4.000993 11.55105 3.545616 -3.97156 11.57946 3.616974 -4.081232 11.37528 3.620055 -4.063997 11.56197 3.673262 -4.124659 11.57156 3.63943 -4.080059 11.59835 3.685532 -4.159108 11.38726 3.725256 -4.183124 11.57989 3.81249 -4.299543 11.40461 3.873924 -4.345664 11.59774 3.734553 -4.187451 11.61414 3.750704 -4.231822 11.39697 3.927078 -4.421898 11.4146 4.012345 -4.490585 11.6061 3.929162 -4.398393 11.63515 3.87129 -4.36286 11.41042 3.831096 -4.293607 11.62651 4.078696 -4.577145 11.41927 4.141081 -4.619637 11.60651 4.028844 -4.501671 11.63978 4.20913 -4.704514 11.41532 4.260578 -4.734415 11.60043 4.233383 -4.703151 11.63584 4.130227 -4.603304 11.6401 4.321876 -4.809969 11.40594 4.369627 -4.83494 11.58946 4.338372 -4.801071 11.62675 4.419114 -4.897473 11.39341 4.467168 -4.921464 11.57529 4.445248 -4.896922 11.61256 4.502238 -4.969764 11.37947 4.558723 -4.999778 11.55825 4.554028 -4.990601 11.59313 4.579348 -5.034606 11.36369 4.6487 -5.072542 11.53609 4.656536 -5.095564 11.3428 4.735036 -5.134959 11.50532 4.666118 -5.080794 11.56494 4.798393 -5.189715 11.28141 4.818141 -5.185631 11.46358 4.785263 -5.162182 11.51636 4.731714 -5.148857 11.31464 4.861241 -5.221919 11.24198 4.898961 -5.22451 11.40961 4.931986 -5.25028 11.18744 4.974429 -5.251015 11.3466 4.914444 -5.226557 11.43295 5.020302 -5.275477 11.10621 5.042212 -5.268702 11.28213 5.126463 -5.298357 10.99905 5.104681 -5.282258 11.21919 5.051459 -5.267066 11.30878 5.165499 -5.2947 11.15694 5.229527 -5.320754 10.89524 5.227568 -5.308293 11.09456 5.189201 -5.295963 11.16871 5.291238 -5.325018 11.03415 5.313202 -5.344705 10.81839 5.352903 -5.345952 10.98174 5.324154 -5.331461 11.04074 5.382311 -5.372413 10.76511 5.412367 -5.372795 10.93976 5.446987 -5.407472 10.727 5.474164 -5.408886 10.90668 5.450788 -5.389615 10.95261 5.515148 -5.454579 10.6999 5.539606 -5.45654 10.88379 5.587446 -5.516477 10.68652 5.608057 -5.517289 10.87388 5.564789 -5.472235 10.91223 5.652316 -5.584977 10.65054 5.551434 -5.485616 10.6525 5.437447 -5.403 10.69287 5.31082 -5.344847 10.78099 5.175868 -5.30934 10.90895 5.038122 -5.280445 11.04903 4.901102 -5.239971 11.17327 4.771951 -5.17559 11.25661 4.652817 -5.094212 11.3052 4.540737 -5.004003 11.33334 4.431938 -4.910349 11.35284 4.325063 -4.814494 11.36702 4.22007 -4.716573 11.37612 4.116911 -4.616725 11.38038 4.015525 -4.515091 11.38006 3.91584 -4.411811 11.37543 3.817771 -4.307024 11.36679 3.721225 -4.200866 11.35442 3.626098 -4.093471 11.33864 3.532281 -3.984969 11.31974 3.439657 -3.875489 11.29805 3.348103 -3.765152 11.27388 3.257492 -3.654078 11.24755 3.167693 -3.542385 11.21937 3.078573 -3.430185 11.18968 2.989996 -3.317589 11.15877 2.901824 -3.204705 11.12697 2.81392 -3.091638 11.09459 2.726145 -2.978494 11.06195 2.638359 -2.865377 11.02935 2.550426 -2.752389 10.99711 2.462209 -2.639633 10.96553 2.373571 -2.527215 10.93493 2.284219 -2.415028 10.90481 2.392528 -2.338446 10.70827 2.434956 -2.315275 10.83669 2.305307 -2.401126 11.1896 2.299003 -2.40142 11.17194 2.425282 -2.324949 10.64875 2.461506 -2.32551 10.60286 2.47118 -2.315836 10.7908 2.505244 -2.330367 10.76566 2.506324 -2.329725 10.8041 2.49557 -2.340041 10.57773 2.594568 -2.391872 10.72987 2.790773 -2.534478 10.70154 2.5057 -2.331603 10.84192 2.607619 -2.41764 10.5334 2.492955 -2.343094 10.54437 5.622889 -5.338665 10.4121 5.642165 -5.344983 10.60826 5.529109 -5.164263 10.52119 5.552577 -5.198406 10.57557 5.496553 -5.139216 10.31802 5.394621 -4.967851 10.4415 5.341816 -4.918113 10.23261 5.236208 -4.756884 10.37387 5.353906 -4.909774 10.45981 5.15309 -4.674888 10.16248 5.056473 -4.538372 10.32398 5.138051 -4.633291 10.38179 4.935072 -4.421213 10.1166 4.866884 -4.326604 10.29544 4.907447 -4.368767 10.33814 4.712502 -4.184966 10.099 4.685007 -4.137659 10.28635 4.504435 -3.979927 10.1029 4.515369 -3.971458 10.29077 4.664554 -4.11547 10.32476 4.358495 -3.824779 10.30389 4.411709 -3.872241 10.33713 4.316154 -3.804642 10.11962 4.213284 -3.693974 10.32243 4.145087 -3.652092 10.14346 4.078318 -3.575969 10.34425 4.151061 -3.63761 10.37062 3.988174 -3.516685 10.17113 3.952704 -3.468731 10.3679 3.844069 -3.395406 10.2005 3.835762 -3.370775 10.39233 3.884555 -3.409912 10.42056 3.711931 -3.286276 10.23011 3.726884 -3.28093 10.41683 3.626026 -3.198669 10.44076 3.591454 -3.188157 10.25888 3.533204 -3.123628 10.46364 3.613946 -3.18736 10.4824 3.482701 -3.100463 10.28599 3.448219 -3.055373 10.48517 3.384927 -3.022159 10.31104 3.370375 -2.993145 10.50526 3.295539 -2.950887 10.33435 3.297723 -2.935252 10.52426 3.340845 -2.968099 10.55168 3.210915 -2.883592 10.35665 3.228181 -2.879951 10.54258 3.159757 -2.825598 10.56069 3.127518 -2.817351 10.37873 3.091096 -2.771067 10.57888 3.043269 -2.75044 10.40104 3.021669 -2.715959 10.5973 3.066758 -2.75024 10.62404 2.958228 -2.683118 10.42384 2.951733 -2.660707 10.6162 2.873288 -2.616554 10.44749 2.882024 -2.60615 10.6357 2.789323 -2.551872 10.47231 2.813662 -2.553396 10.65578 2.745059 -2.501429 10.67719 2.703002 -2.486972 10.49987 2.673274 -2.448328 10.70123 2.777415 -2.547855 10.44181 3.05341 -2.763624 10.36431 3.327506 -2.981491 10.29195 3.600617 -3.200761 10.22267 3.871234 -3.423321 10.16082 4.13775 -3.651029 10.11088 4.398405 -3.885669 10.0774 4.651256 -4.128911 10.06503 4.894154 -4.382218 10.07843 5.124759 -4.646753 10.12209 5.340612 -4.923244 10.20012 5.539278 -5.211884 10.3159 5.516836 -5.188708 10.28038 5.533328 -5.172166 10.60115 2.787813 -2.534592 10.74009 3.061674 -2.748595 10.66306 3.33368 -2.964784 10.59123 3.604724 -3.182293 10.52234 3.873335 -3.402967 10.46065 4.137946 -3.628619 10.41051 4.396847 -3.860998 10.37637 4.648149 -4.101736 10.36278 4.889767 -4.35228 10.37426 5.119429 -4.613788 10.41524 5.334744 -4.887005 10.48974 2.307565 -2.401164 11.19341 2.394442 -2.513194 11.21873 5.670393 -5.567432 10.93341 2.482992 -2.625533 11.24934 2.571125 -2.738201 11.28092 2.658975 -2.851094 11.31314 2.746678 -2.96411 11.34572 2.83437 -3.077144 11.37833 2.922192 -3.190095 11.41066 3.01028 -3.302856 11.44241 3.098773 -3.415323 11.47326 3.187807 -3.527387 11.5029 3.277517 -3.638939 11.531 3.368038 -3.749866 11.55726 3.459499 -3.860051 11.58135 3.552026 -3.969376 11.60297 3.645742 -4.077716 11.62179 3.740763 -4.184947 11.6375 3.837198 -4.290938 11.64979 3.935151 -4.395555 11.65837 4.034714 -4.498663 11.66293 4.135971 -4.600124 11.66319 4.238995 -4.699798 11.65888 4.343845 -4.797546 11.64974 4.450574 -4.893224 11.63552 4.559198 -4.98673 11.61607 4.671041 -5.076642 11.58784 4.789741 -5.157586 11.53925 4.918188 -5.221415 11.45607 5.054481 -5.261569 11.33239 5.192035 -5.290415 11.1925 5.327332 -5.326076 11.06429 5.454677 -5.384662 10.97581 5.569181 -5.467715 10.93533 3.045168 -2.765115 10.34224 2.771303 -2.551108 10.41926 3.317178 -2.981306 10.27041 3.588226 -3.198818 10.20152 3.856841 -3.419496 10.13983 4.121455 -3.645152 10.0897 4.380359 -3.877533 10.05557 4.631664 -4.118275 10.04198 4.873282 -4.368823 10.05347 5.102944 -4.630333 10.09445 5.318256 -4.903549 10.16897 2.284834 -2.415588 10.89667 2.288761 -2.417672 10.86815 2.377933 -2.529708 10.89795 5.653888 -5.58395 10.61263 2.466486 -2.642051 10.92856 2.554621 -2.754722 10.96014 2.642473 -2.867618 10.99237 2.730178 -2.980637 11.02494 2.817873 -3.093674 11.05755 2.905697 -3.206627 11.08989 2.993787 -3.319392 11.12164 3.082283 -3.431861 11.15249 3.171319 -3.543929 11.18212 3.261032 -3.655483 11.21023 3.351556 -3.766413 11.23649 3.44302 -3.876601 11.26058 3.535549 -3.985928 11.2822 3.629268 -4.094271 11.30102 3.724292 -4.201504 11.31672 3.820731 -4.307497 11.32902 3.918687 -4.412116 11.33759 4.018252 -4.515226 11.34215 4.119513 -4.616688 11.34241 4.222539 -4.716363 11.3381 4.327393 -4.814111 11.32895 4.434121 -4.909794 11.31474 4.542766 -5.003276 11.29523 4.654597 -5.093203 11.26704 4.773287 -5.174136 11.21845 4.901703 -5.23797 11.13534 5.038001 -5.27809 11.01158 5.17556 -5.306934 10.87168 5.310856 -5.342606 10.74348 5.438193 -5.401189 10.65501 5.552684 -5.484239 10.61455 9.730259 -9.452913 11.19976 9.734795 -9.453293 11.19403 9.651027 -9.338792 11.24411 9.657382 -9.339142 11.2349 9.662647 -9.338969 11.21982 6.483885 -6.36403 10.63845 6.371855 -6.281378 10.91975 6.368544 -6.284283 10.93383 6.364763 -6.287529 10.94172 9.580967 -9.226288 11.25971 9.497258 -9.115077 11.2951 9.411813 -9.005183 11.32657 9.324954 -8.896407 11.35477 9.237004 -8.788531 11.38041 9.148306 -8.6813 11.40427 9.059273 -8.57439 11.42727 8.970251 -8.467514 11.45024 8.881317 -8.360577 11.47341 8.79246 -8.253552 11.49679 8.703491 -8.146585 11.51995 8.614176 -8.039876 11.54234 8.52433 -7.93358 11.56351 8.433782 -7.827841 11.58306 8.342353 -7.722823 11.60054 8.249873 -7.61869 11.61554 8.156173 -7.515609 11.62761 8.061103 -7.413755 11.63634 7.964512 -7.313303 11.64131 7.866266 -7.214442 11.64211 7.766242 -7.117357 11.63832 7.66433 -7.022244 11.62958 7.560439 -6.929304 11.61548 7.454398 -6.838768 11.59553 7.344164 -6.752832 11.56427 7.226335 -6.677181 11.50999 7.098873 -6.619727 11.4199 6.965417 -6.584101 11.29401 6.831881 -6.556191 11.15809 6.701364 -6.519605 11.03722 6.579321 -6.460322 10.95645 6.469398 -6.378548 10.92023 9.575747 -9.22662 11.27464 9.492087 -9.115557 11.30991 9.406695 -9.005796 11.34127 9.31989 -8.897142 11.36939 9.231999 -8.789373 11.39496 9.143361 -8.682235 11.41877 9.054387 -8.575403 11.44175 8.965421 -8.468593 11.46471 8.876543 -8.36172 11.48787 8.787745 -8.254764 11.51124 8.698836 -8.147876 11.53438 8.60958 -8.041252 11.55673 8.519797 -7.935045 11.57786 8.429313 -7.829403 11.59737 8.337952 -7.724486 11.61481 8.245542 -7.620461 11.62976 8.151917 -7.51749 11.64179 8.056926 -7.415751 11.65047 7.960419 -7.315419 11.6554 7.862261 -7.216678 11.65615 7.762333 -7.119717 11.65233 7.660522 -7.024731 11.64355 7.556736 -6.931916 11.62943 7.450817 -6.841518 11.60946 7.340796 -6.75582 11.57816 7.22333 -6.680506 11.52392 7.096435 -6.623435 11.43407 6.963421 -6.588005 11.30849 6.829954 -6.560107 11.17264 6.69914 -6.52338 11.05157 6.576588 -6.46378 10.97056 6.466314 -6.381701 10.93428 9.569449 -9.226478 11.28366 9.485852 -9.115608 11.31876 9.40053 -9.006024 11.34998 9.313799 -8.897528 11.37799 9.225982 -8.7899 11.40348 9.137421 -8.682884 11.42723 9.048527 -8.576151 11.45018 8.959638 -8.46943 11.47313 8.870835 -8.362642 11.49628 8.782112 -8.255778 11.51962 8.693283 -8.148993 11.54273 8.604105 -8.042481 11.56504 8.514404 -7.936394 11.58612 8.424005 -7.830879 11.60558 8.332734 -7.726096 11.62296 8.240416 -7.62221 11.63785 8.146889 -7.519387 11.64981 8.052 -7.417798 11.65844 7.955603 -7.317622 11.6633 7.857563 -7.219041 11.664 7.757759 -7.122244 11.66013 7.65608 -7.027422 11.65131 7.552436 -6.934774 11.63716 7.446677 -6.844559 11.61716 7.336937 -6.759172 11.58582 7.219944 -6.684302 11.53161 7.093791 -6.627732 11.44207 6.961351 -6.592556 11.31691 6.82797 -6.564672 11.18115 6.696767 -6.527761 11.05982 6.573556 -6.467747 10.97849 6.462828 -6.385271 10.94214 9.756591 -9.438786 10.89288 6.593065 -6.447251 10.64978 9.753298 -9.436841 10.86902 6.593791 -6.445799 10.67466 9.677148 -9.324463 10.93804 9.673892 -9.32263 10.91413 9.669076 -9.32074 10.89343 6.382806 -6.26947 10.59105 6.715821 -6.505084 10.7554 6.846336 -6.541676 10.87626 6.979876 -6.569587 11.01218 7.113343 -6.605204 11.1381 7.240795 -6.66265 11.22819 7.358618 -6.738292 11.28247 7.468852 -6.824221 11.31374 7.574898 -6.914757 11.3337 7.678793 -7.007701 11.34779 7.780706 -7.102815 11.35654 7.880733 -7.199901 11.36032 7.978981 -7.298764 11.35953 8.075574 -7.399217 11.35456 8.170647 -7.501072 11.34584 8.264348 -7.604154 11.33376 8.356833 -7.708289 11.31877 8.448263 -7.813309 11.30128 8.538811 -7.919049 11.28173 8.628662 -8.025348 11.26056 8.717981 -8.132056 11.23819 8.806946 -8.239026 11.21502 8.895786 -8.346071 11.19159 8.984731 -8.453008 11.16844 9.073787 -8.559857 11.14554 9.162807 -8.666777 11.1225 9.251496 -8.774019 11.09863 9.339451 -8.881896 11.07299 9.426313 -8.990671 11.04479 9.511758 -9.100568 11.01333 9.595469 -9.211782 10.97793 9.587496 -9.208424 10.93299 9.503898 -9.097553 10.96808 9.418575 -8.987966 10.99931 9.331842 -8.879471 11.02731 9.244023 -8.771842 11.0528 9.155469 -8.664814 11.07658 9.066586 -8.558072 11.09956 8.977661 -8.451376 11.12243 8.88885 -8.344588 11.14556 8.800147 -8.237707 11.16896 8.711317 -8.130916 11.19207 8.622136 -8.024405 11.21437 8.532431 -7.918317 11.23545 8.442032 -7.8128 11.25491 8.350757 -7.708014 11.27229 8.258438 -7.604128 11.28718 8.164909 -7.501303 11.29914 8.070018 -7.399713 11.30776 7.973618 -7.299536 11.31263 7.875576 -7.200953 11.31332 7.775768 -7.104154 11.30945 7.674088 -7.009333 11.30063 7.570443 -6.916681 11.28648 7.46468 -6.826467 11.26647 7.354937 -6.741086 11.23512 7.23795 -6.666226 11.18091 7.111804 -6.609663 11.09137 6.979355 -6.574495 10.96619 6.845972 -6.546611 10.83043 6.714767 -6.509694 10.7091 6.591573 -6.449677 10.6278 6.480861 -6.367208 10.59146 9.592255 -9.210107 10.95388 9.508594 -9.09904 10.98915 9.423201 -8.989278 11.02051 9.336395 -8.880624 11.04862 9.248497 -8.772854 11.0742 9.159869 -8.665705 11.09803 9.070906 -8.558862 11.12104 8.981907 -8.452079 11.14392 8.89302 -8.345207 11.16707 8.804239 -8.238232 11.19048 8.715332 -8.13134 11.21363 8.626071 -8.024716 11.23597 8.536285 -7.918508 11.2571 8.4458 -7.812863 11.27661 8.354437 -7.707944 11.29406 8.262024 -7.603918 11.309 8.168397 -7.500947 11.32103 8.073404 -7.399206 11.32971 7.976892 -7.298871 11.33463 7.878734 -7.200129 11.33539 7.778802 -7.103168 11.33156 7.67699 -7.00818 11.32278 7.573203 -6.915363 11.30867 7.467279 -6.824965 11.28869 7.357258 -6.739273 11.25738 7.239796 -6.663969 11.20313 7.11291 -6.606906 11.11328 6.979887 -6.571485 10.98769 6.846416 -6.543585 10.85183 6.715601 -6.506853 10.73077 -5.983442 -5.901503 9.764038 -6.077171 -5.838634 9.764038 -6.035342 -5.778892 9.764039 -6.035342 -5.778893 10.5512 -5.95756 -5.856674 9.764038 -5.975601 -5.737064 9.764039 -5.99158 -5.745366 10.87742 -6.025293 -5.769483 10.52616 -6.003364 -5.752674 10.69197 -6.014786 -5.760855 10.50154 -5.868555 -6.136587 9.764037 -6.096051 -5.909091 9.764038 -6.077171 -5.838634 11.76404 -5.95756 -5.998095 9.764038 -5.983442 -5.953267 9.764038 -6.071579 -5.827512 10.72653 -6.069598 -5.823911 10.67213 -6.064268 -5.815034 10.63493 -6.05091 -5.796298 10.59363 -5.941194 -6.130229 9.764037 -6.089694 -5.981729 9.764038 -6.096051 -5.909091 11.76404 -6.007308 -6.0994 9.764037 -6.058865 -6.047843 9.764037 -6.089694 -5.98173 11.76404 -6.058865 -6.047844 11.76404 -6.007308 -6.0994 11.76404 -5.941194 -6.13023 11.76404 -5.912732 -6.023978 9.764037 -5.798098 -6.117706 9.764037 -5.868555 -6.136587 11.76404 -5.816138 -5.998096 9.764038 -5.738357 -6.075877 9.764037 -5.782118 -6.109405 10.87741 -5.860968 -6.023978 9.764037 -5.798098 -6.117707 11.76404 -5.790257 -5.953268 9.764038 -5.696528 -6.016137 9.764038 -5.738357 -6.075878 10.5512 -5.770335 -6.102097 10.69197 -5.758913 -6.093915 10.50154 -5.748405 -6.085288 10.52616 -5.905144 -5.718184 9.764039 -5.677648 -5.94568 9.764038 -5.696528 -6.016137 11.76404 -5.816139 -5.856674 9.764038 -5.790257 -5.901503 9.764038 -5.702119 -6.027259 10.72653 -5.722789 -6.058473 10.59363 -5.704102 -6.030859 10.67213 -5.709432 -6.039736 10.63493 -5.832505 -5.72454 9.764039 -5.684004 -5.87304 9.764038 -5.677648 -5.94568 11.76404 -5.766391 -5.75537 9.764039 -5.714834 -5.806926 9.764039 -5.684004 -5.873041 11.76404 -5.714834 -5.806927 11.76404 -5.766391 -5.75537 11.76404 -5.832505 -5.724541 11.76404 -5.860967 -5.830792 9.764038 -5.905144 -5.718184 11.76404 -5.912731 -5.830792 9.764038 -5.975601 -5.737064 11.76404 -5.95756 -5.856675 11.76404 -5.983442 -5.901504 11.76404 -5.912731 -5.830793 11.76404 -5.860967 -5.830792 11.76404 -5.816139 -5.856675 11.76404 -5.790257 -5.901504 11.76404 -5.790257 -5.953268 11.76404 -5.816138 -5.998096 11.76404 -5.860968 -6.023978 11.76404 -5.912732 -6.023978 11.76404 -5.95756 -5.998096 11.76404 -5.983442 -5.953267 11.76404 -6.035342 -5.778893 11.76404 -6.035342 -5.778893 10.97687 -6.06698 -5.819438 10.84963 -6.061992 -5.81152 10.975 -6.055791 -5.802655 11.01165 -6.047488 -5.792125 11.00953 -6.041584 -5.785409 10.99329 -6.014382 -5.760546 10.92629 -5.738357 -6.075878 11.76404 -5.738357 -6.075878 10.97687 -5.732115 -6.069362 10.99329 -5.706718 -6.035333 10.84963 -5.711706 -6.043251 10.975 -5.717907 -6.052116 11.01165 -5.726212 -6.062646 11.00953 -5.759317 -6.094225 10.92629 -6.155298 -5.688771 10.58959 -6.164844 -5.694916 10.64099 -6.160861 -5.692493 10.60964 -6.074924 -5.822662 10.74115 -6.166633 -5.695663 10.67882 -6.066265 -5.809817 10.95004 -6.075939 -5.819491 10.7621 -6.153264 -5.682294 10.93854 -6.064612 -5.810024 10.96409 -6.156298 -5.684938 10.9052 -6.14225 -5.673883 10.97122 -6.148333 -5.678405 10.96176 -6.13595 -5.669424 10.96547 -5.996697 -5.740249 10.87742 -6.270634 -5.360287 10.74098 -5.777002 -6.114522 10.87741 -5.637749 -6.185347 10.96547 -5.42728 -6.599603 10.70323 -5.757654 -6.095175 10.50154 -5.618401 -6.165999 10.58959 -6.016045 -5.759596 10.50154 -5.608854 -6.159854 10.64099 -5.614555 -6.163397 10.60152 -5.611297 -6.161301 10.61905 -5.698774 -6.032109 10.74115 -5.607015 -6.159259 10.6919 -5.607393 -6.159158 10.66584 -5.707434 -6.044954 10.95004 -5.69776 -6.03528 10.7621 -5.621897 -6.173662 10.94762 -5.709087 -6.044747 10.96409 -5.619183 -6.171427 10.92829 -5.629347 -6.179351 10.96973 -5.625365 -6.176365 10.96176 -5.633573 -6.182415 10.97099 -5.491933 -6.509452 10.73168 -5.568811 -6.273482 10.94076 -5.50078 -6.347185 10.93346 -5.434364 -6.407808 10.94092 -5.370323 -6.456452 10.96073 -5.309268 -6.494328 10.99056 -5.233667 -6.87819 10.59388 -5.340809 -6.747646 10.59282 -5.586257 -6.341106 10.48117 -5.593562 -6.334324 10.51136 -5.603236 -6.344007 10.69938 -5.599185 -6.352818 10.72269 -5.530457 -6.454984 10.74267 -5.552515 -6.423318 10.74518 -5.564296 -6.406176 10.74468 -5.567468 -6.401521 10.74424 -5.580401 -6.382305 10.74054 -5.591095 -6.365934 10.73369 -5.546902 -6.2909 10.94292 -5.448492 -6.389022 10.94329 -5.337231 -6.471958 10.97973 -5.250812 -6.523082 11.02878 -5.192128 -6.545212 11.07582 -5.213249 -6.532454 11.06143 -5.131218 -6.562963 11.13136 -5.070725 -6.577268 11.19079 -5.081585 -6.56958 11.18309 -5.012544 -6.589416 11.25003 -4.954716 -6.601329 11.30912 -5.042879 -7.131163 10.51385 -4.894751 -6.615038 11.36864 -4.948295 -6.597451 11.31874 -4.836091 -6.631345 11.42314 -4.780961 -6.651016 11.46877 -4.816512 -6.632339 11.44343 -4.725022 -6.676309 11.5082 -4.663929 -6.709912 11.54358 -4.691222 -6.688335 11.5326 -4.596553 -6.753563 11.57411 -4.855122 -7.359276 10.46192 -4.525304 -6.80614 11.59814 -4.574784 -6.762693 11.58675 -4.45929 -6.859373 11.61458 -4.46537 -6.847721 11.61813 -4.398581 -6.910832 11.62649 -4.671595 -7.566696 10.43117 -4.33685 -6.964683 11.63663 -4.359797 -6.937726 11.63816 -4.267704 -7.026708 11.64579 -4.189487 -7.099042 11.65336 -4.256314 -7.030184 11.65235 -4.492665 -7.755523 10.41844 -4.101827 -7.182819 11.65835 -4.154788 -7.124817 11.66121 -4.003143 -7.280491 11.65966 -4.055126 -7.221429 11.66514 -4.318681 -7.927331 10.42123 -3.891727 -7.3949 11.6558 -3.957219 -7.319828 11.6645 -3.76632 -7.528628 11.64509 -3.860948 -7.419826 11.65971 -4.150522 -8.084631 10.43521 -3.628225 -7.681405 11.6262 -3.672763 -7.623899 11.63926 -3.766177 -7.521243 11.65116 -3.988487 -8.229293 10.45756 -3.479063 -7.852039 11.59857 -3.580551 -7.727626 11.62444 -3.83286 -8.36287 10.48594 -3.318273 -8.041066 11.56223 -3.399078 -7.937628 11.58773 -3.48938 -7.832256 11.60712 -3.541478 -8.603775 10.55089 -3.141824 -8.252408 11.51733 -3.309469 -8.04358 11.5667 -3.683834 -8.487428 10.51742 -3.277046 -8.815397 10.61885 -2.946985 -8.486741 11.46651 -3.131642 -8.256633 11.52137 -3.405896 -8.712771 10.5851 -3.220384 -8.149966 11.54444 -3.153697 -8.913016 10.65196 -2.750807 -8.722386 11.41572 -2.865482 -8.57671 11.45199 -2.954287 -8.470087 11.47491 -3.043007 -8.363392 11.49805 -2.915085 -9.101774 10.71611 -2.576485 -8.935569 11.36571 -2.688203 -8.790209 11.40537 -3.034683 -9.007072 10.68408 -2.776676 -8.683328 11.42906 -2.66205 -9.299739 10.78697 -2.428186 -9.124286 11.3137 -2.513825 -9.005993 11.35209 -2.792205 -9.198572 10.74967 -2.600471 -8.897678 11.37998 -2.520259 -9.40467 10.83441 -2.300713 -9.295153 11.25785 -2.345059 -9.226031 11.28611 -2.428583 -9.11538 11.32102 -2.284681 -9.514602 10.99609 -2.191207 -9.450666 11.19865 -2.263546 -9.338109 11.24678 -2.303468 -9.523542 10.96041 -2.324752 -9.526453 10.92927 -2.346337 -9.522877 10.9061 -2.365984 -9.513343 10.89309 -2.275048 -9.524665 10.96437 -2.184449 -9.451956 11.2024 -2.305779 -9.537327 10.90853 -2.339765 -9.536802 10.86547 -2.371723 -9.523169 10.84189 -2.701958 -9.283149 10.7258 -3.022771 -9.030854 10.63763 -3.342775 -8.777611 10.55172 -3.660487 -8.521258 10.47276 -3.972697 -8.257908 10.40989 -4.275826 -7.983815 10.37253 -4.566042 -7.695881 10.36959 -4.840896 -7.393287 10.40529 -5.099457 -7.076918 10.47968 -5.552966 -6.250015 10.56568 -5.527892 -6.271872 10.57345 -5.427787 -6.3776 10.56258 -5.407958 -6.580219 10.32736 -5.48154 -6.47879 10.36903 -5.489483 -6.319739 10.55765 -5.573958 -6.355948 10.45746 -5.557453 -6.37702 10.43479 -5.547257 -6.390344 10.42323 -5.54054 -6.399209 10.4163 -5.52033 -6.426182 10.39782 -4.816078 -6.612228 11.04782 -5.148431 -6.948673 10.18719 -5.324151 -6.73134 10.27191 -4.887911 -6.592676 10.98055 -4.972631 -6.57426 10.89522 -5.06003 -6.555969 10.80629 -5.136024 -6.537064 10.73283 -5.200798 -6.516034 10.67654 -5.257431 -6.491838 10.6348 -5.311894 -6.462258 10.60278 -5.368522 -6.424667 10.57828 -4.474785 -6.811487 11.23059 -4.882318 -7.284714 10.0972 -5.082791 -7.060586 10.15882 -4.538185 -6.762285 11.21232 -4.599037 -6.719382 11.18923 -4.653739 -6.685163 11.16287 -4.70443 -6.657606 11.1331 -4.756577 -6.633732 11.09671 -4.190155 -7.060959 11.27583 -4.62191 -7.580447 10.05174 -4.824244 -7.37696 10.0844 -4.27269 -6.985325 11.26695 -4.345048 -6.921125 11.25645 -4.410808 -6.864519 11.24468 -3.992681 -7.252182 11.28387 -4.373952 -7.835775 10.04226 -4.549365 -7.679502 10.0488 -4.097263 -7.149126 11.28191 -3.740585 -7.516222 11.2685 -4.137749 -8.059303 10.05857 -4.259179 -7.967447 10.05168 -3.874448 -7.373379 11.28006 -3.588474 -7.685078 11.24696 -3.914632 -8.257066 10.09119 -3.956058 -8.241502 10.08908 -3.414984 -7.884817 11.21318 -3.704957 -8.434562 10.1326 -3.213744 -8.123407 11.16511 -3.508297 -8.595647 10.17838 -3.643868 -8.504829 10.15196 -2.986712 -8.396533 11.10579 -3.324033 -8.743377 10.22539 -2.766281 -8.661248 11.04881 -3.151504 -8.880095 10.27147 -3.326178 -8.76116 10.23092 -2.990555 -9.007312 10.31488 -3.006196 -9.014375 10.31683 -2.577804 -8.890604 10.9962 -2.837792 -9.128272 10.3558 -2.685545 -9.247304 10.39854 -2.4194 -9.091193 10.94192 -2.524636 -9.368302 10.4499 -2.685416 -9.266666 10.40497 -2.286646 -9.268527 10.88455 -2.346637 -9.493996 10.51721 -2.17186 -9.431318 10.82277 -2.32699 -9.50353 10.53022 -2.355209 -9.506655 10.52106 -2.305404 -9.507106 10.5534 -2.32325 -9.520288 10.54464 -2.284121 -9.504195 10.58453 -2.289264 -9.520813 10.5877 -2.265333 -9.495255 10.62021 -2.165399 -9.432907 10.83232 -2.258534 -9.508151 10.64354 -2.15579 -9.436201 10.86197 -2.159319 -9.434813 10.84813 -2.24453 -9.319089 10.8773 -2.326044 -9.207009 10.91664 -2.494812 -8.98697 10.98262 -2.409568 -9.096356 10.95155 -2.581461 -8.878653 11.0105 -2.846456 -8.557662 11.08256 -2.669195 -8.771183 11.0359 -2.75766 -8.664292 11.05961 -3.024023 -8.344371 11.12853 -2.935299 -8.451065 11.10541 -3.290472 -8.024538 11.19723 -3.112639 -8.237594 11.1519 -3.201381 -8.130922 11.17498 -3.470386 -7.81321 11.23766 -3.380084 -7.918583 11.21826 -3.653774 -7.60485 11.26979 -3.56156 -7.708578 11.25498 -3.74719 -7.502191 11.28169 -3.938236 -7.300774 11.29503 -3.841962 -7.400774 11.29024 -4.036145 -7.202374 11.29567 -4.13581 -7.105761 11.29174 -4.237339 -7.011127 11.28287 -4.340823 -6.918666 11.26868 -4.446399 -6.828662 11.24865 -4.555815 -6.74364 11.21726 -4.672248 -6.669291 11.1631 -4.797532 -6.613304 11.07393 -4.929324 -6.578422 10.94922 -5.062616 -6.550551 10.81356 -5.194283 -6.513419 10.69191 -5.318247 -6.452921 10.61024 -5.429491 -6.369989 10.57381 -5.617401 -6.169834 10.9052 -5.607731 -6.160154 10.71726 -5.551043 -6.233584 10.69572 -5.545409 -6.261413 10.87999 -5.533212 -6.279007 10.90048 -2.249035 -9.299998 10.99887 -2.27472 -9.287428 11.19483 -2.159589 -9.451693 11.1316 -2.161903 -9.452804 11.15564 -2.149916 -9.442019 10.94366 -2.268225 -9.526 10.89618 -2.360524 -9.14856 11.05028 -2.409885 -9.106075 11.25426 -2.323141 -9.225211 11.24001 -2.241435 -9.337976 11.20004 -2.490051 -8.981093 11.0991 -2.459698 -9.041705 11.273 -2.406879 -9.113922 11.27547 -2.512481 -8.974664 11.29134 -2.492354 -9.003954 11.30699 -2.537906 -8.920992 11.11486 -2.56852 -8.90461 11.30938 -2.588306 -8.858503 11.13041 -2.627671 -8.831696 11.32709 -2.579243 -8.895115 11.33523 -2.641317 -8.793518 11.14582 -2.69019 -8.755528 11.34465 -2.667225 -8.787183 11.36091 -2.696896 -8.726019 11.16116 -2.756826 -8.67507 11.36244 -2.755952 -8.679904 11.38478 -2.755396 -8.655481 11.17665 -2.808526 -8.612972 11.37582 -2.817471 -8.580972 11.19265 -2.860516 -8.55065 11.38912 -2.845016 -8.572957 11.4078 -2.865873 -8.522962 11.20502 -2.913251 -8.487418 11.40262 -2.914994 -8.464039 11.21763 -2.96668 -8.423207 11.4165 -2.934066 -8.466049 11.43078 -2.964614 -8.404377 11.23056 -3.019437 -8.359673 11.43037 -3.015489 -8.343098 11.24394 -3.07039 -8.298265 11.44382 -3.023026 -8.359081 11.45395 -3.066501 -8.28162 11.25741 -3.120142 -8.238335 11.45692 -3.111912 -8.25202 11.47734 -3.116384 -8.221539 11.27054 -3.16879 -8.179827 11.46961 -3.212915 -8.105635 11.29547 -3.231681 -8.104429 11.48571 -3.200911 -8.145015 11.50051 -3.164995 -8.163092 11.28319 -3.27489 -8.031653 11.31092 -3.292116 -8.032341 11.5007 -3.290255 -8.038265 11.52291 -3.333831 -7.961737 11.32504 -3.350552 -7.963086 11.51462 -3.390076 -7.895518 11.33788 -3.407534 -7.89607 11.52753 -3.380134 -7.931922 11.5441 -3.444092 -7.832461 11.34951 -3.462945 -7.831477 11.53935 -3.495995 -7.772429 11.35997 -3.516893 -7.769198 11.55007 -3.470715 -7.826133 11.56366 -3.545707 -7.7155 11.36926 -3.569512 -7.709098 11.5597 -3.562179 -7.721061 11.58118 -3.684067 -7.560363 11.39085 -3.620733 -7.651258 11.56822 -3.670566 -7.595657 11.57564 -3.654699 -7.616873 11.59619 -3.811441 -7.442397 11.59158 -3.748438 -7.513734 11.60829 -3.91836 -7.310658 11.41068 -3.936919 -7.311218 11.59892 -3.843551 -7.411817 11.61704 -3.807639 -7.42647 11.40413 -4.017756 -7.210275 11.41195 -4.047183 -7.200417 11.59961 -3.940188 -7.311304 11.62203 -4.107099 -7.123064 11.40921 -4.144363 -7.106395 11.59554 -4.138559 -7.115225 11.61909 -4.038483 -7.212376 11.62285 -4.187708 -7.046894 11.4035 -4.230385 -7.026082 11.5882 -4.260314 -6.980366 11.39568 -4.306151 -6.957645 11.57877 -4.240527 -7.020043 11.61035 -4.325042 -6.922731 11.38655 -4.372838 -6.899202 11.56816 -4.34448 -6.927034 11.59627 -4.383928 -6.871674 11.37648 -4.437261 -6.844394 11.55579 -4.496935 -6.778567 11.35087 -4.507447 -6.787587 11.53857 -4.45059 -6.836423 11.57633 -4.440567 -6.823932 11.36503 -4.552713 -6.736716 11.33295 -4.58388 -6.731239 11.51273 -4.560951 -6.750353 11.54507 -4.605647 -6.700494 11.31145 -4.656183 -6.684872 11.47935 -4.699296 -6.646288 11.26069 -4.72158 -6.649717 11.44044 -4.679003 -6.674507 11.49076 -4.653873 -6.670903 11.28746 -4.745878 -6.624524 11.22875 -4.781892 -6.623504 11.39655 -4.797645 -6.604628 11.18774 -4.842752 -6.603115 11.34447 -4.806815 -6.616832 11.4005 -4.857942 -6.586519 11.13345 -4.907238 -6.586361 11.28305 -4.928194 -6.569822 11.06453 -4.970207 -6.572679 11.21963 -4.940541 -6.581096 11.27441 -5.005391 -6.553842 10.98576 -5.031255 -6.560184 11.15715 -5.079756 -6.537822 10.91068 -5.09352 -6.546537 11.09459 -5.074108 -6.553182 11.13845 -5.143661 -6.521255 10.84976 -5.157336 -6.529755 11.03406 -5.198733 -6.503156 10.80218 -5.219002 -6.508795 10.98168 -5.204425 -6.516679 11.01773 -5.247313 -6.482834 10.76582 -5.27864 -6.481838 10.93962 -5.293456 -6.458858 10.73729 -5.340567 -6.44562 10.90654 -5.326134 -6.457592 10.93714 -5.390602 -6.392811 10.69728 -5.406125 -6.397812 10.8837 -5.340919 -6.429275 10.71429 -5.4424 -6.348581 10.68754 -5.474702 -6.336863 10.87389 -5.435823 -6.376013 10.90097 -5.496029 -6.295756 10.68651 -5.521051 -6.266831 10.66409 -5.423673 -6.363831 10.66458 -5.313999 -6.445406 10.70074 -5.192304 -6.504496 10.7813 -5.061988 -6.541003 10.90201 -4.928418 -6.568919 11.03797 -4.794681 -6.604646 11.16409 -4.66688 -6.662312 11.25434 -4.548834 -6.738149 11.30866 -4.438473 -6.824212 11.33993 -4.332357 -6.914824 11.35988 -4.228402 -7.007836 11.37396 -4.126431 -7.103018 11.38269 -4.026352 -7.200171 11.38646 -3.928055 -7.299099 11.38564 -3.831417 -7.399615 11.38066 -3.7363 -7.501533 11.3719 -3.64256 -7.604673 11.35981 -3.550038 -7.708864 11.34479 -3.458572 -7.813937 11.32728 -3.367989 -7.919726 11.30771 -3.278107 -8.026073 11.28652 -3.188757 -8.132822 11.26413 -3.099762 -8.239831 11.24095 -3.010894 -8.346912 11.21751 -2.921921 -8.453879 11.19436 -2.832838 -8.56076 11.17146 -2.743789 -8.667718 11.14841 -2.655068 -8.775009 11.12451 -2.567083 -8.882941 11.09884 -2.48019 -8.99178 11.0706 -2.310975 -9.213041 11.00363 -2.394714 -9.101749 11.03908 -2.229269 -9.325807 10.96366 -2.258551 -9.516326 10.70824 -2.149643 -9.440545 10.91746 -2.300979 -9.539498 10.83666 -2.170921 -9.453381 11.19038 -2.164702 -9.453236 11.17146 -5.521324 -6.266865 10.638 -5.424869 -6.365176 10.61353 -5.522629 -6.267763 10.61309 -2.291305 -9.529824 10.64873 -2.327529 -9.529263 10.60283 -2.337203 -9.538936 10.79077 -2.371268 -9.524405 10.76564 -2.361594 -9.514731 10.5777 -2.532799 -9.411098 10.70358 -2.548081 -9.383152 10.50704 -5.467164 -6.536351 10.41404 -5.403427 -6.657278 10.55329 -5.336034 -6.732227 10.33073 -5.201944 -6.942751 10.4452 -5.058383 -7.108664 10.2036 -5.001671 -7.201697 10.3697 -4.780032 -7.443446 10.13098 -4.806818 -7.433602 10.32202 -4.616597 -7.643515 10.29667 -4.514063 -7.731001 10.1032 -4.431271 -7.834217 10.28976 -4.260594 -7.980334 10.10852 -4.251849 -8.007309 10.2979 -4.021005 -8.198372 10.13625 -4.078904 -8.165287 10.31716 -3.913044 -8.310344 10.34393 -3.79604 -8.391834 10.17679 -3.754224 -8.444607 10.37553 -3.585653 -8.565777 10.22369 -3.602706 -8.569438 10.40987 -3.458519 -8.686025 10.44539 -3.389174 -8.724127 10.27275 -3.321804 -8.795179 10.48085 -3.205722 -8.869867 10.32128 -3.191609 -8.898356 10.51562 -3.035295 -9.004538 10.36729 -3.066997 -8.99681 10.54928 -2.942456 -9.095296 10.58281 -2.8747 -9.131605 10.41044 -2.815121 -9.195912 10.61719 -2.715737 -9.256281 10.45456 -2.679992 -9.300937 10.65592 -6.236301 -5.408415 10.75406 -6.207453 -5.578258 10.94017 -6.277005 -5.503527 10.93351 -6.344871 -5.442378 10.94215 -6.410176 -5.393702 10.96355 -6.382136 -5.18081 10.65351 -6.407343 -5.130495 10.6131 -6.198937 -5.50088 10.45038 -6.180137 -5.520446 10.51137 -6.170463 -5.510772 10.69933 -6.174328 -5.50145 10.7288 -6.18767 -5.514063 10.47538 -6.188997 -5.512594 10.47177 -6.22613 -5.422919 10.75598 -6.213026 -5.441841 10.75659 -6.196536 -5.466202 10.753 -6.194554 -5.469189 10.7521 -6.183564 -5.486139 10.74403 -6.175631 -5.499161 10.73199 -6.231516 -5.5625 10.94276 -6.333199 -5.462264 10.94462 -6.472243 -5.356188 10.99515 -6.448446 -5.378568 10.98522 -6.531775 -5.32797 11.03544 -6.514822 -4.986071 10.57366 -6.592469 -5.306095 11.08539 -6.576837 -5.319333 11.07422 -6.655165 -5.288633 11.1436 -6.716403 -5.274657 11.20442 -6.712644 -5.283421 11.20276 -6.775561 -5.262468 11.26486 -6.834765 -5.250077 11.3251 -6.671919 -4.776015 10.50551 -6.897137 -5.235159 11.38617 -6.849919 -5.254651 11.34239 -6.965439 -5.214093 11.44695 -7.039731 -5.182747 11.50221 -6.985134 -5.215032 11.46537 -7.117404 -5.140022 11.54719 -7.112471 -5.152039 11.5482 -6.850467 -4.557817 10.45449 -7.197589 -5.086463 11.58145 -7.282064 -5.021712 11.60683 -7.230496 -5.071776 11.5968 -7.369502 -4.948903 11.62566 -7.341959 -4.982301 11.62509 -7.03975 -4.345178 10.42444 -7.459253 -4.870945 11.64084 -7.450342 -4.889065 11.64458 -7.556985 -4.783074 11.65353 -7.556846 -4.793653 11.65886 -7.222396 -4.154945 10.41467 -7.665711 -4.681509 11.66274 -7.66148 -4.696173 11.66807 -7.783592 -4.566866 11.66691 -7.7643 -4.596767 11.67246 -7.392544 -3.987838 10.41859 -7.910256 -4.438436 11.66464 -7.865363 -4.495573 11.67229 -7.549881 -3.840362 10.43128 -8.046072 -4.294801 11.65457 -7.964743 -4.39273 11.66784 -7.69566 -3.708809 10.44959 -8.191633 -4.134294 11.63534 -8.062521 -4.288373 11.65937 -7.831166 -3.590195 10.47132 -8.347671 -3.955155 11.60562 -8.253652 -4.075662 11.6316 -8.15879 -4.18264 11.64719 -8.074662 -3.384093 10.51945 -8.514873 -3.755859 11.56432 -8.439596 -3.858483 11.59141 -7.957291 -3.482447 10.49497 -8.347214 -3.967567 11.6129 -8.285251 -3.211205 10.56796 -8.694146 -3.535043 11.51086 -8.530915 -3.74853 11.56743 -8.183975 -3.293846 10.54398 -8.542 -3.00476 10.6327 -8.887202 -3.291029 11.44529 -8.710876 -3.526494 11.51329 -8.463814 -3.067265 10.61252 -8.378469 -3.13582 10.59091 -8.621298 -3.637829 11.54129 -8.821997 -2.782097 10.70648 -9.09669 -3.021994 11.36867 -8.976104 -3.189797 11.42132 -8.753174 -2.836765 10.68826 -8.684582 -2.891255 10.67011 -8.614878 -2.946687 10.65175 -8.888144 -3.30237 11.453 -8.799779 -3.414637 11.48375 -9.099731 -2.564166 10.78344 -9.326237 -2.726473 11.28377 -9.151364 -2.96416 11.3565 -9.031374 -2.61693 10.76337 -8.961584 -2.671564 10.74387 -8.891561 -2.726895 10.72496 -9.063798 -3.077026 11.38906 -9.489019 -2.34017 10.99614 -9.581194 -2.403219 11.19589 -9.414663 -2.626021 11.2602 -9.470232 -2.331229 10.96046 -9.448947 -2.328318 10.92932 -9.427363 -2.331894 10.90615 -9.407714 -2.341429 10.89313 -9.318617 -2.402836 10.8575 -9.240007 -2.459167 10.82883 -9.168292 -2.512215 10.80481 -9.32666 -2.738555 11.29176 -9.23894 -2.851302 11.32397 -9.498652 -2.330107 10.96442 -9.591913 -2.401721 11.20022 -9.503079 -2.513805 11.22957 -9.467921 -2.317444 10.90858 -9.433935 -2.31797 10.86552 -9.404211 -2.335713 10.87317 -9.125906 -2.535823 10.77255 -8.855533 -2.746939 10.69629 -8.586953 -2.960381 10.62533 -8.319292 -3.175018 10.5571 -8.053963 -3.392622 10.49569 -7.792469 -3.614938 10.44527 -7.536444 -3.843652 10.41012 -7.287686 -4.080345 10.39459 -7.048184 -4.326426 10.40306 -6.8201 -4.583044 10.43978 -6.605722 -4.850968 10.50868 -9.600543 -2.422567 10.82001 -9.446709 -2.351242 10.53027 -9.427062 -2.360776 10.51726 -9.422822 -2.354323 10.5116 -9.514094 -2.531788 10.84931 -9.314863 -2.43848 10.47287 -9.144515 -2.554436 10.41097 -9.468296 -2.347665 10.55345 -9.450449 -2.334484 10.54469 -9.418491 -2.348117 10.52111 -9.48958 -2.350577 10.58458 -9.484435 -2.333958 10.58775 -9.508366 -2.359518 10.62026 -9.610575 -2.420384 10.83765 -9.515166 -2.346621 10.64359 -9.617262 -2.418315 10.86021 -9.521688 -2.532419 10.868 -9.430294 -2.63808 10.87826 -9.219339 -2.507939 10.43933 -9.349143 -2.741442 10.90684 -9.433267 -2.644639 10.89863 -9.132811 -2.573026 10.41173 -9.270746 -2.841874 10.93519 -9.345263 -2.757176 10.93019 -8.96315 -2.704913 10.36312 -9.195129 -2.939375 10.96335 -9.257541 -2.869926 10.9624 -9.048514 -2.637995 10.38686 -8.877663 -2.7726 10.34022 -9.103865 -3.057138 10.99745 -9.169964 -2.982787 10.99493 -8.792955 -2.839883 10.3178 -9.015718 -3.170456 11.02984 -9.082396 -3.095656 11.02749 -8.709073 -2.906515 10.2956 -8.930942 -3.279238 11.06073 -8.994698 -3.20843 11.05976 -8.533529 -3.046322 10.24961 -8.849593 -3.382898 11.08944 -8.906736 -3.321005 11.09143 -8.623808 -2.974326 10.27314 -8.43457 -3.125602 10.22428 -8.771727 -3.481326 11.1159 -8.818369 -3.433276 11.12219 -8.324414 -3.214475 10.1969 -8.697223 -3.574694 11.14018 -8.729463 -3.545135 11.15173 -8.626008 -3.662977 11.16214 -8.639883 -3.656473 11.17972 -8.202426 -3.313912 10.16788 -8.558159 -3.746103 11.1818 -7.922801 -3.547508 10.10864 -8.314001 -4.036185 11.24089 -8.549496 -3.767177 11.20587 -8.068678 -3.424511 10.13809 -7.763927 -3.684961 10.08108 -8.107247 -4.268695 11.27403 -8.272225 -4.094316 11.27004 -8.458174 -3.877132 11.22985 -8.36579 -3.986219 11.25134 -7.590607 -3.84007 10.05764 -7.931066 -4.456278 11.28871 -8.081088 -4.307032 11.2978 -8.17736 -4.201296 11.28563 -7.399487 -4.018903 10.04183 -7.780565 -4.608315 11.29068 -7.883925 -4.514234 11.31072 -7.983307 -4.41139 11.30627 -7.18851 -4.228352 10.03986 -7.651632 -4.732516 11.28459 -7.782859 -4.61543 11.31089 -6.964401 -4.468724 10.06079 -7.540709 -4.834817 11.2735 -7.575398 -4.812317 11.29728 -7.680037 -4.714837 11.30649 -7.446228 -4.918707 11.25987 -7.468894 -4.907734 11.28301 -7.364242 -4.989065 11.2449 -6.748616 -4.722997 10.11031 -7.284808 -5.054309 11.22664 -7.36049 -5.000948 11.26346 -7.205958 -5.113649 11.20153 -7.249041 -5.090437 11.2352 -7.133657 -5.161273 11.16978 -6.56394 -4.96418 10.18303 -7.069416 -5.196986 11.13307 -7.131025 -5.170688 11.18661 -7.002535 -5.226876 11.08547 -6.920236 -5.253452 11.01376 -7.003718 -5.233687 11.10385 -6.815742 -5.277508 10.91025 -6.868498 -5.273271 10.98079 -6.413025 -5.182751 10.27009 -6.704638 -5.300876 10.79735 -6.731219 -5.30204 10.84115 -6.611838 -5.325424 10.70952 -6.535323 -5.354057 10.6479 -6.595411 -5.337962 10.71262 -6.289981 -5.379633 10.36511 -6.466227 -5.389847 10.60504 -6.394153 -5.438223 10.57455 -6.46703 -5.397196 10.62364 -6.317837 -5.502318 10.55882 -6.351796 -5.480888 10.58305 -6.238055 -5.584655 10.56211 -6.250121 -5.581119 10.58119 -6.25483 -5.427871 10.38673 -6.21106 -5.485723 10.43119 -6.21314 -5.483066 10.42835 -6.230585 -5.460342 10.40798 -6.244691 -5.441549 10.39483 -6.425947 -5.149117 10.25154 -6.624322 -4.869593 10.14711 -6.838697 -4.601671 10.07821 -7.066781 -4.345053 10.04149 -7.306283 -4.098969 10.03302 -7.555041 -3.862275 10.04855 -7.811069 -3.633559 10.0837 -8.072564 -3.411242 10.13411 -8.337895 -3.193636 10.19553 -8.605558 -2.978996 10.26376 -8.874141 -2.765554 10.33472 -6.165968 -5.694616 10.71726 -6.229105 -5.592405 10.87982 -6.241999 -5.571601 10.91029 -6.244608 -5.595356 10.69073 -9.563425 -2.488385 10.96336 -9.55883 -2.472324 11.14962 -9.614109 -2.403079 11.13165 -9.61002 -2.401592 11.16586 -9.623784 -2.412753 10.94371 -9.505475 -2.328771 10.89623 -9.504799 -2.540466 11.16777 -9.520739 -2.513842 11.19467 -9.504514 -2.562744 10.98324 -9.451972 -2.607478 11.18603 -9.446997 -2.635795 11.00323 -9.400307 -2.673334 11.20429 -9.432104 -2.626258 11.22528 -9.390818 -2.707503 11.02321 -9.349785 -2.737986 11.22247 -9.335934 -2.777836 11.04309 -9.288216 -2.81704 11.24497 -9.343889 -2.73901 11.25685 -9.282343 -2.846711 11.06276 -9.22824 -2.894245 11.26714 -9.255957 -2.851995 11.28909 -9.229979 -2.914142 11.08215 -9.169679 -2.969727 11.28891 -9.168174 -2.96511 11.32168 -9.170316 -2.991052 11.10434 -9.112526 -3.043409 11.31019 -9.112064 -3.066147 11.12601 -9.056738 -3.115273 11.33087 -9.080401 -3.078251 11.35433 -9.055113 -3.139488 11.1471 -9.002177 -3.185429 11.35094 -8.999474 -3.210991 11.16752 -8.948759 -3.253927 11.37034 -8.992499 -3.191315 11.38671 -8.945211 -3.280521 11.18716 -8.896524 -3.32067 11.38901 -8.904329 -3.304196 11.4185 -8.892388 -3.347942 11.20595 -8.845372 -3.385746 11.40693 -8.830929 -3.425988 11.22729 -8.795197 -3.449254 11.42409 -8.815755 -3.416789 11.44941 -8.771475 -3.500998 11.24731 -8.746034 -3.511126 11.44044 -8.713986 -3.573 11.26598 -8.697846 -3.571389 11.45598 -8.726637 -3.528986 11.47911 -8.658464 -3.641979 11.2833 -8.634937 -3.649423 11.47544 -8.636841 -3.640677 11.50728 -8.605017 -3.707807 11.29923 -8.573544 -3.724811 11.49345 -8.540772 -3.786125 11.31734 -8.513636 -3.797577 11.50999 -8.546234 -3.751747 11.53361 -8.478988 -3.860539 11.3336 -8.455093 -3.867863 11.52511 -8.454682 -3.862081 11.55778 -8.419873 -3.930854 11.34801 -8.397954 -3.935631 11.53878 -8.36308 -3.99754 11.36074 -8.342138 -4.000993 11.55107 -8.36206 -3.971559 11.57948 -8.290702 -4.081231 11.37529 -8.287621 -4.063996 11.56199 -8.234415 -4.124659 11.57158 -8.268247 -4.080058 11.59837 -8.222144 -4.159107 11.38728 -8.18242 -4.183124 11.57991 -8.095186 -4.299542 11.40463 -8.033753 -4.345664 11.59776 -8.173124 -4.187451 11.61416 -8.156973 -4.231822 11.39699 -7.980598 -4.421898 11.41462 -7.89533 -4.490585 11.60612 -7.978514 -4.398393 11.63517 -8.036387 -4.36286 11.41044 -8.076581 -4.293607 11.62653 -7.82898 -4.577144 11.41929 -7.766595 -4.619636 11.60652 -7.878831 -4.501671 11.6398 -7.698546 -4.704514 11.41534 -7.647098 -4.734415 11.60045 -7.674293 -4.703151 11.63586 -7.777449 -4.603303 11.64012 -7.585801 -4.809968 11.40596 -7.538049 -4.834941 11.58948 -7.569304 -4.801071 11.62677 -7.488561 -4.897473 11.39344 -7.440507 -4.921464 11.5753 -7.462428 -4.896922 11.61258 -7.405438 -4.969764 11.37949 -7.348952 -4.999777 11.55826 -7.353648 -4.990601 11.59315 -7.328328 -5.034605 11.36371 -7.258975 -5.072542 11.53611 -7.25114 -5.095563 11.34282 -7.17264 -5.134959 11.50534 -7.241558 -5.080792 11.56496 -7.109282 -5.189715 11.28143 -7.089535 -5.185631 11.4636 -7.122413 -5.162182 11.51638 -7.175962 -5.148857 11.31466 -7.046435 -5.221918 11.242 -7.008716 -5.224509 11.40963 -6.975689 -5.25028 11.18746 -6.933247 -5.251015 11.34662 -6.993232 -5.226557 11.43297 -6.887374 -5.275477 11.10624 -6.865464 -5.268701 11.28215 -6.781213 -5.298358 10.99907 -6.802995 -5.282258 11.21921 -6.856217 -5.267066 11.3088 -6.742177 -5.2947 11.15696 -6.67815 -5.320754 10.89526 -6.680109 -5.308293 11.09458 -6.718475 -5.295963 11.16873 -6.616439 -5.325018 11.03417 -6.594474 -5.344705 10.81841 -6.554774 -5.345952 10.98176 -6.583523 -5.331461 11.04076 -6.525365 -5.372412 10.76513 -6.49531 -5.372795 10.93978 -6.460691 -5.407472 10.72702 -6.433512 -5.408885 10.9067 -6.456888 -5.389615 10.95263 -6.392528 -5.454578 10.69992 -6.368071 -5.456541 10.88381 -6.32023 -5.516476 10.68654 -6.299618 -5.517288 10.8739 -6.342888 -5.472235 10.91225 -6.255361 -5.584977 10.65057 -6.356243 -5.485616 10.65252 -6.47023 -5.402999 10.69289 -6.596857 -5.344847 10.78101 -6.731808 -5.30934 10.90897 -6.869554 -5.280444 11.04905 -7.006575 -5.239971 11.17329 -7.135725 -5.175589 11.25663 -7.254859 -5.094212 11.30522 -7.366939 -5.004002 11.33336 -7.475738 -4.910349 11.35286 -7.582613 -4.814494 11.36704 -7.687607 -4.716572 11.37614 -7.790765 -4.616724 11.3804 -7.892151 -4.515091 11.38008 -7.991836 -4.41181 11.37545 -8.089905 -4.307024 11.36681 -8.186451 -4.200865 11.35444 -8.281578 -4.093471 11.33866 -8.375394 -3.984969 11.31976 -8.468019 -3.875488 11.29807 -8.559573 -3.765152 11.2739 -8.650183 -3.654078 11.24757 -8.739983 -3.542385 11.21939 -8.829102 -3.430185 11.1897 -8.91768 -3.317589 11.15879 -9.005851 -3.204704 11.12699 -9.093755 -3.091638 11.09461 -9.181531 -2.978494 11.06196 -9.269317 -2.865377 11.02937 -9.357251 -2.752388 10.99713 -9.445467 -2.639633 10.96555 -9.534105 -2.527214 10.93495 -9.623456 -2.415028 10.90483 -9.51515 -2.338445 10.70829 -9.472721 -2.315275 10.83671 -9.60237 -2.401125 11.18962 -9.608673 -2.401419 11.17196 -9.482395 -2.324949 10.64878 -9.44617 -2.325509 10.60288 -9.436496 -2.315835 10.79082 -9.402432 -2.330367 10.76568 -9.401352 -2.329724 10.80412 -9.412106 -2.34004 10.57775 -9.313107 -2.391872 10.72989 -9.116903 -2.534478 10.70156 -9.401976 -2.331603 10.84194 -9.300058 -2.417639 10.53342 -9.414721 -2.343093 10.54439 -6.284788 -5.338665 10.41212 -6.265512 -5.344983 10.60828 -6.378567 -5.164263 10.52121 -6.355101 -5.198406 10.57559 -6.411123 -5.139215 10.31804 -6.513056 -4.967852 10.44152 -6.56586 -4.918113 10.23263 -6.671469 -4.756883 10.3739 -6.553771 -4.909773 10.45983 -6.754586 -4.674887 10.1625 -6.851203 -4.538372 10.324 -6.769626 -4.633291 10.38181 -6.972604 -4.421214 10.11662 -7.040791 -4.326604 10.29546 -7.000229 -4.368766 10.33817 -7.195174 -4.184966 10.09902 -7.22267 -4.137659 10.28637 -7.403241 -3.979927 10.10292 -7.392306 -3.971457 10.29079 -7.243122 -4.11547 10.32478 -7.54918 -3.824778 10.30391 -7.495966 -3.872241 10.33715 -7.591521 -3.804642 10.11965 -7.694392 -3.693973 10.32245 -7.762589 -3.652091 10.14348 -7.829359 -3.575968 10.34427 -7.756616 -3.637609 10.37063 -7.919502 -3.516684 10.17115 -7.954972 -3.468731 10.36792 -8.063606 -3.395405 10.20052 -8.071913 -3.370774 10.39235 -8.02312 -3.409912 10.42058 -8.195745 -3.286277 10.23013 -8.180791 -3.28093 10.41685 -8.28165 -3.198668 10.44078 -8.316223 -3.188156 10.2589 -8.374472 -3.123629 10.46366 -8.29373 -3.18736 10.48242 -8.424975 -3.100463 10.28601 -8.459456 -3.055373 10.48519 -8.522749 -3.022158 10.31106 -8.537301 -2.993144 10.50529 -8.612136 -2.950887 10.33437 -8.609953 -2.935251 10.52428 -8.566832 -2.968098 10.5517 -8.696761 -2.883592 10.35667 -8.679495 -2.879951 10.5426 -8.74792 -2.825598 10.56071 -8.780158 -2.817351 10.37875 -8.81658 -2.771067 10.5789 -8.864407 -2.75044 10.40106 -8.886007 -2.715959 10.59732 -8.840918 -2.750239 10.62406 -8.949447 -2.683117 10.42386 -8.955943 -2.660706 10.61622 -9.034388 -2.616554 10.44751 -9.025652 -2.60615 10.63572 -9.118352 -2.551871 10.47233 -9.094015 -2.553396 10.6558 -9.162616 -2.501428 10.67721 -9.204673 -2.486972 10.49989 -9.234401 -2.448327 10.70125 -9.130262 -2.547854 10.44183 -8.854267 -2.763624 10.36433 -8.58017 -2.981491 10.29197 -8.307059 -3.20076 10.22269 -8.036441 -3.423321 10.16084 -7.769927 -3.651028 10.1109 -7.509271 -3.88567 10.07742 -7.25642 -4.12891 10.06505 -7.013522 -4.382218 10.07845 -6.782917 -4.646753 10.12211 -6.567065 -4.923244 10.20014 -6.368398 -5.211884 10.31592 -6.390841 -5.188709 10.2804 -6.374349 -5.172166 10.60117 -9.119863 -2.534591 10.74011 -8.846001 -2.748595 10.66308 -8.573996 -2.964783 10.59125 -8.302952 -3.182293 10.52236 -8.03434 -3.402966 10.46067 -7.76973 -3.628619 10.41053 -7.510828 -3.860998 10.3764 -7.259526 -4.101736 10.3628 -7.01791 -4.35228 10.37428 -6.788248 -4.613788 10.41526 -6.572933 -4.887005 10.48976 -9.600111 -2.401164 11.19343 -9.513235 -2.513193 11.21875 -6.237283 -5.567431 10.93343 -9.424684 -2.625533 11.24936 -9.336551 -2.738201 11.28094 -9.248702 -2.851094 11.31316 -9.160999 -2.964109 11.34574 -9.073306 -3.077144 11.37834 -8.985484 -3.190094 11.41068 -8.897396 -3.302856 11.44243 -8.808903 -3.415322 11.47328 -8.71987 -3.527387 11.50291 -8.630158 -3.638939 11.53102 -8.539638 -3.749865 11.55728 -8.448177 -3.860051 11.58137 -8.35565 -3.969376 11.60299 -8.261935 -4.077716 11.62181 -8.166914 -4.184947 11.63752 -8.070478 -4.290938 11.64981 -7.972524 -4.395555 11.65839 -7.872962 -4.498662 11.66295 -7.771704 -4.600123 11.66321 -7.668682 -4.699798 11.6589 -7.563831 -4.797547 11.64976 -7.457102 -4.893224 11.63554 -7.348478 -4.98673 11.61608 -7.236635 -5.076642 11.58786 -7.117934 -5.157586 11.53927 -6.989488 -5.221414 11.45609 -6.853195 -5.261569 11.33241 -6.715641 -5.290414 11.19252 -6.580345 -5.326077 11.06431 -6.453 -5.384661 10.97583 -6.338495 -5.467715 10.93535 -8.862508 -2.765115 10.34226 -9.136373 -2.551108 10.41928 -8.590498 -2.981305 10.27043 -8.319451 -3.198818 10.20154 -8.050835 -3.419496 10.13985 -7.786222 -3.64515 10.08972 -7.527318 -3.877533 10.05559 -7.276012 -4.118275 10.042 -7.034394 -4.368823 10.05349 -6.804731 -4.630332 10.09447 -6.58942 -4.903549 10.16899 -9.622842 -2.415588 10.8967 -9.618917 -2.417671 10.86817 -9.529743 -2.529708 10.89797 -6.253788 -5.583951 10.61265 -9.441189 -2.642051 10.92859 -9.353055 -2.754722 10.96016 -9.265203 -2.867618 10.99239 -9.177498 -2.980636 11.02496 -9.089803 -3.093673 11.05757 -9.001979 -3.206627 11.08991 -8.913888 -3.319391 11.12166 -8.825393 -3.431862 11.15251 -8.736357 -3.543928 11.18214 -8.646643 -3.655483 11.21025 -8.55612 -3.766412 11.23651 -8.464656 -3.876601 11.2606 -8.372126 -3.985928 11.28222 -8.278409 -4.094271 11.30103 -8.183384 -4.201504 11.31674 -8.086945 -4.307497 11.32904 -7.98899 -4.412116 11.33761 -7.889424 -4.515225 11.34217 -7.788163 -4.616687 11.34243 -7.685137 -4.716362 11.33812 -7.580283 -4.814111 11.32897 -7.473555 -4.909794 11.31476 -7.36491 -5.003275 11.29524 -7.25308 -5.093203 11.26706 -7.134389 -5.174135 11.21847 -7.005973 -5.237969 11.13537 -6.869675 -5.278089 11.0116 -6.732116 -5.306934 10.8717 -6.59682 -5.342605 10.7435 -6.469485 -5.401189 10.65503 -6.354992 -5.484239 10.61457 -2.17742 -9.452914 11.19978 -2.172883 -9.453294 11.19405 -2.256651 -9.338792 11.24413 -2.250296 -9.339143 11.23492 -2.245032 -9.33897 11.21984 -5.423791 -6.364029 10.63847 -5.53582 -6.281378 10.91977 -5.539133 -6.284282 10.93385 -5.542913 -6.287529 10.94174 -2.326711 -9.226289 11.25973 -2.41042 -9.115077 11.29513 -2.495865 -9.005182 11.32659 -2.582724 -8.896408 11.35479 -2.670675 -8.788531 11.38043 -2.759372 -8.6813 11.40429 -2.848405 -8.574389 11.42729 -2.937427 -8.467514 11.45027 -3.026361 -8.360577 11.47343 -3.115218 -8.253551 11.49681 -3.204187 -8.146585 11.51997 -3.293502 -8.039876 11.54236 -3.383348 -7.933579 11.56353 -3.473895 -7.827842 11.58308 -3.565323 -7.722823 11.60056 -3.657805 -7.61869 11.61556 -3.751504 -7.515609 11.62763 -3.846575 -7.413753 11.63636 -3.943166 -7.313303 11.64133 -4.04141 -7.214441 11.64213 -4.141435 -7.117356 11.63834 -4.243346 -7.022243 11.6296 -4.347239 -6.929303 11.6155 -4.45328 -6.838767 11.59555 -4.563513 -6.752831 11.56429 -4.681342 -6.67718 11.51001 -4.808804 -6.619726 11.41992 -4.94226 -6.584101 11.29403 -5.075796 -6.556192 11.15811 -5.206313 -6.519605 11.03724 -5.328355 -6.460322 10.95648 -5.438279 -6.378548 10.92025 -2.331932 -9.226621 11.27466 -2.415592 -9.115557 11.30993 -2.500984 -9.005796 11.34129 -2.587787 -8.897142 11.3694 -2.67568 -8.789374 11.39498 -2.764318 -8.682235 11.41879 -2.853291 -8.575402 11.44177 -2.942256 -8.468593 11.46474 -3.031134 -8.361719 11.4879 -3.119933 -8.254763 11.51126 -3.208842 -8.147875 11.5344 -3.298096 -8.041253 11.55675 -3.387881 -7.935045 11.57788 -3.478364 -7.829403 11.59739 -3.569725 -7.724487 11.61483 -3.662136 -7.62046 11.62978 -3.75576 -7.51749 11.64181 -3.850752 -7.41575 11.65049 -3.947258 -7.315417 11.65542 -4.045416 -7.216677 11.65617 -4.145345 -7.119716 11.65235 -4.247156 -7.02473 11.64357 -4.350941 -6.931915 11.62945 -4.45686 -6.841518 11.60948 -4.56688 -6.755819 11.57818 -4.684348 -6.680505 11.52394 -4.811243 -6.623434 11.43409 -4.944256 -6.588005 11.30851 -5.077723 -6.560107 11.17266 -5.208537 -6.52338 11.05159 -5.331089 -6.463779 10.97058 -5.441362 -6.381701 10.9343 -2.338229 -9.226478 11.28368 -2.421827 -9.115608 11.31878 -2.507149 -9.006023 11.35 -2.593878 -8.897528 11.37801 -2.681696 -8.789901 11.4035 -2.770256 -8.682883 11.42725 -2.859151 -8.576151 11.4502 -2.948041 -8.46943 11.47315 -3.036844 -8.362642 11.4963 -3.125565 -8.255777 11.51964 -3.214396 -8.148993 11.54275 -3.303572 -8.042481 11.56506 -3.393274 -7.936393 11.58614 -3.483672 -7.830879 11.6056 -3.574944 -7.726095 11.62298 -3.667263 -7.62221 11.63787 -3.760789 -7.519386 11.64983 -3.855677 -7.417798 11.65846 -3.952074 -7.317622 11.66332 -4.050114 -7.21904 11.66402 -4.149919 -7.122243 11.66015 -4.251597 -7.027421 11.65133 -4.355242 -6.934773 11.63718 -4.461 -6.844559 11.61718 -4.57074 -6.759171 11.58584 -4.687733 -6.684302 11.53163 -4.813887 -6.627731 11.44209 -4.946326 -6.592555 11.31693 -5.079707 -6.564671 11.18117 -5.210909 -6.52776 11.05984 -5.33412 -6.467747 10.97851 -5.444849 -6.385272 10.94216 -2.151087 -9.438787 10.8929 -5.314611 -6.44725 10.6498 -2.15438 -9.436841 10.86904 -5.313885 -6.445799 10.67468 -2.230529 -9.324464 10.93806 -2.233786 -9.32263 10.91415 -2.238602 -9.32074 10.89345 -5.52487 -6.26947 10.59107 -5.191856 -6.505085 10.75542 -5.06134 -6.541676 10.87628 -4.927801 -6.569587 11.01221 -4.794334 -6.605204 11.13812 -4.666882 -6.66265 11.22821 -4.549059 -6.738292 11.28249 -4.438825 -6.824221 11.31376 -4.332779 -6.914756 11.33372 -4.228885 -7.0077 11.34781 -4.126971 -7.102814 11.35656 -4.026944 -7.1999 11.36034 -3.928696 -7.298763 11.35955 -3.832103 -7.399215 11.35459 -3.73703 -7.501071 11.34586 -3.64333 -7.604154 11.33378 -3.550845 -7.708289 11.31879 -3.459415 -7.813308 11.3013 -3.368866 -7.919049 11.28175 -3.279017 -8.025348 11.26058 -3.189697 -8.132056 11.23821 -3.100731 -8.239026 11.21504 -3.011892 -8.346072 11.19161 -2.922947 -8.453008 11.16846 -2.833891 -8.559857 11.14556 -2.744872 -8.666777 11.12252 -2.656182 -8.774019 11.09865 -2.568228 -8.881896 11.07301 -2.481365 -8.990671 11.04481 -2.39592 -9.100568 11.01335 -2.312209 -9.211782 10.97796 -2.320181 -9.208425 10.93301 -2.403779 -9.097553 10.96811 -2.489103 -8.987967 10.99933 -2.575836 -8.879471 11.02733 -2.663656 -8.771842 11.05282 -2.752209 -8.664814 11.0766 -2.841092 -8.558073 11.09958 -2.930017 -8.451376 11.12245 -3.018828 -8.344589 11.14558 -3.107532 -8.237707 11.16898 -3.196362 -8.130917 11.19209 -3.285542 -8.024407 11.21439 -3.375247 -7.918317 11.23547 -3.465646 -7.812799 11.25493 -3.556921 -7.708014 11.27232 -3.649241 -7.604127 11.2872 -3.742769 -7.501303 11.29917 -3.83766 -7.399713 11.30778 -3.934059 -7.299536 11.31265 -4.032101 -7.200953 11.31334 -4.131909 -7.104155 11.30947 -4.233589 -7.009332 11.30065 -4.337235 -6.916681 11.2865 -4.442997 -6.826467 11.26649 -4.552741 -6.741085 11.23514 -4.669727 -6.666225 11.18093 -4.795873 -6.609663 11.09139 -4.928321 -6.574496 10.96621 -5.061705 -6.54661 10.83045 -5.192909 -6.509693 10.70912 -5.316103 -6.449677 10.62782 -5.426815 -6.367207 10.59148 -2.315423 -9.210107 10.9539 -2.399085 -9.09904 10.98917 -2.484477 -8.989279 11.02053 -2.571284 -8.880623 11.04864 -2.659179 -8.772854 11.07422 -2.747811 -8.665706 11.09805 -2.836771 -8.558862 11.12106 -2.925771 -8.45208 11.14395 -3.014658 -8.345208 11.16709 -3.10344 -8.238231 11.1905 -3.192347 -8.13134 11.21365 -3.281607 -8.024717 11.23599 -3.371393 -7.918508 11.25712 -3.461877 -7.812863 11.27663 -3.553241 -7.707946 11.29408 -3.645654 -7.603917 11.30902 -3.73928 -7.500946 11.32105 -3.834275 -7.399204 11.32973 -3.930784 -7.298871 11.33465 -4.028943 -7.200129 11.33541 -4.128874 -7.103168 11.33158 -4.230687 -7.00818 11.3228 -4.334475 -6.915363 11.30869 -4.440398 -6.824965 11.28871 -4.55042 -6.739273 11.2574 -4.667881 -6.663969 11.20315 -4.794767 -6.606905 11.1133 -4.92779 -6.571485 10.98771 -5.061261 -6.543585 10.85185 -5.192075 -6.506853 10.73079 -5.368686 -5.405231 -46.98106 -2.823104 -2.85964 -15.80415 -5.356068 -5.420203 -46.97625 -2.810486 -2.874612 -15.79934 -5.346288 -5.436954 -46.96202 -2.800705 -2.891361 -15.78512 -5.339722 -5.454837 -46.93892 -2.794139 -2.909245 -15.76202 -5.336621 -5.473168 -46.90783 -2.79104 -2.927576 -15.73092 -5.337107 -5.491241 -46.86994 -2.791526 -2.945649 -15.69304 -5.341161 -5.508363 -46.82672 -2.795578 -2.962771 -15.64982 -5.348625 -5.523874 -46.77982 -2.803042 -2.978282 -15.60292 -5.359212 -5.53718 -46.73106 -2.81363 -2.991588 -15.55415 -5.372518 -5.547768 -46.68228 -2.826936 -3.002176 -15.50537 -5.388029 -5.555232 -46.63538 -2.842447 -3.00964 -15.45848 -5.40515 -5.559284 -46.59216 -2.859569 -3.013693 -15.41526 -5.423224 -5.559771 -46.55427 -2.877643 -3.014178 -15.37737 -5.441555 -5.556671 -46.52318 -2.895974 -3.011079 -15.34628 -5.459439 -5.550104 -46.50008 -2.913857 -3.004513 -15.32318 -5.476189 -5.540325 -46.48586 -2.930607 -2.994733 -15.30895 -5.49116 -5.527706 -46.48106 -2.945579 -2.982115 -15.30415 -5.503778 -5.512734 -46.48585 -2.958197 -2.967143 -15.30895 -5.513558 -5.495985 -46.50008 -2.967977 -2.950393 -15.32318 -5.520124 -5.478101 -46.52319 -2.974543 -2.93251 -15.34628 -5.523224 -5.459771 -46.55427 -2.977643 -2.914178 -15.37737 -5.522738 -5.441697 -46.59216 -2.977156 -2.896105 -15.41526 -5.518685 -5.424576 -46.63538 -2.973104 -2.878983 -15.45848 -5.511223 -5.409063 -46.68228 -2.96564 -2.863472 -15.50538 -5.500633 -5.395758 -46.73106 -2.955052 -2.850167 -15.55415 -5.487329 -5.38517 -46.77983 -2.941746 -2.839578 -15.60292 -5.471817 -5.377707 -46.82672 -2.926235 -2.832115 -15.64982 -5.454695 -5.373653 -46.86994 -2.909113 -2.828062 -15.69304 -5.436622 -5.373168 -46.90783 -2.89104 -2.827576 -15.73092 -5.418291 -5.376267 -46.93892 -2.872709 -2.830676 -15.76202 -5.400407 -5.382833 -46.96202 -2.854825 -2.837242 -15.78512 -5.383656 -5.392613 -46.97625 -2.838076 -2.847022 -15.79934 5.62529 5.592367 -46.48107 3.07971 3.046773 -15.30416 5.637909 5.577394 -46.48587 3.092329 3.031802 -15.30896 5.647689 5.560645 -46.5001 3.102109 3.015053 -15.32319 5.654255 5.542762 -46.5232 3.108675 2.997169 -15.34629 5.657354 5.52443 -46.55429 3.111774 2.978838 -15.37738 5.656868 5.506357 -46.59217 3.111289 2.960764 -15.41527 5.652816 5.489235 -46.6354 3.107236 2.943643 -15.45849 5.645351 5.473724 -46.6823 3.099772 2.928131 -15.50538 5.634764 5.460418 -46.73107 3.089184 2.914826 -15.55416 5.621459 5.44983 -46.77984 3.075879 2.904237 -15.60293 5.605947 5.442367 -46.82674 3.060367 2.896774 -15.64983 5.588825 5.438313 -46.86996 3.043245 2.892721 -15.69305 5.570751 5.437828 -46.90784 3.025172 2.892235 -15.73093 5.552422 5.440927 -46.93894 3.006841 2.895335 -15.76202 5.534537 5.447494 -46.96204 2.988957 2.901901 -15.78513 5.517788 5.457273 -46.97626 2.972207 2.911681 -15.79935 5.502815 5.469892 -46.98106 2.957236 2.924299 -15.80416 5.490198 5.484864 -46.97626 2.944617 2.93927 -15.79935 5.480417 5.501613 -46.96204 2.934837 2.95602 -15.78513 5.473851 5.519497 -46.93893 2.928271 2.973904 -15.76202 5.470752 5.537828 -46.90784 2.925172 2.992236 -15.73093 5.471237 5.555902 -46.86996 2.925658 3.010308 -15.69305 5.47529 5.573023 -46.82674 2.929711 3.02743 -15.64983 5.482754 5.588534 -46.77984 2.937174 3.042942 -15.60293 5.493342 5.60184 -46.73106 2.947762 3.056247 -15.55416 5.506648 5.612429 -46.68229 2.961068 3.066835 -15.50538 5.52216 5.619892 -46.6354 2.97658 3.074299 -15.45848 5.539281 5.623944 -46.59217 2.993701 3.078352 -15.41526 5.557354 5.624431 -46.55429 3.011775 3.078838 -15.37738 5.575685 5.621331 -46.5232 3.030106 3.075738 -15.34629 5.59357 5.614764 -46.5001 3.047989 3.069172 -15.32319 5.610319 5.604984 -46.48587 3.064739 3.059392 -15.30896 5.634774 -5.395746 -46.73107 3.089183 -2.850166 -15.55416 5.645362 -5.409051 -46.6823 3.099771 -2.863472 -15.50539 5.652826 -5.424563 -46.6354 3.107235 -2.878983 -15.45849 5.656878 -5.441685 -46.59218 3.111288 -2.896105 -15.41527 5.657365 -5.459758 -46.55429 3.111773 -2.914178 -15.37738 5.654265 -5.478089 -46.5232 3.108674 -2.932509 -15.34629 5.647699 -5.495973 -46.5001 3.102108 -2.950393 -15.32319 5.637919 -5.512722 -46.48587 3.092328 -2.967143 -15.30896 5.625301 -5.527694 -46.48107 3.07971 -2.982114 -15.30416 5.610329 -5.540312 -46.48587 3.064738 -2.994733 -15.30896 5.593579 -5.550092 -46.5001 3.047988 -3.004513 -15.32319 5.575695 -5.556658 -46.5232 3.030105 -3.011079 -15.34629 5.557364 -5.559758 -46.55429 3.011774 -3.014178 -15.37738 5.539291 -5.559272 -46.59218 2.9937 -3.013692 -15.41527 5.52217 -5.55522 -46.6354 2.976579 -3.00964 -15.45849 5.506658 -5.547756 -46.6823 2.961067 -3.002176 -15.50539 5.493353 -5.537168 -46.73107 2.947762 -2.991588 -15.55416 5.482765 -5.523862 -46.77984 2.937173 -2.978282 -15.60293 5.475301 -5.50835 -46.82674 2.92971 -2.962771 -15.64983 5.471248 -5.491229 -46.86996 2.925657 -2.945649 -15.69305 5.470762 -5.473155 -46.90785 2.925171 -2.927576 -15.73093 5.473862 -5.454824 -46.93894 2.928271 -2.909245 -15.76203 5.480428 -5.436941 -46.96204 2.934837 -2.891361 -15.78513 5.490208 -5.420191 -46.97626 2.944617 -2.874611 -15.79936 5.502826 -5.40522 -46.98107 2.957235 -2.85964 -15.80416 5.517798 -5.392601 -46.97626 2.972207 -2.847022 -15.79936 5.534547 -5.382821 -46.96204 2.988956 -2.837241 -15.78513 5.552431 -5.376255 -46.93894 3.00684 -2.830675 -15.76203 5.570762 -5.373156 -46.90784 3.025171 -2.827576 -15.73093 5.588836 -5.373641 -46.86996 3.043245 -2.828062 -15.69305 5.605957 -5.377694 -46.82674 3.060366 -2.832114 -15.64983 5.621469 -5.385158 -46.77984 3.075878 -2.839578 -15.60293 -5.362823 5.601827 -46.73105 -2.817229 3.056246 -15.55415 -5.352236 5.588521 -46.77983 -2.806641 3.04294 -15.60292 -5.344771 5.573009 -46.82672 -2.799177 3.027429 -15.64982 -5.340718 5.555887 -46.86994 -2.795125 3.010307 -15.69304 -5.340233 5.537815 -46.90783 -2.794639 2.992234 -15.73093 -5.343332 5.519484 -46.93892 -2.797738 2.973903 -15.76202 -5.349898 5.5016 -46.96202 -2.804304 2.956019 -15.78512 -5.359678 5.48485 -46.97625 -2.814084 2.93927 -15.79935 -5.372296 5.469878 -46.98105 -2.826703 2.924298 -15.80415 -5.387268 5.45726 -46.97625 -2.841674 2.91168 -15.79934 -5.404018 5.447481 -46.96202 -2.858424 2.901899 -15.78512 -5.421902 5.440915 -46.93892 -2.876307 2.895333 -15.76202 -5.440233 5.437815 -46.90783 -2.894639 2.892234 -15.73092 -5.458306 5.4383 -46.86994 -2.912712 2.89272 -15.69304 -5.475427 5.442352 -46.82672 -2.929834 2.896773 -15.64982 -5.49094 5.449818 -46.77982 -2.945345 2.904237 -15.60292 -5.504244 5.460405 -46.73105 -2.958651 2.914825 -15.55415 -5.514832 5.473711 -46.68228 -2.969239 2.92813 -15.50537 -5.522297 5.489222 -46.63538 -2.976703 2.943642 -15.45847 -5.526349 5.506344 -46.59215 -2.980755 2.960763 -15.41525 -5.526835 5.524417 -46.55427 -2.981241 2.978836 -15.37737 -5.523736 5.542748 -46.52318 -2.978141 2.997167 -15.34628 -5.517169 5.560632 -46.50008 -2.971575 3.015051 -15.32318 -5.507389 5.577381 -46.48585 -2.961795 3.031801 -15.30895 -5.494771 5.592353 -46.48105 -2.949177 3.046772 -15.30415 -5.4798 5.604972 -46.48585 -2.934206 3.059391 -15.30895 -5.46305 5.614751 -46.50008 -2.917456 3.069171 -15.32318 -5.445166 5.621318 -46.52318 -2.899572 3.075737 -15.34628 -5.426835 5.624417 -46.55427 -2.881241 3.078836 -15.37737 -5.408761 5.623931 -46.59216 -2.863168 3.078351 -15.41525 -5.391641 5.619879 -46.63538 -2.846046 3.074298 -15.45848 -5.376129 5.612414 -46.68228 -2.830534 3.066834 -15.50538 1.009304 5.976384 10.5854 1.009304 5.976384 10.9854 1.105379 6.951835 10.5854 1.105379 6.951835 10.9854 1.389909 7.889801 10.5854 1.389909 7.889801 10.9854 1.851961 8.754235 10.5854 1.851961 8.754235 10.9854 2.473776 9.511916 10.5854 2.473776 9.511916 10.9854 3.231461 10.13373 10.5854 3.231461 10.13373 10.9854 4.095895 10.59578 10.5854 4.095895 10.59578 10.9854 5.033861 10.8803 10.5854 5.033861 10.8803 10.9854 6.009312 10.97638 10.58539 6.009312 10.97638 10.98539 6.984764 10.8803 10.58539 6.984764 10.8803 10.98539 7.922729 10.59577 10.58539 7.922729 10.59577 10.98539 8.787163 10.13372 10.58539 8.787163 10.13372 10.98539 9.544845 9.511903 10.58539 9.544845 9.511903 10.98539 10.16666 8.754219 10.58539 10.16666 8.754219 10.98539 10.62871 7.889783 10.58539 10.62871 7.889783 10.98538 10.91323 6.951817 10.58538 10.91323 6.951817 10.98538 11.0093 5.976364 10.58538 11.0093 5.976364 10.98538 10.91323 5.000913 10.58538 10.91323 5.000913 10.98538 10.6287 4.062947 10.58538 10.6287 4.062947 10.98538 10.16665 3.198514 10.58538 10.16665 3.198514 10.98538 9.544831 2.440832 10.58538 9.544831 2.440832 10.98538 8.787145 1.81902 10.58538 8.787145 1.81902 10.98538 7.922709 1.356972 10.58539 7.922709 1.356972 10.98538 6.984742 1.072446 10.58539 6.984742 1.072446 10.98539 6.00929 0.976375 10.58539 6.00929 0.976375 10.98539 5.033838 1.072451 10.58539 5.033838 1.072451 10.98539 4.095873 1.356983 10.58539 4.095873 1.356983 10.98539 3.23144 1.819035 10.58539 3.23144 1.819035 10.98539 2.473759 2.440852 10.58539 2.473759 2.440852 10.98539 1.851947 3.198537 10.5854 1.851947 3.198537 10.9854 1.3899 4.062973 10.5854 1.3899 4.062973 10.9854 1.105374 5.00094 10.5854 1.105374 5.00094 10.9854 -10.88746 5.976376 10.55535 -10.88746 5.976376 10.95535 -10.79139 6.951827 10.55535 -10.79139 6.951827 10.95535 -10.50686 7.889792 10.55535 -10.50686 7.889792 10.95535 -10.04481 8.754226 10.55535 -10.04481 8.754226 10.95535 -9.422991 9.511908 10.55535 -9.422991 9.511908 10.95535 -8.665307 10.13372 10.55535 -8.665307 10.13372 10.95535 -7.800873 10.59577 10.55535 -7.800873 10.59577 10.95535 -6.862906 10.88029 10.55535 -6.862906 10.88029 10.95535 -5.887455 10.97637 10.55535 -5.887455 10.97637 10.95535 -4.912003 10.88029 10.55534 -4.912003 10.88029 10.95534 -3.974039 10.59576 10.55534 -3.974039 10.59576 10.95534 -3.109605 10.13371 10.55534 -3.109605 10.13371 10.95534 -2.351923 9.511895 10.55534 -2.351923 9.511895 10.95534 -1.73011 8.75421 10.55534 -1.73011 8.75421 10.95534 -1.268062 7.889774 10.55534 -1.268062 7.889774 10.95534 -0.9835352 6.951808 10.55533 -0.9835351 6.951808 10.95534 -0.8874638 5.976356 10.55533 -0.8874638 5.976356 10.95533 -0.9835399 5.000905 10.55533 -0.9835398 5.000905 10.95533 -1.26807 4.062939 10.55533 -1.26807 4.062939 10.95533 -1.730122 3.198505 10.55533 -1.730122 3.198505 10.95533 -2.351938 2.440824 10.55533 -2.351938 2.440824 10.95533 -3.109623 1.819011 10.55533 -3.109623 1.819011 10.95534 -3.974059 1.356964 10.55534 -3.974059 1.356964 10.95534 -4.912026 1.072438 10.55534 -4.912026 1.072438 10.95534 -5.887477 0.9763666 10.55534 -5.887477 0.9763666 10.95534 -6.862929 1.072443 10.55534 -6.862929 1.072443 10.95534 -7.800895 1.356974 10.55534 -7.800895 1.356974 10.95534 -8.665328 1.819027 10.55534 -8.665328 1.819027 10.95534 -9.423008 2.440844 10.55535 -9.423008 2.440844 10.95535 -10.04482 3.198529 10.55535 -10.04482 3.198529 10.95535 -10.50687 4.062964 10.55535 -10.50687 4.062964 10.95535 -10.79139 5.000932 10.55535 -10.79139 5.000932 10.95535 -10.87877 -5.911708 10.55341 -10.87877 -5.911708 10.95341 -10.78269 -4.936256 10.55341 -10.78269 -4.936256 10.95341 -10.49816 -3.998291 10.55341 -10.49816 -3.998291 10.95341 -10.03611 -3.133858 10.55341 -10.03611 -3.133858 10.95341 -9.414297 -2.376176 10.55341 -9.414297 -2.376176 10.95341 -8.656613 -1.754364 10.55341 -8.656613 -1.754364 10.95341 -7.792179 -1.292315 10.55341 -7.792179 -1.292315 10.95341 -6.854212 -1.007789 10.55341 -6.854212 -1.007789 10.95341 -5.87876 -0.9117166 10.55341 -5.87876 -0.9117166 10.95341 -4.903309 -1.007792 10.5534 -4.903309 -1.007792 10.95341 -3.965345 -1.292322 10.5534 -3.965345 -1.292322 10.9534 -3.100912 -1.754373 10.5534 -3.100912 -1.754373 10.9534 -2.343229 -2.376189 10.5534 -2.343229 -2.376189 10.9534 -1.721416 -3.133873 10.5534 -1.721416 -3.133873 10.9534 -1.259368 -3.998308 10.5534 -1.259368 -3.998308 10.9534 -0.9748412 -4.936275 10.5534 -0.9748411 -4.936275 10.9534 -0.8787698 -5.911727 10.55339 -0.8787698 -5.911727 10.95339 -0.9748459 -6.887179 10.55339 -0.9748458 -6.887179 10.95339 -1.259376 -7.825144 10.55339 -1.259376 -7.825144 10.95339 -1.721428 -8.689578 10.55339 -1.721428 -8.689578 10.95339 -2.343244 -9.44726 10.55339 -2.343244 -9.44726 10.95339 -3.100929 -10.06907 10.5534 -3.100929 -10.06907 10.9534 -3.965365 -10.53112 10.5534 -3.965365 -10.53112 10.9534 -4.903331 -10.81564 10.5534 -4.903331 -10.81564 10.9534 -5.878783 -10.91172 10.5534 -5.878783 -10.91172 10.9534 -6.854235 -10.81564 10.5534 -6.854235 -10.81564 10.9534 -7.792201 -10.53111 10.5534 -7.792201 -10.53111 10.9534 -8.656634 -10.06906 10.5534 -8.656634 -10.06906 10.9534 -9.414316 -9.447239 10.55341 -9.414316 -9.447239 10.95341 -10.03612 -8.689556 10.55341 -10.03612 -8.689556 10.95341 -10.49817 -7.825119 10.55341 -10.49817 -7.825119 10.95341 -10.7827 -6.887152 10.55341 -10.7827 -6.887152 10.95341 1.009313 -5.911698 10.55339 1.009313 -5.911698 10.95339 1.105389 -4.936247 10.55339 1.105389 -4.936247 10.95339 1.389919 -3.998281 10.55339 1.389919 -3.998281 10.95339 1.851971 -3.133848 10.55339 1.851971 -3.133848 10.95339 2.473786 -2.376167 10.55339 2.473786 -2.376167 10.95339 3.23147 -1.754354 10.55339 3.23147 -1.754354 10.95339 4.095905 -1.292306 10.55339 4.095905 -1.292306 10.95339 5.03387 -1.007779 10.55339 5.03387 -1.007779 10.95339 6.009322 -0.9117071 10.55339 6.009322 -0.9117071 10.95339 6.984773 -1.007782 10.55338 6.984773 -1.007782 10.95339 7.922738 -1.292312 10.55338 7.922738 -1.292312 10.95338 8.787173 -1.754364 10.55338 8.787173 -1.754364 10.95338 9.544856 -2.376179 10.55338 9.544856 -2.376179 10.95338 10.16667 -3.133864 10.55338 10.16667 -3.133864 10.95338 10.62871 -3.998299 10.55338 10.62871 -3.998299 10.95338 10.91324 -4.936266 10.55338 10.91324 -4.936266 10.95338 11.00931 -5.911718 10.55338 11.00931 -5.911718 10.95338 10.91324 -6.88717 10.55337 10.91324 -6.88717 10.95337 10.62871 -7.825134 10.55337 10.62871 -7.825134 10.95337 10.16666 -8.689567 10.55337 10.16666 -8.689567 10.95337 9.544839 -9.44725 10.55338 9.544839 -9.44725 10.95338 8.787156 -10.06906 10.55338 8.787156 -10.06906 10.95338 7.922719 -10.53111 10.55338 7.922719 -10.53111 10.95338 6.984752 -10.81563 10.55338 6.984752 -10.81563 10.95338 6.0093 -10.91171 10.55338 6.0093 -10.91171 10.95338 5.033848 -10.81563 10.55338 5.033848 -10.81563 10.95338 4.095883 -10.5311 10.55338 4.095883 -10.5311 10.95338 3.23145 -10.06905 10.55338 3.23145 -10.06905 10.95339 2.473769 -9.447231 10.55339 2.473769 -9.447231 10.95339 1.851957 -8.689545 10.55339 1.851957 -8.689545 10.95339 1.38991 -7.825109 10.55339 1.38991 -7.825109 10.95339 1.105384 -6.887143 10.55339 1.105384 -6.887143 10.95339 -1.131666 -3.220204 -13.77851 -1.131666 3.179795 -13.77851 1.268334 3.179795 -13.77851 1.268334 -3.220204 -13.77851 -1.131666 -3.220204 -7.778515 -1.131666 3.179795 -7.778515 1.268334 3.179795 -7.778515 1.268334 -3.220204 -7.778515</float_array> + <technique_common> + <accessor source="#battery_001-mesh-positions-array" count="12616" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="battery_001-mesh-normals"> + <float_array id="battery_001-mesh-normals-array" count="78024">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 0.7071074 -0.7071063 -2.08223e-7 -1.14012e-6 4.22403e-6 -1 0.7071065 -0.707107 0 -0.7071068 -0.7071068 0 0.7071081 -0.7071055 -2.10734e-7 0.7071065 -0.7071071 -1.79484e-7 0.7071067 -0.707107 -2.80979e-7 0.7071068 0.7071068 2.80979e-7 0.7071072 -0.7071064 -1.40489e-7 0.7071059 -0.7071077 -1.40489e-7 -1.14011e-6 4.22403e-6 -1 0.7071068 0.7071068 2.82219e-7 0.7071072 -0.7071065 -3.74133e-7 1.6541e-6 -3.71004e-6 1 0.7071066 -0.707107 0 0.7071066 -0.707107 0 -0.707107 -0.7071065 -2.82219e-7 1.6541e-6 -3.71004e-6 1 0.7071074 -0.7071062 -1.4197e-7 -2.80356e-6 4.8595e-6 -1 0.7070982 -0.7071154 0 -0.7071071 -0.7071065 0 0.7071046 -0.7071089 -1.4049e-7 0.7071073 -0.7071064 -2.80979e-7 0.7071067 0.7071068 2.80979e-7 0.7071071 -0.7071064 0 0.707105 -0.7071086 0 -1.52327e-6 4.60718e-6 -1 0.7071068 0.7071068 2.82219e-7 2.03725e-6 -4.0932e-6 1 -0.707107 -0.7071065 0 2.28958e-6 -5.37349e-6 1 0.7071074 -0.7071063 -1.4197e-7 -5.04643e-7 2.56059e-6 -1 0.7071106 -0.707103 -2.8098e-7 -0.7071068 -0.7071068 2.80979e-7 0.7071048 -0.7071087 -1.4049e-7 0.707112 -0.7071017 -5.61958e-7 0.7071068 0.7071068 0 0.7071072 -0.7071064 0 0.7071045 -0.707109 0 -5.04643e-7 2.56059e-6 -1 0.7071065 0.707107 2.82219e-7 5.04641e-7 -2.56058e-6 1 -0.707107 -0.7071065 0 5.04641e-7 -2.56059e-6 1 0.7071073 -0.7071062 -3.50193e-7 -5.04643e-7 2.56059e-6 -1 0.7070994 -0.7071141 0 -0.7071068 -0.7071068 0 0.7071124 -0.7071012 -3.51222e-7 0.7071084 -0.7071051 -2.80979e-7 0.7071065 0.7071071 2.80979e-7 0.7071071 -0.7071064 -2.80979e-7 0.7071084 -0.7071051 -2.80979e-7 -5.04643e-7 2.56059e-6 -1 0.7071065 0.7071071 2.82219e-7 5.04642e-7 -2.56059e-6 1 -0.7071068 -0.7071068 0 5.04642e-7 -2.56059e-6 1 0.7071072 -0.7071064 -2.08223e-7 -5.0464e-7 2.56058e-6 -1 0.7071008 -0.7071129 0 -0.7071074 -0.7071063 0 0.7071076 -0.707106 -2.10734e-7 0.707102 -0.7071115 0 0.7071071 0.7071065 0 0.7071071 -0.7071064 -2.10734e-7 0.7071071 -0.7071065 -2.10734e-7 -5.04641e-7 2.56058e-6 -1 0.7071068 0.7071068 2.82219e-7 5.0464e-7 -2.56058e-6 1 -0.7071074 -0.7071063 0 5.0464e-7 -2.56058e-6 1 0.7071071 -0.7071064 -2.08223e-7 2.05595e-6 2.05594e-6 -1 0.7071015 -0.7071121 0 -0.7071074 -0.7071063 0 0.7071074 -0.7071062 -2.10734e-7 0.7071012 -0.7071124 0 0.7071071 0.7071065 0 0.7071072 -0.7071064 -2.10734e-7 0.7071072 -0.7071063 -2.10734e-7 -3.06523e-6 3.06522e-6 -1 0.7071068 0.7071068 2.82219e-7 1.00928e-6 -5.12117e-6 1 -0.7071074 -0.7071063 0 0 0 1 0.7071071 -0.7071064 -1.4197e-7 2.05595e-6 2.05595e-6 -1 0.7071023 -0.7071114 0 -0.7071068 -0.7071068 0 0.7071056 -0.707108 -1.4049e-7 0.7071005 -0.7071131 0 0.7071071 0.7071065 0 0.7071072 -0.7071064 -1.40489e-7 0.7071052 -0.7071085 -1.4049e-7 -3.06523e-6 3.06523e-6 -1 0.7071063 0.7071074 8.46657e-7 1.00928e-6 -5.12117e-6 1 -0.7071068 -0.7071068 0 0 0 1 0.7071074 -0.7071063 -2.08223e-7 2.05594e-6 2.05594e-6 -1 0.7071084 -0.7071053 -2.80979e-7 -0.7071068 -0.7071068 2.80979e-7 0.707107 -0.7071065 -2.10735e-7 0.7071205 -0.7070931 -5.61958e-7 0.7071065 0.707107 0 0.7071072 -0.7071064 -1.4049e-7 0.7071048 -0.7071089 -1.4049e-7 -3.06523e-6 3.06523e-6 -1 0.7071065 0.707107 0 1.00928e-6 -5.12117e-6 1 -0.7071068 -0.7071068 2.82219e-7 0 0 1 0.7071071 -0.7071064 -2.08223e-7 2.05595e-6 2.05594e-6 -1 0.7071038 -0.7071098 0 -0.707107 -0.7071065 0 0.7071068 -0.7071067 -2.10734e-7 0.707099 -0.7071146 0 0.7071068 0.7071068 0 0.7071072 -0.7071064 -2.10734e-7 0.7071079 -0.7071058 -2.10734e-7 -3.06523e-6 3.06523e-6 -1 0.7071065 0.707107 2.82219e-7 1.00928e-6 -5.12117e-6 1 -0.707107 -0.7071065 0 0 0 1 0.7071071 -0.7071064 -2.08223e-7 2.05595e-6 2.05594e-6 -1 0.7071045 -0.707109 0 -0.707107 -0.7071065 0 0.7071066 -0.7071069 -2.10735e-7 0.7070981 -0.7071154 0 0.7071068 0.7071068 0 0.7071071 -0.7071064 -2.10734e-7 0.707108 -0.7071056 -2.10734e-7 -3.06523e-6 3.06522e-6 -1 0.7071068 0.7071068 0 1.00928e-6 -5.12117e-6 1 -0.707107 -0.7071065 0 0 0 1 0.7071072 -0.7071064 -3.40727e-7 -1.63728e-5 8.14902e-6 -1 0.7071052 -0.7071083 0 -0.7071068 -0.7071068 0 0.7070975 -0.7071162 0 0.7071065 0.7071071 0 0.7071071 -0.7071064 -2.10734e-7 0.7071081 -0.7071054 -2.10734e-7 0.7071048 -0.7071089 7.33e-7 4.11189e-6 4.11189e-6 -1 0.7071065 0.7071071 0 4.11189e-6 4.11189e-6 1 -0.7071068 -0.7071068 0 8.14903e-6 -1.63728e-5 1 0.7071071 -0.7071064 -1.51432e-7 -1.63728e-5 8.14899e-6 -1 0.7071081 -0.7071055 -1.12391e-6 -0.7071062 -0.7071073 5.61955e-7 0.707158 -0.7070557 -1.12395e-6 0.7071065 0.7071071 -5.61955e-7 0.7071061 -0.7071074 -1.88316e-7 0.7071068 -0.7071067 6.51926e-7 4.11188e-6 4.11189e-6 -1 0.7071059 0.7071076 0 4.11189e-6 4.11189e-6 1 -0.7071068 -0.7071068 0 8.14903e-6 -1.63728e-5 1 0.7071068 -0.7071068 -1.66578e-7 -2.03726e-6 4.0932e-6 -1 0.7071086 -0.707105 -5.6196e-7 -0.7071057 -0.7071079 5.61958e-7 0.7071111 -0.7071025 -2.80977e-7 0.7071076 0.7071059 2.80979e-7 0.7071065 -0.707107 0 0.707107 -0.7071065 -1.88851e-7 0.7071068 -0.7071068 -1.69758e-7 0.7071068 -0.7071068 -1.70743e-7 -1.39711e-6 3.96704e-6 -1 0.7071076 0.707106 2.82219e-7 0.707107 -0.7071066 -1.4197e-7 7.56961e-7 -3.84088e-6 1 0.7071057 -0.7071078 -1.40489e-7 0.7071068 -0.7071068 0 0.7071059 -0.7071077 0 -0.7071063 -0.7071074 0 7.56962e-7 -3.84088e-6 1 7.84993e-7 5.38284e-6 -1 0.7071078 -0.7071058 -2.80979e-7 -0.7071062 -0.7071073 -2.80979e-7 0.7071105 -0.707103 -2.80978e-7 0.7071074 0.7071064 2.8098e-7 7.85002e-7 5.38284e-6 -1 0.7071076 0.707106 0 0.7071068 -0.7071068 -1.4197e-7 7.56962e-7 -3.84088e-6 1 0.7071059 -0.7071077 -1.4049e-7 0.7071066 -0.707107 0 0.7071057 -0.7071079 0 -0.7071059 -0.7071076 0 7.56963e-7 -3.84088e-6 1 -5.04642e-7 2.56059e-6 -1 0.7071086 -0.707105 -2.80978e-7 -0.707106 -0.7071076 -2.80979e-7 0.7071101 -0.7071035 -2.80978e-7 0.7071073 0.7071062 2.80979e-7 -5.0464e-7 2.56059e-6 -1 0.7071076 0.7071059 0 0.7071066 -0.707107 -2.17687e-7 5.04641e-7 -2.56059e-6 1 0.707108 -0.7071055 -2.10734e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071086 -0.707105 -2.80979e-7 -0.7071057 -0.7071079 0 5.04642e-7 -2.56059e-6 1 -5.04643e-7 2.56059e-6 -1 0.7071086 -0.707105 -2.80978e-7 -0.7071063 -0.7071073 -2.80979e-7 0.707117 -0.7070968 -5.61957e-7 0.7071068 0.7071068 0 -5.04642e-7 2.56059e-6 -1 0.7071071 0.7071065 -2.82219e-7 0.7071067 -0.707107 0 5.04643e-7 -2.56059e-6 1 0.7071049 -0.7071086 0 0.7071066 -0.707107 0 0.7071046 -0.707109 0 -0.7071057 -0.7071079 2.82219e-7 5.04643e-7 -2.56059e-6 1 -5.0464e-7 2.56059e-6 -1 0.7071093 -0.7071043 -2.80977e-7 -0.7071065 -0.707107 -2.80978e-7 0.7071093 -0.7071043 -2.80977e-7 0.7071071 0.7071065 2.80978e-7 -5.04641e-7 2.56059e-6 -1 0.7071074 0.7071062 0 0.7071066 -0.707107 -1.4197e-7 3.06523e-6 -3.06523e-6 1 0.7071065 -0.7071071 -1.4049e-7 0.7071068 -0.7071068 -2.10734e-7 0.7071077 -0.7071059 -2.10734e-7 -0.7071063 -0.7071074 0 4.07451e-6 -8.18639e-6 1 -6.13045e-6 6.13045e-6 -1 0.7071096 -0.707104 -2.80978e-7 -0.7071068 -0.7071068 -2.80979e-7 0.7071088 -0.7071048 -2.80978e-7 0.7071071 0.7071065 2.80979e-7 -1.00928e-6 5.12117e-6 -1 0.7071074 0.7071063 0 0.7071068 -0.7071068 -1.4197e-7 3.06523e-6 -3.06523e-6 1 0.7071066 -0.7071069 -1.4049e-7 0.7071066 -0.707107 0 0.7071037 -0.7071099 0 -0.7071065 -0.707107 0 4.07451e-6 -8.1864e-6 1 -6.13045e-6 6.13045e-6 -1 0.7071192 -0.7070944 -5.61948e-7 -0.7071065 -0.7071071 -5.61958e-7 0.7071083 -0.7071053 -2.80978e-7 0.7071071 0.7071065 2.80979e-7 -1.00928e-6 5.12117e-6 -1 0.7071074 0.7071063 0 0.7071068 -0.7071068 -2.17687e-7 3.06523e-6 -3.06523e-6 1 0.7071076 -0.7071061 -2.10734e-7 0.7071064 -0.7071071 0 0.7071032 -0.7071103 0 -0.7071059 -0.7071076 0 4.07451e-6 -8.1864e-6 1 -6.13045e-6 6.13045e-6 -1 0.7071109 -0.7071028 -2.80977e-7 -0.707106 -0.7071076 -2.80979e-7 0.7071061 -0.7071076 0 0.7071071 0.7071065 0 -1.00928e-6 5.12117e-6 -1 0.707107 0.7071065 0 0.7071066 -0.707107 -2.08223e-7 3.06523e-6 -3.06523e-6 1 0.7071074 -0.7071062 -2.10734e-7 0.7071065 -0.707107 -2.10734e-7 0.7071083 -0.7071053 -2.10735e-7 -0.7071057 -0.7071079 0 4.07451e-6 -8.1864e-6 1 -6.13044e-6 6.13045e-6 -1 0.7071111 -0.7071024 -2.80978e-7 -0.7071068 -0.7071067 -2.8098e-7 0.7071068 -0.7071068 0 0.7071073 0.7071062 0 -1.00928e-6 5.12117e-6 -1 0.7071073 0.7071062 0 0.7071068 -0.7071068 0 3.06523e-6 -3.06523e-6 1 0.7071066 -0.7071071 -1.70866e-7 0.7071068 -0.7071067 0 -0.7071065 -0.707107 0 4.07451e-6 -8.18639e-6 1 0.7071065 -0.7071071 -2.10734e-7 -0.7071071 -0.7071065 -2.10734e-7 0.7071066 -0.7071071 -2.32522e-7 1.63639e-6 -3.91934e-6 1 1.63639e-6 -3.91934e-6 1 -0.7071068 -0.7071068 0 0.7071076 -0.707106 -8.82353e-7 -0.7069684 -0.706968 0.01980018 0.7071064 -0.7071071 0 -0.7058017 -0.7058027 0.06071752 -0.7069678 -0.7069686 0.01979935 0.7071074 -0.7071062 -1.07351e-6 -0.7031075 -0.7031087 0.1061969 -0.7058017 -0.7058026 0.06071764 0.7071068 -0.7071068 0 -0.6977863 -0.6977877 0.1618227 -0.7031077 -0.7031086 0.1061972 0.7071068 -0.7071068 0 -0.6869643 -0.6869657 0.2369772 -0.6977865 -0.6977875 0.1618231 0.707107 -0.7071067 -1.91966e-6 -0.6621873 -0.6621901 0.350731 -0.6869641 -0.686966 0.2369766 0.7071052 -0.7071083 4.38235e-6 -0.5908142 -0.5908203 0.5494268 0.7071074 -0.7071062 1.32418e-6 -0.6621871 -0.6621918 0.3507282 -0.313733 -0.3137373 0.8961811 -0.5908128 -0.5908148 0.5494344 0.38879 0.3887857 0.8352772 0.3887907 0.3887856 0.8352769 -0.3137329 -0.3137373 0.8961811 0.7071076 -0.7071061 -3.98757e-7 0.7071062 0.7071073 -1.32919e-7 -1.59248e-6 3.96324e-6 -1 -1.59248e-6 3.96324e-6 -1 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071071 -0.7071066 -4.68322e-7 -9.63357e-7 -9.63357e-7 1 0.7071067 -0.7071068 -3.66493e-7 0.7071068 0.7071068 0 0.7071068 -0.7071068 -1.68587e-7 0.7071057 0.7071079 0 1.6202e-6 -4.51027e-6 1 -5.34632e-6 6.91457e-6 -1 0.7071068 0.7071068 1.69331e-7 -0.6933755 -0.6933751 -0.1961163 1.56826e-6 1.56825e-6 -1 -0.7071071 -0.7071065 0 -0.6933761 -0.6933743 -0.1961162 0.707107 -0.7071067 -4.03573e-7 -2.95986e-6 5.27794e-6 -1 0.7071068 -0.7071068 -3.51224e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -1.02973e-6 4.71758e-6 -1 0.7071073 -0.7071063 -4.43487e-7 -0.6933748 -0.6933758 0.1961162 0.7071068 -0.7071067 -2.19527e-7 -0.7071062 -0.7071074 0 5.61957e-6 5.61959e-6 1 -0.6933742 -0.6933764 0.196116 0.693377 0.6933733 0.1961167 6.64133e-6 -1.78805e-5 1 0.7071071 0.7071065 0 0.6933755 0.6933749 0.1961163 0.7024384 0.7024404 -0.1147078 0.7024387 0.7024399 -0.114708 0.7071065 0.7071071 0 0.7071063 0.7071074 0 0.7071068 0.7071068 0 -0.7071072 0.7071064 2.80979e-7 -0.707107 0.7071066 1.32505e-7 -0.7071073 0.7071063 0 -0.707107 0.7071065 4.08874e-7 -0.7071072 0.7071063 3.14466e-7 -0.7071015 0.7071121 2.80981e-7 -0.7071073 0.7071064 0 -0.7071068 0.7071068 2.53375e-7 -0.7071067 0.7071069 1.79348e-7 -0.7071069 0.7071067 2.30092e-7 -0.7071086 0.7071051 1.40489e-7 -0.7071078 0.7071057 0 -0.7071072 0.7071064 0 -0.707107 0.7071066 1.40489e-7 -0.7071071 0.7071064 1.40489e-7 -0.707107 0.7071067 2.08527e-7 -0.707102 0.7071117 2.80981e-7 -0.7071116 0.707102 0 -0.7071036 0.70711 5.61958e-7 -0.7071071 0.7071064 0 -0.707107 0.7071066 1.40489e-7 -0.7071075 0.7071061 1.40489e-7 -0.7070789 0.7071346 8.42947e-7 -0.707111 0.7071026 0 -0.7071093 0.7071043 0 -0.7071071 0.7071064 1.4197e-7 -0.707107 0.7071065 2.10734e-7 -0.7071064 0.7071072 2.10734e-7 -0.707103 0.7071105 2.80981e-7 -0.7071081 0.7071053 1.4049e-7 -0.7071101 0.7071036 0 -0.7071071 0.7071064 1.4197e-7 -0.707107 0.7071065 2.10734e-7 -0.7071062 0.7071073 2.10734e-7 -0.7071036 0.7071101 2.8098e-7 -0.707108 0.7071055 1.4049e-7 -0.7071109 0.7071028 0 -0.7071071 0.7071064 1.4197e-7 -0.7071066 0.707107 3.51224e-7 -0.7071028 0.7071108 3.51225e-7 -0.707104 0.7071096 2.8098e-7 -0.7071079 0.7071056 1.4049e-7 -0.7071121 0.7071015 0 -0.7071071 0.7071064 0 -0.707107 0.7071066 1.40489e-7 -0.7071083 0.7071053 1.40489e-7 -0.7070909 0.7071228 8.42955e-7 -0.7071089 0.7071047 0 -0.707104 0.7071097 2.80978e-7 -0.7071071 0.7071064 0 -0.707107 0.7071067 1.4049e-7 -0.7071084 0.7071052 1.40489e-7 -0.7070991 0.7071143 5.61958e-7 -0.7071085 0.7071051 0 -0.7071133 0.7071002 0 -0.7071071 0.7071064 1.4197e-7 -0.707107 0.7071066 2.10734e-7 -0.7071057 0.7071079 2.10734e-7 -0.7071052 0.7071083 2.80979e-7 -0.7071073 0.7071062 1.4049e-7 -0.7071141 0.7070994 0 -0.707107 0.7071066 2.74475e-7 -0.707107 0.7071066 2.80979e-7 -0.7071027 0.7071109 2.80979e-7 -0.7071088 0.7071048 0 -0.7071061 0.7071076 2.80979e-7 -0.7071151 0.7070985 0 -0.7071069 0.7071065 1.51435e-7 -0.7071069 0.7071066 2.10734e-7 -0.7071056 0.707108 2.10735e-7 -0.707106 0.7071076 6.0364e-7 -0.7071077 0.7071058 0 -0.7071159 0.7070977 0 -0.707107 0.7071066 0 -0.7071064 0.7071071 1.89456e-7 -0.7071068 0.7071068 5.58796e-7 -0.707107 0.7071065 0 -0.7071141 0.7070994 0 -0.707107 0.7071066 1.96865e-7 -0.7071068 0.7071068 2.87158e-7 -0.7071065 0.707107 3.38089e-7 -0.7071 0.7071135 3.65339e-7 -0.7071068 0.7071068 2.17688e-7 -0.7071058 0.7071077 2.10734e-7 -0.7071065 0.7071071 2.80979e-7 -0.707107 0.7071065 1.40489e-7 -0.7071073 0.7071062 1.40489e-7 -0.7071134 0.7071002 0 -0.707107 0.7071067 2.08223e-7 -0.7071061 0.7071075 2.10734e-7 -0.7071086 0.7071051 0 -0.707107 0.7071067 2.10734e-7 -0.7071065 0.7071071 2.10734e-7 -0.7071126 0.707101 0 -0.707107 0.7071067 1.4197e-7 -0.7071084 0.7071052 1.40489e-7 -0.7071093 0.7071043 0 -0.707107 0.7071066 1.40489e-7 -0.7071073 0.7071063 1.40489e-7 -0.7071047 0.7071089 2.80978e-7 -0.707107 0.7071067 2.8394e-7 -0.7071047 0.7071089 2.8098e-7 -0.7071048 0.7071088 2.80978e-7 -0.7071072 0.7071064 2.10734e-7 -0.7071061 0.7071076 2.10734e-7 -0.7071108 0.7071028 0 -0.7071071 0.7071064 2.08223e-7 -0.7071064 0.7071071 2.10734e-7 -0.7071109 0.7071028 0 -0.7071071 0.7071064 2.10734e-7 -0.7071059 0.7071077 2.10734e-7 -0.7071101 0.7071036 0 -0.7071071 0.7071064 2.08223e-7 -0.7071066 0.707107 2.10734e-7 -0.7071116 0.707102 0 -0.7071071 0.7071064 2.10734e-7 -0.7071057 0.7071079 2.10734e-7 -0.7071093 0.7071043 0 -0.7071071 0.7071064 2.08223e-7 -0.7071068 0.7071068 2.10734e-7 -0.7071123 0.7071012 0 -0.7071071 0.7071064 2.10734e-7 -0.7071055 0.707108 2.10734e-7 -0.7071086 0.7071051 0 -0.7071072 0.7071064 3.50193e-7 -0.7071059 0.7071077 3.51224e-7 -0.7071131 0.7071005 0 -0.7071074 0.7071062 2.80979e-7 -0.7071027 0.7071108 2.8098e-7 -0.7071073 0.7071063 0 -0.7071073 0.7071062 0 -0.7071141 0.7070994 0 -0.7071069 0.7071068 1.75612e-7 -0.707107 0.7071065 2.46449e-7 -0.7071073 0.7071062 0 -0.7071067 0.7071068 1.79612e-7 -0.707107 0.7071065 1.37172e-7 -0.707107 0.7071065 2.29248e-7 -0.7071069 0.7071067 3.37175e-7 -0.707107 0.7071065 1.93648e-7 -0.7071076 0.7071061 -4.07454e-7 -0.707107 0.7071065 0 -0.7071079 0.7071056 0 -0.7071074 0.7071062 2.01906e-7 -0.7071042 0.7071095 1.61303e-6 -0.7071077 0.7071058 -3.45513e-7 -0.7071072 0.7071064 0 -0.7071073 0.7071064 0 -0.7071073 0.7071063 1.49523e-6 -0.7071076 0.7071061 7.06784e-7 -0.7071078 0.7071058 -1.27411e-6 0.7071066 0.707107 0 -1.67747e-6 3.97639e-6 -1 0.7071065 0.7071072 2.80979e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071066 0.7071071 0 0.7071065 0.7071071 0 0.7071079 0.7071055 2.80979e-7 -0.7071071 0.7071065 2.80979e-7 0.7071068 0.7071068 1.40489e-7 0.7071071 0.7071065 1.40489e-7 -1.67747e-6 3.97639e-6 -1 -0.7071071 0.7071065 2.82219e-7 0.7071066 0.707107 0 1.42047e-6 -3.71939e-6 1 0.7071063 0.7071073 -1.2935e-7 0.7071062 0.7071074 0 0.7071071 -0.7071065 0 1.42047e-6 -3.71939e-6 1 0.7071068 0.7071068 0 -2.06529e-6 5.13052e-6 -1 0.7071163 0.7070971 2.80975e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071067 0.7071069 0 0.7071084 0.7071051 2.80979e-7 -0.7071071 0.7071065 2.80979e-7 0.7071068 0.7071068 0 0.7071062 0.7071073 0 -2.06529e-6 5.13052e-6 -1 -0.7071071 0.7071065 2.8222e-7 1.5513e-6 -4.61653e-6 1 0.7071071 -0.7071065 0 1.55131e-6 -4.61653e-6 1 0.7071066 0.707107 0 -4.11189e-6 4.11189e-6 -1 0.7071037 0.7071098 0 0.7071068 -0.7071068 -5.61959e-7 0.7071067 0.7071068 0 0.7071014 0.7071122 -2.80977e-7 -0.7071071 0.7071065 2.80979e-7 0.7071068 0.7071068 1.40489e-7 0.7071076 0.7071059 1.40489e-7 -4.11189e-6 4.11189e-6 -1 -0.7071073 0.7071062 5.64439e-7 4.11189e-6 -4.11189e-6 1 0.7071068 -0.7071068 -5.64439e-7 4.11189e-6 -4.11189e-6 1 0.7071066 0.707107 0 -3.08392e-6 3.08392e-6 -1 0.7071146 0.7070989 2.80977e-7 0.7071068 -0.7071068 -2.8098e-7 0.7071042 0.7071093 0 0.707105 0.7071086 0 -0.7071071 0.7071065 0 0.7071068 0.7071068 0 0.7071064 0.7071072 0 -3.08392e-6 3.08391e-6 -1 -0.7071073 0.7071062 2.82219e-7 4.11189e-6 -4.11189e-6 1 0.7071068 -0.7071068 -2.8222e-7 4.11189e-6 -4.11189e-6 1 0.7071067 0.707107 0 -3.08392e-6 3.08392e-6 -1 0.7071136 0.7071 2.80977e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071068 0.7071068 0 0.7071048 0.7071088 0 -0.7071071 0.7071065 0 0.7071065 0.7071071 0 0.7071048 0.7071088 0 -3.08392e-6 3.08391e-6 -1 -0.7071073 0.7071062 2.82219e-7 3.08392e-6 -3.08392e-6 1 0.7071068 -0.7071068 -2.82219e-7 3.08392e-6 -3.08392e-6 1 0.7071062 0.7071074 0 -4.11189e-6 4.11189e-6 -1 0.7071129 0.7071007 2.80976e-7 0.7071068 -0.7071068 -2.80979e-7 0.707105 0.7071086 0 0.7071048 0.7071088 0 -0.7071071 0.7071065 0 0.7071064 0.7071071 0 0.7071068 0.7071068 0 -5.12117e-6 -1.00929e-6 -1 -0.7071074 0.7071063 2.82219e-7 7.17712e-6 -1.04666e-6 1 0.7071068 -0.7071068 -2.82219e-7 2.05594e-6 -2.05594e-6 1 0.7071062 0.7071074 0 -4.11189e-6 4.11189e-6 -1 0.7071119 0.7071017 2.80977e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071069 0.7071067 0 0.7071046 0.7071091 0 -0.7071071 0.7071065 0 0.7071064 0.7071071 1.4049e-7 0.7071091 0.7071044 1.40489e-7 -5.12117e-6 -1.00929e-6 -1 -0.7071074 0.7071063 2.82219e-7 7.17712e-6 -1.04666e-6 1 0.7071068 -0.7071068 -2.82219e-7 2.05594e-6 -2.05594e-6 1 0.7071062 0.7071073 0 -4.11189e-6 4.11189e-6 -1 0.7071055 0.707108 0 0.7071068 -0.7071068 -5.61958e-7 0.7071068 0.7071067 0 0.7070937 0.7071198 -2.80974e-7 -0.7071071 0.7071065 2.80979e-7 0.7071065 0.7071071 1.4049e-7 0.7071096 0.7071041 1.40489e-7 -5.12117e-6 -1.00929e-6 -1 -0.707107 0.7071065 2.82219e-7 7.17712e-6 -1.04666e-6 1 0.7071068 -0.7071068 -5.64438e-7 2.05594e-6 -2.05594e-6 1 0.7071062 0.7071074 0 -4.11189e-6 4.11189e-6 -1 0.7071101 0.7071036 2.80978e-7 0.7071068 -0.7071068 -2.80979e-7 0.707107 0.7071065 0 0.7071037 0.7071098 0 -0.7071071 0.7071065 0 0.7071064 0.7071071 1.4049e-7 0.7071097 0.7071039 1.40488e-7 -5.12117e-6 -1.00929e-6 -1 -0.707107 0.7071065 0 7.17712e-6 -1.04666e-6 1 0.7071068 -0.7071068 -2.82219e-7 2.05594e-6 -2.05594e-6 1 0.7071062 0.7071074 0 -4.11189e-6 4.11189e-6 -1 0.7071093 0.7071043 2.80978e-7 0.7071068 -0.7071068 -2.80979e-7 0.7071066 0.7071071 0 0.7071032 0.7071103 0 -0.7071071 0.7071065 0 0.7071064 0.7071071 0 0.7071065 0.707107 0 -5.12117e-6 -1.00929e-6 -1 -0.707107 0.7071065 0 7.17712e-6 -1.04666e-6 1 0.7071068 -0.7071068 -2.82219e-7 2.05594e-6 -2.05594e-6 1 0.7071064 0.7071071 0 2.01856e-6 1.02423e-5 -1 0.7071065 0.707107 0 0.7071071 -0.7071065 0 0.707103 0.7071106 0 -0.707107 0.7071065 0 0.7071065 0.7071071 0 0.7071066 0.707107 0 0.707108 0.7071055 6.89864e-7 0 0 -1 -0.707107 0.7071065 0 4.11189e-6 -4.11189e-6 1 0.7071068 -0.7071068 -2.8222e-7 -6.13045e-6 -6.13046e-6 1 0.7071064 0.7071071 -4.54304e-7 2.01856e-6 1.02423e-5 -1 0.7071068 0.7071068 0 0.7071071 -0.7071065 0 0.7071027 0.7071108 0 -0.707107 0.7071065 0 0.7071068 0.7071069 0 0.7071067 0.707107 1.86263e-7 0 0 -1 -0.707107 0.7071065 0 4.11189e-6 -4.11189e-6 1 0.7071068 -0.7071068 -2.8222e-7 -6.13045e-6 -6.13046e-6 1 0.707107 0.7071066 2.72582e-7 -1.29431e-6 4.35954e-6 -1 0.7071058 0.7071079 0 0.707107 -0.7071065 0 0.7071035 0.7071101 0 -0.7071068 0.7071068 0 0.7071065 0.707107 0 0.7071065 0.7071071 0 0.7071066 0.7071069 0 0.7071068 0.7071068 0 -1.42047e-6 3.71939e-6 -1 -0.7071068 0.7071068 0 0.707107 0.7071066 1.4197e-7 1.80362e-6 -3.33624e-6 1 0.7071088 0.7071047 1.40489e-7 0.7071068 0.7071068 0 0.7071062 0.7071074 0 0.7071068 -0.7071068 -2.82219e-7 3.08392e-6 -3.08392e-6 1 -2.56993e-6 2.56993e-6 -1 0.7071055 0.707108 0 0.7071068 -0.7071068 0 0.707104 0.7071095 0 -0.7071068 0.7071068 0 -2.31761e-6 3.85022e-6 -1 -0.7071068 0.7071068 0 0.7071068 0.7071068 0 3.34558e-6 -4.8782e-6 1 0.7071064 0.7071073 0 0.7071068 0.7071068 0 0.7071062 0.7071074 0 0.7071065 -0.707107 -2.8222e-7 4.62587e-6 -4.62588e-6 1 -4.11189e-6 4.11189e-6 -1 0.7071052 0.7071083 0 0.7071068 -0.7071068 0 0.7071042 0.7071093 0 -0.7071068 0.7071068 0 -4.11189e-6 4.11189e-6 -1 -0.7071068 0.7071068 0 0.7071067 0.7071067 1.4197e-7 5.13986e-6 -5.13986e-6 1 0.7071083 0.7071053 1.40489e-7 0.7071068 0.7071068 1.40489e-7 0.7071073 0.7071063 1.40489e-7 0.7071065 -0.7071071 -2.8222e-7 5.13986e-6 -5.13986e-6 1 -4.11189e-6 4.11189e-6 -1 0.7070997 0.7071139 -2.80976e-7 0.7071068 -0.7071068 -2.80979e-7 0.7070977 0.707116 -2.80975e-7 -0.7071068 0.7071068 2.80978e-7 -4.11189e-6 4.11189e-6 -1 -0.7071068 0.7071068 2.82219e-7 0.7071068 0.7071068 1.4197e-7 6.16784e-6 -6.16784e-6 1 0.7071079 0.7071056 1.40489e-7 0.7071067 0.7071067 1.4049e-7 0.7071076 0.7071058 1.40489e-7 0.7071065 -0.7071071 -5.64439e-7 6.16783e-6 -6.16784e-6 1 -3.08392e-6 3.08392e-6 -1 0.7071045 0.707109 0 0.7071068 -0.7071068 0 0.707105 0.7071086 0 -0.7071068 0.7071068 0 -3.08392e-6 3.08392e-6 -1 -0.7071068 0.7071068 0 0.7071068 0.7071068 1.4197e-7 -1.00928e-6 -5.12117e-6 1 0.7071079 0.7071058 1.40489e-7 0.7071067 0.707107 0 0.7071061 0.7071074 0 0.7071065 -0.7071071 -2.82219e-7 -1.00929e-6 -5.12117e-6 1 1.00928e-6 5.12117e-6 -1 0.7071043 0.7071093 0 0.7071068 -0.7071068 0 0.7071055 0.707108 0 -0.7071068 0.7071068 0 1.00928e-6 5.12117e-6 -1 -0.7071071 0.7071065 2.8222e-7 0.7071066 0.707107 0 -1.00928e-6 -5.12117e-6 1 0.7071066 0.707107 0 0.7071067 0.707107 0 0.7071062 0.7071073 0 0.7071065 -0.707107 -2.8222e-7 -1.00929e-6 -5.12117e-6 1 1.00928e-6 5.12117e-6 -1 0.707104 0.7071095 0 0.7071068 -0.7071068 0 0.7071058 0.7071078 0 -0.7071068 0.7071068 0 1.00928e-6 5.12117e-6 -1 -0.7071071 0.7071065 2.8222e-7 0.7071066 0.707107 0 -1.00928e-6 -5.12117e-6 1 0.7071065 0.707107 0 0.7071067 0.707107 0 0.7071063 0.7071073 0 0.7071065 -0.707107 -2.8222e-7 -1.00929e-6 -5.12117e-6 1 1.00928e-6 5.12117e-6 -1 0.7071038 0.7071098 0 0.7071068 -0.7071068 0 0.7071061 0.7071076 0 -0.7071068 0.7071068 0 1.00928e-6 5.12117e-6 -1 -0.7071071 0.7071065 2.8222e-7 0.7071066 0.707107 0 -1.00928e-6 -5.12117e-6 1 0.7071065 0.7071071 0 0.7071067 0.707107 0 0.7071064 0.7071073 0 0.7071065 -0.707107 -2.8222e-7 -1.00929e-6 -5.12117e-6 1 1.00928e-6 5.12117e-6 -1 0.7071035 0.7071101 0 0.7071068 -0.7071068 0 0.7071064 0.7071073 0 -0.7071068 0.7071068 0 1.00928e-6 5.12117e-6 -1 -0.7071071 0.7071065 2.8222e-7 0.7071065 0.707107 1.89293e-7 -1.00928e-6 -5.12117e-6 1 0.7071073 0.7071062 0 0.7071067 0.7071069 2.85098e-7 0.7071065 -0.707107 -2.8222e-7 -1.00929e-6 -5.12117e-6 1 0.7071063 0.7071072 0 0.7071065 -0.7071071 0 0.7071066 0.7071071 0 1.66033e-6 -3.95925e-6 1 1.47674e-6 -3.96724e-6 1 0.7071065 -0.7071071 0 0.7071049 0.7071087 -9.12643e-7 0.7069679 -0.7069685 0.01980018 0.7071059 0.7071076 0 0.7058023 -0.7058019 0.0607177 0.7069684 -0.7069679 0.01979935 0.707107 0.7071067 9.96538e-7 0.7031082 -0.7031078 0.1061986 0.7058024 -0.705802 0.06071764 0.7071055 0.7071081 -1.43159e-6 0.6977875 -0.6977868 0.1618219 0.7031085 -0.7031077 0.1061981 0.7071065 0.707107 1.95673e-6 0.6869657 -0.6869648 0.2369759 0.6977878 -0.6977866 0.1618214 0.7071064 0.7071072 -2.20845e-7 0.6621885 -0.6621899 0.3507292 0.6869643 -0.6869654 0.2369782 0.7071045 0.707109 -2.09425e-6 0.5908143 -0.5908165 0.549431 0.7071064 0.7071073 4.23004e-7 0.6621881 -0.6621899 0.35073 0.313737 -0.3137384 0.8961793 0.5908161 -0.5908169 0.5494285 -0.3887877 0.3887855 0.8352784 -0.3887876 0.388786 0.8352782 0.3137345 -0.3137367 0.8961808 0.7071068 0.7071068 1.32919e-7 -0.7071068 0.7071068 1.32919e-7 -4.66968e-7 5.06481e-6 -1 -3.19694e-6 5.49586e-6 -1 -0.7071067 0.7071067 1.33506e-7 -0.7071068 0.7071068 1.82257e-7 0.7071064 0.7071071 -1.27724e-7 6.43698e-6 -3.06519e-7 1 0.7071067 0.7071067 0 -0.7071068 0.7071068 1.82489e-7 0.7071066 0.707107 0 -0.7071068 0.7071068 2.52881e-7 2.89007e-6 -2.89007e-6 1 2.20982e-6 1.00511e-5 -1 -0.7071068 0.7071068 2.53997e-7 0.6933751 -0.6933755 -0.1961164 -3.13651e-6 3.13651e-6 -1 0.7071068 -0.7071068 -1.75612e-7 0.6933752 -0.6933752 -0.1961165 0.7071064 0.7071071 0 -1.59008e-6 3.889e-6 -1 0.7071068 0.7071068 1.40489e-7 0.7071068 -0.7071068 -1.75799e-7 0.7071065 -0.707107 -1.70381e-7 -1.54698e-6 4.03748e-6 -1 0.7071061 0.7071076 -1.55221e-7 0.6933755 -0.693375 0.196116 0.7071066 0.707107 1.66308e-7 0.707107 -0.7071065 -1.79689e-7 5.61959e-6 -5.61958e-6 1 0.6933758 -0.6933748 0.196116 -0.6933764 0.693374 0.1961163 -6.13045e-6 -6.13046e-6 1 -0.7071068 0.7071068 1.89456e-7 -0.693374 0.6933764 0.1961168 -0.7024392 0.7024395 -0.1147077 -0.7024393 0.7024396 -0.1147077 -0.7071068 0.7071068 1.8929e-7 -0.7071068 0.7071068 1.4049e-7 -0.7071068 0.7071068 1.4111e-7 -0.7071065 -0.707107 0 -0.7071064 -0.7071072 -1.4197e-7 -0.7071065 -0.7071071 0 -0.7071062 -0.7071073 0 -0.7071065 -0.7071071 0 -0.7070966 -0.7071169 -2.80983e-7 -0.7071062 -0.7071073 -1.4049e-7 -0.7071067 -0.7071068 0 -0.7071074 -0.7071062 0 -0.7071066 -0.7071069 0 -0.7071037 -0.7071098 -1.40491e-7 -0.7071071 -0.7071065 0 -0.7071067 -0.707107 0 -0.7071067 -0.707107 0 -0.7071068 -0.7071069 0 -0.7071064 -0.7071071 -1.56395e-7 -0.7070971 -0.7071164 -2.80983e-7 -0.7071068 -0.7071068 0 -0.7071073 -0.7071063 0 -0.7071065 -0.707107 0 -0.7071065 -0.707107 0 -0.7071067 -0.707107 0 -0.7071099 -0.7071038 0 -0.7071069 -0.7071067 0 -0.707104 -0.7071097 -2.80981e-7 -0.7071066 -0.707107 0 -0.7071067 -0.707107 0 -0.7071078 -0.7071058 0 -0.707099 -0.7071146 -2.80982e-7 -0.7071093 -0.7071043 0 -0.7071029 -0.7071107 -2.80981e-7 -0.7071066 -0.707107 0 -0.7071062 -0.7071074 0 -0.7071068 -0.7071068 0 -0.7071 -0.7071136 -2.80982e-7 -0.7071113 -0.7071022 0 -0.7071022 -0.7071114 -2.80981e-7 -0.7071062 -0.7071073 0 -0.7071062 -0.7071073 0 -0.7071085 -0.707105 0 -0.7071012 -0.7071124 -2.80981e-7 -0.7071091 -0.7071045 0 -0.7071011 -0.7071124 -2.80981e-7 -0.7071062 -0.7071073 0 -0.7071062 -0.7071073 0 -0.7071069 -0.7071067 0 -0.7071022 -0.7071114 -2.80981e-7 -0.7071072 -0.7071064 0 -0.707109 -0.7071046 0 -0.707106 -0.7071076 -1.4197e-7 -0.7071062 -0.7071073 0 -0.7071068 -0.7071068 0 -0.7071141 -0.7070994 2.80982e-7 -0.7071062 -0.7071074 -1.4049e-7 -0.7070993 -0.7071142 -2.80982e-7 -0.7071061 -0.7071076 -1.4197e-7 -0.7071062 -0.7071073 0 -0.7071071 -0.7071066 0 -0.7071083 -0.7071053 0 -0.7071064 -0.7071073 -1.4049e-7 -0.7070986 -0.7071149 -2.80982e-7 -0.707106 -0.7071076 0 -0.7071062 -0.7071073 0 -0.7071101 -0.7071035 0 -0.7071079 -0.7071058 0 -0.707107 -0.7071064 0 -0.7070976 -0.707116 -2.80983e-7 -0.7071061 -0.7071076 -2.7763e-7 -0.7071062 -0.7071073 0 -0.7071103 -0.7071032 0 -0.7071098 -0.7071039 1.33662e-6 -0.7071075 -0.7071061 0 -0.7070966 -0.707117 -2.80984e-7 -0.7071061 -0.7071076 -1.36291e-6 -0.7071071 -0.7071064 0 -0.7071067 -0.7071069 3.72524e-7 -0.7071073 -0.7071063 0 -0.7070989 -0.7071148 -2.80982e-7 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.707108 -0.7071056 0 -0.707107 -0.7071066 0 -0.7071071 -0.7071065 0 -0.707107 -0.7071065 0 -0.7071068 -0.7071068 -1.40489e-7 -0.7071062 -0.7071073 -1.4049e-7 -0.7070996 -0.7071139 -2.80983e-7 -0.707107 -0.7071066 0 -0.7071093 -0.7071043 0 -0.7071076 -0.7071061 0 -0.7071067 -0.7071067 0 -0.7071069 -0.7071068 0 -0.7071006 -0.707113 -2.80982e-7 -0.707107 -0.7071065 0 -0.707107 -0.7071067 0 -0.7071079 -0.7071058 0 -0.7071067 -0.7071067 -1.4049e-7 -0.7071057 -0.7071078 -1.4049e-7 -0.7071088 -0.7071048 0 -0.707107 -0.7071066 0 -0.707107 -0.7071065 0 -0.7071133 -0.7071002 2.80981e-7 -0.7071068 -0.7071068 -1.4049e-7 -0.7071054 -0.7071081 -1.4049e-7 -0.7071024 -0.7071112 -2.8098e-7 -0.707107 -0.7071066 0 -0.7071083 -0.7071053 0 -0.7071086 -0.7071051 0 -0.7071068 -0.7071068 0 -0.7071069 -0.7071067 0 -0.7071034 -0.7071101 -2.80981e-7 -0.7071068 -0.7071068 0 -0.707108 -0.7071055 0 -0.7071013 -0.7071124 -2.80982e-7 -0.7071068 -0.7071068 0 -0.7071091 -0.7071046 0 -0.7071045 -0.7071092 -2.80981e-7 -0.7071068 -0.7071068 0 -0.7071078 -0.7071058 0 -0.7071002 -0.7071133 -2.80982e-7 -0.7071068 -0.7071068 0 -0.7071093 -0.7071043 0 -0.7071054 -0.7071081 -2.8098e-7 -0.7071068 -0.7071068 0 -0.7071076 -0.707106 0 -0.7070992 -0.7071143 -2.80983e-7 -0.7071068 -0.7071068 0 -0.7071096 -0.707104 0 -0.7071065 -0.7071072 -2.8098e-7 -0.7071068 -0.7071068 -1.59006e-7 -0.7070982 -0.7071154 -2.80983e-7 -0.7071064 -0.7071072 0 -0.7071067 -0.7071068 -2.33479e-7 -0.7071061 -0.7071076 -3.32616e-7 -0.7071068 -0.7071069 0 -0.7071065 -0.7071071 -1.51611e-7 -0.707107 -0.7071067 4.58497e-7 -0.7071065 -0.7071071 0 -0.7071063 -0.7071073 0 -0.7071068 -0.7071068 4.07453e-7 -0.7071063 -0.7071073 0 -0.7071062 -0.7071074 -1.32919e-7 -0.7071057 -0.7071079 -3.12035e-7 -0.7071074 -0.7071062 4.16455e-7 -0.7071074 -0.7071062 4.03098e-7 -0.7071056 -0.707108 -8.03984e-7 -0.7071065 -0.7071071 0 -0.7071051 -0.7071085 -3.71229e-6 -0.7071071 -0.7071065 2.61772e-6 -0.7071064 -0.7071071 -2.54822e-6 -0.7071071 0.7071064 2.08223e-7 -1.52327e-6 4.60718e-6 -1 -0.7071065 0.707107 0 0.7071071 0.7071065 0 -0.7071053 0.7071083 2.10734e-7 -0.7071067 0.707107 1.8447e-7 -0.7071064 0.7071072 2.80979e-7 -0.7071068 -0.7071068 -2.80979e-7 -0.7071073 0.7071062 1.40489e-7 -0.7071072 0.7071064 1.40489e-7 -8.83122e-7 4.48102e-6 -1 -0.7071068 -0.7071068 -2.82219e-7 -0.7071073 0.7071062 0 8.83123e-7 -4.48102e-6 1 -0.7071066 0.707107 4.28899e-7 -0.7071064 0.7071072 3.14466e-7 0.7071068 0.7071068 2.82219e-7 1.00928e-6 -5.12117e-6 1 -0.7071071 0.7071064 0 -2.03726e-6 4.0932e-6 -1 -0.7071151 0.7070985 0 0.7071071 0.7071065 0 -0.7071119 0.7071017 0 -0.7071059 0.7071077 2.8098e-7 -0.7071068 -0.7071068 -2.80979e-7 -0.7071071 0.7071064 0 -0.7071081 0.7071055 0 -2.03725e-6 4.0932e-6 -1 -0.7071068 -0.7071068 -2.82219e-7 2.03726e-6 -4.0932e-6 1 0.7071068 0.7071068 2.82219e-7 2.03726e-6 -4.0932e-6 1 -0.7071071 0.7071064 0 -2.03726e-6 4.0932e-6 -1 -0.7070793 0.7071343 8.42949e-7 0.7071068 0.7071068 2.80979e-7 -0.7071112 0.7071024 0 -0.7070972 0.7071164 8.42942e-7 -0.7071068 -0.7071068 -2.80979e-7 -0.7071071 0.7071064 0 -0.7071087 0.7071048 0 -2.03726e-6 4.0932e-6 -1 -0.7071062 -0.7071073 2.82219e-7 2.03725e-6 -4.0932e-6 1 0.7071071 0.7071065 0 2.03726e-6 -4.0932e-6 1 -0.7071071 0.7071064 1.4197e-7 -2.03726e-6 4.0932e-6 -1 -0.7071032 0.7071103 2.80981e-7 0.7071068 0.7071068 2.80979e-7 -0.7071084 0.7071052 1.4049e-7 -0.7071048 0.7071087 2.8098e-7 -0.7071065 -0.7071071 -2.80979e-7 -0.7071071 0.7071064 1.4049e-7 -0.7071076 0.707106 1.4049e-7 -2.03726e-6 4.0932e-6 -1 -0.7071062 -0.7071073 0 2.03726e-6 -4.0932e-6 1 0.7071068 0.7071068 2.82219e-7 2.03726e-6 -4.0932e-6 1 -0.7071072 0.7071064 1.4197e-7 -2.03725e-6 4.0932e-6 -1 -0.7071037 0.7071098 2.8098e-7 0.7071074 0.7071063 2.80979e-7 -0.7071083 0.7071053 1.4049e-7 -0.7071044 0.7071093 2.8098e-7 -0.7071071 -0.7071065 -2.80979e-7 -0.7071071 0.7071064 1.4049e-7 -0.7071077 0.7071058 1.4049e-7 -2.03726e-6 4.0932e-6 -1 -0.7071068 -0.7071068 0 2.03725e-6 -4.0932e-6 1 0.7071074 0.7071063 2.82219e-7 2.03725e-6 -4.0932e-6 1 -0.7071071 0.7071064 2.8394e-7 2.05595e-6 2.05594e-6 -1 -0.7071042 0.7071093 2.8098e-7 0.7071074 0.7071063 2.80979e-7 -0.7071042 0.7071093 2.8098e-7 -0.7071039 0.7071098 2.8098e-7 -0.7071071 -0.7071065 -2.80979e-7 -0.7071076 0.707106 1.4049e-7 -0.7071079 0.7071057 1.4049e-7 -3.06523e-6 3.06522e-6 -1 -0.7071068 -0.7071068 0 1.00928e-6 -5.12117e-6 1 0.7071074 0.7071063 2.82219e-7 0 0 1 -0.7071071 0.7071064 0 2.05595e-6 2.05595e-6 -1 -0.7071043 0.7071093 2.8098e-7 0.7071068 0.7071068 2.80979e-7 -0.7071092 0.7071044 0 -0.7070853 0.7071283 8.42962e-7 -0.7071071 -0.7071065 -8.42936e-7 -0.7071072 0.7071064 0 -0.7071108 0.7071028 0 -3.06523e-6 3.06523e-6 -1 -0.7071062 -0.7071073 0 1.00928e-6 -5.12116e-6 1 0.7071068 0.7071068 2.82219e-7 0 0 1 -0.7071074 0.7071063 0 2.05594e-6 2.05594e-6 -1 -0.7070995 0.7071142 5.61958e-7 0.7071068 0.7071068 0 -0.7071087 0.7071048 0 -0.7071031 0.7071105 2.80977e-7 -0.7071065 -0.707107 2.80979e-7 -0.7071072 0.7071064 1.40489e-7 -0.7071084 0.7071052 1.40489e-7 -3.06523e-6 3.06522e-6 -1 -0.7071068 -0.7071068 0 1.00928e-6 -5.12117e-6 1 0.7071068 0.7071068 0 0 0 1 -0.7071074 0.7071063 1.32505e-7 2.05595e-6 2.05594e-6 -1 -0.7071055 0.7071081 2.80979e-7 0.707107 0.7071065 2.80979e-7 -0.7071075 0.707106 1.4049e-7 -0.7071141 0.7070994 0 -0.7071068 -0.7071068 0 -0.7071072 0.7071064 2.10734e-7 -0.7071053 0.7071083 2.10734e-7 -3.06523e-6 3.06522e-6 -1 -0.7071068 -0.7071068 0 1.00928e-6 -5.12117e-6 1 0.707107 0.7071065 2.82219e-7 0 0 1 -0.7071074 0.7071063 2.08223e-7 2.05595e-6 2.05594e-6 -1 -0.7071059 0.7071076 2.80979e-7 0.707107 0.7071065 2.80979e-7 -0.7071067 0.7071068 2.10734e-7 -0.7071148 0.7070987 0 -0.7071068 -0.7071068 0 -0.7071071 0.7071064 2.80979e-7 -0.7071018 0.7071118 2.8098e-7 -3.06523e-6 3.06522e-6 -1 -0.7071068 -0.7071068 0 1.00928e-6 -5.12117e-6 1 0.707107 0.7071065 2.82219e-7 0 0 1 -0.7071074 0.7071063 0 -6.13046e-6 6.13045e-6 -1 -0.7071062 0.7071073 2.80978e-7 0.7071065 0.7071071 2.80978e-7 -0.7071159 0.7070977 0 -0.7071065 -0.7071071 0 -0.7071071 0.7071064 2.10734e-7 -0.7071051 0.7071084 2.10735e-7 -0.7071064 0.7071071 5.17399e-7 4.11189e-6 4.11189e-6 -1 -0.7071065 -0.7071071 0 0 0 1 0.7071068 0.7071068 0 2.01857e-6 -1.02423e-5 1 -0.7071074 0.7071063 -3.02872e-7 -6.13045e-6 6.13044e-6 -1 -0.7071068 0.7071068 2.80978e-7 0.7071059 0.7071077 2.80978e-7 -0.7071167 0.7070969 0 -0.7071065 -0.7071071 0 -0.7071062 0.7071073 1.88316e-7 -0.7071068 0.7071067 9.31322e-7 4.11188e-6 4.11189e-6 -1 -0.7071059 -0.7071076 5.64435e-7 0 0 1 0.7071068 0.7071068 -5.64436e-7 2.01857e-6 -1.02423e-5 1 -0.7071066 0.707107 4.24017e-7 -1.39711e-6 3.96704e-6 -1 -0.7071073 0.7071063 2.80979e-7 0.7071062 0.7071074 2.80979e-7 -0.7071139 0.7070997 0 -0.7071073 -0.7071062 0 -0.7071065 0.707107 4.65661e-7 -0.7071075 0.707106 1.68155e-7 -0.7071068 0.7071068 1.81466e-7 -0.707107 0.7071066 2.17309e-7 -1.39711e-6 3.96704e-6 -1 -0.7071073 -0.7071062 0 -0.7071064 0.7071071 2.08222e-7 2.03725e-6 -4.0932e-6 1 -0.7071059 0.7071077 2.10734e-7 -0.7071067 0.707107 1.40489e-7 -0.7071081 0.7071055 1.40489e-7 0.7071065 0.7071071 0 2.03725e-6 -4.09319e-6 1 -2.03725e-6 4.0932e-6 -1 -0.7071068 0.7071068 2.8098e-7 0.7071062 0.7071074 2.8098e-7 -0.7071132 0.7071005 0 -0.7071073 -0.7071062 0 -2.03725e-6 4.0932e-6 -1 -0.7071073 -0.7071062 0 -0.7071064 0.7071071 2.08222e-7 2.03725e-6 -4.0932e-6 1 -0.7071061 0.7071074 2.10734e-7 -0.7071067 0.707107 1.40489e-7 -0.7071082 0.7071053 1.40489e-7 0.7071065 0.7071071 0 2.03725e-6 -4.09319e-6 1 -4.59783e-6 4.59784e-6 -1 -0.7071063 0.7071073 2.80979e-7 0.7071062 0.7071074 2.80979e-7 -0.7071123 0.7071012 0 -0.7071074 -0.7071063 0 -2.03725e-6 4.0932e-6 -1 -0.7071074 -0.7071063 0 -0.7071064 0.7071071 1.4197e-7 3.06522e-6 -3.06523e-6 1 -0.7071083 0.7071052 1.40489e-7 -0.7071066 0.707107 0 -0.7071093 0.7071042 0 0.7071065 0.707107 0 3.56986e-6 -5.6258e-6 1 -4.59783e-6 4.59784e-6 -1 -0.7071005 0.7071132 5.61958e-7 0.7071063 0.7071074 0 -0.7071048 0.7071087 2.80978e-7 -0.7071068 -0.7071068 2.80979e-7 -2.03726e-6 4.0932e-6 -1 -0.7071068 -0.7071068 2.82219e-7 -0.7071064 0.7071071 2.17687e-7 3.06523e-6 -3.06523e-6 1 -0.7071064 0.7071071 2.10734e-7 -0.7071066 0.707107 1.4049e-7 -0.7071084 0.7071052 1.40489e-7 0.7071065 0.707107 -2.82218e-7 3.56987e-6 -5.6258e-6 1 -4.59783e-6 4.59783e-6 -1 -0.7071052 0.7071083 2.80978e-7 0.7071065 0.7071071 2.80977e-7 -0.7071108 0.7071027 0 -0.7071071 -0.7071065 0 -2.03726e-6 4.0932e-6 -1 -0.707107 -0.7071065 0 -0.7071064 0.7071072 1.4197e-7 -2.05594e-6 -2.05594e-6 1 -0.7071081 0.7071056 1.4049e-7 -0.7071064 0.7071071 1.4049e-7 -0.7071086 0.707105 1.4049e-7 0.7071068 0.7071068 0 -2.05594e-6 -2.05594e-6 1 2.05594e-6 2.05594e-6 -1 -0.7071048 0.7071088 2.8098e-7 0.7071065 0.707107 2.80979e-7 -0.7071058 0.7071078 2.80979e-7 -0.707107 -0.7071065 -2.80979e-7 2.05594e-6 2.05594e-6 -1 -0.7071068 -0.7071068 0 -0.7071064 0.7071072 1.4197e-7 -2.05594e-6 -2.05594e-6 1 -0.7071079 0.7071056 1.4049e-7 -0.7071064 0.7071071 1.4049e-7 -0.7071087 0.7071049 1.4049e-7 0.7071067 0.7071067 0 -2.05594e-6 -2.05594e-6 1 2.05594e-6 2.05594e-6 -1 -0.7071043 0.7071093 2.8098e-7 0.7071065 0.707107 2.80979e-7 -0.7071063 0.7071073 2.80979e-7 -0.707107 -0.7071065 -2.80979e-7 2.05594e-6 2.05594e-6 -1 -0.7071068 -0.7071068 0 -0.7071064 0.7071072 1.4197e-7 -2.05594e-6 -2.05594e-6 1 -0.7071078 0.7071057 1.4049e-7 -0.7071064 0.7071071 1.4049e-7 -0.7071088 0.7071047 1.4049e-7 0.7071062 0.7071073 5.64437e-7 -2.05594e-6 -2.05595e-6 1 2.05594e-6 2.05595e-6 -1 -0.7071038 0.7071098 2.8098e-7 0.707106 0.7071076 2.80979e-7 -0.7071068 0.7071068 2.80979e-7 -0.7071068 -0.7071068 -2.80979e-7 2.05594e-6 2.05595e-6 -1 -0.7071065 -0.7071071 0 -0.7071064 0.7071072 2.08223e-7 -2.05594e-6 -2.05594e-6 1 -0.7071073 0.7071064 2.10734e-7 -0.7071064 0.7071071 2.10734e-7 -0.7071064 0.7071073 2.10734e-7 0.7071062 0.7071073 0 -2.05594e-6 -2.05595e-6 1 2.05594e-6 2.05594e-6 -1 -0.7071036 0.7071101 2.8098e-7 0.7071062 0.7071073 2.80979e-7 -0.7071071 0.7071066 2.80979e-7 -0.707107 -0.7071065 -2.80979e-7 2.05594e-6 2.05594e-6 -1 -0.7071068 -0.7071068 0 -0.7071064 0.7071071 6.0574e-7 -2.05594e-6 -2.05594e-6 1 -0.7071076 0.7071061 1.82257e-7 -0.7071069 0.7071067 0 0.7071065 0.707107 0 -2.05594e-6 -2.05595e-6 1 -0.7071073 0.7071064 0 0.7071065 0.7071071 0 -0.7071066 0.7071071 3.18188e-7 2.88962e-6 -5.34818e-6 1 2.87366e-6 -4.98099e-6 1 0.7071065 0.7071071 0 -0.707108 0.7071056 -4.63701e-7 0.706968 0.7069684 0.01979976 -0.7071062 0.7071073 9.47044e-7 0.7058026 0.7058017 0.0607177 0.7069684 0.7069678 0.0198006 -0.7071082 0.7071054 -1.18288e-6 0.7031081 0.703108 0.1061987 0.7058022 0.7058023 0.06071674 -0.7071068 0.7071069 1.11995e-6 0.6977871 0.6977872 0.1618217 0.7031078 0.7031083 0.1061982 -0.7071074 0.7071061 -9.04062e-7 0.6869655 0.6869637 0.2369793 0.6977877 0.6977863 0.1618231 -0.7071074 0.7071062 -3.22774e-7 0.6621906 0.6621876 0.3507299 0.6869657 0.6869633 0.2369799 -0.707103 0.7071106 6.47668e-6 0.5908159 0.5908125 0.5494335 -0.7071075 0.7071062 1.65523e-7 0.6621904 0.6621883 0.3507285 0.3137369 0.3137314 0.8961818 0.5908159 0.5908126 0.5494335 -0.388787 -0.3887921 0.8352757 -0.3887875 -0.388792 0.8352754 0.3137381 0.3137332 0.8961808 -0.7071076 0.7071061 1.32919e-7 -0.7071062 -0.7071074 -1.32919e-7 -1.4967e-6 3.86745e-6 -1 -1.4967e-6 3.86745e-6 -1 -0.7071067 -0.7071067 0 -0.7071068 -0.7071068 0 -0.7071071 0.7071064 1.70299e-7 4.68542e-6 -7.57548e-6 1 -0.707107 0.7071066 2.02649e-7 -0.7071063 -0.7071074 0 -0.707107 0.7071065 3.37175e-7 -0.7071062 -0.7071073 -1.68588e-7 2.10187e-6 -4.02858e-6 1 -5.34632e-6 6.91457e-6 -1 -0.7071068 -0.7071068 0 0.6933754 0.6933754 -0.1961159 1.56825e-6 1.56825e-6 -1 0.7071068 0.7071068 0 0.693374 0.6933765 -0.196116 -0.7071069 0.7071067 1.5522e-7 -1.7673e-6 3.98e-6 -1 -0.707107 0.7071067 1.40489e-7 0.7071064 0.707107 0 0.7071068 0.7071068 0 -1.61882e-6 3.9369e-6 -1 -0.7071073 0.7071063 0 0.6933767 0.6933737 0.1961166 -0.7071068 0.7071067 1.39698e-7 0.707107 0.7071065 0 0 0 1 0.6933742 0.6933764 0.1961161 -0.6933735 -0.693377 0.1961158 5.10876e-7 -1.175e-5 1 -0.707107 -0.7071065 0 -0.6933743 -0.6933761 0.196116 -0.7024398 -0.7024389 -0.1147081 -0.7024396 -0.702439 -0.114708 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 -1.4049e-7 -0.7071068 -0.7071068 -1.4111e-7 0.7071074 -0.7071062 -2.80979e-7 0.707107 -0.7071066 -1.32505e-7 0.7071074 -0.7071062 -3.00372e-7 0.707107 -0.7071067 0 0.7071075 -0.7071061 -1.32076e-7 0.7071118 -0.7071017 -2.80977e-7 0.7071073 -0.7071062 -4.21468e-7 0.7071068 -0.7071068 -1.98591e-7 0.7071068 -0.7071067 -1.83832e-7 0.7071068 -0.7071068 -1.97221e-7 0.7071048 -0.7071089 -1.40489e-7 0.7071079 -0.7071056 -2.80979e-7 0.707107 -0.7071067 0 0.707107 -0.7071065 0 0.7071069 -0.7071068 0 0.707107 -0.7071066 0 0.7071114 -0.7071022 -2.80977e-7 0.7071017 -0.707112 0 0.707111 -0.7071025 -5.61959e-7 0.7071071 -0.7071064 -1.32505e-7 0.707107 -0.7071065 0 0.7071064 -0.7071071 0 0.7071105 -0.707103 -2.80981e-7 0.7071048 -0.7071089 -1.4049e-7 0.7071092 -0.7071045 -2.80978e-7 0.7071072 -0.7071064 -3.50193e-7 0.707107 -0.7071065 -2.80979e-7 0.7071092 -0.7071045 -2.80979e-7 0.7070994 -0.7071141 0 0.7071124 -0.7071012 -3.51222e-7 0.7071091 -0.7071044 -2.80978e-7 0.7071072 -0.7071064 -2.08223e-7 0.707107 -0.7071066 -1.4049e-7 0.7071065 -0.707107 -1.4049e-7 0.7071008 -0.7071129 0 0.7071075 -0.707106 -2.10734e-7 0.7071096 -0.7071039 -2.80978e-7 0.7071071 -0.7071064 -2.08223e-7 0.707107 -0.7071066 -1.4049e-7 0.7071065 -0.7071071 -1.4049e-7 0.7071015 -0.7071121 0 0.7071073 -0.7071062 -2.10734e-7 0.7071101 -0.7071034 -2.80977e-7 0.7071071 -0.7071064 -1.32505e-7 0.707107 -0.7071066 0 0.7071044 -0.7071092 0 0.7071022 -0.7071113 0 0.7071055 -0.7071081 -1.4049e-7 0.7071196 -0.707094 -5.61958e-7 0.707107 -0.7071066 -1.4197e-7 0.707107 -0.7071066 -1.40489e-7 0.7071062 -0.7071074 -1.4049e-7 0.7071139 -0.7070998 -5.61958e-7 0.7071059 -0.7071077 -1.4049e-7 0.7071112 -0.7071024 -2.80977e-7 0.7071071 -0.7071064 -2.08223e-7 0.707107 -0.7071066 -1.4049e-7 0.7071061 -0.7071076 -1.4049e-7 0.7071037 -0.7071098 0 0.7071068 -0.7071067 -2.10734e-7 0.7071117 -0.707102 -2.80977e-7 0.7071071 -0.7071064 -2.08223e-7 0.707107 -0.7071067 -1.4049e-7 0.7071059 -0.7071076 -1.4049e-7 0.7071045 -0.707109 0 0.7071066 -0.707107 -2.10734e-7 0.7070997 -0.7071139 0 0.707107 -0.7071067 -3.15489e-7 0.7071069 -0.7071066 -2.10734e-7 0.7071093 -0.7071043 -2.10734e-7 0.7071051 -0.7071085 5.174e-7 0.7071053 -0.7071083 0 0.7071538 -0.7070597 -1.12395e-6 0.707107 -0.7071066 0 0.7071064 -0.7071072 -1.69513e-7 0.7071069 -0.7071068 3.72531e-7 0.7071081 -0.7071056 -1.12391e-6 0.7070999 -0.7071136 0 0.707107 -0.7071066 -1.51435e-7 0.7071068 -0.7071068 0 0.7071073 -0.7071063 -1.705e-7 0.7071064 -0.7071073 -1.67192e-7 0.7071069 -0.7071066 -2.08223e-7 0.7071082 -0.7071054 -2.10734e-7 0.7071063 -0.7071073 0 0.707107 -0.7071066 -2.10734e-7 0.7071074 -0.7071062 -2.10734e-7 0.7071008 -0.7071129 0 0.707107 -0.7071066 -2.08223e-7 0.707108 -0.7071056 -2.10734e-7 0.7071055 -0.707108 0 0.707107 -0.7071066 -2.10734e-7 0.7071076 -0.7071059 -2.10734e-7 0.7071014 -0.7071121 0 0.707107 -0.7071067 -1.4197e-7 0.7071057 -0.7071079 -1.4049e-7 0.7071048 -0.7071088 0 0.7071073 -0.7071062 -2.80979e-7 0.7071088 -0.7071048 -2.80978e-7 0.7071094 -0.7071042 -2.8098e-7 0.7071073 -0.7071062 -1.4197e-7 0.7071058 -0.7071077 -1.4049e-7 0.7071089 -0.7071048 -2.8098e-7 0.7071073 -0.7071062 -1.40489e-7 0.7071061 -0.7071074 -1.4049e-7 0.7071028 -0.7071108 0 0.7071073 -0.7071063 -2.08223e-7 0.7071071 -0.7071064 -2.10734e-7 0.707103 -0.7071106 0 0.7071073 -0.7071062 -2.10734e-7 0.7071079 -0.7071056 -2.10734e-7 0.7071036 -0.7071101 0 0.7071073 -0.7071063 -2.08223e-7 0.707107 -0.7071065 -2.10734e-7 0.7071022 -0.7071114 0 0.7071073 -0.7071062 -2.10734e-7 0.7071081 -0.7071055 -2.10734e-7 0.7071115 -0.7071021 -5.61954e-7 0.7071069 -0.7071066 -2.08223e-7 0.7071073 -0.7071063 -2.10734e-7 0.7071015 -0.7071121 0 0.7071071 -0.7071065 -2.80979e-7 0.7071106 -0.7071031 -2.80978e-7 0.7071055 -0.7071081 0 0.7071071 -0.7071065 -2.08223e-7 0.7071071 -0.7071065 -2.10734e-7 0.7071005 -0.7071131 0 0.7071071 -0.7071064 -2.10734e-7 0.7071082 -0.7071053 -2.10734e-7 0.7071063 -0.7071073 0 0.7071071 -0.7071064 -2.72582e-7 0.7070997 -0.7071138 0 0.707107 -0.7071067 -1.75612e-7 0.707107 -0.7071065 -1.68624e-7 0.7071073 -0.7071062 -4.43487e-7 0.707107 -0.7071068 -2.19526e-7 0.7071071 -0.7071064 -3.10441e-7 0.7071068 -0.7071066 0 0.7071071 -0.7071065 -2.52881e-7 0.7071068 -0.7071068 -1.70866e-7 0.7071075 -0.7071061 -5.82076e-7 0.7071068 -0.7071068 0 0.707107 -0.7071065 -2.65838e-7 0.7071094 -0.7071042 -1.13189e-6 0.7071068 -0.7071068 0 0.7071089 -0.7071047 -1.14595e-6 0.7071061 -0.7071076 8.38565e-7 0.7071074 -0.7071062 -4.14009e-7 0.7071077 -0.7071059 -1.9077e-6 0.7071062 -0.7071074 2.43448e-6 0.7071068 -0.7071068 -1.81773e-6 -0.7071063 -0.7071074 0 -1.5513e-6 4.61653e-6 -1 -0.7071069 -0.7071068 -2.80979e-7 -0.7071071 0.7071065 2.80979e-7 -0.707107 -0.7071065 0 -0.7071068 -0.7071068 0 -0.7071059 -0.7071077 -2.80979e-7 0.7071071 -0.7071065 -2.80979e-7 -0.7071063 -0.7071074 0 -0.7071071 -0.7071064 0 -1.67746e-6 3.97638e-6 -1 0.7071071 -0.7071065 -2.82219e-7 -0.7071063 -0.7071074 -2.00428e-7 2.44844e-6 -4.74736e-6 1 -0.707107 -0.7071067 0 -0.7071071 -0.7071065 0 -0.7071068 0.7071068 0 1.8083e-6 -4.87352e-6 1 -0.7071061 -0.7071076 -1.4197e-7 -2.31761e-6 3.85022e-6 -1 -0.7071104 -0.7071033 0 -0.7071068 0.7071068 0 -0.7071039 -0.7071098 -1.4049e-7 -0.7071051 -0.7071084 -2.8098e-7 0.7071071 -0.7071065 -2.80979e-7 -0.7071062 -0.7071073 0 -0.7071073 -0.7071062 0 -2.06529e-6 5.13052e-6 -1 0.7071071 -0.7071065 -2.82219e-7 1.5513e-6 -4.61653e-6 1 -0.7071068 0.7071068 0 2.83159e-6 -4.36421e-6 1 -0.707106 -0.7071076 -1.4197e-7 -2.57928e-6 5.6445e-6 -1 -0.7071217 -0.7070919 2.80985e-7 -0.7071068 0.7071068 2.80979e-7 -0.7071043 -0.7071093 -1.4049e-7 -0.7071083 -0.7071053 0 0.707107 -0.7071065 -5.61958e-7 -0.7071062 -0.7071073 0 -0.7071073 -0.7071064 0 -2.57928e-6 5.6445e-6 -1 0.7071071 -0.7071065 -5.64438e-7 2.57928e-6 -5.6445e-6 1 -0.7071068 0.7071068 2.82219e-7 2.57927e-6 -5.6445e-6 1 -0.7071061 -0.7071075 0 -1.5513e-6 4.61653e-6 -1 -0.7071096 -0.7071041 0 -0.7071068 0.7071068 0 -0.707107 -0.7071067 0 -0.7071034 -0.7071102 -2.80981e-7 0.707107 -0.7071065 -2.8098e-7 -0.7071062 -0.7071073 0 -0.7071088 -0.7071048 0 -1.5513e-6 4.61653e-6 -1 0.707107 -0.7071065 -2.8222e-7 2.57928e-6 -5.6445e-6 1 -0.7071068 0.7071068 0 2.57927e-6 -5.6445e-6 1 -0.7071061 -0.7071076 -1.4197e-7 -1.5513e-6 4.61653e-6 -1 -0.7071093 -0.7071042 0 -0.7071068 0.7071068 0 -0.7071048 -0.7071088 -1.4049e-7 -0.7071023 -0.7071112 -2.80981e-7 0.7071071 -0.7071065 -2.80979e-7 -0.7071067 -0.7071067 1.4049e-7 -0.7071124 -0.7071011 1.40493e-7 -1.5513e-6 4.61653e-6 -1 0.7071074 -0.7071062 0 1.5513e-6 -4.61653e-6 1 -0.7071068 0.7071068 0 1.5513e-6 -4.61653e-6 1 -0.7071066 -0.707107 0 -4.11189e-6 4.11189e-6 -1 -0.7071088 -0.7071048 0 -0.7071068 0.7071068 0 -0.7071069 -0.7071068 0 -0.7071008 -0.7071127 -2.80981e-7 0.7071071 -0.7071065 -2.80979e-7 -0.7071067 -0.7071067 0 -0.7071088 -0.7071048 0 -5.12117e-6 -1.00929e-6 -1 0.7071073 -0.7071062 0 7.17712e-6 -1.04666e-6 1 -0.7071068 0.7071068 0 2.05594e-6 -2.05594e-6 1 -0.7071066 -0.707107 -1.4197e-7 -4.11189e-6 4.11189e-6 -1 -0.7071086 -0.707105 0 -0.7071068 0.7071068 0 -0.7071053 -0.7071083 -1.4049e-7 -0.7070998 -0.7071138 -2.80982e-7 0.7071071 -0.7071065 -2.80979e-7 -0.7071067 -0.7071067 0 -0.7071068 -0.7071068 0 -5.12117e-6 -1.00929e-6 -1 0.7071073 -0.7071062 0 7.17712e-6 -1.04666e-6 1 -0.7071068 0.7071068 0 2.05594e-6 -2.05594e-6 1 -0.7071066 -0.707107 -1.4197e-7 -4.11189e-6 4.11189e-6 -1 -0.7071136 -0.7071 2.80982e-7 -0.7071068 0.7071068 2.80979e-7 -0.7071056 -0.7071079 -1.4049e-7 -0.7071093 -0.7071043 0 0.707107 -0.7071065 -5.61958e-7 -0.7071068 -0.7071068 0 -0.7071067 -0.7071068 0 -5.12117e-6 -1.00929e-6 -1 0.7071073 -0.7071062 -2.82219e-7 7.17712e-6 -1.04666e-6 1 -0.7071068 0.7071068 2.82219e-7 2.05594e-6 -2.05594e-6 1 -0.7071066 -0.707107 -1.32505e-7 -4.11189e-6 4.11189e-6 -1 -0.7071079 -0.7071058 0 -0.7071068 0.7071068 0 -0.7071058 -0.7071079 -1.4049e-7 -0.707098 -0.7071155 -2.80983e-7 0.707107 -0.7071065 -2.8098e-7 -0.7071066 -0.707107 -1.40489e-7 -0.7071039 -0.7071096 -1.40491e-7 -5.12117e-6 -1.00929e-6 -1 0.7071074 -0.7071063 0 7.17712e-6 -1.04666e-6 1 -0.7071068 0.7071068 0 2.05594e-6 -2.05594e-6 1 -0.7071066 -0.707107 0 -4.11189e-6 4.11189e-6 -1 -0.7071073 -0.7071063 0 -0.7071068 0.7071068 0 -0.7071065 -0.707107 0 -0.7071104 -0.7071033 0 0.707107 -0.7071065 0 -0.7071066 -0.707107 0 -0.707107 -0.7071065 0 -5.12117e-6 -1.00929e-6 -1 0.7071071 -0.7071065 0 7.17712e-6 -1.04666e-6 1 -0.7071068 0.7071068 0 2.05595e-6 -2.05595e-6 1 -0.7071066 -0.707107 0 -4.11189e-6 4.11189e-6 -1 -0.7071071 -0.7071065 0 -0.7071068 0.7071068 0 -0.7071106 -0.707103 0 0.7071071 -0.7071065 0 -0.7071066 -0.707107 0 -0.707107 -0.7071066 0 -0.7071068 -0.7071068 0 -4.11189e-6 4.11189e-6 -1 0.7071071 -0.7071065 0 4.11189e-6 -4.11189e-6 1 -0.7071068 0.7071068 0 4.11189e-6 -4.11189e-6 1 -0.7071066 -0.707107 -2.27153e-7 -4.11189e-6 4.11189e-6 -1 -0.7071068 -0.7071068 0 -0.7071068 0.7071068 0 -0.7071108 -0.7071027 0 0.7071071 -0.7071065 0 -0.7071066 -0.707107 0 -0.7071066 -0.7071069 -1.24177e-7 -4.11189e-6 4.11189e-6 -1 0.7071071 -0.7071065 0 4.11189e-6 -4.11189e-6 1 -0.7071068 0.7071068 0 4.11189e-6 -4.11189e-6 1 -0.7071064 -0.7071071 -2.57439e-7 -1.67746e-6 3.97638e-6 -1 -0.7071076 -0.7071061 0 -0.7071068 0.7071068 0 -0.707099 -0.7071146 -2.80982e-7 0.7071068 -0.7071068 -2.80979e-7 -0.707107 -0.7071065 0 -0.7071065 -0.707107 0 -0.7071069 -0.7071067 0 -0.7071068 -0.7071068 0 -1.67746e-6 3.97638e-6 -1 0.7071068 -0.7071068 -2.82219e-7 -0.7071066 -0.707107 0 5.23329e-7 -3.58856e-6 1 -0.7071069 -0.7071067 0 -0.7071062 -0.7071073 -2.10735e-7 -0.7071064 -0.7071071 -2.10734e-7 -0.7071074 0.7071062 5.64439e-7 1.80362e-6 -3.33623e-6 1 -1.28964e-6 2.82225e-6 -1 -0.7071083 -0.7071053 0 -0.7071065 0.7071071 0 -0.7071093 -0.7071042 0 0.707107 -0.7071065 0 -1.03732e-6 4.10254e-6 -1 0.7071068 -0.7071068 -2.82219e-7 -0.7071063 -0.7071074 0 5.23332e-7 -3.58856e-6 1 -0.7071069 -0.7071065 0 -0.7071062 -0.7071073 0 -0.7071076 -0.7071059 0 -0.7071068 0.7071068 2.82219e-7 1.80362e-6 -3.33624e-6 1 0 6.14915e-6 -1 -0.7071085 -0.707105 0 -0.7071062 0.7071073 0 -0.707109 -0.7071045 0 0.7071071 -0.7071065 0 -5.2333e-7 3.58856e-6 -1 0.7071068 -0.7071068 -2.82219e-7 -0.7071062 -0.7071073 -1.4197e-7 1.5513e-6 -4.61653e-6 1 -0.7071051 -0.7071085 -1.4049e-7 -0.7071062 -0.7071073 -1.4049e-7 -0.7071065 -0.707107 -1.4049e-7 -0.7071065 0.7071071 2.82219e-7 -1.00928e-6 -5.12117e-6 1 0 6.14915e-6 -1 -0.7071141 -0.7070994 2.80982e-7 -0.7071068 0.7071068 2.80979e-7 -0.7071157 -0.707098 2.80982e-7 0.707107 -0.7071065 -2.80979e-7 -5.2333e-7 3.58856e-6 -1 0.7071068 -0.7071068 -5.64438e-7 -0.7071062 -0.7071073 -1.4197e-7 1.5513e-6 -4.61653e-6 1 -0.7071054 -0.7071081 -1.4049e-7 -0.7071062 -0.7071073 -1.4049e-7 -0.7071062 -0.7071074 -1.4049e-7 -0.7071068 0.7071068 2.82219e-7 -1.00928e-6 -5.12117e-6 1 0 6.14915e-6 -1 -0.7071093 -0.7071043 0 -0.7071065 0.7071071 0 -0.7071083 -0.7071053 0 0.707107 -0.7071065 0 -5.2333e-7 3.58856e-6 -1 0.7071068 -0.7071068 -2.82218e-7 -0.7071062 -0.7071073 -2.17687e-7 2.05594e-6 -2.05594e-6 1 -0.7071042 -0.7071095 -2.10736e-7 -0.7071071 -0.7071064 1.4049e-7 -0.7071126 -0.707101 1.40493e-7 -0.7071068 0.7071068 2.82217e-7 7.17711e-6 -1.04666e-6 1 -5.12118e-6 -1.00929e-6 -1 -0.7071088 -0.7071048 0 -0.7071073 0.7071062 0 -0.7071076 -0.7071061 0 0.707107 -0.7071065 0 -4.11189e-6 4.11189e-6 -1 0.7071068 -0.7071068 -2.82219e-7 -0.7071071 -0.7071065 0 2.05595e-6 -2.05594e-6 1 -0.7071065 -0.7071071 0 -0.7071071 -0.7071064 0 -0.7071069 -0.7071068 0 -0.7071076 0.7071059 2.82219e-7 7.17713e-6 -1.04666e-6 1 -5.12118e-6 -1.00928e-6 -1 -0.7071091 -0.7071046 0 -0.7071071 0.7071065 0 -0.7071073 -0.7071062 0 0.707107 -0.7071065 0 -4.11189e-6 4.11189e-6 -1 0.7071068 -0.7071068 -2.82219e-7 -0.7071071 -0.7071065 0 2.05595e-6 -2.05594e-6 1 -0.7071065 -0.7071071 0 -0.7071071 -0.7071064 0 -0.7071068 -0.7071068 0 -0.7071074 0.7071063 2.82219e-7 7.17712e-6 -1.04666e-6 1 -5.12117e-6 -1.00928e-6 -1 -0.7071093 -0.7071043 0 -0.7071068 0.7071068 0 -0.707107 -0.7071065 0 0.7071068 -0.7071068 0 -4.11189e-6 4.11189e-6 -1 0.7071068 -0.7071068 0 -0.7071071 -0.7071065 0 2.05594e-6 -2.05594e-6 1 -0.7071066 -0.707107 0 -0.7071071 -0.7071064 0 -0.7071068 -0.7071069 0 -0.707107 0.7071065 2.82219e-7 7.17712e-6 -1.04666e-6 1 -5.12118e-6 -1.00928e-6 -1 -0.7071095 -0.707104 0 -0.7071071 0.7071065 0 -0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 -4.11189e-6 4.11189e-6 -1 0.7071068 -0.7071068 0 -0.7071071 -0.7071064 2.27152e-7 2.05594e-6 -2.05594e-6 1 -0.7071058 -0.7071078 0 -0.7071067 -0.7071068 -3.90691e-7 -0.7071074 0.7071063 2.82219e-7 7.17712e-6 -1.04666e-6 1 -0.7071066 -0.7071069 0 -0.7071065 0.7071071 0 -0.707107 -0.7071065 1.71332e-7 2.31486e-7 -5.21248e-6 1 2.80181e-6 -5.10073e-6 1 -0.7071068 0.7071068 2.11664e-7 -0.7071073 -0.7071062 4.45835e-7 -0.7069679 0.7069684 0.0197997 -0.7071068 -0.7071068 0 -0.7058019 0.7058024 0.0607177 -0.706968 0.7069684 0.01979976 -0.7071063 -0.7071073 -5.67134e-7 -0.7031083 0.703108 0.1061972 -0.7058022 0.7058021 0.06071722 -0.7071062 -0.7071074 -6.91449e-7 -0.6977866 0.6977869 0.1618248 -0.703108 0.7031083 0.1061977 -0.7071059 -0.7071077 -1.65951e-6 -0.6869652 0.6869642 0.2369789 -0.6977874 0.6977865 0.1618237 -0.7071059 -0.7071076 -4.24703e-7 -0.6621899 0.6621879 0.3507301 -0.6869657 0.6869639 0.2369782 -0.7071129 -0.7071008 8.57085e-6 -0.5908166 0.590814 0.5494311 -0.7071061 -0.7071076 -1.01153e-6 -0.66219 0.6621879 0.3507299 -0.3137343 0.313732 0.8961825 -0.5908154 0.5908136 0.5494328 0.3887907 -0.3887926 0.8352738 0.3887906 -0.3887925 0.8352738 -0.3137336 0.3137316 0.8961829 -0.7071061 -0.7071076 0 0.7071068 -0.7071068 0 -3.29272e-6 5.40007e-6 -1 -5.62756e-7 4.96902e-6 -1 0.7071068 -0.7071068 0 0.7071068 -0.7071068 -1.82257e-7 -0.7071067 -0.707107 0 -1.75158e-7 -5.9553e-6 1 -0.7071066 -0.707107 0 0.7071068 -0.7071068 -1.82489e-7 -0.7071066 -0.707107 0 0.7071073 -0.7071062 -2.52881e-7 3.37175e-6 -3.37175e-6 1 2.20982e-6 1.00511e-5 -1 0.7071068 -0.7071068 -1.69332e-7 -0.6933756 0.693375 -0.1961157 -3.13651e-6 3.13651e-6 -1 -0.7071071 0.7071065 1.69758e-7 -0.693375 0.6933757 -0.1961156 -0.7071067 -0.707107 -1.24176e-7 -2.27497e-6 4.57389e-6 -1 -0.7071068 -0.7071068 0 -0.707107 0.7071065 1.69332e-7 -0.7071074 0.7071062 1.74865e-7 -2.27497e-6 4.57389e-6 -1 -0.7071063 -0.7071073 -1.99569e-7 -0.6933764 0.693374 0.1961165 -0.7071066 -0.7071069 0 -0.7071068 0.7071068 1.83743e-7 5.61959e-6 -5.61958e-6 1 -0.6933757 0.6933747 0.1961166 0.6933754 -0.6933754 0.1961159 5.61958e-6 -5.61958e-6 1 0.7071068 -0.7071068 -1.8447e-7 0.6933754 -0.6933754 0.1961159 0.7024395 -0.7024392 -0.1147083 0.7024397 -0.702439 -0.1147081 0.7071071 -0.7071065 -1.89791e-7 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071073 0.7071063 0 0.7071059 0.7071077 0 0.7071076 0.7071061 7.05874e-7 0.7071061 0.7071076 -4.99734e-7 0.7071073 0.7071063 0 0.7071181 0.7070954 2.80975e-7 0.7071065 0.7071071 0 0.7071066 0.707107 1.23263e-7 0.7071077 0.7071059 0 0.7071071 0.7071065 1.91743e-7 0.7071075 0.707106 0 0.7071068 0.7071068 0 0.7071059 0.7071077 0 0.7071061 0.7071075 1.4049e-7 0.7071074 0.7071061 1.40489e-7 0.7071061 0.7071076 -1.9115e-7 0.7071174 0.7070961 2.80975e-7 0.7071078 0.7071059 0 0.7071039 0.7071096 -2.80978e-7 0.7071059 0.7071077 0 0.7071061 0.7071075 1.4049e-7 0.7071079 0.7071057 1.40489e-7 0.7071048 0.7071088 0 0.7071077 0.7071059 0 0.707106 0.7071076 0 0.7071059 0.7071077 0 0.7071061 0.7071075 0 0.707107 0.7071065 0 0.7071156 0.707098 2.80976e-7 0.7071052 0.7071083 0 0.7071058 0.7071077 0 0.7071061 0.7071076 0 0.7071066 0.7071069 1.4049e-7 0.7071083 0.7071052 1.40489e-7 0.7071053 0.7071083 0 0.7071031 0.7071107 0 0.7071053 0.7071083 0 0.7071066 0.7071069 0 0.7071066 0.707107 0 0.7071068 0.7071067 0 0.7071051 0.7071086 0 0.707107 0.7071066 0 0.7071051 0.7071086 0 0.7071066 0.7071069 1.4197e-7 0.7071066 0.707107 1.4049e-7 0.7071088 0.7071047 1.40489e-7 0.7071053 0.7071083 0 0.7071086 0.707105 1.40489e-7 0.7070958 0.7071177 -2.80974e-7 0.7071066 0.707107 1.4197e-7 0.7071066 0.7071069 1.4049e-7 0.7071093 0.7071044 1.40489e-7 0.7071002 0.7071134 -2.80976e-7 0.7071082 0.7071054 1.40489e-7 0.7071043 0.7071093 0 0.7071066 0.707107 2.17687e-7 0.7071064 0.7071071 1.4049e-7 0.7071094 0.7071043 1.40488e-7 0.707106 0.7071076 0 0.707109 0.7071045 2.10733e-7 0.7071038 0.7071098 0 0.7071064 0.7071072 0 0.7071064 0.7071072 0 0.7071067 0.707107 0 0.7071068 0.7071068 0 0.7071075 0.7071061 0 0.7071035 0.7071101 0 0.7071064 0.7071071 -1.26196e-7 0.7071064 0.7071071 0 0.7071067 0.707107 0 0.7071096 0.707104 1.33662e-6 0.707107 0.7071065 0 0.7071033 0.7071104 0 0.7071065 0.7071072 -9.84326e-7 0.7071068 0.7071069 0 0.7071068 0.7071068 0 0.7071073 0.7071062 0 0.7070816 0.707132 -5.61938e-7 0.7071061 0.7071075 0 0.7071066 0.707107 2.40592e-7 0.7071061 0.7071076 0 0.7071092 0.7071044 1.23846e-7 0.7071066 0.707107 1.4197e-7 0.7071089 0.7071046 1.40489e-7 0.7071076 0.707106 2.80979e-7 0.7071064 0.7071071 0 0.7071064 0.7071071 0 0.707114 0.7070997 2.80976e-7 0.7071064 0.7071071 0 0.7071066 0.7071069 0 0.7071083 0.7071052 2.80978e-7 0.7071062 0.7071073 0 0.7071055 0.7071081 0 0.7071132 0.7071004 2.80977e-7 0.7071063 0.7071073 0 0.7071026 0.7071109 0 0.7071093 0.7071043 2.80978e-7 0.7071066 0.7071069 0 0.7071063 0.7071073 0 0.7071119 0.7071017 2.80977e-7 0.7071064 0.7071072 0 0.7071065 0.707107 0 0.7071051 0.7071086 0 0.7071065 0.7071071 0 0.7071063 0.7071072 0 0.7071112 0.7071024 2.80975e-7 0.7071064 0.7071071 -2.74475e-7 0.7070994 0.7071142 -2.80973e-7 0.7071111 0.7071025 2.80976e-7 0.7071074 0.7071061 1.40489e-7 0.7071078 0.7071058 1.40489e-7 0.7071091 0.7071044 2.80978e-7 0.7071076 0.7071061 0 0.7071056 0.7071079 0 0.7071116 0.707102 2.80977e-7 0.7071073 0.7071062 0 0.7071037 0.7071099 0 0.7071084 0.7071052 2.80978e-7 0.7071074 0.7071062 0 0.7071058 0.7071077 0 0.7071126 0.7071009 2.80976e-7 0.7071071 0.7071064 0 0.7071036 0.7071101 0 0.7071077 0.7071059 2.80978e-7 0.707107 0.7071066 0 0.707105 0.7071086 0 0.7071036 0.7071101 0 0.7071073 0.7071062 0 0.7071061 0.7071074 0 0.7071064 0.7071073 2.80979e-7 0.7071071 0.7071064 5.45166e-7 0.7071033 0.7071104 0 0.7071064 0.7071071 0 0.7071065 0.7071071 0 0.7071063 0.7071073 0 0.7071068 0.7071067 1.79612e-7 0.7071066 0.707107 1.22732e-7 0.7071064 0.7071071 0 0.7071065 0.7071071 0 0.7071075 0.707106 0 0.707106 0.7071075 -1.04774e-6 0.7071075 0.7071061 2.10734e-7 0.7071064 0.7071071 0 0.7071076 0.707106 4.0993e-7 0.7071042 0.7071093 -1.06166e-6 0.707109 0.7071045 1.60664e-6 0.7071062 0.7071074 -4.03433e-7 0.7071071 0.7071065 4.22756e-7 0.7071089 0.7071047 7.06367e-6 0.7071062 0.7071074 -9.42374e-7 0.7071064 0.7071071 2.20845e-7 -1.14543e-6 3.96948e-6 -1 0.4530771 -0.8914714 -1.96799e-7 4.1474e-6 5.08174e-7 -1 0.8914713 -0.4530771 0 -2.41316e-6 5.13769e-6 -1 -1.66331e-6 3.95155e-6 -1 0.8914713 -0.4530771 0 -1.66717e-6 4.44619e-6 -1 -0.1557745 -0.9877927 -2.18063e-7 0.4530771 -0.8914714 -1.96815e-7 -1.3353e-6 4.14911e-6 -1 -0.7071037 -0.7071099 -1.561e-7 -0.1557745 -0.9877927 -2.18063e-7 -7.51651e-7 4.61814e-6 -1 -0.9877936 -0.1557684 0 -1.77484e-6 3.7634e-6 -1 -1.68121e-6 3.85703e-6 -1 -2.68662e-6 5.32923e-6 -1 -1.63481e-6 3.58977e-6 -1 -2.14942e-6 4.56837e-6 -1 -0.7071037 -0.7071099 -1.561e-7 -1.82984e-6 3.54602e-6 -1 -0.8914713 0.4530771 0 -1.80949e-6 3.5603e-6 -1 -0.9877936 -0.1557684 0 -1.23133e-6 4.13846e-6 -1 -0.4530821 0.8914688 1.96799e-7 -1.25167e-6 4.12419e-6 -1 -0.8914713 0.4530771 0 -1.8029e-6 3.58565e-6 -1 0.1557684 0.9877936 2.18063e-7 -1.68894e-6 3.68086e-6 -1 -0.4530821 0.8914688 1.96799e-7 -3.0097e-6 3.57161e-6 -1 0.7071068 0.7071068 1.56099e-7 -1.46508e-6 3.92348e-6 -1 0.1557684 0.9877936 2.18063e-7 1.56781e-6 4.19446e-6 -1 0.9877908 0.1557857 0 -1.85255e-6 3.92441e-6 -1 -2.05613e-6 3.87073e-6 -1 0.7071068 0.7071068 1.56099e-7 -1.23159e-6 3.74032e-6 -1 -2.42935e-6 4.21191e-6 -1 -1.43589e-6 3.95284e-6 -1 -1.06199e-6 3.92987e-6 -1 0.9877908 0.1557857 0 0 3.6335e-6 -1 0.4530696 -0.8914752 0 1.33919e-6 1.93539e-6 -1 0.8914726 -0.4530746 0 -3.78394e-6 6.10658e-6 -1 0.8914726 -0.4530746 0 -2.36043e-6 5.05665e-6 -1 -0.1557633 -0.9877945 0 0.4530696 -0.8914752 0 -1.1173e-6 4.36708e-6 -1 -0.7071068 -0.7071068 0 -0.1557633 -0.9877945 0 -1.91662e-6 3.64495e-6 -1 -0.9877929 -0.1557735 0 -1.77489e-6 3.76335e-6 -1 -1.60817e-6 3.93007e-6 -1 -1.95183e-6 4.76879e-6 -1 -1.6947e-6 4.30774e-6 -1 -0.7071068 -0.7071068 0 -1.97238e-6 3.61852e-6 -1 -0.891465 0.4530895 0 -1.87409e-6 3.68748e-6 -1 -0.9877929 -0.1557735 0 -1.29598e-6 4.26559e-6 -1 -0.4530895 0.891465 0 -1.39427e-6 4.19663e-6 -1 -0.891465 0.4530895 0 -1.77481e-6 3.76342e-6 -1 0.1557716 0.9877932 0 -1.91656e-6 3.64501e-6 -1 -0.4530895 0.891465 0 -1.51593e-6 3.96852e-6 -1 0.7071006 0.707113 0 -1.5883e-6 3.94993e-6 -1 0.1557716 0.9877932 0 1.99808e-6 4.26227e-6 -1 0.9877947 0.1557614 0 -2.13052e-6 3.76412e-6 -1 -2.17619e-6 3.75066e-6 -1 0.7071006 0.707113 0 -3.59199e-7 3.34031e-6 -1 -2.36409e-6 4.09888e-6 -1 -1.43592e-6 3.876e-6 -1 -1.09988e-6 3.86417e-6 -1 0.9877947 0.1557614 0 0.4530746 -0.8914726 0 0.8914726 -0.4530746 0 0.8914726 -0.4530746 0 -0.1557614 -0.9877947 0 0.4530746 -0.8914726 0 0 4.46954e-6 -1 -0.707113 -0.7071006 0 -0.1557614 -0.9877947 0 -5.04242e-6 3.94146e-6 -1 -0.9877929 -0.1557735 0 -4.11919e-7 4.19786e-6 -1 -1.9083e-6 3.90533e-6 -1 -3.00053e-6 3.26224e-6 -1 -0.707113 -0.7071006 0 -3.99429e-6 5.51804e-6 -1 -0.8914726 0.4530746 0 -1.73547e-6 3.97452e-6 -1 -1.39182e-6 3.85591e-6 -1 -2.15391e-6 4.00465e-6 -1 -0.9877929 -0.1557735 0 -2.79124e-6 5.49207e-6 -1 -0.4530746 0.8914726 0 -2.35783e-6 5.09358e-6 -1 -1.53491e-6 3.86864e-6 -1 -0.8914726 0.4530746 0 -1.66424e-6 4.46494e-6 -1 0.1557595 0.9877951 0 -0.4530746 0.8914726 0 -1.32351e-6 4.16087e-6 -1 0.7071068 0.7071068 0 0.1557595 0.9877951 0 0.9877967 0.1557492 0 -2.59336e-6 5.26563e-6 -1 -1.48296e-6 3.58975e-6 -1 -2.01999e-6 4.49373e-6 -1 0.7071068 0.7071068 0 0.9877967 0.1557492 0 0.4530821 -0.8914688 -1.96799e-7 0.8914688 -0.4530821 0 0.8914688 -0.4530821 0 -0.1557735 -0.9877929 -2.18063e-7 0.4530821 -0.8914688 -1.96817e-7 -1.5957e-6 3.88868e-6 -1 -0.7071068 -0.7071068 -1.56099e-7 -0.1557735 -0.9877929 -2.18063e-7 -5.62171e-6 3.85019e-6 -1 -0.9877935 -0.1557694 0 -1.27907e-6 3.98924e-6 -1 -9.84029e-7 4.06498e-6 -1 -2.93558e-6 3.29978e-6 -1 -0.7071068 -0.7071068 -1.56099e-7 1.48135e-6 1.86314e-6 -1 -0.8914726 0.4530746 0 -8.59907e-7 3.78963e-6 -1 -2.48341e-6 4.30566e-6 -1 -1.43594e-6 4.14036e-6 -1 -0.9877935 -0.1557694 0 -2.76827e-6 5.44683e-6 -1 -0.4530771 0.8914714 3.93599e-7 -3.57283e-6 5.95545e-6 -1 -0.8914739 0.4530721 2.00039e-7 -1.61559e-6 4.77355e-6 -1 0.1557694 0.9877935 2.18063e-7 -0.4530721 0.8914739 1.968e-7 -1.01229e-6 4.47209e-6 -1 0.7071068 0.7071068 1.56099e-7 0.1557694 0.9877935 2.18063e-7 0.9877929 0.1557735 0 -2.20169e-6 4.97242e-6 -1 -1.35817e-6 3.58981e-6 -1 0.7071068 0.7071067 1.56099e-7 0.9877929 0.1557735 0 -2.44553e-6 4.16818e-6 -1 0.6331864 -0.7739993 -3.41733e-7 -2.0268e-6 4.55103e-6 -1 0.7740041 -0.6331806 -2.79559e-7 0.7740041 -0.6331806 -2.79559e-7 -2.34032e-6 4.38352e-6 -1 0.4709712 -0.8821486 -3.89483e-7 -2.12792e-6 4.50869e-6 -1 0.6331864 -0.7739993 -3.41506e-7 -1.5087e-6 4.96554e-6 -1 0.2907113 -0.9568108 -4.22447e-7 0.4709712 -0.8821486 -3.89483e-7 -1.96309e-6 4.595e-6 -1 0.0968815 -0.995296 -4.39439e-7 0.2907113 -0.9568108 -4.22447e-7 -9.80316e-7 5.5019e-6 -1 -0.09686839 -0.9952972 -4.3944e-7 0.0968815 -0.995296 -4.39439e-7 -2.0423e-6 3.5862e-6 -1 -0.2907443 -0.9568009 -8.44886e-7 -4.24176e-6 2.19985e-6 -1 -0.09688037 -0.9952961 -8.78878e-7 -1.09557e-6 4.3601e-6 -1 -0.4718073 -0.8817018 -3.89285e-7 -0.2907332 -0.9568042 -4.22444e-7 -1.88118e-6 3.63396e-6 -1 -0.6334813 -0.7737579 -3.41626e-7 -0.4718073 -0.8817018 -3.89285e-7 -1.70805e-5 -9.12772e-6 -1 -0.7737569 -0.6334827 -2.79693e-7 -2.66949e-5 -2.00055e-5 -1 -1.18589e-5 -4.45319e-6 -1 3.19479e-6 8.50765e-6 -1 -0.6334813 -0.7737579 -3.41626e-7 -3.0253e-6 3.52418e-6 -1 -0.8817018 -0.4718073 -2.0831e-7 -0.7737569 -0.6334827 -2.79693e-7 1.36692e-5 1.9031e-5 -1 -0.9568032 -0.2907366 1.65714e-7 -0.8816994 -0.4718117 0 -1.95461e-6 3.59923e-6 -1 -0.995296 -0.09688037 0 -0.9568054 -0.2907289 -1.28361e-7 -2.69349e-6 4.05171e-6 -1 -0.995296 0.09688156 0 1.57699e-7 5.88825e-6 -1 -0.9952961 -0.09688037 0 -2.79336e-6 3.98076e-6 -1 -0.9568108 0.2907112 1.28354e-7 -0.995296 0.09688156 0 -2.07637e-6 4.55907e-6 -1 -0.8821486 0.4709711 2.07941e-7 -0.9568108 0.2907113 1.28354e-7 -2.0578e-6 4.57639e-6 -1 -0.7740041 0.6331806 2.79559e-7 -0.8821486 0.4709712 2.07941e-7 -2.50494e-6 4.24081e-6 -1 -0.6331864 0.7739993 3.41733e-7 -2.19229e-6 4.4293e-6 -1 -0.7740041 0.6331806 2.79559e-7 -1.70686e-6 4.81292e-6 -1 -0.4709566 0.8821564 3.89486e-7 -0.6331864 0.7739993 3.41733e-7 -2.13582e-6 4.45238e-6 -1 -0.2907146 0.9568098 4.22447e-7 -0.4709566 0.8821564 3.89486e-7 -1.27263e-6 5.28792e-6 -1 -0.0968815 0.995296 4.39439e-7 -0.2907146 0.9568098 4.22447e-7 -1.81923e-6 4.67005e-6 -1 0.09685647 0.9952983 4.3944e-7 -1.87491e-6 4.63508e-6 -1 -0.0968815 0.995296 4.39439e-7 -1.07379e-6 4.19667e-6 -1 0.2907443 0.9568009 4.22443e-7 -1.35025e-5 -3.6373e-6 -1 0.09685647 0.9952983 4.3944e-7 -2.79165e-6 2.79243e-6 -1 0.4717979 0.8817068 5.70269e-7 0.2907366 0.9568032 7.16523e-7 -1.88091e-6 3.63422e-6 -1 0.6334885 0.773752 3.41624e-7 0.4718023 0.8817044 3.89286e-7 -1.28444e-5 -5.65965e-6 -1 0.7737521 0.6334885 2.79695e-7 -2.48557e-5 -1.82509e-5 -1 3.19342e-6 8.50632e-6 -1 0.6334885 0.773752 3.41624e-7 -6.25651e-6 1.7951e-6 -1 0.8817045 0.4718023 2.08308e-7 -5.54832e-6 2.35279e-6 -1 0.773752 0.6334885 2.79695e-7 1.60205e-5 1.97454e-5 -1 0.9568032 0.2907366 1.28365e-7 0.8817044 0.4718022 2.08308e-7 -3.13117e-6 3.4847e-6 -1 0.9952974 0.09686726 0 0.9568021 0.2907399 2.56733e-7 -2.53347e-6 4.03611e-6 -1 0.9952971 -0.09686958 0 0.9952974 0.09686607 0 -2.84565e-6 3.9967e-6 -1 0.9568098 -0.2907146 -1.28355e-7 -2.19784e-6 4.38284e-6 -1 0.9952971 -0.09686958 0 -2.04082e-6 4.54009e-6 -1 0.8821486 -0.4709712 -2.07941e-7 0.9568098 -0.2907146 -1.28355e-7 0.8821486 -0.4709712 -2.07941e-7 -1.85858e-6 3.6569e-6 -1 0.4530791 -0.8914703 -3.93598e-7 -1.39806e-6 4.08952e-6 -1 0.8914825 -0.4530552 0 0.89148 -0.45306 -2.00033e-7 -1.47728e-6 5.18134e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 1.90661e-7 6.08174e-6 -1 0.4530791 -0.8914703 -3.93582e-7 2.29373e-6 7.6066e-6 -1 -0.7071128 -0.7071008 -3.12196e-7 -0.1557664 -0.9877939 -4.36127e-7 -3.64729e-6 3.2487e-6 -1 -0.9877921 -0.1557782 0 -5.79413e-7 6.02539e-6 -1 -0.7071127 -0.7071008 -3.12196e-7 -2.33287e-6 4.56463e-6 -1 -0.8914777 0.4530648 2.00035e-7 -2.32369e-6 4.5723e-6 -1 -0.987792 -0.1557782 0 -2.32373e-6 4.57226e-6 -1 -0.4530695 0.8914753 3.93601e-7 -2.33291e-6 4.56459e-6 -1 -0.8914777 0.4530648 2.00035e-7 -5.79327e-7 6.02547e-6 -1 0.1557801 0.9877918 4.36126e-7 -3.64724e-6 3.24876e-6 -1 -0.4530695 0.8914753 3.93601e-7 1.29898e-6 7.67473e-6 -1 0.7070948 0.7071188 3.12204e-7 -5.06765e-7 6.09803e-6 -1 0.1557801 0.9877918 4.36126e-7 -2.22135e-6 3.4736e-6 -1 0.9877939 0.1557664 0 6.12148e-7 7.0713e-6 -1 -1.50452e-6 3.95596e-6 -1 0.7071008 0.7071128 0 0.9877939 0.1557664 0 0.4530599 -0.89148 -3.93603e-7 0.89148 -0.4530599 -2.00033e-7 0.89148 -0.4530599 -2.00033e-7 -0.1557683 -0.9877936 -4.36127e-7 0.4530599 -0.89148 -3.93587e-7 -0.7071068 -0.7071068 -3.12199e-7 -0.1557683 -0.9877936 -4.36127e-7 -4.5508e-6 3.10631e-6 -1 -0.9877936 -0.1557683 0 -0.7071068 -0.7071068 -3.12199e-7 -2.01611e-6 5.24839e-6 -1 -0.8914777 0.4530648 2.00035e-7 -0.9877936 -0.1557683 0 -2.55078e-6 5.019e-6 -1 -0.4530695 0.8914753 3.93601e-7 -2.0659e-6 5.19539e-6 -1 -0.8914777 0.4530648 2.00035e-7 -2.24152e-6 5.18478e-6 -1 0.1557664 0.9877939 4.36127e-7 -0.4530695 0.8914753 3.93601e-7 7.66567e-6 1.19161e-5 -1 0.7071068 0.7071068 3.12199e-7 0.1557664 0.9877939 4.36127e-7 0.9877939 0.1557664 0 0.7071068 0.7071068 3.12199e-7 0.9877939 0.1557664 0 -2.32372e-6 4.57228e-6 -1 0.4530647 -0.8914776 -3.93601e-7 -2.26466e-6 4.5299e-6 -1 0.8914801 -0.4530599 -2.00033e-7 -1.70452e-6 5.09004e-6 -1 0.8914801 -0.4530599 -2.00033e-7 -1.47151e-6 5.21797e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 -3.64725e-6 3.24875e-6 -1 0.4530647 -0.8914776 -3.93591e-7 5.3592e-6 1.06721e-5 -1 -0.7071068 -0.7071068 -3.12199e-7 -1.32403e-6 5.36545e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 -2.15782e-6 3.4836e-6 -1 -0.9877921 -0.1557782 0 2.89111e-5 2.95778e-5 -1 -0.7071068 -0.7071068 -3.12199e-7 -1.48104e-6 4.13178e-6 -1 -0.8914703 0.4530792 2.00042e-7 -0.987792 -0.1557782 0 -1.93475e-6 3.80673e-6 -1 -0.4530839 0.8914679 3.93597e-7 -1.59788e-6 3.98812e-6 -1 -0.8914703 0.4530792 2.00042e-7 -8.06965e-7 4.58197e-6 -1 0.1557782 0.9877921 4.36126e-7 -0.4530839 0.8914679 3.93597e-7 -4.26802e-7 4.8862e-6 -1 0.7071068 0.7071068 3.12199e-7 0.1557782 0.9877921 4.36126e-7 -2.62401e-6 4.17486e-6 -1 0.9877921 0.1557782 0 -1.47151e-6 5.21797e-6 -1 0.7071068 0.7071068 3.12199e-7 -2.29101e-6 4.50786e-6 -1 0.987792 0.1557782 0 -2.51978e-6 4.95788e-6 -1 0.4530791 -0.8914703 -3.93598e-7 -2.74544e-6 4.77436e-6 -1 0.8914751 -0.4530696 -2.00037e-7 0.8914751 -0.4530696 -2.00037e-7 -1.41296e-6 5.58892e-6 -1 -0.1557801 -0.9877918 -4.36126e-7 -2.16318e-6 5.3302e-6 -1 0.4530791 -0.8914703 -3.93582e-7 3.96747e-6 8.21794e-6 -1 -0.7071008 -0.7071128 -3.12202e-7 -0.1557801 -0.9877918 -4.36126e-7 -0.9877939 -0.1557664 0 -0.7071008 -0.7071128 -3.12202e-7 -0.8914777 0.4530648 2.00035e-7 -0.9877939 -0.1557664 0 -0.4530695 0.8914753 3.93601e-7 -0.8914777 0.4530648 2.00035e-7 0.1557664 0.9877939 4.36127e-7 -0.4530695 0.8914753 3.93601e-7 0.7071128 0.7071008 3.12196e-7 0.1557664 0.9877939 4.36127e-7 -5.61325e-6 2.93873e-6 -1 0.9877939 0.1557664 0 -1.95532e-6 5.05697e-6 -1 0.7071128 0.7071008 3.12196e-7 0.9877939 0.1557664 0 -2.52693e-6 4.64281e-6 -1 0.5555153 -0.8315063 0 -2.58199e-6 4.59919e-6 -1 0.8315122 -0.5555065 0 0.8315122 -0.5555065 0 -1.46771e-6 4.93466e-6 -1 0.1950772 -0.9807879 0 -2.8412e-6 4.28113e-6 -1 0.5555154 -0.8315063 0 -1.4469e-6 4.948e-6 -1 -0.1950845 -0.9807865 -4.33033e-7 0.1950699 -0.9807895 -4.33034e-7 0 6.10047e-6 -1 -0.5555047 -0.8315134 -3.67126e-7 -0.1950845 -0.9807865 -4.33033e-7 -3.25519e-6 2.99894e-6 -1 -0.8315087 -0.5555118 -2.45267e-7 -2.28992e-6 4.16923e-6 -1 -0.5555047 -0.8315134 -3.67126e-7 -3.80573e-6 3.61907e-6 -1 -0.9807873 -0.1950801 0 -1.93425e-6 4.7164e-6 -1 -0.8315086 -0.5555118 -2.45267e-7 -3.17653e-6 4.03534e-6 -1 -0.9807879 0.1950771 0 -0.9807873 -0.1950801 0 -2.55123e-6 4.57867e-6 -1 -0.8315087 0.5555118 2.45267e-7 -0.9807879 0.1950771 0 -2.74133e-6 4.96379e-6 -1 -0.5555101 0.8315098 3.67125e-7 -2.12771e-6 5.11332e-6 -1 -0.8315086 0.5555118 2.45267e-7 -1.58479e-6 5.52326e-6 -1 -0.1950771 0.9807879 4.33033e-7 -0.55551 0.8315099 3.67125e-7 -1.28729e-6 5.75083e-6 -1 0.1950815 0.980787 4.33033e-7 -0.1950771 0.9807879 4.33033e-7 1.86422e-6 8.81378e-6 -1 0.5554995 0.831517 0 0.1950889 0.9807856 0 -5.62717e-6 1.41449e-6 -1 0.8315204 0.5554941 0 -2.01123e-6 4.80064e-6 -1 -2.17341e-6 4.74977e-6 -1 0.5554995 0.831517 0 -5.37464e-6 3.30686e-6 -1 0.9807832 0.1951006 0 -2.81808e-6 4.30482e-6 -1 0.8315204 0.5554941 0 -3.4977e-6 4.09925e-6 -1 0.9807876 -0.1950786 0 0.9807832 0.1951006 0 0.9807876 -0.1950786 0 -1.22571e-6 4.12748e-6 -1 0.4530734 -0.8914732 -1.968e-7 -1.82353e-6 3.5428e-6 -1 0.8914725 -0.4530746 0 0.8914725 -0.4530746 0 -1.64026e-6 4.61719e-6 -1 -0.1557658 -0.987794 -2.18063e-7 -1.07955e-6 4.33761e-6 -1 0.4530734 -0.8914732 -1.96816e-7 -1.86762e-6 4.71364e-6 -1 -0.7071021 -0.7071115 -1.561e-7 -0.1557658 -0.987794 -2.18063e-7 -1.54333e-6 3.70382e-6 -1 -0.9877939 -0.155767 0 -1.73282e-6 4.66554e-6 -1 -0.7071036 -0.7071099 -2.3415e-7 -8.07306e-6 6.7191e-6 -1 -0.8914688 0.4530821 0 -1.91315e-6 4.95708e-6 -1 -0.9877938 -0.1557675 0 -2.69043e-6 5.29366e-6 -1 -0.4530771 0.8914713 1.96799e-7 -0.8914688 0.4530821 0 -7.97249e-7 4.95679e-6 -1 0.1557644 0.9877943 2.18063e-7 -0.4530771 0.8914713 1.96799e-7 -5.44283e-7 4.94012e-6 -1 0.7071068 0.7071068 3.12199e-7 0.1557583 0.9877953 4.36127e-7 -7.81158e-7 4.61345e-6 -1 0.9877939 0.155767 0 -1.96598e-6 3.64305e-6 -1 -8.53304e-7 4.93653e-6 -1 0.7071099 0.7071036 1.56099e-7 -1.88338e-6 3.50293e-6 -1 0.9877939 0.155767 0 -2.64815e-6 5.21053e-6 -1 0.4530734 -0.8914732 0 -5.28088e-6 6.17197e-6 -1 0.8914713 -0.4530771 0 0.8914713 -0.4530771 0 -1.59566e-6 4.89996e-6 -1 -0.1557649 -0.9877942 0 0.4530734 -0.8914732 0 -7.50886e-7 4.73352e-6 -1 -0.7071052 -0.7071083 0 -0.1557649 -0.9877942 0 -5.0418e-6 3.9416e-6 -1 -0.9877943 -0.1557644 0 -3.2039e-6 5.03135e-6 -1 -0.7071052 -0.7071083 0 -4.01436e-6 4.65628e-6 -1 -0.8914694 0.4530808 0 -0.9877943 -0.1557644 0 -2.86708e-6 5.64124e-6 -1 -0.4530771 0.8914713 0 -3.37429e-6 5.31074e-6 -1 -0.8914694 0.4530808 0 -2.85264e-7 8.20377e-6 -1 0.1557628 0.9877945 0 -0.4530771 0.8914713 0 6.9686e-6 1.35499e-5 -1 0.7071052 0.7071083 0 -2.76307e-6 5.17844e-6 -1 0.1557628 0.9877945 0 -1.14297e-6 3.76696e-6 -1 0.9877938 0.1557675 0 -3.80012e-6 4.91059e-6 -1 -2.08197e-6 5.65184e-6 -1 -1.7781e-6 5.84613e-6 -1 0.7071052 0.7071083 0 -1.14914e-6 3.76904e-6 -1 -7.49172e-6 7.00344e-6 -1 0.9877938 0.1557675 0 -1.85997e-6 3.65963e-6 -1 0.4530808 -0.8914694 -1.96799e-7 -1.93004e-6 3.59693e-6 -1 0.8914701 -0.4530796 0 0.8914701 -0.4530796 0 -9.07981e-7 4.25437e-6 -1 -0.155775 -0.9877925 -2.18063e-7 -1.53316e-6 4.09094e-6 -1 0.4530808 -0.8914694 -1.96816e-7 -2.88035e-5 -7.96307e-6 -1 -0.7071037 -0.7071099 -1.561e-7 -0.155775 -0.9877926 -2.18063e-7 -2.16536e-6 3.60576e-6 -1 -0.9877936 -0.1557684 0 1.0694e-5 1.19336e-5 -1 -0.7071037 -0.7071099 -1.561e-7 -2.07832e-6 3.67228e-6 -1 -0.8914726 0.4530747 0 -0.9877937 -0.1557684 0 -1.57589e-6 4.8165e-6 -1 -0.4530734 0.8914732 1.968e-7 -2.57909e-6 3.92681e-6 -1 4.56826e-6 1.10742e-5 -1 -0.8914726 0.4530747 0 -1.63088e-6 4.67653e-6 -1 0.1557689 0.9877936 2.18063e-7 -2.90296e-6 3.48943e-6 -1 -0.4530733 0.8914732 1.968e-7 -1.53501e-6 3.94936e-6 -1 0.7071037 0.7071099 1.561e-7 -3.26742e-6 3.04e-6 -1 0.1557689 0.9877936 2.18063e-7 2.25951e-5 1.85626e-5 -1 0.9877935 0.1557684 0 -1.01039e-5 1.31711e-6 -1 -1.47257e-6 3.98394e-6 -1 0.7071037 0.7071099 1.561e-7 0.9877936 0.1557684 0 -2.25284e-6 6.14838e-6 -1 0.4530796 -0.89147 -1.96799e-7 0.8914701 -0.4530796 0 2.66048e-5 3.20613e-5 -1 0.8914701 -0.4530796 0 -1.61102e-6 4.80219e-6 -1 -0.1557735 -0.9877929 -2.18063e-7 -2.95584e-6 5.22846e-6 -1 0.4530796 -0.89147 -1.96817e-7 -8.50709e-7 4.63369e-6 -1 -0.7071052 -0.7071083 -1.561e-7 -0.1557735 -0.9877929 -2.18063e-7 -4.70549e-7 4.66247e-6 -1 -0.9877936 -0.1557684 0 -1.82715e-6 3.79448e-6 -1 -1.42285e-6 4.71761e-6 -1 -0.7071052 -0.7071083 -1.561e-7 -1.89818e-6 3.58073e-6 -1 -0.8914726 0.4530746 0 -0.9877936 -0.1557684 0 -1.45168e-6 4.57208e-6 -1 -0.4530746 0.8914726 1.968e-7 -1.15419e-6 4.41225e-6 -1 -0.8914726 0.4530746 0 -1.63329e-6 4.66119e-6 -1 0.1557724 0.9877929 2.18063e-7 -0.4530746 0.8914726 1.968e-7 -1.83594e-6 4.74532e-6 -1 0.7071068 0.7071068 1.56099e-7 0.1557724 0.9877929 2.18063e-7 0.9877927 0.1557745 0 -2.78482e-6 5.07477e-6 -1 0.7071068 0.7071067 1.56099e-7 0.9877927 0.1557745 0 -1.41449e-6 3.96962e-6 -1 0.5867137 -0.8097945 -1.78769e-7 -1.43287e-6 3.96135e-6 -1 0.8097912 -0.5867182 0 0.8097879 -0.5867227 -1.29524e-7 -2.36516e-6 3.43909e-6 -1 0.306687 -0.9518105 0 0.5867199 -0.80979 0 -1.19499e-6 4.22689e-6 -1 0 -1 0 0.306687 -0.9518105 0 -1.12369e-6 4.28221e-6 -1 -0.3074648 -0.9515595 0 0 -1 0 -5.09275e-5 -3.79028e-5 -1 -0.5868241 -0.8097144 0 -0.3074648 -0.9515595 0 0 5.81108e-6 -1 -0.8097169 -0.5868207 0 3.20073e-6 9.54671e-6 -1 -0.5868241 -0.8097145 0 1.3065e-6 5.43686e-6 -1 -0.9515566 -0.3074734 0 -1.80031e-6 3.77296e-6 -1 -0.8097202 -0.5868161 -1.29544e-7 -2.04275e-6 3.58495e-6 -1 -1 0 0 -0.9515558 -0.3074762 0 -2.48797e-6 3.31568e-6 -1 -0.9518141 0.3066756 0 -1 0 0 -1.49498e-6 4.00637e-6 -1 -0.8097867 0.5867244 0 -0.9518141 0.3066756 0 -1.46133e-6 4.03417e-6 -1 -0.5867244 0.8097867 0 -0.8097867 0.5867244 0 -1.33868e-6 4.15481e-6 -1 -0.3066756 0.9518141 0 -0.5867244 0.8097867 0 -1.19498e-6 4.15495e-6 -1 0 1 0 -1.46519e-6 4.01056e-6 -1 -0.3066756 0.9518142 0 -2.7207e-6 3.21966e-6 -1 0.3074648 0.9515595 0 0 1 0 -1.44318e-6 4.07779e-6 -1 0.5868223 0.8097157 1.78751e-7 0.3074561 0.9515622 2.10065e-7 -2.42509e-5 -1.17106e-5 -1 0.8097157 0.5868223 0 -2.93284e-5 -1.55102e-5 -1 0.5868286 0.8097112 0 -6.36538e-6 1.70424e-6 -1 0.9515604 0.3074619 0 0.8097157 0.5868223 0 -3.98549e-6 3.58502e-6 -1 1 -9.55996e-6 0 0.9515604 0.3074619 0 1.08675e-5 1.66109e-5 -1 0.9518141 -0.3066756 0 1 -9.55996e-6 0 -1.65514e-6 3.87994e-6 -1 0.9518141 -0.3066756 0 -1.31098e-6 4.37464e-6 -1 -0.6339912 -0.7733404 0 -1.20838e-6 4.31085e-6 -1 -0.7071071 -0.7071064 0 -1.16694e-6 4.29523e-6 -1 -0.4707525 -0.8822653 0 -0.6339911 -0.7733403 0 -1.79115e-6 4.59786e-6 -1 -0.2909872 -0.9567269 0 -0.4707525 -0.8822653 0 -0.09853023 -0.9951341 0 -0.2909872 -0.9567269 0 -1.38186e-6 -1 0 -6.90932e-7 -1 -2.20758e-7 -0.09853321 -0.9951338 -2.19684e-7 0.09853678 -0.9951333 0 0.2909883 -0.9567266 0 0.09853678 -0.9951333 0 0.4707527 -0.8822653 0 0.2909883 -0.9567266 0 0.6339882 -0.7733427 0 0.4707527 -0.8822653 0 0.7071068 -0.7071068 0 0.6339882 -0.7733427 0 0.780174 -0.6255626 -1.38098e-7 0.7071067 -0.7071069 -1.56099e-7 -2.38769e-6 4.46391e-6 -1 0.8974835 -0.441048 0 0.7801743 -0.6255621 0 -2.59016e-6 4.36732e-6 -1 0.9718872 -0.2354468 0 0.8974835 -0.441048 0 0 6.28693e-6 -1 0.9718872 -0.2354466 0 -1.06256e-5 -2.03e-6 -1 0.9718872 -0.2354468 0 0.8974835 -0.441048 0 -1.69943e-6 4.48827e-6 -1 0.9718872 -0.2354468 0 0.7801731 -0.6255637 -1.38098e-7 0.8974835 -0.441048 0 0.7071068 -0.7071068 -1.56099e-7 -2.78816e-7 6.06716e-6 -1 -1.26998e-6 4.14831e-6 -1 -1.80248e-6 4.56784e-6 -1 -1.43592e-6 4.28358e-6 -1 -1.38475e-5 1.35827e-5 -1 -3.12515e-6 5.13114e-6 -1 9.35985e-7 4.58325e-6 -1 -2.20702e-6 3.8265e-6 -1 -1.4359e-6 4.13653e-6 -1 -7.03672e-7 4.55111e-6 -1 -2.55118e-5 -1.16824e-5 -1 0.7801731 -0.6255638 -1.38098e-7 -2.10061e-6 4.21626e-6 -1 0.6534901 -0.7569351 0 -2.03101e-6 4.25509e-6 -1 -7.73417e-6 -1.44807e-6 -1 1.40725e-5 2.39271e-5 -1 -1.75546e-6 3.58981e-6 -1 -1.42397e-6 4.14986e-6 -1 0.7071069 -0.7071068 0 0.5363579 -0.8439906 -3.72635e-7 -6.84169e-7 5.63271e-6 -1 0.6534888 -0.7569363 -3.34199e-7 0.4084212 -0.9127935 -1.20904e-6 0.5363546 -0.8439928 -1.11791e-6 0.2712079 -0.9625208 -4.24968e-7 0.4084251 -0.9127918 -4.03012e-7 0.2994236 -0.9541203 -4.21259e-7 0.2712079 -0.9625208 -4.24968e-7 0.4876407 -0.8730443 -3.85463e-7 0.2994236 -0.9541203 -4.21259e-7 0.6553421 -0.7553323 -3.33491e-7 0.4876407 -0.8730443 -3.85463e-7 0.7955274 -0.6059176 -2.67522e-7 0.6553421 -0.7553323 -3.33491e-7 0.9023092 -0.4310894 -1.90333e-7 0.7955274 -0.6059176 -2.67522e-7 -2.49418e-6 4.03574e-6 -1 0.9712221 -0.2381755 0 0.9023092 -0.4310895 -1.90333e-7 -2.67969e-6 4.04639e-6 -1 0.9993773 -0.03528606 0 -1.62898e-6 4.90094e-6 -1 0.9712219 -0.2381763 -2.10317e-7 -3.57247e-6 3.60527e-6 -1 0.9856038 0.1690721 1.49296e-7 -1.15303e-6 5.57304e-6 -1 0.9993773 -0.03528606 0 2.98003e-6 8.54556e-6 -1 0.9304857 0.3663279 1.6174e-7 -5.65635e-6 1.52139e-6 -1 0.9856038 0.1690715 0 -1.78393e-6 3.80179e-6 -1 0.8363332 0.5482215 2.42049e-7 -1.67575e-6 3.88977e-6 -1 0.9304859 0.366328 1.6174e-7 0.7071084 0.7071052 3.12198e-7 0.8363332 0.5482215 2.42049e-7 0.5482168 0.8363362 3.69256e-7 0.7071085 0.7071052 3.12198e-7 0.3663308 0.9304847 4.10824e-7 0.5482168 0.8363362 3.69256e-7 0.169071 0.9856039 4.3516e-7 0.3663308 0.9304847 4.10824e-7 -0.03528934 0.9993772 4.41241e-7 0.169071 0.9856038 4.3516e-7 -0.2381778 0.9712216 4.2881e-7 -0.03528934 0.9993772 4.41241e-7 -0.4310828 0.9023124 3.98385e-7 -0.2381778 0.9712216 4.2881e-7 -0.6059197 0.7955259 3.51237e-7 -0.4310828 0.9023124 3.98385e-7 -0.7553386 0.6553348 0 -0.6059176 0.7955274 0 -0.8730401 0.4876484 0 -0.7553386 0.6553347 0 -0.9541219 0.2994185 0 -0.8730401 0.4876483 0 -0.962521 0.2712072 0 -0.9541219 0.2994185 0 -0.9127935 0.4084214 0 -0.962521 0.2712072 0 -0.8439939 0.5363529 0 -0.9127935 0.4084214 0 -0.7569309 0.653495 0 -0.8439939 0.5363529 0 -0.7071071 0.7071065 0 -6.07247e-6 5.99898e-6 -1 -3.20971e-7 4.40393e-6 -1 -1.45087e-6 3.95815e-6 -1 -1.43591e-6 3.96701e-6 -1 -2.22845e-6 3.35019e-6 -1 -4.70419e-6 1.22261e-6 -1 -2.76924e-5 2.42079e-5 -1 -4.32618e-7 3.41374e-6 -1 -1.73733e-6 4.45489e-6 -1 -1.43592e-6 4.21788e-6 -1 -0.7569309 0.653495 0 -0.6255626 0.780174 0 -7.02299e-7 5.42e-6 -1 -1.73856e-6 3.58977e-6 -1 -1.76811e-6 3.51627e-6 -1 -0.7071071 0.7071065 0 -0.441048 0.8974835 1.98127e-7 -0.6255638 0.7801732 1.72229e-7 -1.94084e-6 5.11696e-6 -1 -0.2354466 0.9718872 2.14552e-7 1.73621e-6 7.38087e-6 -1 -0.441048 0.8974835 1.98127e-7 -1.83267e-6 4.67046e-6 -1 -0.2354466 0.9718872 2.14552e-7 -2.29553e-6 4.67145e-6 -1 -0.2354466 0.9718872 2.14552e-7 -2.24282e-6 4.56388e-6 -1 -0.4410487 0.8974832 1.98127e-7 -0.2354466 0.9718872 2.14552e-7 -0.6255646 0.7801724 3.44459e-7 -0.4410502 0.8974825 3.96253e-7 -0.7071067 0.7071068 1.56099e-7 -0.6255635 0.7801733 1.72229e-7 -0.7733414 0.6339897 1.39958e-7 -0.7071067 0.7071069 1.56099e-7 -0.882266 0.4707512 0 -0.7733414 0.6339897 1.39958e-7 -1.96183e-6 4.58363e-6 -1 -0.9567283 0.2909827 0 -0.882266 0.4707512 0 -4.84334e-6 3.52424e-6 -1 -0.9951338 0.0985338 0 -0.9567283 0.2909827 0 -3.74879e-6 3.97286e-6 -1 -1 6.90932e-7 0 -1 6.90933e-7 0 -0.9951338 0.09853351 0 -3.36615e-6 4.23369e-6 -1 -0.9951338 -0.09853351 0 -6.00937e-6 2.15921e-6 -1 -0.9567263 -0.2909892 0 -0.9951338 -0.09853351 0 -6.5178e-6 1.71045e-6 -1 -0.8822659 -0.4707514 0 -0.9567263 -0.2909892 0 -1.47223e-5 -6.19259e-6 -1 -0.7733427 -0.6339882 -1.39958e-7 -0.8822659 -0.4707514 0 -0.7071061 -0.7071076 -2.36116e-7 -0.7071065 -0.7071071 -1.561e-7 -0.7733427 -0.6339882 -1.39958e-7 0.7071069 -0.7071066 -2.34149e-7 -0.7071068 -0.7071068 -2.34149e-7 0.707107 -0.7071066 -2.34149e-7 -0.7071068 0.7071068 0 -0.7071063 -0.7071073 0 -0.7071068 -0.7071068 -1.56099e-7 -0.7071069 0.7071067 1.56099e-7 0.7071068 0.7071068 3.13268e-7 0.499624 0.8662425 0 0.499624 0.8662425 0 0.707103 0.7071105 0 0.8662403 0.4996276 2.20594e-7 1 -1.14873e-5 0 0.8662431 0.4996226 0 0.8662395 -0.4996289 0 1 -1.14873e-5 0 0.7071076 -0.7071061 0 0.8662395 -0.4996289 0 0.4996376 -0.8662346 0 0.7071076 -0.7071061 0 0 -1 0 0.4996376 -0.8662346 0 -0.4996326 -0.8662374 0 0 -1 0 -0.707103 -0.7071105 0 -0.7071067 -0.7071068 3.12199e-7 -0.4996277 -0.8662404 2.20594e-7 -0.8662503 -0.4996103 0 -1 0 0 -0.8662503 -0.4996103 0 -0.8662503 0.4996103 0 -1 0 0 -0.7071061 0.7071076 0 -0.8662503 0.4996103 0 -0.499624 0.8662425 0 -0.7071061 0.7071076 0 -1.14873e-5 1 0 -0.499624 0.8662425 0 -1.14873e-5 1 0 -0.8662425 -0.499624 0 -0.7071068 -0.7071068 0 -1 -1.14873e-5 0 -0.8662424 -0.499624 0 -0.8662374 0.4996325 0 -1 -1.14873e-5 0 -0.707107 0.7071066 0 -0.8662374 0.4996325 0 -0.4996283 0.86624 0 -0.707107 0.7071066 0 -5.74359e-6 1 0 -0.4996283 0.86624 0 -1.78175e-6 4.1247e-6 -1 0.4996283 0.86624 1.91229e-7 -1.14872e-5 1 2.20758e-7 -1.40469e-6 3.86362e-6 -1 0.7071068 0.7071068 1.58318e-7 -1.17545e-5 1.01084e-5 -1 0.7071068 0.7071068 1.56099e-7 0.4996283 0.86624 1.91229e-7 -1.68106e-6 4.02334e-6 -1 0.86624 0.4996283 0 -9.60989e-7 3.60646e-6 -1 -2.65534e-6 4.30775e-6 -1 -2.36811e-6 4.30771e-6 -1 1 -5.74359e-6 0 0.866236 0.4996351 3.30895e-7 5.08428e-5 -2.76609e-5 -1 0.8662384 -0.4996307 0 -1.81543e-6 4.11145e-6 -1 1 -5.74353e-6 0 0.7071071 -0.7071065 0 -1.87207e-6 3.96816e-6 -1 0.86624 -0.4996283 0 0.4996189 -0.8662453 0 0.7071071 -0.7071065 0 0 -1 0 0.4996189 -0.8662453 0 -0.499624 -0.8662425 0 0 -1 0 -0.7071068 -0.7071068 0 -0.4996276 -0.8662403 -1.61865e-7 0.7071049 0.7071086 3.13267e-7 0.4996258 0.8662415 1.9123e-7 0.4996258 0.8662414 1.9123e-7 0.707103 0.7071105 1.561e-7 0.8662425 0.499624 1.39658e-7 1 0 0 0.8662428 0.4996233 0 0.86624 -0.4996283 0 1 0 0 0.7071068 -0.7071068 -1.56099e-7 0.86624 -0.4996283 0 0.4996283 -0.86624 -1.91229e-7 0.7071068 -0.7071068 -1.56099e-7 0 -1 -2.20758e-7 0.4996283 -0.86624 -1.91229e-7 -0.499624 -0.8662425 -3.8246e-7 -5.74366e-6 -1 -4.41516e-7 -0.7071049 -0.7071087 -1.5495e-7 -0.7071068 -0.7071068 0 -0.4996189 -0.8662453 -1.61871e-7 -0.8662428 -0.4996233 0 -1 0 0 -0.8662428 -0.4996233 0 -0.86624 0.4996283 0 -1 0 0 -0.7071069 0.7071067 1.56099e-7 -0.86624 0.4996283 0 -0.4996283 0.86624 1.91229e-7 -0.7071069 0.7071067 1.56099e-7 -5.74366e-6 1 2.20758e-7 -0.4996283 0.86624 1.91229e-7 -5.74366e-6 1 2.20758e-7 -0.8662414 -0.4996258 0 -0.7071068 -0.7071068 -1.5495e-7 -1 0 0 -0.8662415 -0.4996258 0 -0.8662388 0.49963 0 -1 0 0 -0.7071074 0.7071059 1.53989e-7 -0.7071075 0.707106 1.56099e-7 -0.8662388 0.49963 0 -0.4996239 0.8662424 1.9123e-7 0 1 2.20758e-7 -0.4996239 0.8662424 1.9123e-7 0.4996214 0.8662438 1.9123e-7 0 1 2.20758e-7 0.7071049 0.7071086 0 0.7071068 0.7071068 1.56099e-7 0.4996214 0.8662438 1.9123e-7 0.8662439 0.4996214 0 1 0 0 0.8662425 0.499624 0 0.8662425 -0.499624 0 1 0 0 0.7071074 -0.7071061 -1.53988e-7 0.7071068 -0.7071068 0 0.8662425 -0.499624 0 0.49963 -0.8662388 -1.91229e-7 -5.74366e-6 -1 -2.20758e-7 0.49963 -0.8662388 -1.91229e-7 -0.499624 -0.8662425 -3.8246e-7 -1.14873e-5 -1 -4.41516e-7 -0.7071086 -0.7071049 0 -0.4996189 -0.8662453 -1.61871e-7 -0.7071067 0.7071069 0 -0.7071074 -0.7071063 -1.56099e-7 -0.7071068 -0.7071068 0 0.7071063 0.7071073 1.561e-7 -0.707107 0.7071067 1.52177e-7 0.707107 -0.7071067 -1.56099e-7 0.7071063 0.7071073 1.561e-7 0.7071069 -0.7071067 -1.56099e-7 2.01897e-6 -4.51415e-6 1 3.44223e-6 -6.77291e-6 1 3.46353e-6 -6.79921e-6 1 1.96767e-6 -4.42632e-6 1 1.29914e-6 -3.0884e-6 1 7.97365e-7 -4.95599e-6 1 1.12938e-6 -4.55854e-6 1 1.78744e-6 -3.90048e-6 1 1.64772e-6 -3.91709e-6 1 1.43587e-6 -3.78784e-6 1 1.884e-6 -3.7069e-6 1 1.50195e-6 -4.2514e-6 1 2.40398e-6 -2.96581e-6 1 1.884e-6 -3.7069e-6 1 7.73926e-7 -4.61463e-6 1 8.69133e-7 -4.50066e-6 1 2.59371e-6 -1.79381e-6 1 2.00542e-6 -3.38314e-6 1 1.01491e-6 -1.35883e-5 1 -1.77565e-6 -1.17352e-5 1 6.2984e-7 -5.95562e-6 1 1.53096e-6 -2.44557e-6 1 1.81864e-6 -4.79976e-6 1 1.65432e-6 -4.28281e-6 1 1.65826e-6 -4.30772e-6 1 4.66579e-6 -7.60333e-6 1 5.52743e-6 -1.0876e-5 1 2.10728e-6 -4.8206e-6 1 9.40785e-7 -4.03695e-6 1 5.36994e-7 -3.07309e-6 1 1.93813e-6 -4.64321e-6 1 8.6912e-7 -4.50068e-6 1 7.73939e-7 -4.61461e-6 1 1.48862e-6 -3.89993e-6 1 5.42092e-7 -3.03856e-6 1 1.43592e-6 -3.88452e-6 1 2.65979e-6 -4.61158e-6 1 1.7391e-6 -3.42173e-6 1 1.24767e-6 -4.12212e-6 1 1.24762e-6 -4.12217e-6 1 1.73905e-6 -3.42177e-6 1 7.73973e-7 -4.61459e-6 1 8.692e-7 -4.50059e-6 1 2.1661e-6 -2.2214e-6 1 1.6968e-6 -3.69175e-6 1 1.30077e-6 -1.17766e-5 1 2.41727e-6 -1.58011e-6 1 1.69787e-6 -3.57048e-6 1 1.23354e-6 -5.94561e-6 1 2.5123e-6 -6.46355e-6 1 1.78576e-6 -4.35866e-6 1 1.49556e-6 -2.87183e-6 1 1.07646e-6 -5.50479e-6 1 4.59089e-6 1.91017e-5 1 1.82808e-6 -3.44029e-6 1 2.33341e-6 -1.7254e-6 1 3.31133e-6 -6.51539e-6 1 1.61431e-6 -4.06186e-6 1 1.75188e-6 -4.6302e-6 1 2.41647e-6 -6.38673e-6 1 1.57242e-6 -2.8718e-6 1 1.94241e-6 -4.47521e-6 1 3.32093e-6 -6.52718e-6 1 1.91668e-6 -4.43439e-6 1 1.99882e-6 -4.58247e-6 1 1.57996e-6 -3.71231e-6 1 1.43595e-6 -3.63199e-6 1 2.17106e-6 -2.21644e-6 1 1.89941e-7 -1.88203e-5 1 1.53801e-6 -3.73034e-6 1 4.40264e-7 -7.89337e-6 1 -7.54835e-6 1.14208e-5 1 1.67853e-6 -4.02477e-6 1 2.05877e-6 -4.5675e-6 1 1.18476e-6 -2.34765e-6 1 1.69591e-6 -4.30777e-6 1 -1.33317e-6 -1.06644e-6 1 2.61281e-6 -5.34855e-6 1 2.25495e-6 -5.12232e-6 1 1.76587e-6 -4.45824e-6 1 1.93456e-6 -4.64669e-6 1 3.43554e-7 -2.82489e-6 1 1.43593e-6 -3.28428e-6 1 -2.95018e-7 -2.37404e-6 1 1.9127e-6 -3.49336e-6 1 8.28383e-7 -5.72781e-6 1 2.42878e-7 -6.26314e-6 1 2.29994e-6 -2.95317e-6 1 1.71229e-6 -3.65234e-6 1 7.73039e-7 -4.62268e-6 1 1.27752e-6 -4.42294e-6 1 1.67423e-6 -3.79127e-6 1 2.86273e-6 -2.26224e-6 1 3.24413e-6 -1.65715e-6 1 9.02824e-7 -4.65987e-6 1 -7.25538e-7 -6.42161e-6 1 -1.07137e-5 -1.78312e-5 1 -1.70878e-5 -2.3463e-5 1 -2.18437e-5 -2.84486e-5 1 3.48727e-5 3.63366e-5 1 -3.56175e-7 -8.39966e-6 1 1.64195e-6 -4.90397e-6 1 2.67248e-6 -3.69024e-6 1 1.95113e-6 -4.47214e-6 1 1.53768e-6 -5.06087e-6 1 1.80334e-6 -4.61519e-6 1 2.18779e-6 -4.09798e-6 1 8.73531e-7 -5.78299e-6 1 2.51584e-6 -3.98676e-6 1 -3.12375e-6 -1.21343e-5 1 6.5436e-7 -5.72306e-6 1 2.6195e-6 -3.92794e-6 1 1.95884e-6 -4.73811e-6 1 2.34553e-6 -4.31907e-6 1 6.23838e-6 -1.23657e-6 1 7.51173e-6 7.83616e-7 1 5.41286e-6 -2.24646e-6 1 8.64428e-6 1.24966e-6 1 -1.60929e-5 -2.44018e-5 1 3.31942e-5 2.68186e-5 1 2.84488e-5 2.1844e-5 1 6.93587e-6 1.32191e-6 1 -1.53696e-7 -6.69469e-6 1 1.70626e-6 -4.69226e-6 1 9.88303e-7 -5.41916e-6 1 3.28712e-6 -2.62472e-6 1 2.21818e-6 -4.28423e-6 1 1.54326e-6 -5.07931e-6 1 2.24639e-6 -4.20757e-6 1 1.99078e-6 -2.70127e-6 1 1.85857e-6 -3.6569e-6 1 1.53128e-6 -3.96436e-6 1 1.73804e-7 -6.09082e-6 1 4.4431e-6 1.92775e-7 1 5.06619e-7 -6.48651e-6 1 2.59463e-6 -4.17952e-6 1 -1.79357e-6 -8.56772e-6 1 2.35893e-6 -4.64152e-6 1 2.39632e-6 -4.59681e-6 1 3.38768e-6 -3.41119e-6 1 2.35889e-6 -4.64156e-6 1 2.39361e-6 -4.21119e-6 1 5.4308e-7 -6.25579e-6 1 7.45136e-7 -4.97441e-6 1 9.49978e-7 -5.42562e-6 1 3.87581e-7 -7.24185e-6 1 6.06563e-7 -5.8165e-6 1 1.97009e-6 -4.89007e-6 1 2.3484e-6 -4.6208e-6 1 2.3791e-6 -4.58812e-6 1 2.48204e-6 -4.19733e-6 1 2.18046e-6 -4.756e-6 1 3.02968e-6 -3.34581e-6 1 2.48613e-6 -2.95296e-6 1 1.87325e-6 -3.68593e-6 1 1.87327e-6 -3.68591e-6 1 -1.03179e-5 -1.69227e-5 1 7.9764e-7 -4.64146e-6 1 7.26664e-7 -5.09115e-6 1 1.20683e-6 -4.26197e-6 1 1.76393e-6 -3.47063e-6 1 2.27295e-6 -2.84473e-6 1 5.40646e-7 -6.03297e-6 1 1.328e-6 -3.74976e-6 1 2.76058e-6 -1.48975e-6 1 1.34726e-5 7.83929e-6 1 2.59464e-6 -4.17952e-6 1 -1.91082e-7 -6.96524e-6 1 1.4947e-6 -4.13865e-6 1 2.23178e-6 -4.51331e-6 1 2.38234e-6 -4.68745e-6 1 1.94766e-6 -5.04095e-6 1 2.44501e-6 -4.20311e-6 1 3.53708e-6 -2.83847e-6 1 1.34543e-6 -5.03014e-6 1 4.76526e-7 -6.67732e-6 1 -9.76911e-6 -1.88763e-5 1 3.10579e-6 -4.37428e-6 1 -3.71082e-6 -9.93376e-6 1 3.05756e-6 -4.57218e-6 1 3.04699e-6 -4.49583e-6 1 4.14066e-6 -3.06611e-6 1 7.55848e-6 4.5057e-7 1 0 -6.88231e-6 1 1.03092e-6 -5.85307e-6 1 1.04826e-6 -5.7978e-6 1 1.77276e-6 -5.75442e-6 1 2.14645e-6 -4.79711e-6 1 2.00675e-6 -5.20018e-6 1 1.63256e-6 -5.88555e-6 1 2.92524e-6 -4.25369e-6 1 2.21756e-6 -4.33082e-6 1 1.78129e-6 -5.24769e-6 1 2.8658e-6 -3.3198e-6 1 3.87127e-6 -2.0125e-6 1 1.0329e-6 -5.33772e-6 1 1.33224e-6 -5.09082e-6 1 1.2119e-5 1.20392e-5 1 2.66718e-6 -4.08077e-6 1 1.70787e-6 -3.69769e-6 1 2.18947e-6 -6.34482e-6 1 2.67297e-6 -5.25937e-6 1 3.28989e-6 -4.656e-6 1 6.34597e-6 -2.15704e-6 1 1.08467e-5 4.26533e-6 1 2.88023e-6 -4.99555e-6 1 1.23536e-6 -2.17854e-6 1 2.82541e-6 -5.87293e-6 1 3.87986e-6 -3.42882e-6 1 3.37628e-6 -4.21643e-6 1 5.11071e-7 -1.00558e-6 1 1.22165e-6 -2.89498e-6 1 1.97459e-6 -4.37147e-6 1 1.74072e-6 -4.37275e-6 1 1.76593e-6 -4.45817e-6 1 1.46362e-6 -2.92387e-6 1 2.22744e-6 -5.89987e-6 1 1.89336e-6 -6.46331e-6 1 1.83736e-6 -4.42185e-6 1 1.39133e-6 -2.73761e-6 1 1.56842e-6 -2.91043e-6 1 1.56277e-6 -2.82471e-6 1 2.74166e-6 -2.63896e-6 1 1.54517e-6 -4.33728e-6 1 8.86972e-7 -4.90348e-6 1 1.90053e-6 -3.73948e-6 1 2.42284e-6 -2.9554e-6 1 1.43377e-6 -4.21673e-6 1 1.25557e-6 -2.95977e-6 1 1.76681e-6 -3.98507e-6 1 1.96028e-6 -4.62099e-6 1 9.88361e-7 -3.74485e-6 1 1.6975e-6 -3.88458e-6 1 1.74316e-6 -3.96758e-6 1 1.83275e-6 -4.41949e-6 1 1.85997e-6 -3.65963e-6 1 1.56587e-6 -3.92277e-6 1 1.12654e-6 -2.98013e-6 1 1.85247e-6 -4.72877e-6 1 4.99487e-7 -6.84496e-6 1 2.89263e-6 -4.28051e-6 1 1.9341e-6 -5.23904e-6 1 2.02237e-6 -5.2181e-6 1 2.52591e-6 -4.97001e-6 1 3.71323e-6 -3.63122e-6 1 4.24014e-6 -3.89898e-6 1 -1.08336e-5 -1.83295e-5 1 2.61916e-5 2.05469e-5 1 2.18368e-6 -5.97121e-6 1 2.05592e-6 -5.56816e-6 1 1.10225e-6 -1.09149e-6 1 2.77008e-6 -2.45851e-6 1 1.64019e-6 -4.22444e-6 1 1.56648e-6 -4.25672e-6 1 1.80417e-6 -6.98134e-6 1 5.01186e-6 6.2436e-7 1 2.77922e-6 -2.40067e-6 1 1.82461e-7 -8.09639e-6 1 7.58398e-7 -6.23233e-6 1 1.92858e-6 -3.79468e-6 1 4.41682e-7 -5.4565e-6 1 2.26225e-6 -2.80104e-6 1 1.84631e-6 -4.39219e-6 1 2.78887e-6 -1.59864e-6 1 2.12251e-6 -6.56477e-6 1 -6.13912e-6 -1.93219e-5 1 3.0266e-6 -2.19289e-6 1 7.03246e-7 -5.00515e-6 1 2.05835e-6 -3.17725e-6 1 1.20534e-6 -4.77999e-6 1 2.06483e-6 -3.17157e-6 1 1.32368e-6 -4.58694e-6 1 9.06963e-7 -5.20732e-6 1 -8.62692e-5 -1.23081e-4 1 -1.48614e-5 -2.7655e-5 1 -1.71216e-7 -8.29002e-6 1 0 -8.07337e-6 1 3.74091e-6 -3.80774e-6 1 8.79969e-6 1.2062e-5 1 2.56273e-6 -4.96664e-6 1 -4.40369e-6 -1.72717e-5 1 2.05874e-6 -5.69144e-6 1 2.6724e-6 -4.77993e-6 1 5.92005e-6 -5.94426e-7 1 1.02028e-5 4.4618e-6 1 4.91767e-6 -1.30653e-6 1 5.90461e-6 -4.41363e-7 1 7.16598e-6 6.65794e-6 1 1.22567e-6 -4.43374e-6 1 0 -6.30203e-6 1 1.3248e-6 -4.11156e-6 1 -1.65219e-5 -2.25429e-5 1 2.24518e-6 -2.13842e-6 1 6.432e-7 -6.49574e-6 1 1.72733e-6 -3.85072e-6 1 2.82245e-6 -2.24412e-6 1 -2.96427e-7 -6.21807e-6 1 5.18246e-6 0 1 2.93523e-6 -6.09624e-6 1 1.85399e-6 -4.35687e-6 1 1.78671e-6 -4.23482e-6 1 1.78929e-6 -4.24014e-6 1 1.57316e-6 -4.23132e-6 1 1.82973e-6 -3.69347e-6 1 1.583e-6 -4.6047e-6 1 1.95578e-5 1.85742e-5 1 2.45169e-6 -3.73601e-6 1 0 -6.26774e-6 1 -7.31826e-7 -1.52971e-6 1 1.25649e-6 -4.05335e-6 1 7.02143e-6 -1.14871e-5 1 -1.44755e-6 -1.83459e-7 1 2.09457e-6 -6.51699e-6 1 1.71789e-6 -3.72488e-6 1 1.59219e-6 -4.24696e-6 1 1.56777e-6 -4.3077e-6 1 1.75189e-6 -3.9825e-6 1 2.63416e-6 -2.63421e-6 1 1.88261e-6 -4.31941e-6 1 1.85206e-6 -4.37417e-6 1 -2.74441e-6 -8.97065e-6 1 -9.61995e-7 -7.43889e-6 1 1.00513e-5 1.13255e-6 1 2.07123e-6 -3.59095e-6 1 1.98613e-6 -4.21589e-6 1 1.62228e-6 -4.86989e-6 1 1.835e-6 -4.84532e-6 1 2.65465e-6 -3.83752e-6 1 4.96651e-6 -5.54827e-7 1 0 -6.76314e-6 1 8.07697e-7 -4.75783e-6 1 1.00023e-6 -4.52111e-6 1 2.9182e-6 -2.37354e-6 1 1.72531e-6 -3.84022e-6 1 9.77788e-7 -1.69528e-6 1 1.61224e-6 -3.98301e-6 1 2.05861e-6 -2.8516e-6 1 1.19669e-6 -4.30777e-6 1 -1.14634e-6 -7.31832e-6 1 4.37588e-6 -8.92432e-7 1 -8.8882e-6 9.59881e-6 1 3.7534e-6 -6.83732e-6 1 -6.94121e-7 -1.26396e-6 1 1.69936e-6 -4.30775e-6 1 -5.07483e-7 -6.65101e-6 1 1.4359e-6 -5.55068e-6 1 2.86912e-6 -4.97445e-6 1 -3.6147e-7 -6.92463e-6 1 -2.50718e-6 -1.04097e-5 1 2.42798e-6 -3.86055e-6 1 2.42978e-6 -4.70241e-6 1 2.22607e-6 -4.6376e-6 1 2.49777e-6 -5.21662e-6 1 1.53108e-6 -3.73726e-6 1 1.57024e-5 -2.72243e-5 1 1.39068e-6 -3.35996e-6 1 1.39068e-6 -3.35997e-6 1 1.4359e-6 -3.46922e-6 1 1.43594e-6 -3.46932e-6 1 1.57022e-5 -2.72239e-5 1 1.53109e-6 -3.73728e-6 1 1.75588e-6 -3.98014e-6 1 -3.81162e-6 2.4228e-6 -1 0.8914701 0.4530796 0 -5.20815e-7 5.83828e-6 -1 0.4530746 0.8914726 1.968e-7 -1.7117e-6 4.70161e-6 -1 -8.84516e-7 5.22454e-6 -1 0.4530746 0.8914726 1.968e-7 -2.74462e-6 3.5906e-6 -1 0.9877918 -0.1557796 0 0.8914701 0.4530796 0 -1.58993e-6 4.88054e-6 -1 0.7071099 -0.7071037 -1.56099e-7 0.9877918 -0.1557796 0 -1.33219e-6 3.44175e-6 -1 0.1557684 -0.9877935 -2.18063e-7 -2.02062e-6 4.26585e-6 -1 -1.75052e-6 3.99576e-6 -1 2.38231e-6 9.42899e-6 -1 -1.4359e-6 4.05037e-6 -1 -1.63272e-5 -3.78048e-6 -1 0.7071099 -0.7071037 -1.56099e-7 -1.58802e-6 3.73836e-6 -1 -0.453087 -0.8914663 -1.96798e-7 -1.49212e-6 3.60168e-6 -1 0.1557684 -0.9877935 -2.18063e-7 -2.07029e-6 4.17985e-6 -1 -0.8914688 -0.4530821 0 -2.1662e-6 4.31654e-6 -1 -0.453087 -0.8914663 -1.96798e-7 -2.02066e-6 4.2659e-6 -1 -0.9877935 0.1557694 0 -1.3322e-6 3.44176e-6 -1 -0.8914688 -0.4530821 0 -1.26869e-6 2.36556e-6 -1 -0.7071068 0.7071068 1.56099e-7 -1.60746e-6 3.85269e-6 -1 -0.9877935 0.1557694 0 -2.20577e-6 8.98115e-6 -1 -0.1557745 0.9877927 2.18063e-7 -1.16135e-6 2.0135e-6 -1 -1.79953e-6 4.43371e-6 -1 -0.7071068 0.7071068 1.56099e-7 -1.78526e-6 3.73398e-6 -1 -1.6685e-6 4.03054e-6 -1 -1.78344e-6 3.58979e-6 -1 -1.73791e-6 4.33101e-6 -1 -0.1557745 0.9877927 2.18063e-7 -2.25668e-6 4.08502e-6 -1 0.8914701 0.4530795 0 1.67134e-6 8.43601e-6 -1 0.4530698 0.8914751 0 -4.07547e-6 1.37769e-6 -1 0.4530698 0.8914751 0 -2.13167e-6 4.28334e-6 -1 0.9877947 -0.1557614 0 0.8914701 0.4530795 0 -2.11663e-6 4.31046e-6 -1 0.7071006 -0.707113 0 0.9877947 -0.1557614 0 -2.30535e-6 4.60669e-6 -1 0.1557735 -0.9877929 0 -1.18946e-5 1.60857e-5 -1 -2.54067e-6 6.73176e-6 -1 -6.06686e-7 7.44731e-6 -1 -1.43583e-6 6.98488e-6 -1 0.7071006 -0.707113 0 -1.00986e-6 3.16021e-6 -1 -0.4530895 -0.891465 0 -1.36496e-6 3.6663e-6 -1 0.1557735 -0.9877929 0 -1.94315e-6 4.24449e-6 -1 -0.891465 -0.4530895 0 -1.58805e-6 3.73839e-6 -1 -0.4530895 -0.891465 0 -2.02053e-6 4.26576e-6 -1 -0.987795 0.1557595 0 -2.30528e-6 4.60662e-6 -1 -0.891465 -0.4530895 0 -1.59578e-6 3.78956e-6 -1 -0.7071006 0.707113 0 -1.61356e-6 3.85878e-6 -1 -0.9877951 0.1557595 0 4.60121e-7 -1.29318e-5 -1 -0.1557511 0.9877964 0 -7.92322e-7 1.37372e-6 -1 -1.64995e-6 4.28415e-6 -1 -0.7071006 0.707113 0 -1.432e-6 4.68444e-6 -1 -1.27971e-6 5.08693e-6 -1 -1.63922e-6 3.58981e-6 -1 -1.64432e-6 3.44483e-6 -1 -0.1557511 0.9877964 0 0.8914726 0.4530747 0 0.4530747 0.8914726 0 0.4530747 0.8914726 0 0.9877929 -0.1557735 0 0.8914726 0.4530746 0 -1.60429e-6 3.79801e-6 -1 0.707113 -0.7071006 0 0.9877929 -0.1557735 0 -1.68224e-6 5.66188e-6 -1 0.1557614 -0.9877947 0 -1.54368e-6 3.5193e-6 -1 -1.69785e-6 4.3079e-6 -1 -2.12438e-6 5.12595e-6 -1 0.707113 -0.7071006 0 -4.57811e-6 -4.28988e-7 -1 -0.4530797 -0.89147 0 -1.59458e-6 3.93718e-6 -1 -1.89457e-6 3.06805e-6 -1 -1.65261e-6 4.30772e-6 -1 0.1557614 -0.9877947 0 1.57385e-5 2.36951e-5 -1 -0.8914675 -0.4530845 0 -1.99959e-6 4.4025e-6 -1 -7.9516e-7 5.21164e-6 -1 -0.4530797 -0.89147 0 -2.60464e-6 3.56843e-6 -1 -0.987795 0.1557595 0 -0.8914676 -0.4530845 0 -1.50735e-6 4.79806e-6 -1 -0.7071006 0.707113 0 -0.987795 0.1557595 0 -0.1557614 0.9877947 0 -4.02182e-6 1.90783e-6 -1 -1.43595e-6 3.91073e-6 -1 -8.83776e-7 4.23876e-6 -1 -0.7071006 0.707113 0 -0.1557614 0.9877947 0 0.8914663 0.453087 0 0.4530821 0.8914688 1.96799e-7 0.4530821 0.8914688 1.96799e-7 0.9877929 -0.1557735 0 0.8914663 0.453087 0 -1.01004e-5 2.65535e-5 -1 0.7071068 -0.7071068 -1.56099e-7 0.9877929 -0.1557735 0 2.55888e-6 -8.63137e-5 -1 0.1557694 -0.9877935 -2.18063e-7 -4.36545e-6 1.49021e-5 -1 -1.63658e-6 4.27254e-6 -1 6.59846e-6 -1.14403e-5 -1 0.7071068 -0.7071067 -1.56099e-7 2.81852e-7 7.41761e-6 -1 -0.4530771 -0.8914713 -1.96799e-7 -3.97511e-6 2.24413e-6 -1 -3.79761e-6 2.80257e-6 -1 -3.67338e-6 3.58975e-6 -1 0.1557694 -0.9877935 -2.18063e-7 -2.0007e-6 3.34318e-6 -1 -0.89147 -0.4530796 0 1.61916e-6 9.06925e-6 -1 -0.4530771 -0.8914713 -1.96799e-7 -1.50891e-6 4.18516e-6 -1 -0.9877945 0.1557623 0 -0.89147 -0.4530796 0 -1.30421e-6 4.59482e-6 -1 -0.7071099 0.7071037 1.56099e-7 -0.9877945 0.1557623 0 -0.1557735 0.9877929 2.18063e-7 -1.64759e-6 3.77852e-6 -1 -1.43592e-6 3.90765e-6 -1 -0.7071099 0.7071037 1.56099e-7 -0.1557735 0.9877929 2.18063e-7 -1.40902e-6 3.66901e-6 -1 0.7739935 0.6331936 2.79565e-7 -1.62603e-6 3.90636e-6 -1 0.6331864 0.7739993 3.41733e-7 0.6331864 0.7739993 3.41733e-7 -1.79195e-6 4.21903e-6 -1 0.8821564 0.4709566 2.07935e-7 -1.5396e-6 3.7908e-6 -1 0.7739935 0.6331936 2.79412e-7 -1.75423e-6 4.16513e-6 -1 0.9568098 0.2907146 1.28355e-7 0.8821564 0.4709566 2.07935e-7 -1.34146e-6 3.65896e-6 -1 0.995296 0.0968815 0 0.9568098 0.2907146 1.28355e-7 -1.15951e-5 1.47704e-5 -1 0.9952996 -0.09684449 0 0.995296 0.0968815 0 1.89835e-6 2.55519e-6 -1 0.9568009 -0.2907443 -1.28368e-7 3.75593e-6 -3.91865e-7 -1 0.9952996 -0.09684449 0 2.10515e-6 2.30221e-6 -1 0.8817018 -0.4718073 -2.0831e-7 0.9568009 -0.2907443 -1.28368e-7 6.33014e-6 -2.26884e-6 -1 0.7737521 -0.6334885 -2.79695e-7 0.8817018 -0.4718073 -2.0831e-7 -8.10692e-6 1.10882e-5 -1 0.6334885 -0.7737521 -3.41624e-7 2.68395e-5 -2.34524e-5 -1 -7.25379e-7 2.84287e-6 -1 5.29585e-5 -5.08324e-5 -1 0.7737521 -0.6334885 -2.79695e-7 -2.74736e-6 5.13421e-6 -1 0.4718073 -0.8817018 -3.89285e-7 0.6334886 -0.7737521 -3.41624e-7 -9.8284e-7 3.23453e-6 -1 0.2907332 -0.9568042 -4.22444e-7 0.4718073 -0.8817017 -3.89285e-7 -1.92327e-6 4.18666e-6 -1 0.09686839 -0.9952972 -4.3944e-7 0.2907332 -0.9568042 -4.22444e-7 -1.19429e-6 3.3031e-6 -1 -0.0968815 -0.995296 -4.39439e-7 -1.52917e-6 3.82298e-6 -1 0.09686839 -0.9952972 -4.3944e-7 -1.84864e-6 4.22413e-6 -1 -0.2907146 -0.9568098 -4.22447e-7 -0.0968815 -0.995296 -4.39439e-7 -1.45551e-6 3.73673e-6 -1 -0.4709712 -0.8821486 -3.89483e-7 -0.2907146 -0.9568098 -4.22447e-7 -1.62027e-6 3.91337e-6 -1 -0.6331806 -0.7740041 -3.41735e-7 -0.4709711 -0.8821486 -3.89483e-7 -6.49789e-6 1.20424e-5 -1 -0.7739993 -0.6331864 -2.79562e-7 -1.56863e-6 3.86615e-6 -1 -0.6331806 -0.7740041 -3.41735e-7 -1.13938e-6 4.56746e-6 -1 -0.8821487 -0.4709712 -2.07941e-7 -0.7739993 -0.6331864 -2.79562e-7 -9.95048e-7 4.39574e-6 -1 -0.9568108 -0.2907113 -1.28354e-7 -0.8821486 -0.4709712 -2.07941e-7 -3.73098e-7 3.75321e-6 -1 -0.9952948 -0.09689348 0 -0.9568108 -0.2907113 -1.28354e-7 -1.67103e-6 3.95212e-6 -1 -0.9952972 0.09686839 0 -3.16201e-6 6.32614e-6 -1 -0.9952948 -0.09689348 0 -1.47739e-6 3.58098e-6 -1 -0.9568009 0.2907443 1.28368e-7 -2.02586e-6 4.45115e-6 -1 -0.9952972 0.09686839 0 -2.40472e-6 4.71542e-6 -1 -0.8817118 0.4717885 2.08302e-7 -0.9568009 0.2907443 1.28368e-7 -3.04011e-6 5.40285e-6 -1 -0.7737462 0.6334958 2.79698e-7 -0.8817118 0.4717885 2.08302e-7 -4.22518e-6 6.34693e-6 -1 -0.6334944 0.7737472 3.41622e-7 -6.53085e-7 2.93936e-6 -1 2.68444e-6 -5.59289e-7 -1 -0.7737462 0.6334958 2.79698e-7 -3.97052e-7 2.34388e-6 -1 -0.4718022 0.8817044 3.89287e-7 -1.83653e-6 4.17184e-6 -1 -0.6334944 0.7737472 3.41622e-7 -2.16004e-6 4.53182e-6 -1 -0.2907332 0.9568042 4.22444e-7 -0.4718022 0.8817044 3.89287e-7 -1.07453e-6 3.25331e-6 -1 -0.09686839 0.9952972 4.3944e-7 -0.2907332 0.9568042 4.22444e-7 -1.87282e-6 4.11861e-6 -1 0.0968815 0.995296 4.39439e-7 -0.09686839 0.9952972 4.3944e-7 -1.32101e-6 3.38351e-6 -1 0.2907113 0.9568108 4.22447e-7 -1.6042e-6 3.8586e-6 -1 0.0968815 0.995296 4.39439e-7 -1.98313e-6 4.3642e-6 -1 0.4709712 0.8821486 3.89483e-7 0.2907113 0.9568108 4.22447e-7 0.4709712 0.8821486 3.89483e-7 -6.97722e-7 4.71386e-6 -1 0.8914753 0.4530695 2.00037e-7 -8.83084e-7 4.91117e-6 -1 0.4530696 0.8914751 3.936e-7 0.4530696 0.8914751 3.936e-7 -1.77577e-6 4.10392e-6 -1 0.9877939 -0.1557664 0 -3.28569e-6 6.90097e-6 -1 0.8914753 0.4530695 2.00197e-7 -1.41004e-6 3.53524e-6 -1 0.7071068 -0.7071068 -3.12199e-7 0.9877939 -0.1557664 0 -2.27049e-6 4.69865e-6 -1 0.1557664 -0.9877939 -4.36127e-7 -9.17514e-7 3.20379e-6 -1 0.7071068 -0.7071068 -3.12199e-7 -1.44252e-6 3.81032e-6 -1 -0.4530599 -0.89148 -3.93603e-7 -1.7506e-6 4.17876e-6 -1 0.1557664 -0.9877939 -4.36127e-7 -1.75065e-6 4.17882e-6 -1 -0.8914777 -0.4530648 -2.00035e-7 -1.44254e-6 3.81034e-6 -1 -0.4530599 -0.8914801 -3.93603e-7 -9.17521e-7 3.2038e-6 -1 -0.9877939 0.1557664 0 -2.2705e-6 4.69866e-6 -1 -0.8914777 -0.4530648 -2.00035e-7 -4.30409e-7 2.55557e-6 -1 -0.7071068 0.7071068 3.12199e-7 -1.53952e-6 3.8258e-6 -1 -0.9877939 0.1557664 0 -1.71447e-6 6.0225e-6 -1 -0.1557664 0.9877939 4.36127e-7 -5.15778e-6 7.9363e-6 -1 -1.18673e-6 5.23822e-6 -1 -0.7071068 0.7071068 3.12199e-7 -0.1557664 0.9877939 4.36127e-7 0.8914753 0.4530695 2.00037e-7 0.4530648 0.8914777 3.93602e-7 0.4530648 0.8914777 3.93602e-7 0.9877958 -0.1557546 0 0.8914752 0.4530695 2.00197e-7 0.7071008 -0.7071128 -3.12202e-7 0.9877958 -0.1557546 0 -1.31865e-6 3.51236e-6 -1 0.1557664 -0.9877939 -4.36127e-7 0.7071008 -0.7071128 -3.12202e-7 -1.49059e-6 3.71582e-6 -1 -0.4530696 -0.8914751 -3.936e-7 0.1557664 -0.9877939 -4.36127e-7 -1.74916e-6 4.17945e-6 -1 -0.8914654 -0.4530886 -2.00046e-7 -1.62718e-6 3.84413e-6 -1 -0.4530696 -0.8914751 -3.936e-7 -1.70251e-6 4.09241e-6 -1 -0.9877936 0.1557683 0 -0.8914654 -0.4530886 -2.00046e-7 -1.14137e-6 3.26654e-6 -1 -0.7071068 0.7071068 3.12199e-7 -0.9877936 0.1557683 0 -0.1557664 0.9877939 4.36127e-7 -0.7071068 0.7071068 3.12199e-7 -0.1557664 0.9877939 4.36127e-7 -1.81501e-6 4.14605e-6 -1 0.89148 0.4530599 2.00033e-7 -1.47723e-6 3.74208e-6 -1 0.4530648 0.8914777 3.93602e-7 -1.47721e-6 3.74206e-6 -1 0.4530648 0.8914777 3.93602e-7 -1.725e-6 4.09596e-6 -1 0.9877936 -0.1557683 0 -1.34436e-6 3.67539e-6 -1 0.8914801 0.4530599 2.00198e-7 3.40764e-6 -2.345e-6 -1 0.7071128 -0.7071008 -3.12196e-7 -1.63594e-6 4.0069e-6 -1 0.9877936 -0.1557682 0 -1.3583e-6 3.76384e-6 -1 0.1557664 -0.9877939 -4.36127e-7 -4.47262e-6 7.4719e-6 -1 0.7071128 -0.7071008 -3.12196e-7 -1.42879e-6 3.83743e-6 -1 -0.4530696 -0.8914751 -3.936e-7 0.1557664 -0.9877939 -4.36127e-7 -1.77673e-6 4.16545e-6 -1 -0.8914703 -0.4530791 -2.00042e-7 -1.73358e-6 4.08531e-6 -1 -0.4530696 -0.8914751 -3.936e-7 -1.13978e-6 3.23885e-6 -1 -0.9877939 0.1557664 0 -0.8914703 -0.4530791 -2.00042e-7 -5.50233e-6 8.69022e-6 -1 -0.7071008 0.7071128 3.12202e-7 -0.9877939 0.1557664 0 -2.25231e-6 4.58334e-6 -1 -0.1557664 0.9877939 4.36127e-7 -1.23223e-5 1.57093e-5 -1 -0.7071008 0.7071128 3.12202e-7 -1.815e-6 4.14603e-6 -1 -0.1557664 0.9877939 4.36127e-7 -6.62929e-7 4.73154e-6 -1 0.8914752 0.4530695 2.00037e-7 -7.61299e-6 1.32774e-5 -1 0.4530648 0.8914777 3.93602e-7 0.4530648 0.8914776 3.93602e-7 -1.52049e-6 4.06364e-6 -1 0.9877958 -0.1557546 0 -2.28732e-6 6.2873e-6 -1 0.8914753 0.4530695 2.00197e-7 0 1.16836e-6 -1 0.7071068 -0.7071068 -3.12199e-7 0.9877958 -0.1557546 0 0.1557664 -0.9877939 -4.36127e-7 0.7071068 -0.7071068 -3.12199e-7 -0.4530599 -0.89148 -3.93603e-7 0.1557664 -0.9877939 -4.36127e-7 -0.8914752 -0.4530695 -2.00037e-7 -0.4530599 -0.89148 -3.93603e-7 -0.9877937 0.1557683 0 -0.8914753 -0.4530695 -2.00037e-7 -0.7071128 0.7071008 3.12196e-7 -0.9877936 0.1557683 0 -2.31908e-6 5.00675e-6 -1 -0.1557664 0.9877939 4.36127e-7 -1.73955e-6 4.00597e-6 -1 -0.7071127 0.7071008 3.12196e-7 -0.1557664 0.9877939 4.36127e-7 -1.76528e-6 3.99434e-6 -1 0.8315063 0.5555153 2.45269e-7 -1.54296e-6 3.7137e-6 -1 0.5555101 0.8315098 3.67125e-7 0.5555101 0.8315098 3.67125e-7 -1.43026e-6 3.6053e-6 -1 0.9807875 0.1950786 0 -1.5097e-6 3.77226e-6 -1 0.8315063 0.5555154 2.45498e-7 -6.49351e-6 1.15022e-5 -1 0.9807864 -0.1950845 0 0.9807875 0.1950786 0 2.92846e-7 2.67863e-6 -1 0.8315098 -0.5555101 -2.45267e-7 0.9807865 -0.1950845 0 -2.54092e-6 4.66381e-6 -1 0.5555101 -0.8315099 -3.67125e-7 1.20132e-6 1.5772e-6 -1 0.8315099 -0.5555101 -2.45267e-7 -1.10113e-6 3.09149e-6 -1 0.1950801 -0.9807873 -4.33033e-7 -1.59769e-6 3.93836e-6 -1 0.5555101 -0.8315098 -3.67125e-7 -2.02474e-6 4.48756e-6 -1 -0.1950771 -0.9807879 -4.33033e-7 0.1950801 -0.9807873 -4.33033e-7 -5.3599e-6 8.32581e-6 -1 -0.555503 -0.8315146 -3.67127e-7 -0.1950771 -0.9807879 -4.33033e-7 -1.71207e-6 4.02991e-6 -1 -0.8315099 -0.5555101 -2.45266e-7 -2.13673e-6 5.77258e-6 -1 -0.555503 -0.8315146 -3.67127e-7 -1.7145e-6 4.03494e-6 -1 -0.9807897 -0.1950683 0 -0.8315098 -0.5555101 -2.45267e-7 -1.45259e-6 3.69255e-6 -1 -0.9807856 0.1950889 0 -0.9807897 -0.1950683 0 -1.87418e-6 4.12633e-6 -1 -0.8315122 0.5555065 2.45265e-7 -0.9807856 0.1950889 0 -1.017e-6 3.24327e-6 -1 -0.5555047 0.8315134 3.67126e-7 -1.69138e-6 3.9498e-6 -1 -1.68757e-6 3.93765e-6 -1 -0.8315122 0.5555065 2.45265e-7 -1.83891e-6 4.35587e-6 -1 -0.1950947 0.9807844 4.33032e-7 -1.64154e-6 3.85025e-6 -1 -0.5555047 0.8315134 3.67126e-7 -1.65251e-6 3.91434e-6 -1 0.1950845 0.9807865 4.33033e-7 -0.1950947 0.9807844 4.33032e-7 0.1950845 0.9807865 4.33033e-7 -7.31825e-7 3.11607e-6 -1 0.8914745 0.4530709 0 -1.5034e-6 3.90498e-6 -1 0.4530734 0.8914732 1.968e-7 0.4530734 0.8914732 1.968e-7 -2.20812e-6 4.29545e-6 -1 0.9877935 -0.1557689 0 -2.26457e-6 4.18223e-6 -1 0.8914745 0.4530709 0 -1.84971e-6 5.14033e-6 -1 0.7071083 -0.7071052 -1.56099e-7 0.9877935 -0.1557689 0 -1.55746e-6 4.87039e-6 -1 0.1557675 -0.9877938 -2.18063e-7 -1.97542e-6 4.78803e-6 -1 0.7071083 -0.7071052 -1.56099e-7 -1.94436e-6 3.03731e-6 -1 -0.4530796 -0.8914701 -1.96799e-7 -1.40735e-6 4.91468e-6 -1 0.1557675 -0.9877937 -2.18063e-7 -1.57515e-6 4.43151e-6 -1 -0.8914713 -0.4530771 0 -0.4530796 -0.8914701 -1.96799e-7 -1.61598e-6 4.20203e-6 -1 -0.9877947 0.1557618 0 -0.8914713 -0.4530771 0 -1.64023e-6 3.83398e-6 -1 -0.7071083 0.7071052 1.56099e-7 -0.9877947 0.1557618 0 -2.33111e-6 4.77043e-6 -1 -0.1557635 0.9877944 2.18063e-7 -1.47266e-6 3.72229e-6 -1 -1.64061e-6 3.86677e-6 -1 -0.7071083 0.7071052 1.56099e-7 -1.58975e-6 4.0346e-6 -1 -0.1557635 0.9877944 2.18063e-7 2.18106e-6 1.68046e-5 -1 0.8914726 0.4530746 0 -5.14983e-6 -3.26973e-6 -1 0.4530771 0.8914713 0 0.4530771 0.8914713 0 -1.54114e-6 4.19024e-6 -1 0.9877937 -0.1557679 0 0.8914726 0.4530746 0 -1.61609e-6 3.80982e-6 -1 0.7071099 -0.7071037 0 0.9877937 -0.1557679 0 -1.29382e-6 3.19858e-6 -1 0.1557644 -0.9877943 0 -1.62292e-6 3.75362e-6 -1 0.7071099 -0.7071037 0 -2.12621e-6 4.39525e-6 -1 -0.4530796 -0.8914701 0 0.1557644 -0.9877943 0 -6.94085e-6 1.21685e-5 -1 -0.891472 -0.4530759 0 -1.43594e-6 3.72015e-6 -1 -0.4530797 -0.8914701 0 1.44526e-6 3.71933e-6 -1 -0.9877946 0.1557623 0 -0.8914719 -0.4530758 0 1.75789e-5 -1.53851e-5 -1 -0.7071083 0.7071052 0 4.28482e-7 4.55209e-6 -1 -0.9877946 0.1557623 0 -2.03369e-6 2.88419e-6 -1 -0.155767 0.9877939 0 -1.56513e-6 3.97286e-6 -1 -5.52601e-6 1.31538e-5 -1 -1.46293e-7 4.73986e-6 -1 -0.7071083 0.7071052 0 -1.66736e-6 3.9709e-6 -1 -4.56014e-6 -1.70178e-6 -1 -0.155767 0.9877939 0 -1.30926e-6 3.6946e-6 -1 0.8914701 0.4530796 0 -2.05737e-6 4.53073e-6 -1 0.4530771 0.8914713 0 0.4530771 0.8914713 0 -1.32947e-6 3.36745e-6 -1 0.9877925 -0.155775 0 -1.44111e-6 3.79451e-6 -1 0.8914701 0.4530796 0 -2.30561e-6 5.59621e-6 -1 0.7071083 -0.7071052 0 0.9877925 -0.155775 0 -1.28781e-6 3.16025e-6 -1 0.1557714 -0.9877931 0 -3.45636e-7 1.70541e-6 -1 0.7071084 -0.7071052 0 -2.16829e-6 4.31242e-6 -1 -0.4530771 -0.8914714 0 0.1557714 -0.9877931 0 -1.4029e-6 3.64703e-6 -1 -0.8914719 -0.4530758 0 -2.10446e-6 4.43809e-6 -1 -3.1116e-7 2.6448e-6 -1 -0.4530771 -0.8914714 0 -1.96987e-6 4.25785e-6 -1 -0.9877937 0.1557679 0 -1.35737e-6 3.60151e-6 -1 -0.8914719 -0.4530758 0 -1.5275e-6 3.72125e-6 -1 -0.7071068 0.7071068 0 -1.63161e-6 3.9196e-6 -1 -0.9877937 0.1557679 0 -1.31103e-6 3.30765e-6 -1 -0.1557675 0.9877938 0 -1.61008e-6 3.87467e-6 -1 -1.60707e-6 3.86493e-6 -1 -0.7071068 0.7071068 0 -0.1557675 0.9877938 0 -1.21175e-6 3.74416e-6 -1 0.89147 0.4530796 0 0.4530771 0.8914713 0 1.20423e-6 1.05363e-6 -1 0.4530771 0.8914713 0 5.18444e-7 1.33388e-5 -1 0.9877927 -0.1557745 0 -2.26717e-6 4.55071e-6 -1 0.8914701 0.4530796 0 -1.59747e-6 3.79122e-6 -1 0.7071068 -0.7071068 0 0.9877927 -0.1557745 0 -2.39971e-6 5.20512e-6 -1 0.1557689 -0.9877935 0 -1.55004e-6 3.87715e-6 -1 -1.58276e-6 3.89148e-6 -1 0.7071068 -0.7071068 0 -7.73083e-6 1.22409e-5 -1 -0.4530734 -0.8914732 0 0.1557689 -0.9877935 0 -1.91959e-6 3.38443e-6 -1 -0.8914739 -0.4530722 0 -5.9269e-7 5.85411e-6 -1 -0.4530734 -0.8914732 0 -1.88495e-6 3.45503e-6 -1 -0.9877935 0.1557684 0 -0.8914739 -0.4530722 0 -1.38022e-6 4.67084e-6 -1 -0.7071083 0.7071052 0 -0.9877935 0.1557684 0 -0.1557675 0.9877937 0 -1.64033e-6 3.92166e-6 -1 -0.7071083 0.7071052 0 -0.1557675 0.9877938 0 -1.81492e-6 4.53137e-6 -1 0.8097944 0.5867137 1.29522e-7 -1.54161e-6 3.92417e-6 -1 0.5867182 0.8097912 1.78768e-7 0.5867182 0.8097912 1.78768e-7 -1.17871e-6 3.39132e-6 -1 0.9518105 0.306687 0 0.8097944 0.5867137 1.29497e-7 -1.30906e-6 3.58495e-6 -1 1 0 0 0.9518105 0.306687 0 -1.92944e-6 4.38447e-6 -1 0.9515566 -0.3074734 0 1 0 0 -1.81131e-6 4.24502e-6 -1 0.8097157 -0.5868224 -1.29546e-7 0.9515566 -0.3074734 0 -3.79389e-6 7.25797e-6 -1 0.5868224 -0.8097157 -1.78751e-7 -6.63831e-6 9.75143e-6 -1 0.8097157 -0.5868224 -1.29546e-7 -7.20483e-7 2.22979e-6 -1 0.3074648 -0.9515595 -2.10064e-7 -3.09749e-6 6.6681e-6 -1 0.5868224 -0.8097157 -1.78751e-7 -2.38999e-6 5.24916e-6 -1 0 -1 -2.20758e-7 0.3074648 -0.9515595 -2.10064e-7 -1.36748e-6 3.55851e-6 -1 -0.3066728 -0.951815 -2.10121e-7 0 -1 -2.20758e-7 -1.58253e-6 3.86768e-6 -1 -0.5867334 -0.8097801 -1.78765e-7 -0.3066728 -0.951815 -2.10121e-7 -2.01258e-6 4.38823e-6 -1 -0.8097833 -0.5867289 -1.29525e-7 -0.5867334 -0.8097801 -1.78765e-7 -1.06725e-6 3.42717e-6 -1 -0.9518122 -0.3066814 0 -0.8097833 -0.5867289 -1.29525e-7 -1.53974e-6 3.58498e-6 -1 -1 0 0 -1.79775e-6 4.06781e-6 -1 -0.9518122 -0.3066814 0 -2.05463e-6 4.42491e-6 -1 -0.9515595 0.3074648 0 -1 0 0 -2.05002e-6 4.41804e-6 -1 -0.8097112 0.5868287 1.29547e-7 -0.9515594 0.3074648 0 6.34527e-6 -6.73236e-6 -1 -0.5868224 0.8097157 1.78751e-7 -2.83694e-6 5.53829e-6 -1 -0.8097112 0.5868287 1.29547e-7 -9.8072e-7 3.03506e-6 -1 -0.3074762 0.9515558 2.10064e-7 -0.5868223 0.8097157 1.78751e-7 -2.38994e-6 4.81826e-6 -1 9.55996e-6 1 2.20758e-7 -0.3074762 0.9515558 2.10064e-7 -1.34536e-6 3.62717e-6 -1 0.3066728 0.951815 2.10121e-7 9.55996e-6 1 2.20758e-7 -1.48209e-6 3.76165e-6 -1 0.3066728 0.951815 2.10121e-7 -1.90263e-6 4.49819e-6 -1 0.7733415 -0.6339897 0 -2.12825e-6 4.13524e-6 -1 0.7071071 -0.7071064 0 -1.91295e-6 4.47947e-6 -1 0.8822628 -0.4707573 0 0.7733415 -0.6339897 0 -2.21212e-6 3.86239e-6 -1 0.9567288 -0.2909811 0 0.8822622 -0.4707584 0 0.9951333 -0.09853738 0 0.9567288 -0.2909811 0 1 3.45466e-7 0 1 3.45466e-7 0 0.9951333 -0.09853738 0 0.9951333 0.09853798 0 0.9567267 0.2909877 0 0.9951333 0.09853798 0 0.8822665 0.4707502 0 0.9567268 0.2909878 0 0.773343 0.6339879 0 0.8822659 0.4707514 0 0.7071068 0.7071068 0 0.773343 0.6339879 0 0.6255633 0.7801735 0 0.7071068 0.7071067 0 -1.59967e-6 3.95579e-6 -1 0.4410461 0.8974844 0 0.6255633 0.7801735 0 -1.60839e-6 3.97406e-6 -1 0.2354485 0.9718868 0 0.4410461 0.8974844 0 -1.43913e-6 3.70795e-6 -1 0.2354449 0.9718877 0 -3.03856e-6 5.77045e-6 -1 0.2354485 0.9718868 0 0.4410472 0.8974839 0 -1.70335e-6 3.97217e-6 -1 0.2354449 0.9718877 0 0.6255657 0.7801715 1.72229e-7 0.4410457 0.8974846 1.98127e-7 0.7071067 0.7071069 1.56099e-7 4.96319e-7 2.6168e-6 -1 -2.45154e-6 3.76769e-6 -1 -3.9259e-6 1.89639e-6 -1 -2.05592e-6 4.30768e-6 -1 1.3203e-5 2.46739e-5 -1 -1.85913e-6 2.54769e-6 -1 -1.64653e-6 4.12359e-6 -1 -1.62955e-6 4.05307e-6 -1 -1.44327e-6 3.58975e-6 -1 -1.9236e-6 4.43811e-6 -1 -1.7111e-5 2.76476e-5 -1 0.6255657 0.7801715 1.72229e-7 -1.55559e-6 3.85263e-6 -1 0.7569351 0.6534901 0 -2.50969e-6 5.56293e-6 -1 -7.89324e-6 1.09465e-5 -1 -3.11125e-6 6.83696e-6 -1 -1.43591e-6 5.53307e-6 -1 -1.08817e-6 5.32724e-6 -1 0.7071068 0.7071068 0 0.8439939 0.5363529 0 -1.75595e-6 4.05298e-6 -1 0.7569351 0.6534901 0 0.9127928 0.4084232 1.80325e-7 0.8439931 0.536354 2.36809e-7 0.9625204 0.2712094 1.19743e-7 0.9127927 0.4084232 1.80325e-7 0.95412 0.2994245 1.32201e-7 0.9625204 0.2712094 1.19743e-7 0.8730451 0.4876393 2.15301e-7 0.95412 0.2994245 1.32201e-7 0.7553309 0.6553438 2.89345e-7 0.8730451 0.4876393 2.15301e-7 0.6059176 0.7955274 3.51238e-7 0.7553308 0.6553437 2.89345e-7 0.4310894 0.9023092 3.98384e-7 0.6059176 0.7955274 3.51238e-7 -1.60145e-6 3.94164e-6 -1 0.2381763 0.9712219 4.2881e-7 0.4310894 0.9023092 3.98384e-7 -3.92111e-6 6.75794e-6 -1 0.03529268 0.999377 4.41241e-7 -1.7575e-6 4.0977e-6 -1 0.2381763 0.9712219 4.2881e-7 -1.90804e-6 4.97544e-6 -1 -0.1690753 0.9856032 4.35159e-7 -9.0351e-7 3.74035e-6 -1 0.03529268 0.999377 4.41241e-7 -2.25868e-6 5.73712e-6 -1 -0.366328 0.9304859 4.10824e-7 -4.67845e-7 3.53525e-6 -1 -0.1690753 0.9856032 4.35159e-7 7.06896e-6 -4.71705e-6 -1 -0.5482199 0.8363342 3.69255e-7 2.16055e-6 1.31789e-6 -1 -0.366328 0.9304859 4.10824e-7 -0.7071085 0.7071052 3.12198e-7 -0.5482199 0.8363342 3.69255e-7 -0.8363347 0.5482192 0 -0.7071068 0.7071068 0 -0.9304859 0.366328 0 -0.8363347 0.5482192 0 -0.9856038 0.169071 0 -0.9304859 0.366328 0 -0.999377 -0.03529268 0 -0.9856038 0.169071 0 -0.9712216 -0.2381778 0 -0.999377 -0.03529268 0 -0.9023111 -0.4310854 0 -0.9712216 -0.2381778 0 -0.7955278 -0.605917 0 -0.9023111 -0.4310854 0 -0.6553386 -0.7553354 -3.33493e-7 -0.795529 -0.6059154 -2.67521e-7 -0.4876433 -0.8730429 -3.85462e-7 -0.6553386 -0.7553354 -3.33493e-7 -0.2994245 -0.95412 -4.21259e-7 -0.4876433 -0.873043 -3.85462e-7 -0.2712045 -0.9625217 -4.24969e-7 -0.2994245 -0.95412 -4.21259e-7 -0.4084242 -0.9127922 -4.03012e-7 -0.2712045 -0.9625217 -4.24969e-7 -0.5363546 -0.8439928 -3.72636e-7 -0.4084242 -0.9127922 -4.03012e-7 -0.6534938 -0.756932 -3.34198e-7 -0.5363546 -0.8439928 -3.72636e-7 -0.7071066 -0.7071069 -3.12199e-7 -1.40216e-6 4.7828e-6 -1 -1.65282e-6 3.87896e-6 -1 -1.70444e-6 4.00982e-6 -1 -1.45583e-6 3.58981e-6 -1 -2.27288e-6 4.63962e-6 -1 0 1.85816e-6 -1 2.37296e-5 3.81032e-5 -1 -2.30002e-6 3.91922e-6 -1 -2.67392e-6 3.45067e-6 -1 -1.99998e-6 4.30772e-6 -1 -0.6534938 -0.7569319 -3.34197e-7 -0.780174 -0.6255626 -1.38098e-7 -2.72507e-6 4.72475e-6 -1 -1.43592e-6 3.99485e-6 -1 -9.8836e-6 7.39126e-6 -1 -0.7071066 -0.7071069 -1.56099e-7 -0.8974835 -0.441048 0 -0.780174 -0.6255626 -1.38098e-7 -3.05787e-6 6.27141e-6 -1 -0.9718872 -0.235447 0 -1.52686e-6 3.78473e-6 -1 -0.8974835 -0.441048 0 -1.66205e-6 4.03841e-6 -1 -0.9718872 -0.2354468 0 -1.65964e-6 5.15823e-6 -1 -0.9718872 -0.2354472 0 -1.65146e-6 3.99767e-6 -1 -0.8974835 -0.441048 0 -0.9718872 -0.2354468 0 -0.7801728 -0.6255641 0 -0.8974835 -0.441048 0 -0.7071065 -0.7071071 0 -0.7801727 -0.6255641 0 -0.6339912 -0.7733404 -1.70721e-7 -0.7071066 -0.707107 -1.56099e-7 -0.47075 -0.8822665 -1.94767e-7 -0.6339912 -0.7733404 -1.70721e-7 -1.83131e-6 4.46577e-6 -1 -0.2909855 -0.9567275 -2.11205e-7 -0.47075 -0.8822665 -1.94767e-7 -9.03518e-6 2.40601e-5 -1 -0.0985338 -0.9951338 -2.19684e-7 -0.2909855 -0.9567275 -2.11205e-7 -1.72732e-6 6.23054e-6 -1 -6.90932e-7 -1 -2.20758e-7 -6.90932e-7 -1 -2.20758e-7 -0.0985338 -0.9951338 -2.19684e-7 -2.20926e-6 6.93757e-6 -1 0.0985338 -0.9951338 -2.19684e-7 -2.04729e-6 6.73119e-6 -1 0.2909883 -0.9567266 -2.11205e-7 0.0985338 -0.9951338 -2.19684e-7 -5.95222e-6 1.11554e-5 -1 0.4707539 -0.8822646 -1.94767e-7 0.2909883 -0.9567266 -2.11205e-7 -1.42387e-5 1.97579e-5 -1 0.6339885 -0.7733424 0 0.4707562 -0.8822633 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.6339886 -0.7733424 0 0.7071066 0.7071069 0 0.7071068 -0.7071068 -1.56099e-7 0.7071066 0.707107 1.561e-7 -0.7071068 -0.7071068 -1.56099e-7 0.7071068 -0.7071068 -1.56099e-7 0.7071071 -0.7071064 0 -0.7071067 -0.7071069 0 -0.7071068 0.7071068 0 -0.8662425 0.499624 0 -0.8662425 0.499624 0 -0.7071068 0.7071068 0 -0.4996276 0.8662403 0 1.14873e-5 1 0 -0.4996276 0.8662403 0 0.4996376 0.8662346 0 1.14873e-5 1 0 0.7071075 0.7071061 0 0.4996376 0.8662346 0 0.8662325 0.4996412 2.206e-7 0.7071068 0.7071068 3.12199e-7 1 0 0 0.8662325 0.4996412 2.206e-7 0.8662325 -0.4996412 -2.206e-7 1 0 0 0.7071217 -0.7070919 -3.13268e-7 0.7071217 -0.7070919 -3.12192e-7 0.8662325 -0.4996412 -2.206e-7 0.4996289 -0.8662395 -3.82459e-7 0 -1 0 0.4996376 -0.8662346 0 -0.4996189 -0.8662453 0 0 -1 0 -0.7071076 -0.7071061 0 -0.4996189 -0.8662453 0 -0.8662425 -0.499624 0 -0.7071076 -0.7071061 0 -1 0 0 -0.8662425 -0.499624 0 -1 0 0 0.499624 -0.8662425 0 0.707103 -0.7071105 0 1.14873e-5 -1 0 0.499624 -0.8662425 0 -0.4996325 -0.8662374 0 1.14873e-5 -1 0 -0.7071068 -0.7071068 0 -0.4996325 -0.8662374 0 -0.8662374 -0.4996325 0 -0.7071068 -0.7071068 0 -1 -5.74359e-6 0 -0.8662374 -0.4996325 0 -2.87938e-6 4.15724e-6 -1 -0.86624 0.4996283 0 -1 -5.74359e-6 0 5.03866e-7 1.00328e-5 -1 -0.7071067 0.7071067 0 2.5973e-5 5.22444e-5 -1 -0.7071068 0.7071068 0 -0.86624 0.4996283 0 -1.58966e-6 4.19887e-6 -1 -0.4996283 0.86624 0 -1.58967e-6 4.19886e-6 -1 -1.43591e-6 4.57036e-6 -1 -1.43587e-6 4.57044e-6 -1 5.74359e-6 1 0 -0.4996283 0.86624 0 -2.53594e-4 -4.13699e-4 -0.9999998 0.4996326 0.8662374 0 -1.73958e-6 3.71521e-6 -1 5.74359e-6 1 0 0.7071065 0.7071071 0 -2.87939e-6 4.15722e-6 -1 0.4996325 0.8662374 0 0.8662453 0.4996189 0 0.7071065 0.7071071 0 1 0 0 0.8662453 0.4996189 0 0.8662453 -0.4996189 0 1 0 0 0.707103 -0.7071105 0 0.8662453 -0.4996189 0 -0.7071087 0.707105 1.5495e-7 -0.8662414 0.4996258 0 -0.8662414 0.4996258 0 -0.7071087 0.7071049 1.56099e-7 -0.499624 0.8662424 1.9123e-7 0 1 2.20758e-7 -0.4996239 0.8662424 1.9123e-7 0.4996326 0.8662374 1.91229e-7 0 1 2.20758e-7 0.7071065 0.7071071 1.561e-7 0.4996325 0.8662374 1.91229e-7 0.8662374 0.4996325 0 0.7071067 0.7071069 0 1 0 0 0.8662374 0.4996325 0 0.8662425 -0.499624 0 1 0 0 0.7071049 -0.7071087 0 0.7071049 -0.7071087 0 0.8662425 -0.499624 0 0.49963 -0.8662388 0 0 -1 0 0.49963 -0.8662388 0 -0.4996325 -0.8662375 0 0 -1 0 -0.7071065 -0.7071071 0 -0.4996325 -0.8662374 0 -0.86624 -0.4996283 0 -0.7071067 -0.7071069 -1.56099e-7 -1 -5.74363e-6 0 -0.86624 -0.4996283 0 -1 -5.74363e-6 0 0.49963 -0.8662388 -1.91229e-7 0.7071049 -0.7071086 -1.58319e-7 0 -1 -2.20758e-7 0.49963 -0.8662388 -1.9163e-7 -0.4996344 -0.8662363 -1.91229e-7 0 -1 -2.20758e-7 -0.7071053 -0.7071082 -1.59122e-7 -0.7071053 -0.7071082 -1.561e-7 -0.4996344 -0.8662364 -1.91229e-7 -0.8662425 -0.499624 0 -1 0 0 -0.8662424 -0.499624 0 -0.8662424 0.499624 0 -1 0 0 -0.7071086 0.7071049 1.54951e-7 -0.7071086 0.7071049 1.56099e-7 -0.8662424 0.499624 0 -0.4996189 0.8662453 1.91231e-7 0 1 2.20758e-7 -0.4996189 0.8662453 1.91231e-7 0.499624 0.8662425 1.9123e-7 0 1 2.20758e-7 0.7071061 0.7071075 1.59122e-7 0.707106 0.7071075 1.561e-7 0.499624 0.8662424 1.9123e-7 0.8662363 0.4996344 0 1 -1.14873e-5 0 0.8662363 0.4996344 0 0.8662425 -0.499624 0 1 -1.14873e-5 0 0.7071049 -0.7071087 -1.561e-7 0.8662425 -0.499624 0 -0.7071067 -0.707107 -1.56099e-7 0.7071068 -0.7071068 -1.56099e-7 0.7071068 -0.7071068 -1.56099e-7 -0.7071068 0.7071068 0 -0.7071064 -0.7071073 0 0.707107 0.7071067 0 -0.7071071 0.7071065 0 0.7071067 0.7071068 1.56099e-7 8.52879e-7 -5.18491e-6 1 8.99006e-6 1.08108e-6 1 2.67015e-6 -4.03608e-6 1 2.26635e-6 -4.35931e-6 1 2.19914e-6 -4.39289e-6 1 2.8913e-6 -5.19264e-6 1 2.32287e-6 -4.71779e-6 1 1.62411e-6 -4.01903e-6 1 1.23125e-6 -4.80003e-6 1 1.5316e-6 -4.30774e-6 1 6.01777e-7 -3.18219e-6 1 1.53715e-6 -3.83849e-6 1 9.63138e-6 -1.19327e-5 1 8.69602e-6 -1.12764e-5 1 2.32285e-6 -4.71777e-6 1 2.89124e-6 -5.19259e-6 1 -2.26921e-5 5.14183e-6 1 1.36984e-6 -3.76475e-6 1 1.65206e-5 -7.34202e-6 1 2.30748e-5 -1.49733e-5 1 4.68534e-6 -7.31947e-6 1 2.18749e-6 -6.67821e-6 1 -8.3815e-7 -7.00599e-6 1 1.35386e-6 -6.30925e-6 1 1.4359e-6 -6.29631e-6 1 5.91428e-7 -5.69952e-6 1 3.5261e-6 -3.43985e-6 1 1.8318e-6 -4.55908e-6 1 1.81095e-6 -4.59013e-6 1 2.24059e-6 -4.1965e-6 1 9.5563e-7 -5.34315e-6 1 1.22633e-5 -1.45646e-5 1 1.35135e-5 -1.5609e-5 1 1.87132e-6 -3.96686e-6 1 8.7287e-7 -5.41515e-6 1 2.19157e-6 -2.87185e-6 1 0 -6.70732e-6 1 2.04326e-6 -4.1936e-6 1 1.53716e-6 -3.83851e-6 1 1.53714e-6 -3.83848e-6 1 2.04324e-6 -4.19358e-6 1 2.26682e-6 -4.36237e-6 1 1.01676e-6 -3.3181e-6 1 -1.75645e-5 2.20825e-6 1 1.91284e-6 -4.00839e-6 1 8.72677e-6 -6.11273e-6 1 -1.73931e-6 -3.98976e-6 1 5.16995e-6 -6.48703e-6 1 3.56004e-6 -6.1723e-6 1 -1.00273e-6 -6.53452e-6 1 -3.00603e-7 -6.29217e-6 1 1.43584e-6 -5.95324e-6 1 -1.59719e-5 6.15599e-7 1 6.56561e-5 -1.35106e-5 1 3.22464e-6 -5.85886e-6 1 5.60127e-6 -6.55919e-6 1 -2.78923e-6 -8.39364e-6 1 3.16058e-6 -5.47978e-6 1 4.71489e-7 -5.69634e-6 1 0 -5.90369e-6 1 1.43597e-6 -5.54049e-6 1 8.62193e-7 -5.16661e-6 1 2.64664e-6 -3.96782e-6 1 8.18995e-7 -5.19384e-6 1 2.22192e-6 -4.41563e-6 1 9.78388e-7 -5.01422e-6 1 2.17323e-6 -2.87181e-6 1 -1.8002e-5 4.51822e-7 1 4.50565e-5 -1.02626e-5 1 5.4031e-6 -6.72021e-6 1 6.2822e-6 -6.95202e-6 1 8.29534e-6 -1.01601e-6 1 1.74144e-6 -5.90474e-6 1 -2.46311e-6 -7.48062e-6 1 1.60116e-6 -5.88041e-6 1 1.43592e-6 -5.9235e-6 1 6.00261e-7 -5.68197e-6 1 2.27005e-6 -4.14326e-6 1 1.82193e-6 -4.85211e-6 1 8.58768e-7 -5.44578e-6 1 3.27916e-6 -3.27916e-6 1 0 -6.21843e-6 1 1.27559e-6 -4.30771e-6 1 1.3137e-6 -4.23523e-6 1 2.20467e-6 -4.37785e-6 1 9.04613e-7 -3.11732e-6 1 1.87589e-6 -4.17964e-6 1 1.41532e-6 -3.812e-6 1 1.86022e-6 -4.18593e-6 1 1.1731e-6 -3.52082e-6 1 1.92276e-6 -4.18146e-6 1 1.58948e-6 -3.97215e-6 1 1.17227e-6 -3.85793e-6 1 3.77465e-6 -5.49825e-6 1 2.75801e-6 -5.15418e-6 1 7.81969e-7 -3.32773e-6 1 -6.04574e-7 -1.44754e-6 1 -4.19924e-5 3.7742e-5 1 2.49171e-6 -4.69331e-6 1 2.68279e-7 -3.57225e-6 1 4.02163e-6 -6.52793e-6 1 -4.46354e-7 -2.99641e-6 1 -4.5735e-7 -2.98708e-6 1 2.60244e-6 -5.8099e-6 1 -7.37e-7 -3.35597e-6 1 1.54212e-6 -4.71449e-6 1 -3.33362e-7 -3.62849e-6 1 9.63577e-6 -1.14041e-5 1 2.09608e-6 -4.51054e-6 1 1.44047e-6 -3.7649e-6 1 1.35192e-6 -3.71272e-6 1 1.89213e-6 -4.081e-6 1 1.17546e-6 -3.49658e-6 1 1.92327e-6 -4.18666e-6 1 1.02573e-6 -3.37569e-6 1 1.28149e-6 -3.5369e-6 1 2.41332e-6 -4.50995e-6 1 -3.14e-7 -1.98911e-6 1 7.81502e-6 -1.02834e-5 1 4.14859e-6 -6.27386e-6 1 -2.32472e-5 1.98601e-5 1 -7.98702e-6 3.86313e-6 1 -4.20306e-6 5.34753e-7 1 -3.79582e-7 -3.0167e-6 1 1.29803e-6 -4.67368e-6 1 1.55761e-5 -1.3642e-5 1 7.77717e-7 -4.10985e-6 1 5.48328e-7 -2.96548e-6 1 1.9788e-6 -4.11927e-6 1 8.89661e-7 -4.89823e-6 1 1.82963e-6 -4.13859e-6 1 3.40176e-6 -5.81211e-6 1 2.43237e-6 -5.72521e-6 1 6.07493e-6 -8.2001e-6 1 2.68029e-6 -5.01133e-6 1 2.25978e-6 -4.63074e-6 1 5.22175e-6 -7.59271e-6 1 1.85893e-6 -4.12378e-6 1 1.45492e-6 -3.78596e-6 1 1.52037e-6 -3.65715e-6 1 7.38697e-7 -3.00355e-6 1 2.22808e-6 -4.42967e-6 1 2.91087e-6 -5.04765e-6 1 6.78999e-7 -3.16619e-6 1 7.15955e-6 -9.28471e-6 1 3.61217e-6 -5.15834e-6 1 2.67038e-6 -5.34064e-6 1 1.64895e-6 -3.8373e-6 1 7.3459e-7 -3.00562e-6 1 1.49059e-6 -3.71582e-6 1 2.39931e-6 -5.51553e-6 1 3.52517e-6 -6.1233e-6 1 5.17605e-6 -7.30134e-6 1 9.96728e-7 -4.68754e-6 1 9.03281e-7 -4.6094e-6 1 9.03273e-7 -4.60939e-6 1 2.45002e-6 -5.83709e-6 1 -7.49919e-7 -2.94089e-6 1 1.25057e-6 -4.78587e-6 1 3.17094e-6 -5.89793e-6 1 9.43159e-7 -4.58911e-6 1 1.01647e-6 -4.64873e-6 1 2.41223e-6 -5.59746e-6 1 1.6849e-6 -5.34665e-6 1 3.29434e-7 -4.57976e-6 1 8.64427e-7 -3.19547e-6 1 2.22808e-6 -4.42968e-6 1 4.77414e-6 -6.97575e-6 1 9.29626e-6 -1.16273e-5 1 1.46244e-6 -3.77118e-6 1 8.8203e-6 -1.24122e-5 1 2.05041e-6 -4.08779e-6 1 2.2047e-6 -4.28141e-6 1 -8.67854e-6 4.42807e-6 1 5.1451e-6 -7.2703e-6 1 7.80168e-7 -4.71169e-6 1 -2.46601e-5 1.66549e-5 1 1.9177e-6 -4.01325e-6 1 4.88841e-6 -8.23124e-6 1 1.45847e-6 -3.90135e-6 1 2.10138e-6 -4.1021e-6 1 5.85286e-7 -2.94236e-6 1 1.24307e-6 -3.58166e-6 1 -3.77956e-6 2.25605e-7 1 2.88251e-6 -5.27933e-6 1 1.45843e-6 -4.83271e-6 1 -1.39865e-6 -3.61163e-6 1 7.74148e-7 -4.45979e-6 1 -5.02981e-7 -3.98976e-6 1 5.95759e-6 -7.517e-6 1 2.53688e-6 -4.80729e-6 1 1.23257e-6 -3.58125e-6 1 1.64e-6 -3.77511e-6 1 1.75087e-6 -3.91357e-6 1 -1.20227e-6 -1.64226e-6 1 -7.62267e-7 -1.79017e-6 1 -2.07554e-7 -2.46271e-6 1 -2.67334e-6 -2.38557e-6 1 1.64154e-6 -4.91558e-6 1 8.22836e-7 -4.69856e-6 1 1.56401e-6 -3.78572e-6 1 1.87118e-6 -4.28102e-6 1 1.07535e-6 -3.46731e-6 1 4.17527e-7 -2.6478e-6 1 3.22385e-6 -5.41758e-6 1 1.40359e-6 -3.85175e-6 1 2.73075e-6 -3.58837e-6 1 1.38186e-6 -4.16893e-6 1 2.58067e-6 -4.68613e-6 1 1.8972e-6 -4.24913e-6 1 -1.38283e-5 -1.05161e-5 1 -5.46718e-6 -7.37156e-6 1 4.32031e-7 -4.36326e-6 1 8.71727e-7 -5.1478e-6 1 2.32311e-6 -4.71953e-6 1 2.49243e-6 -4.68617e-6 1 3.31551e-7 -3.21008e-6 1 2.7652e-6 -4.65305e-6 1 1.389e-6 -4.13005e-6 1 -4.14887e-6 -5.5966e-6 1 2.20719e-6 -3.98446e-6 1 1.81647e-6 -4.0102e-6 1 -2.63897e-6 -2.74165e-6 1 -1.11282e-6 -3.97613e-6 1 -1.06777e-6 -4.0285e-6 1 1.26585e-6 -6.33271e-6 1 2.60663e-7 -5.66311e-6 1 -5.64632e-7 -4.54245e-6 1 2.36537e-6 -4.98757e-6 1 4.19793e-7 -5.95769e-6 1 2.66623e-6 -4.85995e-6 1 2.39453e-6 -5.11426e-6 1 2.42788e-6 -4.945e-6 1 2.8423e-6 -3.59681e-6 1 9.3501e-7 -5.02332e-6 1 3.07072e-6 -5.41537e-6 1 2.14046e-6 -4.37566e-6 1 8.024e-7 -5.08839e-6 1 2.28086e-6 -4.47461e-6 1 -1.26353e-7 -3.13785e-6 1 2.45331e-6 -5.54518e-6 1 2.15642e-6 -5.24828e-6 1 1.99635e-6 -4.5734e-6 1 1.40597e-6 -4.51748e-6 1 0 -3.32058e-6 1 1.4945e-6 -3.92242e-6 1 -1.47655e-5 1.1654e-5 1 3.16108e-6 -5.41894e-6 1 2.29029e-6 -4.51116e-6 1 2.01186e-6 -4.59942e-6 1 2.3125e-6 -4.50624e-6 1 0 -3.17597e-6 1 1.4837e-6 -4.05153e-6 1 1.72086e-6 -4.59301e-6 1 2.72896e-7 -5.09333e-6 1 4.04687e-6 -6.24061e-6 1 7.25578e-7 -3.2722e-6 1 3.05982e-6 -5.69399e-6 1 8.51093e-6 -7.37821e-6 1 2.14814e-6 -4.14028e-6 1 1.62272e-6 -3.67016e-6 1 5.91017e-7 -3.74788e-6 1 1.95099e-6 -4.10339e-6 1 6.20793e-6 -6.20793e-6 1 -2.442e-7 -4.69816e-6 1 -1.23422e-5 3.13658e-6 1 2.43899e-6 -4.70289e-6 1 1.51699e-7 -2.81325e-6 1 -5.63651e-7 -1.74939e-6 1 2.38995e-6 -4.47278e-6 1 1.32624e-6 -3.90437e-6 1 4.33868e-6 -5.6674e-6 1 -1.82609e-6 -1.52639e-6 1 1.3471e-5 -1.26953e-5 1 4.23733e-6 -5.78563e-6 1 -1.96935e-7 -2.44371e-6 1 2.75932e-6 -4.77998e-6 1 2.2248e-6 -4.31121e-6 1 -1.52845e-6 -4.03067e-6 1 3.90711e-6 -6.02152e-6 1 -3.73773e-7 -4.5504e-6 1 2.96212e-6 -6.41202e-6 1 2.38999e-6 -6.02684e-6 1 -1.54705e-6 -2.97198e-6 1 8.03737e-6 -1.10902e-5 1 2.11938e-6 -4.46828e-6 1 7.54885e-6 -1.0662e-5 1 -1.42712e-5 4.61142e-6 1 1.65205e-6 -3.91655e-6 1 2.71338e-6 -4.77993e-6 1 4.75003e-6 -6.01171e-6 1 -3.0512e-6 5.42463e-7 1 1.86626e-5 -1.02716e-5 1 -7.83487e-7 -3.12224e-6 1 8.70405e-7 -3.80013e-6 1 2.33452e-6 -4.79812e-6 1 4.65306e-7 -3.33111e-6 1 6.49678e-6 -8.6547e-6 1 1.84811e-6 -4.35685e-6 1 2.98989e-6 -3.64709e-6 1 8.46942e-7 -4.82842e-6 1 2.77852e-6 -3.89196e-6 1 1.22199e-6 -4.46184e-6 1 4.56562e-7 -4.09671e-6 1 3.73535e-6 -6.10729e-6 1 -2.53018e-5 1.64105e-5 1 1.25503e-6 -3.62698e-6 1 -1.04077e-6 -2.07235e-6 1 0 -6.06687e-6 1 -3.96897e-7 -6.45913e-6 1 1.43587e-6 -5.0378e-6 1 1.38329e-5 4.25038e-6 1 -4.15654e-6 -5.72605e-6 1 9.89152e-7 -5.03184e-6 1 9.26327e-6 -7.02401e-6 1 1.43592e-6 -3.877e-6 1 2.62414e-6 -4.54976e-6 1 5.74179e-7 -3.20835e-6 1 1.45484e-6 -4.55584e-6 1 1.15664e-6 -4.38949e-6 1 5.82399e-6 -9.05683e-6 1 4.62332e-6 -7.65966e-6 1 2.01461e-6 -4.30777e-6 1 1.0698e-6 -2.71157e-6 1 2.12966e-6 -5.23066e-6 1 8.30417e-7 -4.0765e-6 1 3.68852e-6 -6.52536e-6 1 1.49642e-6 -4.74251e-6 1 3.70624e-7 -3.43803e-6 1 1.60572e-6 -4.44256e-6 1 0 -3.57228e-6 1 2.72872e-6 -5.79613e-6 1 1.04892e-5 -1.28411e-5 1 3.92182e-6 -7.49966e-6 1 -1.12629e-6 -5.64256e-6 1 2.78898e-7 -5.25286e-6 1 2.95214e-7 -5.25929e-6 1 2.87181e-6 -6.78442e-6 1 4.76149e-6 -8.25511e-6 1 1.08767e-5 -1.35104e-5 1 3.17094e-5 1.80359e-5 1 -5.31956e-7 -6.597e-6 1 -4.29057e-7 -6.51488e-6 1 2.87181e-6 -3.91925e-6 1 -3.51294e-7 -3.12601e-6 1 3.17769e-7 -4.3077e-6 1 3.74069e-6 -1.28213e-5 1 1.8118e-6 -4.0993e-6 1 9.09743e-7 -3.54392e-6 1 1.22148e-6 -4.60628e-6 1 2.21373e-6 -4.60415e-6 1 1.27338e-6 -4.61977e-6 1 2.61864e-6 -4.54011e-6 1 2.42026e-6 -5.05442e-6 1 1.19856e-4 6.58027e-5 1 1.4379e-6 -5.82229e-6 1 2.87798e-6 -4.98857e-6 1 4.52295e-6 -4.30772e-6 1 8.56665e-6 -2.87175e-6 1 5.72492e-5 2.80275e-5 1 2.42024e-6 -5.05442e-6 1 2.70894e-6 -4.69666e-6 1 4.94717e-7 2.45808e-6 -1 -0.4530796 0.8914701 5.90397e-7 1.52491e-5 -5.134e-6 -1 -0.8914738 0.4530722 0 -2.55599e-6 5.26931e-6 -1 -2.70543e-6 5.5057e-6 -1 -0.8914764 0.4530672 3.00055e-7 -1.66893e-6 4.43497e-6 -1 0.1557735 0.9877929 2.18063e-7 -0.4530696 0.891475 1.96817e-7 -1.9208e-6 4.66044e-6 -1 0.7071036 0.7071099 1.561e-7 0.1557735 0.9877929 2.18063e-7 -1.91655e-6 3.64502e-6 -1 0.9877935 0.1557694 0 -1.35947e-5 -6.11058e-6 -1 -1.75352e-6 5.7306e-6 -1 -2.12539e-6 4.83911e-6 -1 -1.38189e-6 3.58975e-6 -1 -1.78642e-6 4.35899e-6 -1 0.7071037 0.7071099 1.561e-7 -3.82586e-6 4.56049e-6 -1 0.8914688 -0.4530821 0 5.64197e-6 1.12035e-5 -1 0.9877935 0.1557694 0 -2.77887e-6 5.46761e-6 -1 0.4530821 -0.8914688 -1.96799e-7 -3.2477e-6 5.13866e-6 -1 0.8914688 -0.4530821 0 -4.7334e-7 7.01077e-6 -1 -0.1557684 -0.9877936 -2.18063e-7 -5.10424e-6 3.14224e-6 -1 0.4530821 -0.8914688 -1.96799e-7 4.5849e-7 5.94292e-6 -1 -0.7071037 -0.7071099 -1.561e-7 -2.13109e-6 5.35301e-6 -1 -0.1557684 -0.9877936 -2.18063e-7 1.56813e-6 4.19449e-6 -1 -0.9877929 -0.1557735 0 2.97998e-6 6.71168e-6 -1 -1.07338e-5 3.09551e-6 -1 -0.7071037 -0.7071099 -1.561e-7 3.73399e-6 1.78526e-6 -1 -2.42935e-6 4.21191e-6 -1 -1.43588e-6 3.95284e-6 -1 -1.06199e-6 3.92988e-6 -1 -0.9877929 -0.1557735 0 -1.38569e-6 4.44225e-6 -1 -0.4530746 0.8914726 0 1.33918e-6 1.9354e-6 -1 -0.8914726 0.4530746 0 -3.41038e-6 5.80244e-6 -1 -0.8914726 0.4530746 0 -1.64233e-6 4.60402e-6 -1 0.1557614 0.9877947 0 -0.4530746 0.8914726 0 -1.85777e-6 4.72352e-6 -1 0.707113 0.7071006 0 0.1557614 0.9877947 0 -1.68894e-6 3.68086e-6 -1 0.9877929 0.1557735 0 -2.71216e-6 2.82608e-6 -1 -1.60817e-6 3.93007e-6 -1 -1.95184e-6 4.76881e-6 -1 -1.6947e-6 4.30774e-6 -1 0.707113 0.7071006 0 -1.97245e-6 3.61847e-6 -1 0.8914726 -0.4530746 0 -1.23131e-6 4.13849e-6 -1 0.9877929 0.1557735 0 -2.71421e-6 5.34049e-6 -1 0.4530746 -0.8914726 0 5.54367e-6 1.11346e-5 -1 0.8914726 -0.4530746 0 -5.01401e-7 6.83303e-6 -1 -0.1557595 -0.9877951 0 -4.87644e-6 3.17826e-6 -1 0.4530746 -0.8914726 0 4.94625e-7 5.979e-6 -1 -0.707113 -0.7071006 0 -1.99476e-6 5.33967e-6 -1 -0.1557595 -0.9877951 0 -2.04783e-5 1.5075e-6 -1 -0.9877947 -0.1557614 0 0 5.80005e-6 -1 -1.0432e-5 2.73881e-6 -1 -0.707113 -0.7071006 0 -6.56665e-7 3.58638e-6 -1 -2.4626e-6 4.26968e-6 -1 -1.43592e-6 4.02314e-6 -1 -1.0167e-6 4.00838e-6 -1 -0.9877947 -0.1557614 0 -0.4530747 0.8914726 0 -0.8914726 0.4530746 0 -0.8914726 0.4530747 0 0.1557633 0.9877943 0 -0.4530747 0.8914726 0 -1.92506e-5 -1.70092e-6 -1 0.7071006 0.707113 0 0.1557633 0.9877943 0 1.33925e-5 6.05901e-6 -1 0.9877947 0.1557614 0 1.32217e-6 6.59048e-6 -1 -5.73317e-7 6.21993e-6 -1 9.06417e-6 9.38874e-6 -1 0.7071006 0.707113 0 2.78615e-7 3.34641e-6 -1 0.8914726 -0.4530746 0 -4.51399e-6 6.62133e-6 -1 -2.60723e-6 5.96318e-6 -1 -1.43596e-6 5.73457e-6 -1 0.9877947 0.1557614 0 -1.00479e-6 3.69282e-6 -1 0.4530696 -0.8914752 0 -5.51744e-7 3.27627e-6 -1 -1.31839e-6 4.41746e-6 -1 0.8914726 -0.4530746 0 -2.37809e-6 4.94443e-6 -1 -0.1557614 -0.9877947 0 0.4530696 -0.8914752 0 -8.27125e-7 3.56039e-6 -1 -0.707113 -0.7071006 0 -0.1557614 -0.9877947 0 -0.9877947 -0.1557614 0 -2.77144e-6 5.25192e-6 -1 -1.48297e-6 3.58977e-6 -1 -1.26794e-6 3.22782e-6 -1 -0.707113 -0.7071006 0 -0.9877947 -0.1557614 0 -0.4530796 0.8914701 1.96799e-7 -0.8914688 0.4530821 0 -0.8914688 0.4530821 0 0.1557735 0.9877929 2.18063e-7 -0.4530796 0.89147 1.96816e-7 3.16299e-6 7.55047e-6 -1 0.7071099 0.7071037 1.56099e-7 0.1557735 0.9877929 2.18063e-7 1.6522e-5 7.34209e-6 -1 0.9877936 0.1557684 0 7.39382e-7 6.66623e-6 -1 4.7758e-7 6.59902e-6 -1 8.50391e-6 9.89788e-6 -1 0.7071099 0.7071037 1.56099e-7 -1.41139e-6 4.20535e-6 -1 0.8914713 -0.4530771 0 -4.41681e-6 6.67834e-6 -1 -3.72511e-6 6.45849e-6 -1 -1.43599e-6 6.09723e-6 -1 0.9877936 0.1557684 0 -2.1432e-6 4.21691e-6 -1 0.4530796 -0.8914701 -1.96799e-7 1.1297e-6 2.14787e-6 -1 0.8914713 -0.4530771 0 -1.74045e-6 3.98167e-6 -1 -0.1557684 -0.9877936 -2.18063e-7 0.4530796 -0.8914701 -1.96799e-7 -1.58194e-6 3.90246e-6 -1 -0.7071099 -0.7071037 -1.56099e-7 -0.1557684 -0.9877936 -2.18063e-7 -0.9877918 -0.1557796 0 -1.81731e-6 4.00147e-6 -1 -1.56616e-6 3.58981e-6 -1 -0.7071099 -0.7071037 -1.56099e-7 -0.9877918 -0.1557796 0 4.72646e-6 1.07256e-5 -1 -0.6331806 0.7740041 3.41735e-7 -2.02676e-6 4.55106e-6 -1 -0.7739993 0.6331864 2.79562e-7 -0.7739993 0.6331864 2.79562e-7 -1.34578e-6 4.13644e-6 -1 -0.4709711 0.8821486 3.89482e-7 -1.50961e-6 4.0399e-6 -1 -0.6331805 0.7740041 3.41503e-7 -1.9181e-6 3.7359e-6 -1 -0.2907112 0.9568108 4.22447e-7 -0.4709711 0.8821486 3.89482e-7 -1.18013e-6 4.33769e-6 -1 -0.09688156 0.995296 4.39439e-7 -0.2907112 0.9568108 4.22447e-7 -1.27426e-5 -6.33219e-6 -1 0.09686839 0.9952973 4.39439e-7 -0.09688156 0.995296 4.39439e-7 -1.2139e-7 7.33119e-6 -1 0.2907366 0.9568032 4.22444e-7 2.19461e-6 8.791e-6 -1 0.09686839 0.9952972 4.3944e-7 -5.50636e-7 6.98031e-6 -1 0.4718073 0.8817018 5.7026e-7 0.2907289 0.9568055 7.16528e-7 5.24214e-6 1.23345e-5 -1 0.6334827 0.7737569 3.41626e-7 0.4718117 0.8816994 3.89284e-7 -1.63117e-5 -8.49814e-6 -1 0.7737579 0.6334813 2.79692e-7 2.18442e-5 2.8449e-5 -1 3.62327e-6 9.34835e-6 -1 4.98919e-5 5.52049e-5 -1 0.6334826 0.7737568 3.41626e-7 -2.85416e-6 3.61575e-6 -1 0.8817018 0.4718073 2.0831e-7 0.7737579 0.6334813 2.79692e-7 -2.51018e-6 3.93527e-6 -1 0.9567975 0.2907552 1.28373e-7 0.8817018 0.4718073 2.0831e-7 -2.94829e-6 3.50254e-6 -1 0.9952972 0.09686839 1.28307e-7 0.9567955 0.2907619 3.85128e-7 -2.69349e-6 4.05172e-6 -1 0.995296 -0.0968815 0 -2.07224e-6 4.45188e-6 -1 0.9952974 0.09686607 0 -2.79336e-6 3.98076e-6 -1 0.9568108 -0.2907113 -1.28354e-7 0.995296 -0.0968815 0 -2.07637e-6 4.55907e-6 -1 0.8821486 -0.4709712 -2.07941e-7 0.9568108 -0.2907113 -1.28354e-7 -2.05777e-6 4.57643e-6 -1 0.7739993 -0.6331864 -2.79562e-7 0.8821486 -0.4709712 -2.07941e-7 -2.50491e-6 4.24082e-6 -1 0.6331806 -0.7740041 -3.41735e-7 -2.1923e-6 4.42929e-6 -1 0.7739993 -0.6331864 -2.79562e-7 -1.70692e-6 4.81287e-6 -1 0.4709712 -0.8821486 -3.89483e-7 0.6331806 -0.7740041 -3.41735e-7 -2.13582e-6 4.45238e-6 -1 0.2907146 -0.9568098 -4.22447e-7 0.4709712 -0.8821486 -3.89483e-7 -1.27263e-6 5.28792e-6 -1 0.0968815 -0.995296 -4.39439e-7 0.2907146 -0.9568098 -4.22447e-7 -1.82615e-6 4.59812e-6 -1 -0.09686726 -0.9952974 -4.3944e-7 -2.02315e-6 4.4744e-6 -1 0.0968815 -0.995296 -4.39439e-7 -1.2139e-7 7.33119e-6 -1 -0.2907366 -0.9568032 -8.44888e-7 1.87176e-5 1.92057e-5 -1 -0.09687918 -0.9952961 -8.78878e-7 -5.50808e-7 6.98017e-6 -1 -0.4717979 -0.8817068 -3.89288e-7 -0.2907256 -0.9568065 -4.22445e-7 5.24308e-6 1.23354e-5 -1 -0.6334899 -0.773751 -3.41623e-7 -0.4717978 -0.8817068 -3.89288e-7 -3.77761e-6 1.7636e-6 -1 -0.7737532 -0.6334872 -2.79695e-7 -4.54831e-6 9.55682e-7 -1 -3.23281e-4 -3.03098e-4 -1 -0.6334899 -0.773751 -3.41623e-7 -3.27158e-6 3.39234e-6 -1 -0.8817044 -0.4718022 -2.08308e-7 1.82002e-7 6.11197e-6 -1 -0.7737532 -0.6334872 -2.79695e-7 -2.65077e-6 3.89258e-6 -1 -0.9568009 -0.2907443 1.65706e-7 -0.8817021 -0.4718066 0 -3.13106e-6 3.48479e-6 -1 -0.9952983 -0.09685647 0 -0.9568032 -0.2907366 -1.28365e-7 -2.53343e-6 4.03614e-6 -1 -0.995296 0.0968815 0 -0.9952983 -0.09685647 0 -2.84574e-6 3.99664e-6 -1 -0.9568142 0.2907003 1.28349e-7 -2.19783e-6 4.38285e-6 -1 -0.995296 0.0968815 0 -2.04085e-6 4.54008e-6 -1 -0.8821537 0.4709616 2.07937e-7 -0.9568142 0.2907003 1.28349e-7 -0.8821537 0.4709616 2.07937e-7 -2.4338e-6 4.78883e-6 -1 -0.4530695 0.8914753 3.93601e-7 -2.55325e-6 4.67662e-6 -1 -0.8914777 0.4530648 2.00035e-7 -0.8914777 0.4530648 2.00035e-7 -1.47731e-6 5.18132e-6 -1 0.1557683 0.9877936 4.36127e-7 -2.62629e-6 4.56107e-6 -1 -0.4530695 0.8914752 3.93585e-7 5.27068e-6 9.52116e-6 -1 0.7071008 0.7071128 3.12202e-7 0.1557683 0.9877936 4.36127e-7 -1.12494e-6 4.41128e-6 -1 0.9877939 0.1557664 0 -7.8549e-7 4.71851e-6 -1 0.7071008 0.7071128 3.12202e-7 -1.3773e-6 4.07893e-6 -1 0.89148 -0.4530599 -2.00033e-7 -1.86552e-6 3.6707e-6 -1 0.9877939 0.1557664 0 -1.8655e-6 3.67072e-6 -1 0.4530599 -0.89148 -3.93603e-7 -1.37725e-6 4.07898e-6 -1 0.89148 -0.4530599 -2.00033e-7 -1.47151e-6 5.21797e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 1.06786e-5 1.62148e-5 -1 0.4530599 -0.89148 -3.93603e-7 4.82012e-6 1.01331e-5 -1 -0.7071068 -0.7071068 -3.12199e-7 -6.03188e-6 6.57593e-7 -1 -0.1557664 -0.9877939 -4.36127e-7 -4.67947e-6 3.08598e-6 -1 -0.9877939 -0.1557664 0 -4.32185e-6 2.10121e-6 -1 -2.788e-6 4.35875e-6 -1 -0.7071068 -0.7071068 -3.12199e-7 -0.9877939 -0.1557664 0 -0.4530648 0.8914777 3.93602e-7 -0.8914728 0.4530743 2.0004e-7 -0.8914728 0.4530743 2.0004e-7 0.1557664 0.9877939 4.36127e-7 -0.4530648 0.8914777 3.93591e-7 0.7071008 0.7071128 3.12202e-7 0.1557664 0.9877939 4.36127e-7 -2.15104e-6 3.48469e-6 -1 0.9877939 0.1557664 0 0.7071008 0.7071128 3.12202e-7 -1.4213e-6 4.1014e-6 -1 0.8914751 -0.4530696 -2.00038e-7 0.9877939 0.1557664 0 -1.91313e-6 3.76423e-6 -1 0.4530791 -0.8914703 -3.93598e-7 -1.64715e-6 3.86099e-6 -1 0.8914751 -0.4530696 -2.00037e-7 -1.68114e-6 3.88859e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 0.4530791 -0.8914703 -3.93598e-7 2.43487e-6 6.68516e-6 -1 -0.7071128 -0.7071008 -3.12196e-7 -0.1557664 -0.9877939 -4.36127e-7 -0.9877921 -0.1557782 0 -0.7071127 -0.7071008 -3.12196e-7 -0.987792 -0.1557782 0 -2.32371e-6 4.57228e-6 -1 -0.4530648 0.8914777 3.93602e-7 -2.33289e-6 4.5646e-6 -1 -0.8914753 0.4530695 2.00037e-7 -2.33287e-6 4.56462e-6 -1 -0.8914753 0.4530695 2.00037e-7 -1.47151e-6 5.21797e-6 -1 0.1557664 0.9877939 4.36127e-7 -3.64724e-6 3.24876e-6 -1 -0.4530647 0.8914776 3.93591e-7 2.40242e-6 7.71546e-6 -1 0.7071008 0.7071128 3.12202e-7 -4.28017e-6 2.40931e-6 -1 0.1557664 0.9877939 4.36127e-7 -4.30504e-6 3.14503e-6 -1 0.9877939 0.1557664 0 -2.62075e-5 -1.52504e-5 -1 0.7071008 0.7071128 3.12202e-7 -2.65295e-6 4.72733e-6 -1 0.8914728 -0.4530743 -2.0004e-7 0.9877939 0.1557664 0 -2.38119e-6 4.68524e-6 -1 0.4530743 -0.8914727 -3.93599e-7 -2.92557e-6 4.39211e-6 -1 0.8914727 -0.4530743 -2.0004e-7 -1.45513e-6 5.32181e-6 -1 -0.1557664 -0.9877939 -4.36127e-7 0.4530743 -0.8914728 -3.93599e-7 5.87386e-6 1.1187e-5 -1 -0.7071008 -0.7071128 -3.12202e-7 -0.1557664 -0.9877939 -4.36127e-7 -3.64723e-6 3.24876e-6 -1 -0.9877939 -0.1557664 0 -5.79406e-7 6.02539e-6 -1 -0.7071008 -0.7071128 -3.12202e-7 -2.32369e-6 4.5723e-6 -1 -0.9877939 -0.1557664 0 -1.8784e-6 3.69586e-6 -1 -0.4530839 0.8914679 3.93597e-7 -1.3957e-6 4.08841e-6 -1 -0.8914703 0.4530792 2.00042e-7 -0.8914703 0.4530792 2.00042e-7 -1.69116e-6 3.82501e-6 -1 0.1557664 0.9877939 4.36127e-7 -1.78603e-6 3.7923e-6 -1 -0.4530839 0.8914679 3.93587e-7 -1.29367e-6 4.01924e-6 -1 0.7071068 0.7071068 3.12199e-7 0.1557664 0.9877939 4.36127e-7 0.9877939 0.1557664 0 0.7071068 0.7071068 3.12199e-7 0.8914776 -0.4530647 -2.00035e-7 0.9877939 0.1557664 0 0.4530599 -0.8914801 -3.93603e-7 0.8914776 -0.4530647 -2.00035e-7 -0.1557664 -0.9877939 -4.36127e-7 0.4530599 -0.8914801 -3.93603e-7 -0.7071068 -0.7071068 -3.12199e-7 -0.1557664 -0.9877939 -4.36127e-7 -8.14931e-7 4.46015e-6 -1 -0.9877921 -0.1557782 0 -1.66527e-6 3.96774e-6 -1 -0.7071068 -0.7071068 -3.12199e-7 -0.987792 -0.1557782 0 -1.53989e-6 4.02585e-6 -1 -0.5555153 0.8315063 3.67123e-7 -1.62399e-6 3.95922e-6 -1 -0.8315099 0.5555101 2.45267e-7 -0.8315098 0.5555101 2.45267e-7 -1.89894e-6 4.65817e-6 -1 -0.1950771 0.9807879 4.33033e-7 -3.50063e-7 5.39516e-6 -1 -0.5555153 0.8315063 3.66519e-7 -1.44691e-6 4.948e-6 -1 0.1950845 0.9807865 4.33033e-7 -0.1950771 0.9807879 4.33033e-7 0 6.10056e-6 -1 0.5555101 0.8315098 3.67125e-7 0.1950845 0.9807865 4.33033e-7 -3.10843e-6 3.09704e-6 -1 0.8315098 0.5555101 2.45267e-7 -2.08399e-6 4.33908e-6 -1 0.5555101 0.8315098 3.67125e-7 -5.06063e-6 2.88326e-6 -1 0.9807891 0.1950713 0 -1.80439e-6 4.79254e-6 -1 0.8315099 0.5555101 2.45267e-7 4.62468e-6 9.29086e-6 -1 0.9807891 -0.1950712 0 0.9807891 0.1950712 0 -1.56029e-6 3.91659e-6 -1 0.8315145 -0.555503 -2.45264e-7 0.9807891 -0.1950712 0 -1.96237e-6 3.79782e-6 -1 0.5555101 -0.8315098 -3.67125e-7 -1.5807e-6 3.89082e-6 -1 0.8315146 -0.555503 -2.45263e-7 -1.30482e-6 4.1159e-6 -1 0.1950683 -0.9807897 -4.33034e-7 0.5555101 -0.8315098 -3.67125e-7 -2.24115e-6 3.39964e-6 -1 -0.1950889 -0.9807856 -4.33032e-7 0.1950683 -0.9807897 -4.33034e-7 7.9038e-7 6.34598e-6 -1 -0.5554977 -0.8315181 -3.67129e-7 -0.1950889 -0.9807856 -4.33033e-7 1.94802e-5 2.56606e-5 -1 -0.8315157 -0.5555012 -2.45263e-7 -1.59607e-6 3.87475e-6 -1 -3.79302e-6 3.18572e-6 -1 -0.5554977 -0.8315181 -3.67129e-7 -1.03076e-6 4.171e-6 -1 -0.9807845 -0.1950948 0 -1.63436e-6 3.93538e-6 -1 -0.8315157 -0.5555012 -2.45263e-7 -1.93636e-6 3.78868e-6 -1 -0.9807865 0.1950845 0 -0.9807844 -0.1950947 0 -0.9807864 0.1950845 0 -1.30433e-6 4.28216e-6 -1 -0.4530771 0.8914713 0 -1.97934e-6 3.62199e-6 -1 -0.8914725 0.4530746 0 -0.8914725 0.4530746 0 -1.64024e-6 4.61718e-6 -1 0.1557644 0.9877943 0 -1.21781e-6 4.40655e-6 -1 -0.4530771 0.8914713 0 -1.86763e-6 4.71365e-6 -1 0.7071052 0.7071083 0 0.1557644 0.9877943 0 -1.4716e-6 3.71513e-6 -1 0.9877943 0.1557639 0 -1.65327e-6 4.63715e-6 -1 0.7071052 0.7071083 0 -8.07342e-6 6.7192e-6 -1 0.8914725 -0.4530746 0 -1.83115e-6 4.93363e-6 -1 0.9877943 0.1557639 0 -2.69043e-6 5.29366e-6 -1 0.4530771 -0.8914713 0 0.8914725 -0.4530746 0 -7.97249e-7 4.95679e-6 -1 -0.1557644 -0.9877943 0 0.4530771 -0.8914713 0 -1.57334e-6 5.00793e-6 -1 -0.7071036 -0.7071098 0 -0.1557644 -0.9877943 0 -1.71008e-6 3.67754e-6 -1 -0.9877949 -0.1557609 0 -1.83651e-6 3.57398e-6 -1 -5.93185e-7 5.01933e-6 -1 -0.7071036 -0.7071098 0 -1.34737e-6 4.04297e-6 -1 -0.9877949 -0.1557609 0 -2.06467e-6 4.06245e-6 -1 -0.4530759 0.891472 1.96799e-7 1.25544e-6 2.84999e-6 -1 -0.8914725 0.4530746 0 -0.8914725 0.4530746 0 -1.7427e-6 3.96744e-6 -1 0.1557644 0.9877942 2.18063e-7 -0.4530759 0.891472 1.96817e-7 -1.55411e-6 3.93028e-6 -1 0.7071037 0.7071099 2.3415e-7 0.1557614 0.9877947 3.27095e-7 1.49099e-5 1.57715e-5 -1 0.9877949 0.1557604 0 -4.46486e-6 4.28369e-6 -1 0.7071052 0.7071083 1.561e-7 -8.64091e-7 4.79921e-6 -1 0.8914713 -0.4530771 -1.50031e-7 0.9877948 0.1557609 0 -1.88623e-6 3.71134e-6 -1 0.4530771 -0.8914713 -1.96799e-7 -2.00153e-6 3.63621e-6 -1 0.8914719 -0.4530758 0 -1.76396e-6 3.8327e-6 -1 -0.1557614 -0.9877947 -3.27095e-7 0.4530746 -0.8914725 -2.95199e-7 -1.3998e-6 4.08457e-6 -1 -0.7071098 -0.7071036 -2.34148e-7 -1.93413e-6 3.62493e-6 -1 -0.1557614 -0.9877947 -3.27095e-7 -1.8847e-5 1.12379e-5 -1 -0.9877939 -0.155767 0 -1.72733e-6 3.8696e-6 -1 -1.89818e-6 3.79589e-6 -1 -1.2756e-6 4.19396e-6 -1 -0.7071083 -0.7071052 -1.56099e-7 -1.00512e-6 5.22346e-6 -1 1.03745e-5 -5.79557e-7 -1 -0.9877939 -0.155767 0 -2.26799e-6 6.17829e-6 -1 -0.4530734 0.8914732 0 -3.9855e-6 4.64157e-6 -1 -0.8914726 0.4530746 0 -0.8914726 0.4530746 0 -1.43585e-6 5.91306e-6 -1 0.155775 0.9877925 0 -2.72414e-6 5.57628e-6 -1 -0.4530734 0.8914732 0 0 6.51123e-6 -1 0.7071052 0.7071083 0 0.155775 0.9877925 0 -1.85563e-6 3.65459e-6 -1 0.9877923 0.1557775 0 1.17488e-5 1.24649e-5 -1 0.7071052 0.7071083 0 -1.93066e-6 3.59725e-6 -1 0.8914701 -0.4530796 0 0.9877923 0.1557775 0 -1.57592e-6 4.81647e-6 -1 0.4530808 -0.8914694 0 -2.5791e-6 3.92679e-6 -1 6.67561e-6 1.31815e-5 -1 0.8914701 -0.4530796 0 -1.63083e-6 4.67658e-6 -1 -0.1557735 -0.9877929 0 -2.90294e-6 3.48945e-6 -1 0.4530808 -0.8914694 0 4.06986e-7 5.89136e-6 -1 -0.7071083 -0.7071052 0 -1.3254e-6 4.98202e-6 -1 -0.1557735 -0.9877929 0 -5.16418e-6 3.92232e-6 -1 -0.9877936 -0.1557684 0 -1.05764e-5 1.06791e-6 -1 -5.43391e-6 2.65677e-6 -1 -0.7071083 -0.7071052 0 -0.9877936 -0.1557684 0 -1.35233e-6 4.37658e-6 -1 -0.4530771 0.8914714 0 -0.8914726 0.4530746 0 -2.2654e-5 -1.47514e-5 -1 -0.8914726 0.4530746 0 -1.61105e-6 4.80219e-6 -1 0.1557714 0.9877931 0 -1.14094e-6 4.65318e-6 -1 -0.4530771 0.8914714 0 -8.50688e-7 4.63369e-6 -1 0.7071036 0.7071099 1.561e-7 0.1557684 0.9877936 2.18063e-7 -4.70545e-7 4.66247e-6 -1 0.9877946 0.1557623 0 -1.62518e-6 3.92371e-6 -1 -1.28625e-6 4.69757e-6 -1 0.7071052 0.7071083 0 -1.89817e-6 3.58074e-6 -1 0.8914701 -0.4530796 0 0.9877946 0.1557623 0 -2.65128e-6 5.21659e-6 -1 0.4530796 -0.89147 0 -1.15419e-6 4.41225e-6 -1 0.8914701 -0.4530796 0 -8.92338e-7 4.35359e-6 -1 -0.1557754 -0.9877924 0 0.4530796 -0.89147 0 -1.83594e-6 4.74532e-6 -1 -0.7071021 -0.7071115 0 -0.1557754 -0.9877924 0 -0.9877936 -0.1557684 0 -1.41611e-6 4.59955e-6 -1 -0.7071036 -0.7071099 -1.561e-7 -0.9877935 -0.1557689 0 -2.27386e-6 5.15569e-6 -1 -0.5867182 0.8097912 1.78768e-7 -2.77195e-6 4.93149e-6 -1 -0.8097944 0.5867137 1.29522e-7 -0.8097944 0.5867137 1.29522e-7 -1.75454e-6 5.44549e-6 -1 -0.3066756 0.9518141 2.10121e-7 -0.5867183 0.8097912 1.78728e-7 -2.39001e-6 5.01767e-6 -1 -9.55986e-6 1 2.20758e-7 -0.3066756 0.9518141 2.10121e-7 -3.8273e-7 6.57518e-6 -1 0.3074734 0.9515566 2.10064e-7 -9.55986e-6 1 2.20758e-7 1.5582e-6 8.21919e-6 -1 0.5868224 0.8097157 3.57502e-7 0.3074648 0.9515595 4.20129e-7 2.33952e-7 6.03417e-6 -1 0.8097157 0.5868224 1.29546e-7 4.11131e-6 1.04573e-5 -1 0.5868287 0.8097112 1.7875e-7 -1.03926e-5 4.02897e-7 -1 0.9515566 0.3074734 0 3.26843e-7 6.14384e-6 -1 0.8097157 0.5868224 1.29546e-7 -4.63748e-6 3.58507e-6 -1 1 -1.91199e-5 0 0.9515566 0.3074734 0 -2.82505e-6 4.68124e-6 -1 0.9518178 -0.3066641 0 1 -1.91199e-5 0 -2.62163e-6 4.82273e-6 -1 0.8097833 -0.5867289 -1.29525e-7 0.9518178 -0.3066641 0 -2.25322e-6 5.12709e-6 -1 0.5867289 -0.8097833 -3.57532e-7 0.8097802 -0.5867334 -2.59052e-7 -1.79664e-6 5.5762e-6 -1 0.3066728 -0.951815 -2.10121e-7 0.5867351 -0.8097789 -1.78765e-7 -2.38999e-6 4.73825e-6 -1 0 -1 -2.20758e-7 -2.65633e-6 4.59592e-6 -1 0.3066728 -0.951815 -2.10121e-7 -6.27163e-7 5.8189e-6 -1 -0.3074648 -0.9515595 -2.10064e-7 0 -1 -2.20758e-7 2.41543e-7 6.40243e-6 -1 -0.5868224 -0.8097157 -1.78751e-7 -0.3074648 -0.9515595 -2.10064e-7 -2.42495e-5 -1.17097e-5 -1 -0.8097157 -0.5868224 -1.29546e-7 -4.44136e-6 3.11294e-6 -1 -0.5868223 -0.8097157 -1.78751e-7 -6.36531e-6 1.70428e-6 -1 -0.9515595 -0.3074648 0 -0.8097157 -0.5868224 -1.29546e-7 -3.98552e-6 3.58498e-6 -1 -1 0 0 -0.9515594 -0.3074648 0 -2.75949e-6 4.66019e-6 -1 -0.9518141 0.3066756 0 -1 0 0 -2.33534e-6 5.0914e-6 -1 -0.9518141 0.3066756 0 -6.62149e-7 3.97131e-6 -1 0.63399 0.7733412 1.70721e-7 -3.37426e-6 5.65721e-6 -1 0.7071068 0.7071068 1.53989e-7 -1.18576e-6 4.25996e-6 -1 0.4707525 0.8822653 1.94767e-7 0.63399 0.7733412 1.71228e-7 -1.80293e-6 4.55917e-6 -1 0.2909844 0.9567277 3.16808e-7 0.4707501 0.8822665 2.92151e-7 0.09853321 0.9951338 2.19684e-7 0.2909872 0.9567269 2.11205e-7 6.90933e-7 1 3.31137e-7 0 1 2.20758e-7 0.09853321 0.9951338 2.19684e-7 -0.09853589 0.9951335 3.29525e-7 -0.2909909 0.9567258 2.11205e-7 -0.09853291 0.9951338 2.19684e-7 -0.4707465 0.8822686 1.94768e-7 -0.2909909 0.9567258 2.11205e-7 -0.6339926 0.773339 1.70721e-7 -0.4707465 0.8822686 1.94768e-7 -0.7071071 0.7071065 2.34149e-7 -0.6339945 0.7733376 2.56081e-7 -0.7801723 0.6255648 0 -0.7071069 0.7071067 0 -2.31352e-6 4.42746e-6 -1 -0.8974838 0.4410477 0 -0.7801726 0.6255643 1.38098e-7 -2.81525e-6 4.18812e-6 -1 -0.9718872 0.235447 0 -0.8974837 0.4410476 0 -2.92793e-6 3.98167e-6 -1 -0.9718877 0.2354451 0 -8.58028e-6 -4.01639e-7 -1 -0.9718872 0.2354472 0 -0.8974841 0.4410469 0 -2.10701e-6 4.80258e-6 -1 -0.9718877 0.2354449 0 -0.7801723 0.6255648 1.38098e-7 -0.8974841 0.4410469 0 -0.7071071 0.7071065 1.56099e-7 -4.37649e-6 1.96948e-6 -1 -3.84757e-6 6.1605e-6 -1 -1.78278e-6 4.5337e-6 -1 -1.43592e-6 4.26471e-6 -1 2.9354e-5 -1.88039e-5 -1 -8.90356e-7 3.84215e-6 -1 -1.40253e-6 3.91125e-6 -1 -2.15182e-6 3.73084e-6 -1 -1.43592e-6 4.01867e-6 -1 -8.04566e-7 4.37614e-6 -1 -2.9635e-6 2.96342e-6 -1 -0.7801722 0.6255647 1.38098e-7 -1.97073e-6 4.28873e-6 -1 -0.6534888 0.7569361 3.34199e-7 -2.03103e-6 4.25509e-6 -1 3.58513e-6 9.87125e-6 -1 -1.20382e-6 4.29861e-6 -1 -1.75547e-6 3.58981e-6 -1 -1.42396e-6 4.14987e-6 -1 -0.7071071 0.7071065 3.12199e-7 -0.5363546 0.8439928 3.72636e-7 -2.02627e-6 4.23318e-6 -1 -0.6534888 0.7569361 3.34199e-7 -0.4084192 0.9127944 4.03013e-7 -0.5363546 0.8439928 3.72636e-7 -0.27121 0.9625202 4.24968e-7 -0.4084192 0.9127944 4.03013e-7 -0.2994245 0.95412 4.21259e-7 -0.27121 0.9625202 4.24968e-7 -0.4876369 0.8730466 3.85464e-7 -0.2994245 0.95412 4.21259e-7 -0.655344 0.7553306 3.3349e-7 -0.4876369 0.8730466 3.85464e-7 -0.7955287 0.605916 2.67522e-7 -0.655344 0.7553306 3.3349e-7 -0.9023092 0.4310894 0 -0.7955274 0.6059176 0 3.36229e-7 6.33772e-6 -1 -0.9712219 0.2381763 0 -0.9023092 0.4310894 0 -2.35023e-6 3.82678e-6 -1 -0.9993772 0.03528934 0 -1.41006e-6 4.59143e-6 -1 -0.9712219 0.2381763 0 -2.28119e-6 4.03768e-6 -1 -0.9856032 -0.1690753 0 -1.5213e-6 4.65572e-6 -1 -0.9993772 0.03528934 0 -4.47341e-6 2.4835e-6 -1 -0.9304847 -0.3663308 0 -1.05549e-6 5.26338e-6 -1 -0.9856032 -0.1690753 0 9.17005e-6 1.44619e-5 -1 -0.8363357 -0.5482176 0 2.50279e-7 7.20719e-6 -1 -0.9304847 -0.3663308 0 -0.7071035 -0.7071101 0 -0.8363357 -0.5482176 0 -0.5482207 -0.8363338 -3.69255e-7 -0.7071052 -0.7071084 -3.122e-7 -0.366328 -0.9304859 -4.10824e-7 -0.5482207 -0.8363338 -3.69255e-7 -0.169071 -0.9856038 -4.3516e-7 -0.366328 -0.9304859 -4.10824e-7 0.03528934 -0.9993772 -8.82482e-7 -0.1690742 -0.9856032 -8.70319e-7 0.2381778 -0.9712215 -8.5762e-7 0.03528934 -0.9993772 -8.82482e-7 0.4310841 -0.9023117 -3.98385e-7 0.2381809 -0.9712207 -4.28809e-7 0.6059176 -0.7955274 -3.51238e-7 0.4310841 -0.9023117 -3.98385e-7 0.7553354 -0.6553386 -2.89342e-7 0.6059176 -0.7955274 -3.51238e-7 0.8730422 -0.4876447 -2.15303e-7 0.7553354 -0.6553386 -2.89342e-7 0.9541203 -0.2994236 -1.322e-7 0.8730422 -0.4876447 -2.15303e-7 0.9625223 -0.2712029 -1.1974e-7 0.9541203 -0.2994236 -1.322e-7 0.9127935 -0.4084214 -1.80325e-7 0.9625222 -0.2712029 -1.1974e-7 0.8439931 -0.536354 -7.10426e-7 0.9127927 -0.4084232 -5.40976e-7 0.7569331 -0.6534925 0 0.8439952 -0.5363508 0 0.7071069 -0.7071066 0 -6.07253e-6 5.99902e-6 -1 -2.69024e-6 5.06101e-6 -1 -2.19882e-6 5.2549e-6 -1 -1.43591e-6 5.70647e-6 -1 -4.07907e-7 6.50654e-6 -1 6.61492e-6 1.25418e-5 -1 -2.26482e-5 2.03676e-5 -1 -6.87083e-7 3.6168e-6 -1 -1.73733e-6 4.4549e-6 -1 -1.43592e-6 4.21788e-6 -1 0.7569331 -0.6534925 0 0.6255617 -0.7801747 -1.7223e-7 -3.85188e-6 2.7712e-6 -1 -3.38839e-6 3.58981e-6 -1 -2.8358e-6 4.96424e-6 -1 0.7071068 -0.7071067 -1.56099e-7 0.4410494 -0.8974828 -1.98126e-7 0.6255617 -0.7801747 -1.7223e-7 -1.76164e-6 5.34205e-6 -1 0.2354491 -0.9718866 0 2.03478e-6 7.67945e-6 -1 0.4410509 -0.8974821 0 -1.8187e-6 4.61282e-6 -1 0.2354451 -0.9718877 0 -2.34131e-6 4.61394e-6 -1 0.2354491 -0.9718866 0 -2.21612e-6 4.50955e-6 -1 0.4410483 -0.8974834 0 0.2354451 -0.9718877 0 0.6255632 -0.7801734 0 0.4410483 -0.8974834 0 0.707107 -0.7071066 0 0.6255632 -0.7801734 0 0.773343 -0.6339879 0 0.7071069 -0.7071067 0 0.8822647 -0.4707537 0 0.773343 -0.6339879 0 -3.24281e-6 4.17582e-6 -1 0.9567286 -0.2909819 0 0.8822641 -0.4707549 0 -3.34754e-6 4.13732e-6 -1 0.9951332 -0.09853857 0 0.956728 -0.2909836 -1.49157e-7 -3.7488e-6 3.97286e-6 -1 1 3.45466e-7 0 1 3.45466e-7 0 0.9951333 -0.09853804 0 1.23112e-5 1.492e-5 -1 0.9951338 0.09853351 0 -9.84889e-7 4.4848e-6 -1 0.9567259 0.2909906 0 0.9951337 0.09853351 0 -2.95256e-6 2.74807e-6 -1 0.8822659 0.4707514 0 0.956726 0.2909906 0 -4.84363e-6 9.26478e-7 -1 0.7733412 0.63399 0 0.8822653 0.4707526 0 0.7071064 0.7071071 0 0.7071068 0.7071068 1.56099e-7 0.77334 0.6339915 1.39959e-7 -0.707107 0.7071066 0 0.707107 0.7071065 1.56099e-7 -0.7071071 0.7071065 1.56099e-7 0.7071069 -0.7071067 -2.34149e-7 0.7071068 0.7071068 2.34149e-7 0.7071065 0.7071071 0 0.707107 -0.7071065 0 -0.7071068 -0.7071068 0 -0.4996289 -0.8662395 0 -0.4996326 -0.8662375 -1.61862e-7 -0.7071068 -0.7071068 0 -0.8662403 -0.4996276 0 -1 1.14873e-5 0 -0.8662403 -0.4996276 0 -0.8662395 0.4996289 0 -1 1.14873e-5 0 -0.7071061 0.7071076 0 -0.8662395 0.4996289 0 -0.4996376 0.8662346 0 -0.7071061 0.7071076 0 0 1 0 -0.4996376 0.8662346 0 0.4996276 0.8662403 0 0 1 0 0.7071105 0.7071031 6.23177e-7 0.7071068 0.7071068 3.12199e-7 0.499619 0.8662453 3.82461e-7 0.8662425 0.499624 4.41184e-7 1 0 0 0.8662453 0.4996189 2.2059e-7 0.8662453 -0.4996189 -2.2059e-7 1 0 0 0.7071075 -0.7071061 -3.12199e-7 0.8662453 -0.4996189 -2.2059e-7 0.4996239 -0.8662424 0 0.7071083 -0.7071053 0 1.14871e-5 -1 0 0.499624 -0.8662424 0 1.14871e-5 -1 0 0.8662425 0.499624 -7.6492e-7 0.7071068 0.7071068 -6.23167e-7 1 0 0 0.8662325 0.4996412 0 0.8662325 -0.4996412 0 1 0 0 0.7071073 -0.7071064 0 0.8662325 -0.4996412 0 0.4996283 -0.86624 0 0.7071073 -0.7071064 0 5.74359e-6 -1 0 0.4996283 -0.86624 0 -1.19481e-6 5.14231e-6 -1 -0.4996283 -0.86624 -1.91229e-7 0 -1 -2.20758e-7 -8.37254e-7 5.0896e-6 -1 -0.7071087 -0.7071049 0 4.72298e-5 -2.39125e-5 -1 -0.7071086 -0.7071049 0 -0.4996258 -0.8662414 0 7.18376e-7 4.57516e-6 -1 -0.866236 -0.4996351 0 7.18433e-7 4.57513e-6 -1 1.36446e-6 4.30775e-6 -1 1.36464e-6 4.30768e-6 -1 -1 1.14872e-5 0 -0.866236 -0.4996351 0 1.95404e-5 -8.77401e-6 -1 -0.86624 0.4996283 0 -7.1548e-6 7.33306e-6 -1 -1 1.14872e-5 0 -0.7071072 0.7071064 0 -1.82692e-6 4.04644e-6 -1 -0.86624 0.4996283 0 -0.4996189 0.8662453 0 -0.7071072 0.7071064 0 0 1 0 -0.4996189 0.8662453 0 0.4996189 0.8662452 0 0 1 0 0.7071142 0.7070994 0 0.4996189 0.8662452 0 -0.7071087 -0.7071049 -1.5495e-7 -0.4996276 -0.8662403 -1.91229e-7 -0.4996294 -0.8662393 -2.72161e-7 -0.7071086 -0.7071049 -1.56098e-7 -0.8662385 -0.4996308 0 -1 0 0 -0.8662385 -0.4996308 0 -0.86624 0.4996283 0 -1 0 0 -0.707107 0.7071066 1.56099e-7 -0.86624 0.4996283 0 -0.4996283 0.86624 0 -0.7071068 0.7071068 0 0 1 0 -0.4996283 0.86624 0 0.499624 0.8662425 0 0 1 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.499624 0.8662425 0 0.8662414 0.4996258 -1.61867e-7 1 0 0 0.8662364 0.4996344 2.20597e-7 0.86624 -0.4996283 0 1 0 0 0.7071071 -0.7071065 0 0.86624 -0.4996283 0 0.4996283 -0.86624 -1.91229e-7 0.707107 -0.7071066 -1.56099e-7 1.14873e-5 -1 -2.20758e-7 0.4996283 -0.8662399 -1.91229e-7 1.14873e-5 -1 -2.20758e-7 0.8662414 0.4996258 -1.61867e-7 0.7071068 0.7071068 0 1 0 0 0.8662363 0.4996344 2.20309e-7 0.8662363 -0.4996344 0 1 0 0 0.7071097 -0.707104 -3.1311e-7 0.7071089 -0.7071046 -1.56099e-7 0.8662363 -0.4996344 0 0.4996196 -0.8662449 -3.82461e-7 5.74359e-6 -1 -2.20758e-7 0.499624 -0.8662424 -1.9123e-7 -0.4996283 -0.86624 -1.91229e-7 5.74359e-6 -1 -2.20758e-7 -0.7071068 -0.7071068 -1.54951e-7 -0.7071068 -0.7071068 -1.56099e-7 -0.4996283 -0.86624 -1.91229e-7 -0.8662403 -0.4996276 0 -1 1.14873e-5 0 -0.8662403 -0.4996276 0 -0.8662425 0.499624 0 -1 1.14873e-5 0 -0.7071083 0.7071053 1.59122e-7 -0.7071083 0.7071053 1.56099e-7 -0.8662425 0.499624 0 -0.4996301 0.8662388 1.91229e-7 5.74363e-6 1 2.20758e-7 -0.49963 0.8662388 1.91229e-7 0.4996239 0.8662424 1.9123e-7 5.74363e-6 1 2.20758e-7 0.7071087 0.7071049 1.56099e-7 0.4996239 0.8662424 1.9123e-7 0.7071068 -0.7071068 -1.56099e-7 0.7071068 0.7071068 1.56099e-7 0.7071068 0.7071068 1.56099e-7 -0.7071068 -0.7071068 -1.56099e-7 0.7071068 -0.7071068 -1.52177e-7 -0.7071065 0.7071071 0 -0.7071063 -0.7071073 0 -0.7071068 0.7071068 1.56099e-7 6.13288e-7 -3.79968e-6 1 3.44205e-6 -6.77269e-6 1 -8.87977e-7 -1.42492e-6 1 1.06268e-6 -4.56906e-6 1 6.48123e-7 -3.73941e-6 1 2.241e-6 -5.81369e-6 1 5.13638e-6 -2.34773e-6 1 9.4252e-7 -6.54159e-6 1 4.03564e-7 -3.15803e-6 1 1.14872e-5 -9.92013e-6 1 2.75354e-6 -5.41777e-6 1 3.0278e-6 -5.0269e-6 1 2.12578e-6 -6.31247e-6 1 2.75353e-6 -5.41779e-6 1 5.13627e-6 -2.34784e-6 1 2.94646e-7 -8.1436e-6 1 8.73467e-7 -5.70778e-6 1 3.42861e-7 -7.14125e-6 1 2.25337e-6 4.27707e-6 1 3.55358e-6 3.90122e-7 1 2.05293e-6 -3.21542e-6 1 1.87409e-6 -3.91203e-6 1 1.81863e-6 -4.79975e-6 1 1.65432e-6 -4.2828e-6 1 1.65825e-6 -4.3077e-6 1 -1.64844e-6 -9.06216e-7 1 3.55359e-6 -6.99206e-6 1 2.20912e-6 -5.10184e-6 1 2.34885e-6 -5.1957e-6 1 3.52871e-7 -3.10212e-6 1 1.82711e-6 -4.75417e-6 1 2.3128e-6 -5.35834e-6 1 3.26181e-6 -4.2223e-6 1 1.09953e-6 -6.38458e-6 1 8.81463e-7 -3.66721e-6 1 1.00515e-5 -9.00274e-6 1 1.28037e-7 -3.10756e-6 1 2.75351e-6 -5.41783e-6 1 3.92985e-6 -3.74128e-6 1 2.77353e-6 -4.89761e-6 1 1.59719e-6 -6.57415e-6 1 3.26186e-6 -4.22225e-6 1 2.31287e-6 -5.35827e-6 1 2.54999e-6 -1.83755e-6 1 1.09831e-6 -6.3858e-6 1 1.55508e-6 -1.50965e-7 1 -3.76015e-7 -9.30843e-6 1 9.52392e-7 -5.63307e-6 1 1.5812e-6 -2.41659e-6 1 1.24965e-6 -3.62042e-6 1 1.43455e-6 -4.15609e-6 1 1.46415e-6 -4.30774e-6 1 2.16961e-6 -2.21794e-6 1 -2.36172e-6 -3.5003e-5 1 1.4618e-6 -3.80655e-6 1 0 -8.54123e-6 1 -2.03918e-6 5.80836e-7 1 1.61431e-6 -4.06181e-6 1 1.80603e-6 -4.06757e-6 1 1.14708e-6 -2.32595e-6 1 1.62297e-6 -4.30772e-6 1 -6.44483e-7 -1.41646e-6 1 -1.73666e-6 2.09282e-7 1 4.12158e-7 -3.09277e-6 1 1.50976e-6 -5.07147e-6 1 5.89654e-7 -3.16001e-6 1 1.00513e-5 -8.43692e-6 1 1.20886e-6 -5.37241e-6 1 1.89888e-7 -1.88207e-5 1 1.4088e-6 -5.17664e-6 1 2.30654e-6 -1.77208e-6 1 -8.48967e-6 1.32726e-5 1 1.85629e-6 -2.25792e-6 1 9.77516e-7 -2.48275e-6 1 2.54342e-6 -6.45992e-6 1 1.98218e-6 -4.30775e-6 1 1.40248e-6 -4.20083e-6 1 4.04305e-7 -3.11763e-6 1 1.71356e-6 -3.94531e-6 1 3.92857e-7 -3.09583e-6 1 1.85361e-6 -4.72767e-6 1 0 -2.54559e-6 1 1.14874e-5 -9.07581e-6 1 2.51262e-6 -4.35631e-6 1 2.46952e-6 -3.94893e-6 1 1.85588e-6 -4.62624e-6 1 2.31335e-6 -4.20797e-6 1 2.04439e-6 -4.54197e-6 1 1.52402e-6 -5.1611e-6 1 4.61746e-6 -1.96527e-6 1 1.12734e-6 -5.95347e-6 1 2.27466e-6 -4.12665e-6 1 1.64184e-6 -4.19924e-6 1 -4.07973e-6 -1.32766e-5 1 4.03812e-6 -1.26777e-6 1 -7.25874e-7 -6.42197e-6 1 5.57955e-6 -3.02857e-7 1 -1.7104e-5 -2.34799e-5 1 -7.98054e-7 -6.38673e-6 1 -8.50697e-7 -7.99743e-6 1 4.26852e-6 -1.49667e-6 1 1.64206e-6 -4.90384e-6 1 9.60292e-7 -5.70681e-6 1 1.96527e-6 -4.61746e-6 1 1.62311e-6 -5.34204e-6 1 2.17741e-6 -4.41213e-6 1 2.30939e-6 -4.32557e-6 1 1.96799e-6 -4.76328e-6 1 1.59973e-6 -5.16606e-6 1 2.92358e-6 -3.28613e-6 1 2.07944e-6 -4.71861e-6 1 1.59605e-6 -5.18301e-6 1 1.95885e-6 -4.73811e-6 1 3.88237e-6 -2.65367e-6 1 1.15954e-6 -4.34581e-6 1 -5.05806e-7 -6.98788e-6 1 9.02727e-7 -4.65999e-6 1 6.65481e-6 1.56328e-6 1 5.37441e-6 -5.53424e-7 1 2.69301e-5 2.26801e-5 1 -2.18442e-5 -2.8449e-5 1 -6.46357e-6 -1.37768e-5 1 -1.53927e-7 -6.69495e-6 1 1.70641e-6 -4.69213e-6 1 9.88375e-7 -5.41909e-6 1 1.95396e-6 -4.50123e-6 1 1.91136e-6 -4.56737e-6 1 1.54326e-6 -5.07931e-6 1 2.24639e-6 -4.20758e-6 1 2.82333e-6 -4.81388e-6 1 1.33453e-6 -5.95015e-6 1 2.96832e-6 -4.41533e-6 1 4.11153e-6 -2.41076e-6 1 4.42244e-6 -1.95316e-6 1 2.61355e-6 -2.82555e-6 1 -8.50199e-6 -1.51068e-5 1 3.85606e-6 -2.74874e-6 1 7.53044e-7 -4.80613e-6 1 1.36589e-6 -4.07321e-6 1 1.49473e-6 -4.13861e-6 1 1.87325e-6 -3.68593e-6 1 3.00313e-6 -2.58555e-6 1 2.57718e-6 -3.05616e-6 1 2.30124e-6 -4.80626e-6 1 5.43394e-6 -9.41646e-7 1 2.68347e-6 -2.38218e-6 1 4.04606e-6 -2.52134e-6 1 1.36328e-6 -4.34412e-6 1 8.00471e-7 -4.8992e-6 1 -4.93734e-6 -1.1007e-5 1 2.67428e-6 -4.16696e-6 1 2.26986e-6 -4.91612e-6 1 7.34363e-6 3.09336e-6 1 2.4861e-6 -2.95299e-6 1 7.53051e-7 -4.80613e-6 1 1.87324e-6 -3.68594e-6 1 2.39357e-6 -4.21123e-6 1 1.3509e-5 8.06992e-6 1 2.17728e-6 -5.59215e-6 1 2.98825e-6 -4.19171e-6 1 1.60611e-6 -6.48449e-6 1 3.89556e-6 -3.66935e-6 1 2.1602e-6 -2.71847e-6 1 8.14776e-7 -6.61999e-6 1 7.29866e-7 -5.64572e-6 1 2.61355e-6 -2.82554e-6 1 -8.50187e-6 -1.51067e-5 1 4.61794e-7 -6.14301e-6 1 1.3659e-6 -4.07319e-6 1 2.3604e-6 -2.88917e-6 1 8.20438e-7 -4.93846e-6 1 1.59699e-6 -4.30693e-6 1 2.51637e-6 -2.66227e-6 1 -2.27938e-6 -8.65498e-6 1 9.53814e-6 5.28781e-6 1 2.56811e-6 -3.1137e-6 1 7.67548e-6 2.9674e-6 1 1.85009e-6 -3.53542e-6 1 2.24079e-6 -3.35406e-6 1 1.8114e-6 -3.6942e-6 1 1.53134e-6 -4.19434e-6 1 2.08094e-6 -3.47587e-6 1 -3.64439e-7 -5.99197e-6 1 -4.51027e-7 -7.55897e-6 1 1.35822e-6 -4.3284e-6 1 7.27926e-7 -6.33813e-6 1 1.36699e-5 2.47235e-5 1 1.99714e-6 -5.1796e-6 1 1.69616e-6 -3.63887e-6 1 1.50961e-6 -3.98057e-6 1 -2.90639e-6 -9.55525e-6 1 3.03109e-6 -3.5202e-6 1 2.3206e-6 -5.01339e-6 1 2.48789e-6 -4.3674e-6 1 4.75117e-6 -1.42471e-6 1 -1.33204e-6 -7.15664e-6 1 2.90788e-6 -3.65952e-6 1 2.38557e-6 -2.67333e-6 1 6.51165e-7 -5.63132e-6 1 9.60237e-7 -4.82778e-6 1 2.70921e-6 -3.12093e-6 1 8.79088e-7 -5.16121e-6 1 2.25942e-6 -3.81121e-6 1 3.16856e-6 -2.65812e-6 1 -8.07194e-6 -1.46533e-5 1 0 -5.21382e-6 1 2.23121e-6 -5.87584e-6 1 1.33783e-6 -3.80012e-6 1 9.65727e-7 -4.66262e-6 1 1.59701e-6 -3.67529e-6 1 5.11075e-7 -1.00559e-6 1 1.93709e-6 -4.79729e-6 1 1.73218e-6 -4.39548e-6 1 2.52276e-6 -6.5142e-6 1 1.46421e-6 -2.92686e-6 1 1.46363e-6 -2.92389e-6 1 2.77331e-6 -2.43803e-6 1 1.63727e-6 -4.35402e-6 1 1.64486e-6 -4.32401e-6 1 1.04349e-6 -2.05317e-6 1 1.67138e-6 -4.47306e-6 1 1.69839e-6 -4.88288e-6 1 8.69791e-7 -4.49684e-6 1 1.71079e-6 -3.81705e-6 1 7.48801e-7 -4.64457e-6 1 1.74215e-6 -3.42787e-6 1 1.34277e-6 -4.02739e-6 1 1.12441e-6 -4.05949e-6 1 1.88336e-6 -4.43965e-6 1 1.54717e-6 -3.76542e-6 1 1.96028e-6 -4.62097e-6 1 8.30013e-7 -4.74911e-6 1 2.09493e-6 -4.99833e-6 1 1.90542e-6 -5.06643e-6 1 1.98178e-6 -4.49522e-6 1 1.85994e-6 -3.65965e-6 1 1.63904e-6 -3.8573e-6 1 1.94942e-6 -4.42926e-6 1 1.3653e-6 -3.02221e-6 1 2.57763e-6 -3.67876e-6 1 1.86479e-6 -4.44262e-6 1 2.59184e-6 -3.71558e-6 1 1.68103e-6 -3.9316e-6 1 9.88345e-7 -5.37611e-6 1 1.83551e-6 -4.42088e-6 1 1.39301e-6 -4.196e-6 1 1.17954e-5 5.43098e-6 1 -1.89664e-5 -2.6869e-5 1 1.36894e-6 -2.9419e-6 1 1.69364e-6 -3.96626e-6 1 1.78083e-6 -4.80048e-6 1 7.76218e-7 -5.0899e-6 1 1.72611e-6 -3.60529e-6 1 1.61281e-6 -3.65491e-6 1 1.80099e-6 -3.54362e-6 1 4.71314e-6 3.25675e-7 1 -2.12724e-7 -1.13609e-5 1 8.17742e-7 -6.70848e-6 1 -1.1954e-6 -1.32242e-5 1 3.0536e-6 -6.00821e-6 1 4.72177e-6 -4.14379e-6 1 3.39337e-6 -4.20158e-6 1 3.08409e-6 -5.38469e-6 1 5.89288e-6 1.50543e-6 1 2.80645e-6 -2.22791e-6 1 8.23436e-6 6.15357e-6 1 1.51591e-6 -4.02147e-6 1 7.03216e-7 -5.00518e-6 1 2.27701e-6 -3.24771e-6 1 2.33323e-6 -4.77998e-6 1 3.92374e-6 -1.80355e-6 1 2.73012e-6 -4.13255e-6 1 6.89095e-6 2.06174e-6 1 -4.91263e-5 -7.1832e-5 1 1.7949e-5 1.78039e-5 1 5.21431e-6 6.17787e-7 1 2.38999e-6 -2.95604e-6 1 -4.99887e-7 -6.25126e-6 1 2.07896e-6 -2.86927e-6 1 1.59498e-6 -4.19068e-6 1 1.54937e-6 -4.04587e-6 1 3.22698e-6 -1.03969e-6 1 7.0888e-7 -4.77999e-6 1 -1.8935e-6 -8.13388e-6 1 6.50635e-6 1.78301e-6 1 5.81091e-6 0 1 1.78351e-6 -3.60457e-6 1 -5.47564e-6 -1.69463e-5 1 1.69208e-6 -3.56286e-6 1 2.38999e-6 -2.72103e-6 1 3.04293e-6 -1.64145e-6 1 7.50348e-6 1.98425e-6 1 2.24519e-6 -2.13838e-6 1 1.8425e-6 -3.23368e-6 1 1.38187e-6 -4.35753e-6 1 1.04141e-6 -4.857e-6 1 2.13685e-6 -3.46122e-6 1 8.09617e-7 -4.96495e-6 1 1.29618e-6 -4.22305e-6 1 1.5396e-6 -4.61462e-6 1 6.9731e-7 -3.08671e-6 1 4.69406e-6 -1.13306e-5 1 2.6509e-7 -8.7805e-6 1 3.98023e-6 -9.92299e-7 1 -5.54208e-7 -7.36068e-6 1 1.95578e-5 1.85742e-5 1 4.90559e-7 -6.31591e-6 1 1.08936e-6 -4.29873e-6 1 1.38346e-6 -4.26178e-6 1 1.18821e-6 -4.01396e-6 1 1.41602e-6 -4.30771e-6 1 -1.6405e-5 1.94782e-5 1 4.74682e-6 -2.84284e-5 1 1.44491e-6 -3.95365e-6 1 1.40086e-6 -4.13661e-6 1 1.33206e-6 -4.30774e-6 1 2.80124e-6 -1.71289e-6 1 1.37332e-6 -3.89505e-6 1 2.15081e-6 -4.16607e-6 1 2.11409e-6 -4.2319e-6 1 -5.37593e-6 -1.17219e-5 1 -1.52196e-6 -8.40992e-6 1 2.87181e-6 -4.99034e-6 1 2.87672e-6 -4.98744e-6 1 1.81888e-6 -4.498e-6 1 -4.25162e-7 -6.99283e-6 1 4.62567e-6 -1.41406e-6 1 2.32577e-6 -4.24189e-6 1 1.25003e-6 -5.00748e-6 1 2.19884e-6 -3.8409e-6 1 1.63626e-6 -4.9231e-6 1 2.95139e-6 -3.30612e-6 1 1.47516e-6 -3.81658e-6 1 -4.04783e-6 -1.06072e-5 1 1.05253e-6 -4.71043e-6 1 1.1651e-6 -5.11636e-6 1 1.52371e-6 -4.20741e-6 1 1.4643e-6 -4.30777e-6 1 4.03974e-6 -9.98606e-7 1 2.63377e-6 -2.63465e-6 1 -1.20624e-6 -4.91352e-7 1 2.11804e-6 -5.09916e-6 1 3.7672e-6 -7.16578e-6 1 7.16534e-6 -1.14872e-5 1 3.37689e-6 -2.80186e-6 1 1.43592e-6 -3.90083e-6 1 7.45641e-7 -4.17835e-6 1 2.7899e-6 -4.4157e-6 1 5.89341e-6 6.25057e-7 1 1.622e-6 -4.13279e-6 1 1.6246e-6 -5.34344e-6 1 9.90849e-7 -6.56175e-6 1 1.01405e-6 -2.74376e-6 1 1.53109e-6 -3.73726e-6 1 1.57015e-5 -2.72227e-5 1 2.08601e-6 -5.03993e-6 1 1.25231e-6 -3.5999e-6 1 2.87183e-6 -7.51277e-6 1 1.4359e-6 -3.46923e-6 1 -2.2067e-5 3.53735e-5 1 1.53109e-6 -3.73728e-6 1 1.59932e-6 -4.07044e-6 1 -2.30026e-6 4.06292e-6 -1 -0.8914714 -0.4530771 0 5.59136e-6 1.78648e-5 -1 -0.4530722 -0.8914738 -1.968e-7 -1.84331e-6 4.55878e-6 -1 -2.56347e-6 4.10352e-6 -1 -0.4530722 -0.8914738 -1.968e-7 -2.73343e-6 3.58882e-6 -1 -0.9877929 0.1557735 0 -0.8914713 -0.4530771 0 -2.10125e-6 4.29504e-6 -1 -0.7071037 0.7071099 1.561e-7 -0.9877929 0.1557735 0 -1.3681e-6 3.66944e-6 -1 -0.1557694 0.9877935 2.18063e-7 -1.08338e-6 3.32862e-6 -1 -1.75052e-6 3.99575e-6 -1 -3.98976e-6 2.13259e-6 -1 -1.4359e-6 4.05036e-6 -1 -7.99375e-7 4.38509e-6 -1 -0.7071037 0.7071099 1.561e-7 -1.51557e-6 3.88095e-6 -1 0.4530796 0.8914701 1.96799e-7 -1.36497e-6 3.66631e-6 -1 -0.1557694 0.9877935 2.18063e-7 -1.81598e-6 4.3091e-6 -1 0.8914688 0.4530821 0 -1.51557e-6 3.88095e-6 -1 0.4530796 0.8914701 1.96799e-7 -1.84296e-6 4.23788e-6 -1 0.9877935 -0.1557694 0 -2.34127e-6 4.83439e-6 -1 0.8914688 0.4530821 0 -1.26869e-6 2.36557e-6 -1 0.7071068 -0.7071068 -1.56099e-7 -1.65162e-6 4.04653e-6 -1 0.9877934 -0.1557694 0 -1.84608e-6 6.7004e-6 -1 0.1557735 -0.9877929 -2.18063e-7 -1.16135e-6 2.0135e-6 -1 -1.56369e-6 3.53933e-6 -1 0.7071068 -0.7071067 -1.56099e-7 -4.19971e-6 1.57039e-6 -1 -3.69022e-6 2.86444e-6 -1 -1.06711e-6 1.29232e-5 -1 -1.59968e-6 4.25128e-6 -1 0.1557735 -0.9877929 -2.18063e-7 -2.17586e-6 4.12612e-6 -1 -0.8914752 -0.4530696 0 1.78653e-7 7.21476e-6 -1 -0.4530647 -0.8914777 0 -1.41996e-6 5.25131e-6 -1 -0.4530647 -0.8914777 0 -2.53435e-6 3.55739e-6 -1 -0.9877947 0.1557614 0 -0.8914752 -0.4530696 0 -2.11663e-6 4.31046e-6 -1 -0.7071006 0.707113 0 -0.9877947 0.1557614 0 -1.3322e-6 3.44176e-6 -1 -0.1557735 0.9877929 0 -2.0206e-6 4.26582e-6 -1 -1.62844e-6 3.87367e-6 -1 -2.46959e-6 3.57719e-6 -1 -2.15379e-6 3.75331e-6 -1 -0.7071006 0.707113 0 -1.58801e-6 3.73835e-6 -1 0.4530845 0.8914675 0 -1.49212e-6 3.60168e-6 -1 -0.1557735 0.9877929 0 -1.81601e-6 4.30913e-6 -1 0.89147 0.4530797 0 -1.00988e-6 3.16023e-6 -1 0.4530845 0.8914675 0 -2.02053e-6 4.26576e-6 -1 0.9877951 -0.1557595 0 -3.27841e-6 5.77153e-6 -1 0.89147 0.4530797 0 -1.21673e-6 2.3136e-6 -1 0.7071068 -0.7071068 0 -1.61356e-6 3.85878e-6 -1 0.9877951 -0.1557595 0 -2.29577e-6 9.55345e-6 -1 0.1557492 -0.9877967 0 -1.05643e-6 1.83163e-6 -1 -1.55795e-6 3.53357e-6 -1 0.7071068 -0.7071068 0 -3.73204e-6 2.48719e-6 -1 1.27178e-6 1.57121e-5 -1 -1.63922e-6 3.58981e-6 -1 -1.61561e-6 4.26047e-6 -1 0.1557492 -0.9877967 0 -0.8914726 -0.4530746 0 -0.4530746 -0.8914726 0 -0.4530746 -0.8914726 0 -0.9877947 0.1557614 0 -0.8914725 -0.4530746 0 -2.11854e-6 5.40917e-6 -1 -0.7071068 0.7071068 0 -0.9877947 0.1557614 0 -1.55507e-6 -1.50997e-7 -1 -0.1557614 0.9877947 0 -1.7037e-6 4.33786e-6 -1 -1.51449e-6 3.36999e-6 -1 -1.76051e-6 4.49504e-6 -1 -0.7071068 0.7071068 0 1.3917e-6 9.60136e-6 -1 0.4530746 0.8914726 0 -4.38672e-6 1.14506e-6 -1 4.8475e-7 1.52584e-5 -1 -1.65261e-6 4.3077e-6 -1 -0.1557614 0.9877947 0 -3.82689e-6 2.41507e-6 -1 0.8914726 0.4530746 0 -2.12751e-6 4.26337e-6 -1 -2.23808e-6 4.1891e-6 -1 0.4530746 0.8914726 0 -2.12516e-6 4.28226e-6 -1 0.9877951 -0.1557595 0 0.8914726 0.4530746 0 -1.59059e-6 4.88131e-6 -1 0.7071006 -0.707113 0 0.9877951 -0.1557595 0 0.1557614 -0.9877947 0 -4.46182e-6 1.581e-6 -1 -1.43595e-6 3.91073e-6 -1 -8.83776e-7 4.23876e-6 -1 0.7071006 -0.707113 0 0.1557614 -0.9877947 0 -0.8914688 -0.4530821 0 -0.4530796 -0.8914701 -1.96799e-7 -0.4530796 -0.8914701 -1.96799e-7 -0.9877918 0.1557796 0 -0.8914688 -0.4530821 0 -2.36486e-6 5.65545e-6 -1 -0.707113 0.7071006 1.56098e-7 -0.9877918 0.1557796 0 -1.70868e-6 5.82923e-6 -1 -0.1557684 0.9877936 2.18063e-7 -1.63595e-6 4.2701e-6 -1 -1.63658e-6 4.27254e-6 -1 5.07576e-7 -8.8003e-7 -1 -0.707113 0.7071006 1.56098e-7 -2.06033e-6 4.52491e-6 -1 0.4530771 0.8914713 1.96799e-7 -8.95552e-7 5.94047e-6 -1 -1.46538e-6 4.14774e-6 -1 -1.55343e-6 3.58976e-6 -1 -0.1557684 0.9877936 2.18063e-7 -3.05495e-6 2.80735e-6 -1 0.8914675 0.4530845 0 -1.64447e-6 5.03852e-6 -1 0.4530771 0.8914713 1.96799e-7 -2.18766e-6 4.29221e-6 -1 0.9877936 -0.1557684 0 0.8914675 0.4530845 0 -2.15794e-6 4.35169e-6 -1 0.7071068 -0.7071068 -1.56099e-7 0.9877936 -0.1557684 0 0.1557745 -0.9877927 -2.18063e-7 -2.54077e-6 3.44157e-6 -1 -1.43592e-6 4.11564e-6 -1 0.7071068 -0.7071067 -1.56099e-7 0.1557745 -0.9877927 -2.18063e-7 -8.06105e-7 4.1622e-6 -1 -0.7740041 -0.6331806 -2.79559e-7 -1.12837e-6 4.51467e-6 -1 -0.6331806 -0.7740041 -3.41735e-7 -0.6331806 -0.7740041 -3.41735e-7 -1.84479e-6 4.19088e-6 -1 -0.8821537 -0.4709616 -2.07937e-7 -3.07505e-6 6.27856e-6 -1 -0.7740041 -0.6331806 -2.79412e-7 -1.81404e-6 4.14693e-6 -1 -0.9568065 -0.2907256 -1.2836e-7 -0.8821537 -0.4709616 -2.07937e-7 -1.41063e-6 3.65224e-6 -1 -0.9952971 -0.09686958 0 -0.9568065 -0.2907256 -1.2836e-7 -1.6889e-6 3.95379e-6 -1 -0.9952985 0.09685528 0 -0.9952971 -0.09686958 0 -1.47742e-6 3.58102e-6 -1 -0.9568032 0.2907366 1.28365e-7 -1.75111e-6 4.01523e-6 -1 -0.9952985 0.09685528 0 -2.40481e-6 4.71553e-6 -1 -0.8817018 0.4718073 2.0831e-7 -0.9568032 0.2907366 1.28365e-7 -3.03937e-6 5.40207e-6 -1 -0.7737628 0.6334754 2.79689e-7 -0.8817017 0.4718073 2.0831e-7 -1.68937e-5 2.18212e-5 -1 -0.6334754 0.7737628 3.41629e-7 1.10083e-6 1.10077e-6 -1 4.90336e-6 -2.52664e-6 -1 2.68425e-6 -5.59083e-7 -1 -0.7737628 0.6334754 2.79689e-7 -1.91579e-6 5.18204e-6 -1 -0.4718073 0.8817018 3.89285e-7 -0.6334755 0.7737628 3.41629e-7 -2.57259e-6 5.88915e-6 -1 -0.2907475 0.9567998 4.22442e-7 -0.4718073 0.8817018 3.89285e-7 -1.19528e-6 4.49469e-6 -1 -0.09685528 0.9952985 4.3944e-7 -0.2907475 0.9567998 4.22442e-7 -1.75474e-6 5.33235e-6 -1 0.09686958 0.9952971 4.39439e-7 -1.24433e-6 4.53996e-6 -1 -0.09685528 0.9952985 4.3944e-7 -1.03616e-6 4.32091e-6 -1 0.2907256 0.9568065 4.22445e-7 0.09686958 0.9952971 4.39439e-7 -1.61992e-6 5.04465e-6 -1 0.4709616 0.8821537 3.89485e-7 0.2907256 0.9568065 4.22445e-7 -1.12706e-6 4.51627e-6 -1 0.6331806 0.7740041 3.41735e-7 0.4709617 0.8821537 3.89485e-7 -1.4363e-6 3.64666e-6 -1 0.7740041 0.6331806 2.79559e-7 -2.98428e-6 6.21433e-6 -1 0.6331806 0.7740041 3.41735e-7 -1.83151e-6 4.19797e-6 -1 0.8821537 0.4709616 2.07937e-7 0.7740041 0.6331806 2.79559e-7 -1.79374e-6 4.15303e-6 -1 0.9568042 0.2907332 1.28363e-7 0.8821537 0.4709616 2.07937e-7 -1.31773e-6 3.66127e-6 -1 0.995296 0.0968815 0 0.9568042 0.2907332 1.28363e-7 -1.67104e-6 3.95212e-6 -1 0.9952972 -0.09686839 0 -1.72343e-6 4.03555e-6 -1 0.995296 0.0968815 0 -1.47743e-6 3.58104e-6 -1 0.9567998 -0.2907475 -1.2837e-7 -2.02591e-6 4.45121e-6 -1 0.9952973 -0.09686839 0 -2.4047e-6 4.71541e-6 -1 0.8817118 -0.4717885 -2.08302e-7 0.9567998 -0.2907475 -1.2837e-7 -3.03976e-6 5.40248e-6 -1 0.773751 -0.6334899 -2.79696e-7 0.8817118 -0.4717885 -2.08302e-7 -1.16478e-5 1.54132e-5 -1 0.6334872 -0.7737532 -3.41624e-7 -1.98619e-5 2.3249e-5 -1 2.82863e-5 -2.72237e-5 -1 0.7737511 -0.6334899 -2.79696e-7 -1.9942e-6 5.32868e-6 -1 0.4717972 -0.8817071 -3.89288e-7 -5.59576e-6 9.90221e-6 -1 0.6334873 -0.7737532 -3.41624e-7 -2.64934e-6 6.14173e-6 -1 0.2907475 -0.9567998 -4.22442e-7 0.4717972 -0.8817071 -3.89288e-7 -1.18815e-6 4.42077e-6 -1 0.09686839 -0.9952973 -4.39439e-7 0.2907475 -0.9567998 -4.22442e-7 -1.78087e-6 5.06323e-6 -1 -0.0968815 -0.995296 -4.39439e-7 0.09686839 -0.9952972 -4.3944e-7 -1.04334e-6 4.29722e-6 -1 -0.2907223 -0.9568075 -4.22446e-7 -1.11677e-6 4.42041e-6 -1 -0.09688156 -0.995296 -4.39439e-7 -1.58815e-6 5.10415e-6 -1 -0.4709616 -0.8821536 -3.89485e-7 -0.2907223 -0.9568075 -4.22446e-7 -0.4709616 -0.8821536 -3.89485e-7 -1.29253e-6 3.56685e-6 -1 -0.8914679 -0.4530839 -2.00044e-7 -1.47019e-6 3.75597e-6 -1 -0.4530696 -0.8914751 -3.936e-7 -0.4530696 -0.8914751 -3.936e-7 -1.77578e-6 4.10392e-6 -1 -0.9877939 0.1557664 0 -1.64804e-6 3.8673e-6 -1 -0.8914679 -0.4530839 -2.00198e-7 -3.32491e-6 6.51266e-6 -1 -0.7071068 0.7071068 3.12199e-7 -0.9877939 0.1557664 0 -2.4887e-6 6.08239e-6 -1 -0.1557664 0.9877939 4.36127e-7 -5.18591e-7 3.90567e-6 -1 -0.7071068 0.7071068 3.12199e-7 -1.02626e-6 4.62943e-6 -1 0.4530648 0.8914777 3.93602e-7 -9.77867e-7 4.57156e-6 -1 -0.1557664 0.9877939 4.36127e-7 -9.77817e-7 4.57151e-6 -1 0.8914753 0.4530695 2.00037e-7 -1.02621e-6 4.62938e-6 -1 0.4530648 0.8914777 3.93602e-7 -4.18061e-7 3.88982e-6 -1 0.9877939 -0.1557664 0 -1.58074e-6 5.17443e-6 -1 0.8914753 0.4530695 2.00037e-7 4.42747e-6 -2.30234e-6 -1 0.7071008 -0.7071128 -3.12202e-7 -4.84275e-6 8.3145e-6 -1 0.9877939 -0.1557664 0 -2.29589e-6 4.85968e-6 -1 0.1557664 -0.9877939 -4.36127e-7 0 2.78154e-6 -1 -1.62051e-6 3.856e-6 -1 0.7071008 -0.7071128 -3.12202e-7 0.1557664 -0.9877939 -4.36127e-7 -0.8914777 -0.4530648 -2.00035e-7 -0.4530695 -0.8914753 -3.93601e-7 -0.4530695 -0.8914753 -3.93601e-7 -0.9877939 0.1557664 0 -0.8914776 -0.4530647 -2.002e-7 -0.7071068 0.7071068 3.12199e-7 -0.9877939 0.1557664 0 -1.31865e-6 3.51236e-6 -1 -0.1557664 0.9877939 4.36127e-7 -0.7071068 0.7071068 3.12199e-7 -1.49055e-6 3.71577e-6 -1 0.4530743 0.8914728 3.93599e-7 -0.1557664 0.9877939 4.36127e-7 -1.74923e-6 4.17959e-6 -1 0.8914751 0.4530696 2.00037e-7 -1.62719e-6 3.84413e-6 -1 0.4530743 0.8914728 3.93599e-7 -1.70246e-6 4.09236e-6 -1 0.9877939 -0.1557664 0 0.8914777 0.4530648 0 1.11074e-6 0 -1 0.7071188 -0.7070947 0 0.9877939 -0.1557664 0 0.1557664 -0.9877939 -4.36126e-7 0.7071129 -0.7071008 -3.12196e-7 0.1557664 -0.9877939 -4.36127e-7 -4.17727e-7 4.01142e-6 -1 -0.8914753 -0.4530695 -2.00037e-7 -8.27289e-6 1.1979e-5 -1 -0.4530647 -0.8914777 -3.93602e-7 -9.91518e-7 4.69764e-6 -1 -0.4530647 -0.8914777 -3.93602e-7 -4.18062e-7 3.88982e-6 -1 -0.9877939 0.1557664 0 -1.58074e-6 5.17443e-6 -1 -0.8914752 -0.4530695 -2.00197e-7 2.04037e-6 0 -1 -0.7071008 0.7071128 3.12202e-7 -3.15075e-6 6.6225e-6 -1 -0.9877939 0.1557664 0 -1.33226e-6 3.59866e-6 -1 -0.1557664 0.9877939 4.36127e-7 1.11444e-5 -1.12567e-5 -1 -0.7071008 0.7071128 3.12202e-7 -1.4746e-6 3.74728e-6 -1 0.4530696 0.8914751 3.936e-7 -0.1557664 0.9877939 4.36127e-7 -1.77676e-6 4.1655e-6 -1 0.8914679 0.4530839 2.00044e-7 -1.61153e-6 3.85864e-6 -1 0.4530696 0.8914751 3.936e-7 -9.39449e-6 1.52474e-5 -1 0.9877939 -0.1557664 0 0.8914679 0.4530839 2.00044e-7 1.28398e-6 1.90376e-6 -1 0.7071068 -0.7071068 -3.12199e-7 0.9877939 -0.1557664 0 -3.17845e-6 5.60661e-6 -1 0.1557664 -0.9877939 -4.36127e-7 -1.01805e-6 3.21965e-6 -1 0.7071068 -0.7071068 -3.12199e-7 -1.75065e-6 4.17882e-6 -1 0.1557664 -0.9877939 -4.36127e-7 -1.83483e-6 4.13601e-6 -1 -0.8914728 -0.4530743 -2.0004e-7 -1.49152e-6 3.71386e-6 -1 -0.4530743 -0.8914728 -3.93599e-7 -0.4530743 -0.8914728 -3.93599e-7 -1.64648e-6 4.08353e-6 -1 -0.9877939 0.1557664 0 -1.58061e-6 3.89253e-6 -1 -0.8914727 -0.4530743 -2.00199e-7 -3.33132e-7 1.39571e-6 -1 -0.7071128 0.7071008 3.12196e-7 -0.9877939 0.1557664 0 -0.1557664 0.9877939 4.36127e-7 -0.7071127 0.7071008 3.12196e-7 0.4530695 0.8914752 3.93601e-7 -0.1557664 0.9877939 4.36127e-7 0.8914777 0.4530648 2.00035e-7 0.4530695 0.8914752 3.936e-7 0.9877939 -0.1557664 0 0.8914777 0.4530648 2.00035e-7 0.7071068 -0.7071068 -3.12199e-7 0.9877939 -0.1557664 0 -1.30432e-6 3.4214e-6 -1 0.1557683 -0.9877936 -4.36127e-7 -1.55931e-6 3.86174e-6 -1 0.7071068 -0.7071068 -3.12199e-7 0.1557683 -0.9877936 -4.36127e-7 -1.76527e-6 3.99434e-6 -1 -0.8315027 -0.5555206 -2.45271e-7 -1.54296e-6 3.7137e-6 -1 -0.5555101 -0.8315098 -3.67125e-7 -0.55551 -0.8315098 -3.67125e-7 -1.70674e-6 4.03651e-6 -1 -0.9807893 -0.1950698 0 -1.63127e-6 3.8779e-6 -1 -0.8315027 -0.5555205 -2.45497e-7 -1.49107e-6 3.70014e-6 -1 -0.9807862 0.195086 0 -0.9807893 -0.1950698 0 -1.76039e-6 4.05031e-6 -1 -0.8315122 0.5555065 2.45265e-7 -0.9807862 0.195086 0 -3.81469e-6 6.57044e-6 -1 -0.5555101 0.8315098 3.67125e-7 -3.89079e-6 6.63322e-6 -1 -0.8315122 0.5555065 2.45265e-7 -1.14165e-6 3.29542e-6 -1 -0.1950698 0.9807893 4.33034e-7 -2.44365e-6 5.51596e-6 -1 -0.55551 0.8315098 3.67125e-7 -1.62915e-6 4.0323e-6 -1 0.1950639 0.9807905 4.33035e-7 -0.1950698 0.9807893 4.33034e-7 -1.46009e-6 3.83774e-6 -1 0.5555101 0.8315098 0 0.1950712 0.9807891 0 -1.71205e-6 4.02988e-6 -1 0.8315122 0.5555065 0 -1.7143e-6 4.03911e-6 -1 0.5555101 0.8315098 0 -1.71451e-6 4.03495e-6 -1 0.9807879 0.1950771 0 0.8315122 0.5555065 0 -1.45254e-6 3.6925e-6 -1 0.9807873 -0.1950801 0 0.9807879 0.1950771 0 -1.87418e-6 4.12633e-6 -1 0.8315122 -0.5555065 0 0.9807873 -0.1950801 0 -5.82102e-6 9.57373e-6 -1 0.5555047 -0.8315134 0 -1.69138e-6 3.9498e-6 -1 -2.31731e-6 5.94557e-6 -1 0.8315122 -0.5555065 0 -9.19474e-7 2.17799e-6 -1 0.1951006 -0.9807832 0 -2.57491e-6 6.41886e-6 -1 0.5555047 -0.8315134 0 -1.65251e-6 3.91434e-6 -1 -0.1950845 -0.9807865 -4.33033e-7 0.1950933 -0.9807846 -4.33032e-7 -0.1950845 -0.9807865 -4.33033e-7 1.39752e-7 5.30305e-6 -1 -0.8914738 -0.4530722 0 -7.93363e-6 1.35579e-5 -1 -0.4530746 -0.8914725 0 -0.4530746 -0.8914726 0 -2.17229e-6 2.71086e-6 -1 -0.9877951 0.1557588 0 -6.17214e-7 5.82959e-6 -1 -0.8914738 -0.4530721 0 -1.35257e-6 4.6432e-6 -1 -0.7071083 0.7071052 0 -0.9877951 0.1557588 0 -1.4104e-6 3.93787e-6 -1 -0.1557665 0.9877939 0 -1.61892e-6 3.89679e-6 -1 -0.7071083 0.7071052 0 -4.03134e-6 -1.06903e-6 -1 0.4530759 0.891472 0 -2.70873e-6 3.55476e-6 -1 -0.1557665 0.9877939 0 -2.73012e-6 3.84452e-6 -1 0.8914725 0.4530746 0 0.4530759 0.891472 0 -8.61524e-7 1.43457e-5 -1 0.9877939 -0.155767 0 0.8914725 0.4530746 0 -1.62732e-6 2.72419e-6 -1 0.7071083 -0.7071052 0 0.9877938 -0.155767 0 -1.39521e-6 3.84152e-6 -1 0.1557644 -0.9877943 0 -1.40359e-6 3.85175e-6 -1 -1.64283e-6 4.05755e-6 -1 0.7071083 -0.7071052 0 -1.58973e-6 4.03459e-6 -1 0.1557644 -0.9877943 0 -2.99049e-6 2.84017e-6 -1 -0.8914738 -0.4530721 0 -5.40544e-6 -3.77272e-6 -1 -0.4530734 -0.8914732 -1.968e-7 -0.4530734 -0.8914732 -1.968e-7 -2.54539e-6 4.34858e-6 -1 -0.9877951 0.1557588 0 -0.8914738 -0.4530721 0 -2.48111e-6 4.67484e-6 -1 -0.7071083 0.7071052 1.56099e-7 -0.9877951 0.1557588 0 -1.3484e-6 3.54475e-6 -1 -0.1557635 0.9877944 2.18063e-7 -2.40247e-6 5.3225e-6 -1 -0.7071083 0.7071052 1.56099e-7 -2.0476e-6 4.54993e-6 -1 0.4530796 0.89147 1.96799e-7 -0.1557635 0.9877944 2.18063e-7 -1.39194e-6 3.65262e-6 -1 0.8914725 0.4530746 0 -1.85193e-6 4.35857e-6 -1 0.4530797 0.89147 1.96799e-7 -1.06793e-6 3.32617e-6 -1 0.9877947 -0.1557618 0 0.8914725 0.4530746 0 -8.08952e-6 1.13801e-5 -1 0.7071068 -0.7071068 -1.56099e-7 -1.38398e-6 3.58502e-6 -1 0.9877947 -0.1557618 0 -2.03369e-6 2.88418e-6 -1 0.1557649 -0.9877942 -2.18063e-7 -1.56513e-6 3.97286e-6 -1 -1.74683e-6 4.39402e-6 -1 -1.24454e-6 3.60843e-6 -1 0.7071068 -0.7071068 -1.56099e-7 -1.91566e-6 3.23433e-6 -1 -5.17094e-6 -3.1492e-6 -1 0.1557649 -0.9877942 -2.18063e-7 -1.30928e-6 3.69462e-6 -1 -0.891472 -0.4530759 0 -1.50124e-6 3.90916e-6 -1 -0.4530771 -0.8914713 -1.96799e-7 -0.4530771 -0.8914713 -1.96799e-7 -6.31394e-6 1.44163e-5 -1 -0.9877936 0.1557689 0 -4.05501e-6 5.77511e-6 -1 -0.891472 -0.4530759 0 -2.56428e-6 5.85488e-6 -1 -0.7071083 0.7071052 1.56099e-7 -0.9877935 0.1557689 0 -1.33664e-6 3.47001e-6 -1 -0.1557705 0.9877933 2.18063e-7 -1.45487e-6 3.65257e-6 -1 -0.7071083 0.7071052 1.56099e-7 -2.09326e-6 4.46008e-6 -1 0.4530796 0.89147 1.96799e-7 -0.1557705 0.9877933 2.18063e-7 -8.33284e-6 1.1461e-5 -1 0.8914694 0.4530808 0 -2.10444e-6 4.43807e-6 -1 -2.41851e-6 4.75214e-6 -1 0.4530797 0.89147 1.96799e-7 -1.01549e-6 4.10736e-6 -1 0.9877927 -0.155774 0 -1.52293e-6 4.65112e-6 -1 0.8914695 0.4530808 0 5.63909e-7 1.62984e-6 -1 0.7071068 -0.7071068 -1.56099e-7 -4.28395e-7 3.52026e-6 -1 0.9877927 -0.155774 0 -2.43721e-6 5.443e-6 -1 0.1557684 -0.9877936 -2.18063e-7 -1.61008e-6 3.87468e-6 -1 -2.78486e-6 7.6769e-6 -1 0.7071068 -0.7071068 -1.56099e-7 0.1557684 -0.9877936 -2.18063e-7 -1.35941e-6 3.66913e-6 -1 -0.8914738 -0.4530721 0 -0.4530734 -0.8914732 -1.968e-7 -9.03103e-7 3.16097e-6 -1 -0.4530734 -0.8914732 -1.968e-7 -2.34143e-6 4.31643e-6 -1 -0.9877938 0.1557675 0 -2.3151e-6 4.39947e-6 -1 -0.8914738 -0.4530721 0 -2.30174e-6 4.49549e-6 -1 -0.7071083 0.7071052 1.56099e-7 -0.9877938 0.1557675 0 -1.35204e-6 3.5677e-6 -1 -0.1557675 0.9877938 2.18063e-7 -3.10078e-6 6.30086e-6 -1 -2.10117e-6 5.86305e-6 -1 -0.7071083 0.7071052 1.56099e-7 -2.06714e-6 4.51145e-6 -1 0.4530821 0.8914688 1.96799e-7 -0.1557675 0.9877938 2.18063e-7 -2.81386e-6 2.92993e-6 -1 0.8914688 0.4530821 0 -1.99758e-6 4.44922e-6 -1 0.4530821 0.8914688 1.96799e-7 -2.50801e-6 3.55329e-6 -1 0.9877927 -0.1557745 0 0.8914688 0.4530821 0 -1.84932e-6 5.13995e-6 -1 0.7071068 -0.7071068 -1.56099e-7 0.9877927 -0.1557745 0 0.155775 -0.9877925 -2.18063e-7 -2.26078e-6 3.95486e-6 -1 0.7071068 -0.7071067 -1.56099e-7 0.155775 -0.9877925 -2.18063e-7 -1.89965e-6 4.47001e-6 -1 -0.8097867 -0.5867244 0 -1.61091e-6 3.82852e-6 -1 -0.5867182 -0.8097912 0 -0.5867182 -0.8097912 0 -1.87412e-6 4.42426e-6 -1 -0.9518141 -0.3066756 0 -0.8097867 -0.5867245 0 -1.30908e-6 3.58497e-6 -1 -1 -9.55996e-6 0 -0.9518141 -0.3066756 0 -6.3116e-7 2.71128e-6 -1 -0.9515595 0.3074648 0 -1 -9.55996e-6 0 -2.11932e-6 4.46821e-6 -1 -0.8097144 0.5868241 0 -0.9515595 0.3074648 0 -1.11465e-6 3.56113e-6 -1 -0.5868161 0.8097203 0 -2.01947e-6 4.35431e-6 -1 -0.8097144 0.5868241 0 -7.20553e-7 2.22992e-6 -1 -0.3074762 0.9515558 0 -1.69825e-6 4.05545e-6 -1 -0.5868161 0.8097203 0 -1.19494e-6 3.08787e-6 -1 9.55977e-6 1 0 -0.3074762 0.9515558 0 -2.22662e-6 4.79368e-6 -1 0.3066697 0.951816 0 9.55977e-6 1 0 -1.58251e-6 3.86765e-6 -1 0.5867244 0.8097867 0 0.3066697 0.951816 0 -2.01256e-6 4.3882e-6 -1 0.8097867 0.5867244 0 0.5867244 0.8097867 0 -1.06729e-6 3.4272e-6 -1 0.9518141 0.3066756 0 0.8097867 0.5867244 0 -1.44573e-6 3.58495e-6 -1 1 0 0 -1.62086e-6 3.91267e-6 -1 0.9518141 0.3066756 0 -1.93745e-6 4.38707e-6 -1 0.9515613 -0.3074589 0 1 0 0 -1.8712e-6 4.28844e-6 -1 0.8097112 -0.5868287 0 0.9515613 -0.3074589 0 6.34761e-6 -6.73548e-6 -1 0.5868287 -0.8097112 0 -1.40439e-6 3.62389e-6 -1 0.8097112 -0.5868287 0 -3.1831e-6 5.97139e-6 -1 0.307462 -0.9515604 0 0.5868287 -0.8097112 0 -1.19499e-6 3.4557e-6 -1 0 -1 0 0.307462 -0.9515604 0 -1.34536e-6 3.62715e-6 -1 -0.306687 -0.9518105 0 0 -1 0 -1.64517e-6 3.92205e-6 -1 -0.306687 -0.9518105 0 -2.27451e-6 3.82359e-6 -1 -0.7733414 0.6339897 1.39958e-7 -6.56455e-7 6.42656e-6 -1 -0.7071068 0.7071068 1.53988e-7 -2.28129e-6 3.8113e-6 -1 -0.8822653 0.4707525 0 -0.7733415 0.6339897 1.39723e-7 -1.91391e-6 4.56908e-6 -1 -0.9567278 0.2909845 0 -0.8822653 0.4707525 0 -0.9951338 0.09853321 0 -0.9567278 0.2909844 0 -1 6.90932e-7 0 -1 6.90932e-7 0 -0.9951338 0.09853321 0 -0.9951334 -0.09853649 0 -0.9567263 -0.2909892 0 -0.9951334 -0.09853649 0 -0.8822671 -0.470749 0 -0.9567263 -0.2909892 0 -0.7733415 -0.6339897 -1.39958e-7 -0.8822671 -0.470749 0 -0.7071067 -0.7071068 -1.56099e-7 -0.7733415 -0.6339897 -1.39958e-7 -0.6255641 -0.7801728 -1.72229e-7 -0.7071067 -0.7071068 -1.56099e-7 -1.59967e-6 3.95578e-6 -1 -0.4410477 -0.8974838 -1.98127e-7 -0.625564 -0.7801727 -1.72229e-7 -1.60839e-6 3.97407e-6 -1 -0.235447 -0.9718872 -2.14552e-7 -0.4410476 -0.8974837 -1.98127e-7 -1.49656e-6 4.43571e-6 -1 -0.235447 -0.9718872 -2.14552e-7 1.65015e-5 -1.87732e-5 -1 -0.235447 -0.9718872 -2.14552e-7 -0.441048 -0.8974835 0 -3.29048e-6 6.22964e-6 -1 -0.2354453 -0.9718877 0 -0.6255647 -0.7801722 0 -0.441048 -0.8974835 0 -0.7071065 -0.707107 0 -1.4402e-6 3.77504e-6 -1 -1.60636e-7 6.67538e-6 -1 -2.72411e-6 3.42174e-6 -1 -2.03706e-6 4.30767e-6 -1 -1.83287e-5 -1.74369e-5 -1 -3.04895e-6 4.84859e-7 -1 -2.23072e-6 6.5499e-6 -1 -1.80549e-6 4.78379e-6 -1 -1.32541e-6 3.58972e-6 -1 -1.04898e-6 3.1015e-6 -1 -2.15012e-6 4.78427e-6 -1 -0.6255647 -0.7801722 0 -2.52829e-6 5.51445e-6 -1 -0.7569361 -0.653489 0 -1.63102e-6 3.906e-6 -1 -2.10794e-6 4.38292e-6 -1 -1.29066e-6 3.68058e-6 -1 -1.43591e-6 3.79362e-6 -1 -1.83615e-6 4.03052e-6 -1 -0.7071065 -0.707107 0 -0.8439921 -0.5363557 0 -1.38225e-6 4.36841e-6 -1 -0.7569361 -0.653489 0 -0.9127922 -0.4084242 0 -0.8439921 -0.5363557 0 -0.9625202 -0.27121 0 -0.9127922 -0.4084242 0 -0.9541209 -0.2994216 0 -0.9625202 -0.27121 0 -0.8730451 -0.4876393 0 -0.9541209 -0.2994216 0 -0.7553323 -0.6553421 0 -0.8730451 -0.4876393 0 -0.6059154 -0.795529 0 -0.7553323 -0.6553421 0 -0.4310882 -0.9023098 -3.98384e-7 -0.6059176 -0.7955274 -3.51238e-7 -1.51224e-6 4.30538e-6 -1 -0.2381755 -0.9712221 -4.2881e-7 -0.4310882 -0.9023098 -3.98384e-7 -1.70817e-6 4.63652e-6 -1 -0.03528934 -0.9993772 -4.41241e-7 -1.11911e-6 3.91225e-6 -1 -0.2381755 -0.9712221 -4.2881e-7 -1.48831e-6 3.7582e-6 -1 0.1690726 -0.9856036 -4.3516e-7 -4.35705e-6 7.2854e-6 -1 -0.03528934 -0.9993772 -4.41241e-7 -1.91731e-6 4.30254e-6 -1 0.3663308 -0.9304847 -4.10824e-7 -1.41476e-6 3.68464e-6 -1 0.1690726 -0.9856036 -4.3516e-7 -3.08206e-7 2.36611e-6 -1 0.5482199 -0.8363342 -3.69255e-7 -1.73437e-6 4.1196e-6 -1 0.3663308 -0.9304847 -4.10824e-7 0.7071068 -0.7071068 -3.12199e-7 0.54822 -0.8363342 -3.69255e-7 0.8363338 -0.5482207 -2.42048e-7 0.7071068 -0.7071068 -3.12199e-7 0.9304859 -0.366328 -1.6174e-7 0.8363338 -0.5482207 -2.42048e-7 0.985604 -0.1690704 0 0.9304859 -0.366328 -1.6174e-7 0.999377 0.03529268 0 0.985604 -0.1690704 0 0.9712223 0.2381747 0 0.999377 0.03529268 0 0.9023111 0.4310854 1.90331e-7 0.9712223 0.2381747 0 0.7955274 0.6059176 2.67522e-7 0.9023111 0.4310854 1.90331e-7 0.6553386 0.7553354 3.33493e-7 0.7955274 0.6059176 2.67522e-7 0.4876433 0.8730429 3.85462e-7 0.6553386 0.7553354 3.33493e-7 0.2994245 0.95412 4.21259e-7 0.4876433 0.8730429 3.85462e-7 0.2712051 0.9625216 4.24969e-7 0.2994246 0.95412 4.21259e-7 0.4084214 0.9127935 4.03013e-7 0.2712051 0.9625216 4.24969e-7 0.5363513 0.8439949 3.72637e-7 0.4084214 0.9127935 4.03013e-7 0.6534925 0.7569331 3.34198e-7 0.5363513 0.8439949 3.72637e-7 0.7071066 0.707107 0 -2.86874e-6 2.2402e-6 -1 -2.09996e-6 5.01232e-6 -1 -1.70444e-6 4.00982e-6 -1 -1.45583e-6 3.58981e-6 -1 -2.27287e-6 4.63962e-6 -1 0 1.85842e-6 -1 -2.62023e-5 -2.74814e-5 -1 -3.4415e-6 2.77773e-6 -1 1.28934e-5 2.32476e-5 -1 -1.99998e-6 4.30772e-6 -1 0.6534938 0.7569319 0 0.7801738 0.6255628 1.38098e-7 -2.62422e-6 4.54981e-6 -1 -1.43588e-6 3.87699e-6 -1 -1.15714e-6 3.76492e-6 -1 0.7071065 0.707107 1.56099e-7 0.8974839 0.4410473 0 0.7801738 0.6255629 1.38098e-7 -1.5551e-6 3.83058e-6 -1 0.9718864 0.2354505 0 -5.14405e-6 9.65979e-6 -1 0.8974841 0.4410469 0 -1.60491e-6 3.81852e-6 -1 0.9718877 0.2354451 0 -1.6048e-6 3.87015e-6 -1 0.9718864 0.2354505 0 -1.65146e-6 3.99766e-6 -1 0.8974828 0.4410495 0 0.9718877 0.2354451 0 0.7801736 0.625563 0 0.8974828 0.4410495 0 0.7071068 0.7071068 1.56099e-7 0.7801733 0.6255634 1.38098e-7 0.6339852 0.7733451 0 0.7071069 0.7071067 0 0.47075 0.8822665 0 0.6339852 0.7733451 0 -1.80272e-6 4.55978e-6 -1 0.2909855 0.9567275 0 0.47075 0.8822665 0 -1.22613e-6 2.99148e-6 -1 0.0985338 0.9951338 0 0.2909855 0.9567275 0 -1.5546e-6 3.79287e-6 -1 6.90933e-7 1 0 6.90933e-7 1 0 0.0985338 0.9951338 0 -1.95622e-6 4.38206e-6 -1 -0.09853321 0.9951338 0 -9.38351e-7 3.08514e-6 -1 -0.29099 0.956726 0 -0.09853321 0.9951338 0 -2.72803e-6 5.1128e-6 -1 -0.47075 0.8822665 0 -0.29099 0.956726 0 -5.97772e-6 8.48644e-6 -1 -0.6339867 0.7733439 0 -0.47075 0.8822665 0 -0.7071079 0.7071058 1.59122e-7 -0.7071081 0.7071053 0 -0.6339867 0.7733439 0 -0.7071067 -0.7071069 -1.56099e-7 -0.7071065 0.707107 0 -0.7071065 -0.7071069 0 0.7071068 0.7071069 0 -0.7071065 0.707107 0 -0.7071068 0.7071068 1.56099e-7 0.7071066 0.7071069 1.56099e-7 0.7071068 -0.7071068 0 0.8662425 -0.499624 0 0.8662425 -0.499624 0 0.7071068 -0.7071068 0 0.4996325 -0.8662374 0 -1.14871e-5 -1 0 0.4996325 -0.8662374 0 -0.4996289 -0.8662395 0 -1.14871e-5 -1 0 -0.7071076 -0.7071061 0 -0.4996289 -0.8662395 0 -0.8662325 -0.4996412 0 -0.7071076 -0.7071061 0 -1 0 0 -0.8662325 -0.4996412 0 -0.8662325 0.4996412 0 -1 0 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.8662325 0.4996412 0 -0.4996203 0.8662445 0 0 1 0 -0.4996203 0.8662445 0 0.4996153 0.8662474 0 0 1 0 0.7071068 0.7071068 0 0.4996153 0.8662474 0 0.8662424 0.4996239 0 0.7071068 0.7071068 0 1 1.14873e-5 0 0.8662425 0.499624 0 1 1.14873e-5 0 -0.499624 0.8662425 0 -0.7071068 0.7071068 0 -1.14873e-5 1 0 -0.499624 0.8662425 0 0.4996325 0.8662374 0 -1.14873e-5 1 0 0.7071066 0.707107 0 0.4996325 0.8662374 0 0.86624 0.4996283 0 0.7071065 0.7071071 1.561e-7 1 1.14872e-5 0 0.86624 0.4996283 0 -2.31097e-6 2.99725e-6 -1 0.8662374 -0.4996325 0 1 1.14872e-5 0 -1.56701e-6 4.20116e-6 -1 0.7071087 -0.7071049 -1.58319e-7 -5.44026e-6 -2.21823e-6 -1 0.7071087 -0.7071049 -1.56099e-7 0.8662374 -0.4996325 0 -1.58966e-6 4.19887e-6 -1 0.4996283 -0.86624 -1.91229e-7 -1.58967e-6 4.19886e-6 -1 -1.43591e-6 4.57036e-6 -1 -1.43587e-6 4.57044e-6 -1 -5.74359e-6 -1 -2.20758e-7 0.4996283 -0.86624 -1.91229e-7 -8.05687e-6 -6.75484e-6 -1 -0.4996325 -0.8662374 0 -1.73958e-6 3.71521e-6 -1 0 -1 0 -0.7071064 -0.7071072 0 -1.86177e-6 3.57029e-6 -1 -0.4996325 -0.8662374 0 -0.8662453 -0.4996189 0 -0.7071064 -0.7071073 0 -1 0 0 -0.8662453 -0.4996189 0 -0.8662425 0.499624 0 -1 0 0 -0.7071068 0.7071068 0 -0.8662425 0.499624 0 0.7071086 -0.7071049 -1.58319e-7 0.8662414 -0.4996258 0 0.8662414 -0.4996258 0 0.7071087 -0.7071049 -1.56099e-7 0.499624 -0.8662425 -1.9123e-7 0 -1 -2.20758e-7 0.499624 -0.8662424 -1.9123e-7 -0.4996325 -0.8662374 -1.91229e-7 0 -1 -2.20758e-7 -0.7071065 -0.7071071 -1.561e-7 -0.4996325 -0.8662374 -1.91229e-7 -0.8662399 -0.4996283 0 -0.7071065 -0.7071071 -1.561e-7 -1 0 0 -0.86624 -0.4996283 0 -0.8662425 0.499624 0 -1 0 0 -0.7071049 0.7071086 1.5495e-7 -0.7071049 0.7071087 1.561e-7 -0.8662425 0.499624 0 -0.49963 0.8662388 1.91229e-7 0 1 2.20758e-7 -0.49963 0.8662388 1.91229e-7 0.4996351 0.866236 1.91228e-7 0 1 2.20758e-7 0.7071067 0.7071069 1.56099e-7 0.4996351 0.866236 1.91228e-7 0.8662374 0.4996325 0 0.7071067 0.7071069 1.56099e-7 1 5.74363e-6 0 0.8662374 0.4996325 0 1 5.74363e-6 0 -0.49963 0.8662388 1.91229e-7 -0.7071049 0.7071086 1.5495e-7 0 1 2.20758e-7 -0.49963 0.8662388 1.9163e-7 0.4996344 0.8662363 1.91229e-7 0 1 2.20758e-7 0.7071047 0.7071089 0 0.7071054 0.7071083 1.561e-7 0.4996344 0.8662363 1.91229e-7 0.8662435 0.4996221 0 1 5.74356e-6 0 0.8662435 0.4996221 0 0.86624 -0.4996283 0 1 5.74356e-6 0 0.7071087 -0.7071049 -1.58319e-7 0.7071068 -0.7071068 0 0.86624 -0.4996283 0 0.4996258 -0.8662414 -1.9123e-7 -5.74363e-6 -1 -2.20758e-7 0.4996258 -0.8662414 -1.9123e-7 -0.4996264 -0.866241 -1.9123e-7 -5.74363e-6 -1 -2.20758e-7 -0.7071068 -0.7071068 -1.53989e-7 -0.7071068 -0.7071068 -1.56099e-7 -0.4996264 -0.866241 -1.9123e-7 -0.8662364 -0.4996345 0 -1 5.74363e-6 0 -0.8662364 -0.4996345 0 -0.8662425 0.499624 0 -1 5.74363e-6 0 -0.7071049 0.7071087 1.561e-7 -0.8662425 0.499624 0 0.7071071 0.7071065 0 -0.7071062 0.7071073 0 -0.7071063 0.7071074 0 0.707107 -0.7071065 -1.56099e-7 0.7071068 0.7071068 1.52177e-7 -0.707107 -0.7071067 -1.56099e-7 0.707107 -0.7071065 -1.56099e-7 -0.7071067 -0.707107 0 8.52941e-7 -5.18487e-6 1 2.96285e-6 -3.72616e-6 1 2.25936e-6 -4.29577e-6 1 2.26634e-6 -4.35931e-6 1 7.36326e-7 -5.12383e-6 1 1.47217e-6 -3.38995e-6 1 3.9234e-7 -2.48789e-6 1 1.69675e-6 -3.7923e-6 1 1.13637e-6 -4.95555e-6 1 1.53161e-6 -4.30773e-6 1 8.86924e-7 -3.03727e-6 1 1.6664e-6 -3.58418e-6 1 1.4079e-6 -4.0928e-6 1 3.19958e-6 -5.34992e-6 1 2.32287e-6 -4.71778e-6 1 5.614e-7 -3.2463e-6 1 1.68916e-6 -3.88295e-6 1 1.36983e-6 -3.76475e-6 1 8.55421e-6 -4.50675e-6 1 -1.37014e-6 -2.53834e-6 1 3.06879e-6 -4.38586e-6 1 2.43593e-6 -4.22338e-6 1 3.50252e-6 -3.2821e-6 1 9.7156e-7 -4.08657e-6 1 1.4359e-6 -4.01329e-6 1 3.86512e-6 -2.68959e-6 1 1.42624e-5 3.76055e-6 1 1.83179e-6 -4.55909e-6 1 1.81094e-6 -4.59013e-6 1 8.5643e-7 -5.43167e-6 1 2.1149e-6 -4.30865e-6 1 1.0167e-6 -3.31804e-6 1 4.48341e-7 -2.84325e-6 1 1.80358e-6 -4.19848e-6 1 -1.37062e-7 -6.26784e-6 1 1.77161e-6 -4.30777e-6 1 3.57992e-6 -1.26381e-6 1 6.01796e-7 -3.18221e-6 1 1.53716e-6 -3.83851e-6 1 2.69344e-6 -4.99479e-6 1 1.7581e-6 -4.3385e-6 1 4.48383e-7 -2.84329e-6 1 1.01675e-6 -3.31809e-6 1 1.7685e-6 -3.96232e-6 1 1.47314e-6 -3.86805e-6 1 4.28798e-6 -3.83392e-6 1 8.67218e-6 -6.66618e-6 1 1.40561e-6 -4.03977e-6 1 5.71735e-7 -3.87675e-6 1 4.39048e-6 -2.98522e-6 1 2.99297e-6 -3.46759e-6 1 1.43585e-6 -3.77152e-6 1 2.07414e-6 -4.26797e-6 1 1.99015e-5 -6.29587e-6 1 1.39329e-6 -4.02745e-6 1 1.02183e-6 -3.91799e-6 1 8.37854e-6 7.70222e-7 1 5.31307e-7 -3.80674e-6 1 3.61148e-6 -3.17313e-6 1 3.03746e-6 -3.39032e-6 1 1.43595e-6 -3.7749e-6 1 7.8005e-7 -5.32821e-6 1 1.39931e-6 -4.91219e-6 1 2.27088e-6 -4.38848e-6 1 2.2219e-6 -4.41565e-6 1 9.78378e-7 -5.01423e-6 1 1.37242e-6 -4.30771e-6 1 1.56958e-6 -3.76334e-6 1 8.55404e-6 -4.5067e-6 1 1.21707e-6 -3.85125e-6 1 5.96011e-6 -5.10194e-6 1 8.29595e-6 -1.01564e-6 1 2.23254e-6 -3.87069e-6 1 7.59405e-6 -1.43741e-6 1 1.00266e-6 -4.03259e-6 1 1.43592e-6 -3.91961e-6 1 6.00257e-7 -5.68198e-6 1 2.55572e-6 -3.88002e-6 1 2.01262e-6 -4.73911e-6 1 2.23881e-6 -4.18485e-6 1 2.10812e-6 -4.30184e-6 1 0 -6.21844e-6 1 1.27558e-6 -4.30771e-6 1 1.31371e-6 -4.23522e-6 1 9.49895e-6 -9.60683e-6 1 1.26414e-6 -4.75183e-6 1 1.04099e-6 -4.50776e-6 1 1.41536e-6 -3.81202e-6 1 1.86018e-6 -4.18589e-6 1 -8.52392e-6 5.86561e-6 1 1.49367e-5 -1.3301e-5 1 1.19821e-6 -4.67265e-6 1 1.0258e-6 -3.37573e-6 1 6.05464e-7 -3.11079e-6 1 2.41319e-6 -4.50983e-6 1 -8.29967e-6 5.39201e-6 1 -1.11826e-5 7.21298e-6 1 1.13366e-5 -1.34618e-5 1 -1.97411e-5 1.61847e-5 1 -6.9832e-6 2.02224e-6 1 -5.11957e-6 5.5467e-7 1 2.17861e-6 -5.36015e-6 1 1.3478e-5 -1.49539e-5 1 1.98818e-6 -4.35391e-6 1 1.00319e-6 -4.39324e-6 1 3.42167e-6 -5.83484e-6 1 1.20744e-6 -4.53115e-6 1 1.37456e-6 -4.6615e-6 1 6.13312e-7 -3.96549e-6 1 1.04576e-6 -4.50432e-6 1 1.20154e-6 -4.59612e-6 1 1.6376e-6 -4.91852e-6 1 2.48562e-6 -5.61004e-6 1 2.01988e-6 -5.18027e-6 1 1.90506e-6 -6.26922e-6 1 5.05896e-6 -8.25718e-6 1 4.48186e-6 -8.37558e-6 1 -1.72399e-6 -2.63958e-6 1 -5.29716e-6 2.39426e-6 1 5.44475e-5 -5.65726e-5 1 2.70478e-5 -3.04349e-5 1 1.74226e-6 -3.90768e-6 1 -1.80709e-6 -7.47356e-7 1 3.63564e-6 -5.80286e-6 1 2.6229e-6 -4.80257e-6 1 -9.46394e-7 -3.12374e-6 1 4.03408e-6 -6.33181e-6 1 8.89315e-7 -4.42791e-6 1 1.09303e-6 -4.59222e-6 1 2.70799e-6 -4.6448e-6 1 5.81267e-7 -3.08359e-6 1 1.70519e-6 -4.27999e-6 1 5.5003e-7 -3.48802e-6 1 3.08536e-6 -5.21061e-6 1 -5.19345e-7 -2.97722e-6 1 1.31235e-5 -1.53251e-5 1 2.82034e-6 -5.02194e-6 1 9.03273e-7 -4.60939e-6 1 2.18231e-6 -5.67888e-6 1 9.96725e-7 -4.68754e-6 1 9.03322e-7 -4.60944e-6 1 6.65811e-7 -4.22224e-6 1 -7.49965e-7 -2.94085e-6 1 6.79e-7 -3.16619e-6 1 -1.33334e-5 9.08286e-6 1 1.58089e-5 -1.47294e-5 1 -2.10196e-6 -7.84807e-7 1 2.66732e-7 -4.27107e-6 1 1.72399e-6 -4.19236e-6 1 2.54558e-6 -4.96417e-6 1 5.15264e-7 -3.26755e-6 1 1.61217e-6 -3.85969e-6 1 2.27256e-6 -4.39773e-6 1 1.06218e-6 -4.55874e-6 1 1.03979e-6 -4.54001e-6 1 1.03984e-6 -4.54006e-6 1 6.34105e-7 -4.02118e-6 1 -5.19346e-7 -2.97722e-6 1 3.74721e-7 -3.1182e-6 1 1.44017e-6 -3.73519e-6 1 4.35996e-7 -3.15743e-6 1 2.57841e-6 -4.89977e-6 1 5.56297e-7 -3.52776e-6 1 1.61353e-6 -3.89234e-6 1 2.2111e-6 -4.33634e-6 1 -2.88725e-7 -3.01359e-6 1 6.024e-7 -3.82012e-6 1 -1.59068e-7 -3.05866e-6 1 2.24777e-6 -5.55008e-6 1 2.78889e-6 -4.48543e-6 1 1.65454e-6 -4.22764e-6 1 1.14378e-6 -3.59959e-6 1 4.54249e-7 -2.88059e-6 1 1.96213e-6 -4.0873e-6 1 -5.1727e-6 9.22284e-7 1 -1.39167e-6 -1.3101e-6 1 2.02101e-5 -1.9453e-5 1 9.28945e-7 -3.77232e-6 1 2.06305e-6 -4.37025e-6 1 1.74738e-6 -3.97176e-6 1 2.05831e-6 -4.31863e-6 1 1.79078e-6 -4.11398e-6 1 1.24308e-6 -3.58168e-6 1 3.46723e-6 -5.76545e-6 1 2.88252e-6 -5.27936e-6 1 3.003e-6 -5.31714e-6 1 3.66845e-6 -4.61947e-6 1 1.54962e-6 -3.79238e-6 1 1.31867e-6 -3.62747e-6 1 1.39311e-6 -3.66811e-6 1 1.13511e-6 -3.46373e-6 1 1.88777e-6 -5.17648e-6 1 3.14188e-6 -5.77321e-6 1 2.01869e-6 -5.26042e-6 1 2.73027e-6 -5.80771e-6 1 4.11007e-7 -2.57398e-6 1 3.81864e-6 -6.70541e-6 1 2.28538e-6 -4.34436e-6 1 1.35147e-6 -3.79676e-6 1 1.22881e-6 -3.64535e-6 1 1.56401e-6 -3.78572e-6 1 2.18056e-6 -4.1238e-6 1 2.35219e-6 -4.29929e-6 1 2.28938e-6 -4.50567e-6 1 -1.5174e-5 1.07864e-5 1 1.54174e-6 -3.59283e-6 1 0 -4.74388e-6 1 1.72733e-6 -4.02024e-6 1 1.14897e-6 -3.77073e-6 1 1.8972e-6 -4.24913e-6 1 -1.98624e-5 -1.35828e-5 1 -7.61896e-6 -8.97814e-6 1 1.92918e-6 -4.10907e-6 1 3.33135e-7 -6.20756e-6 1 2.45884e-6 -5.58031e-6 1 3.23387e-6 -5.42761e-6 1 3.95909e-6 -5.36094e-6 1 3.92916e-6 -5.34319e-6 1 8.02019e-7 -5.28503e-6 1 -1.09034e-6 -5.78616e-6 1 8.32538e-7 -5.27959e-6 1 2.94655e-6 -5.14029e-6 1 1.06793e-6 -3.32617e-6 1 2.91038e-6 -5.13987e-6 1 2.02326e-6 -4.10861e-6 1 4.77122e-7 -3.24555e-6 1 1.98464e-6 -4.24978e-6 1 1.3865e-6 -4.13494e-6 1 2.25266e-6 -4.2729e-6 1 1.6808e-6 -4.55804e-6 1 2.13084e-6 -4.32457e-6 1 2.55279e-6 -3.5603e-6 1 2.42272e-6 -4.22042e-6 1 2.17129e-6 -4.85319e-6 1 4.80478e-7 -5.91761e-6 1 -9.04387e-7 -3.94767e-6 1 7.35566e-7 -5.78056e-6 1 2.36616e-6 -4.99241e-6 1 2.67179e-6 -4.86554e-6 1 1.00395e-6 -3.31609e-6 1 4.39946e-7 -2.78977e-6 1 1.62693e-6 -3.97675e-6 1 1.90119e-6 -5.13309e-6 1 3.2187e-6 -5.34018e-6 1 1.53352e-6 -3.84566e-6 1 4.47087e-7 -2.55182e-6 1 1.81031e-6 -3.9318e-6 1 -1.05364e-6 -1.20422e-6 1 2.18103e-6 -3.81841e-6 1 1.56439e-6 -4.01387e-6 1 1.72561e-6 -3.91934e-6 1 1.72905e-7 -4.76395e-6 1 2.83149e-6 -6.46499e-6 1 1.71711e-6 -3.92059e-6 1 3.12003e-6 -5.39034e-6 1 6.573e-6 -6.573e-6 1 4.2147e-6 -5.40133e-6 1 1.51297e-6 -3.77084e-6 1 5.71755e-7 -3.48003e-6 1 2.14815e-6 -4.14028e-6 1 1.62271e-6 -3.67015e-6 1 2.18853e-6 -3.86605e-6 1 1.66805e-6 -3.72998e-6 1 -2.63331e-6 -1.75421e-6 1 -2.35304e-6 -1.20782e-6 1 2.42631e-6 -4.30297e-6 1 1.70804e-6 -5.71176e-6 1 -8.88299e-7 -3.5668e-6 1 2.83163e-6 -6.81697e-6 1 0 -4.13558e-6 1 9.03482e-7 -4.61837e-6 1 1.66632e-6 -5.15707e-6 1 0 -4.02992e-6 1 -1.10943e-4 8.04049e-5 1 3.10375e-5 -2.58404e-5 1 -7.02689e-7 -2.28033e-6 1 2.46025e-6 -4.77993e-6 1 2.00618e-6 -4.38171e-6 1 2.49037e-6 -4.042e-6 1 1.21117e-6 -3.57348e-6 1 6.0836e-7 -3.19489e-6 1 1.35115e-6 -3.60941e-6 1 0 -2.69975e-6 1 4.5107e-6 -6.19975e-6 1 4.465e-6 -6.16104e-6 1 2.1193e-6 -4.4682e-6 1 7.43451e-7 -2.89869e-6 1 3.9822e-6 -6.30141e-6 1 3.41459e-6 -5.99741e-6 1 1.23061e-6 -4.77997e-6 1 -1.64145e-6 -3.04293e-6 1 -3.05119e-6 5.42451e-7 1 9.17266e-7 -4.50537e-6 1 8.54688e-7 -4.48236e-6 1 5.09022e-6 -6.21839e-6 1 3.12083e-6 -4.87598e-6 1 -1.7306e-6 -1.06843e-6 1 2.47188e-6 -4.77769e-6 1 2.50875e-6 -4.51573e-6 1 7.0391e-7 -5.63765e-6 1 2.48438e-6 -4.65615e-6 1 1.55345e-6 -5.10747e-6 1 7.69911e-7 -3.67153e-6 1 1.90543e-6 -4.2132e-6 1 1.06236e-6 -3.94995e-6 1 2.08151e-5 -1.92678e-5 1 1.76398e-6 -4.65157e-6 1 2.18906e-6 -4.3443e-6 1 4.06231e-6 -2.72231e-6 1 2.89003e-6 -3.64592e-6 1 1.4359e-6 -4.77361e-6 1 -1.79174e-5 -1.92736e-5 1 3.72016e-6 -4.51147e-6 1 4.06473e-6 -4.46498e-6 1 2.61852e-6 -4.11678e-6 1 1.43589e-6 -3.6413e-6 1 0 -2.80055e-6 1 5.7417e-7 -3.20834e-6 1 1.3015e-6 -4.28766e-6 1 2.63916e-6 -5.03387e-6 1 2.44381e-6 -4.83853e-6 1 -5.63149e-7 -1.33949e-6 1 1.747e-6 -4.30777e-6 1 1.60469e-6 -4.06736e-6 1 1.35236e-6 -4.33852e-6 1 1.19416e-6 -3.9873e-6 1 4.21887e-6 -6.50663e-6 1 1.51189e-6 -4.30502e-6 1 1.76837e-6 -4.0996e-6 1 2.00117e-6 -4.28894e-6 1 1.55235e-6 -3.73881e-6 1 7.76833e-7 -3.10806e-6 1 1.83115e-6 -4.18304e-6 1 2.71735e-6 -4.90382e-6 1 -1.12635e-6 -5.64259e-6 1 2.83045e-6 -4.54525e-6 1 1.10071e-6 -3.86282e-6 1 1.43591e-6 -4.06122e-6 1 3.0807e-6 -5.34133e-6 1 4.2458e-7 -3.05874e-6 1 -2.77631e-5 -2.69912e-5 1 4.94403e-6 -1.94339e-6 1 -1.25787e-7 -5.98909e-6 1 1.43591e-6 -4.76105e-6 1 6.99321e-7 -2.06767e-6 1 1.9676e-6 -4.30766e-6 1 1.82088e-6 -3.94275e-6 1 1.16306e-6 -4.84751e-6 1 4.87505e-6 -7.13292e-6 1 1.68922e-6 -4.60528e-6 1 9.71442e-7 -4.60682e-6 1 4.02024e-6 -5.21098e-6 1 9.30722e-7 -4.49919e-6 1 1.36685e-6 -4.001e-6 1 -6.88828e-5 -4.63873e-5 1 2.87849e-6 -3.32458e-6 1 1.43845e-6 -4.15828e-6 1 4.54665e-6 -2.87181e-6 1 5.03218e-7 -4.30769e-6 1 -6.28957e-6 -8.62064e-6 1 1.36683e-6 -4.00101e-6 1 2.07686e-6 -3.60077e-6 1 1.34791e-5 1.83714e-5 -1 -0.4705972 0.8823482 2.19134e-7 -2.52204e-6 4.22146e-6 -1 -0.7071068 0.7071067 0 -4.39789e-6 2.3456e-6 -1 -0.7071068 0.7071067 1.75612e-7 -2.22187e-5 -1.62163e-5 -1 0.09711402 0.9952732 2.47179e-7 -5.42125e-6 -5.2898e-7 -1 -0.4705973 0.8823482 2.19379e-7 2.51674e-5 3.06102e-5 -1 0.6350916 0.7724368 1.91837e-7 -3.37588e-5 -2.77564e-5 -1 0.09711402 0.9952732 2.47179e-7 -8.05386e-6 -2.45107e-6 -1 0.9566773 0.2911505 0 -7.99975e-7 4.64273e-6 -1 -3.73382e-6 2.13763e-6 -1 -4.78089e-6 2.7072e-7 -1 0.6350916 0.7724368 1.91837e-7 4.33628e-7 5.09825e-6 -1 1 2.12427e-7 0 0.9566773 0.2911505 0 2.33704e-5 1.43565e-5 -1 0.9566773 -0.2911505 0 1.37033e-7 5.24704e-6 -1 1 2.12427e-7 0 -2.65607e-6 3.23043e-6 -1 0.6350962 -0.7724331 -1.91837e-7 0.9566773 -0.2911505 0 -4.20957e-7 4.31424e-6 -1 0.09711247 -0.9952734 -2.4718e-7 0.6350962 -0.7724331 -1.91837e-7 3.4093e-6 6.3923e-6 -1 -0.4705961 -0.8823487 -2.19135e-7 0.09711247 -0.9952734 -2.4718e-7 -1.36169e-5 -3.42036e-6 -1 -0.7071065 -0.7071071 -1.75613e-7 -0.4705962 -0.8823487 -2.19135e-7 -1.08621e-5 -6.26495e-6 -1 -0.8662416 -0.4996253 0 5.74381e-6 9.9585e-6 -1 9.69805e-6 1.39127e-5 -1 -0.7071065 -0.7071071 0 -4.92564e-6 0 -1 -1 0 0 0 4.59711e-6 -1 -0.8662416 -0.4996253 0 -3.20758e-6 1.85004e-6 -1 -0.8662418 0.4996252 0 -1.80177e-6 3.12387e-6 -1 -1 0 0 -8.29395e-7 4.22823e-6 -1 -0.8662418 0.4996251 0 -1.23459e-5 -3.84881e-6 -1 0.7071067 0.7071068 1.31709e-7 7.65837e-6 1.3278e-5 -1 0.4996252 0.8662418 0 4.22672e-6 9.8463e-6 -1 0.499624 0.8662424 1.84113e-7 -1.38757e-5 -7.40054e-6 -1 0.8823487 0.4705963 0 1.2589e-6 7.89164e-6 -1 -2.38795e-6 3.02566e-6 -1 0.7071067 0.7071068 0 -5.2897e-6 5.16141e-7 -1 0.9952733 -0.09711349 0 0.8823487 0.4705963 0 -3.14526e-6 2.58603e-6 -1 0.7724343 -0.6350946 0 -3.40061e-6 2.3457e-6 -1 0.9952733 -0.09711349 0 1.53776e-5 2.0015e-5 -1 0.2911503 -0.9566773 0 -3.47033e-6 2.25512e-6 -1 0.7724343 -0.6350946 0 -3.39883e-6 3.82121e-6 -1 0 -1 0 -3.85977e-6 4.33943e-6 -1 4.02602e-7 2.36966e-6 -1 6.94233e-7 2.40855e-6 -1 -1.06794e-5 -4.23381e-6 -1 5.39648e-6 9.76723e-6 -1 0.2911501 -0.9566774 0 -1.25409e-5 2.93363e-5 -1 -0.2911485 -0.9566779 0 -2.91502e-6 4.78563e-6 -1 0 -1 0 -2.53197e-5 -2.08179e-5 -1 -0.7724335 -0.6350957 0 1.88759e-5 2.2958e-5 -1 -1.22244e-6 2.85959e-6 -1 -0.2911485 -0.9566779 0 -5.42125e-6 -5.28971e-7 -1 -0.9952734 -0.09711247 0 4.86753e-7 4.98857e-6 -1 -0.7724335 -0.6350957 0 -3.29843e-6 1.7592e-6 -1 -0.8823493 0.4705952 0 -1.70168e-6 3.19059e-6 -1 -0.9952734 -0.09711247 0 -2.52204e-6 4.22146e-6 -1 -0.707107 0.7071067 0 -8.29396e-7 4.22823e-6 -1 -0.8823493 0.4705952 0 -2.40236e-6 4.16517e-6 -1 -0.4996252 0.8662418 0 -4.27677e-6 2.46673e-6 -1 -0.707107 0.7071067 0 0 6.12948e-6 -1 0 1 0 -6.56752e-6 0 -1 -0.4996252 0.8662418 0 -1.44827e-5 -8.35324e-6 -1 0 1 0 0.8662418 0.499625 0 -6.99249e-6 1.50459e-6 -1 0.7071067 0.7071069 1.75612e-7 0.7071067 0.7071069 0 1 0 0 0.8662418 0.499625 0 0.8662418 -0.4996252 0 1 0 0 0.707107 -0.7071064 0 0.8662418 -0.4996252 0 0.4705952 -0.8823493 -2.19134e-7 0.707107 -0.7071064 -1.75612e-7 -0.09711247 -0.9952734 -2.47179e-7 0.4705952 -0.8823493 -2.19134e-7 -0.6350929 -0.7724358 -1.91837e-7 -0.09711247 -0.9952734 -2.47179e-7 2.8637e-5 3.01841e-5 -1 -0.9566773 -0.2911505 0 -2.54919e-6 4.24984e-6 -1 -3.15455e-6 3.17047e-6 -1 -0.6350929 -0.7724358 -1.91837e-7 4.33627e-7 5.09825e-6 -1 -1 -2.12427e-7 0 -0.9566773 -0.2911505 0 -7.45777e-6 2.26966e-6 -1 -0.9566773 0.2911505 0 1.35978e-7 5.24757e-6 -1 -1 -2.12427e-7 0 -3.32053e-6 4.03861e-6 -1 -0.6350929 0.7724358 1.91837e-7 -0.9566773 0.2911505 0 1.91776e-5 1.49501e-5 -1 -0.09711372 0.9952733 2.47179e-7 -0.6350929 0.7724358 1.91837e-7 -2.9348e-5 -1.1382e-5 -1 0.4705972 0.8823482 2.19134e-7 -0.09711372 0.9952733 2.47179e-7 0.4705972 0.8823482 2.19134e-7 -2.47406e-5 -1.45441e-5 -1 -0.7071065 -0.707107 0 -0.4996262 -0.8662411 0 -0.4996262 -0.8662411 0 -1.38757e-5 -7.40049e-6 -1 -0.8823493 -0.4705952 0 -2.38795e-6 3.02566e-6 -1 1.25787e-6 7.89027e-6 -1 -0.7071065 -0.707107 0 -5.28972e-6 5.1613e-7 -1 -0.9952735 0.09711122 0 -0.8823493 -0.4705952 0 -3.14915e-6 2.58923e-6 -1 -0.7724348 0.6350942 0 -0.9952735 0.09711122 0 -1.3819e-6 4.54067e-6 -1 -0.2911528 0.9566766 0 -3.38881e-7 5.49531e-6 -1 -0.7724348 0.6350942 0 -3.39883e-6 3.33318e-6 -1 -2.12427e-7 1 0 -5.4732e-6 6.92879e-6 -1 -2.30202e-6 4.2596e-6 -1 -2.00785e-6 4.22961e-6 -1 -1.63738e-6 4.38937e-6 -1 -1.14962e-6 4.7696e-6 -1 -0.2911528 0.9566766 0 1.88694e-6 6.20018e-6 -1 0.2911512 0.956677 0 -2.97308e-6 3.877e-6 -1 -2.12427e-7 1 0 0.772435 0.6350939 0 0.291151 0.956677 0 0.9952732 0.09711402 0 0.772435 0.6350939 0 0.8823481 -0.4705972 0 0.9952732 0.09711402 0 0.707107 -0.7071067 0 0.8823481 -0.4705972 0 0.4996253 -0.8662418 -2.46155e-7 0.7071069 -0.7071067 -2.19515e-7 0 -1 0 0.4996263 -0.8662411 0 0 -1 0 -2.49759e-6 2.49759e-6 -1 0.7071067 0.7071068 7.02448e-7 0.707107 -0.7071065 0 0.7071065 -0.7071069 -7.02448e-7 4.88224e-6 1.11682e-5 -1 0.7071067 -0.7071067 -7.02448e-7 6.33418e-7 9.69145e-6 -1 -5.81989e-6 1.47173e-6 -1 0.7071067 0.7071069 6.89869e-7 -9.85497e-6 -2.85619e-7 -1 -0.7071068 -0.7071068 0 2.25525e-7 4.56744e-6 -1 0.7071073 -0.7071064 0 -8.74721e-7 5.02506e-6 -1 2.1868e-7 -1 0 -2.90755e-6 4.68848e-6 -1 -2.10132e-6 4.87977e-6 -1 -1.52799e-6 5.09576e-6 -1 -0.7071068 -0.7071068 0 -0.04203033 -0.9991163 0 2.1868e-7 -1 0 -0.1252129 -0.9921299 -4.84051e-7 -0.04203075 -0.9991163 -4.93331e-7 -0.2077736 -0.978177 0 -0.1252124 -0.99213 0 -0.2887699 -0.9573986 0 -0.2077736 -0.978177 0 -0.3677463 -0.9299262 0 -0.2887699 -0.9573986 0 -0.4442529 -0.8959014 -4.44999e-7 -0.3677466 -0.929926 -4.619e-7 -0.5174258 -0.855728 0 -0.4442527 -0.8959016 0 0.6195269 -0.7849755 0 -0.5174258 -0.855728 0 -2.15645e-6 2.21333e-6 -1 0.6978435 -0.7162504 0 -6.22052e-6 -8.70386e-7 -1 -1.74902e-5 -1.05591e-5 -1 0.6195269 -0.7849755 0 -2.5976e-7 4.46929e-6 -1 0.7685832 -0.6397498 -3.17767e-7 -1.91206e-6 4.41102e-6 -1 0.6978433 -0.7162505 -3.55766e-7 0.7071065 0.707107 0 0.7685834 -0.6397496 0 -0.7069541 0.7072596 3.513e-7 0.7071064 0.7071073 3.51224e-7 0.7071066 0.7071071 0 -0.7069538 0.7072597 0 -9.30239e-7 5.71294e-6 -1 0.707107 -0.7071065 0 -3.47145e-6 3.47145e-6 -1 0.7071066 0.7071071 0 1 0 0 5.20768e-7 7.16524e-6 -1 0.707107 -0.7071065 0 0.9984006 -0.05653488 0 1 0 0 1.49554e-6 3.94041e-6 -1 0.9858725 -0.1674973 0 0.9984006 -0.05653488 0 1.31022e-6 3.89644e-6 -1 0.9608813 -0.2769606 0 0.9858726 -0.1674973 0 -4.30227e-6 1.78206e-6 -1 0.9238796 -0.3826832 0 0.9608813 -0.2769606 0 -4.31251e-6 2.3827e-6 -1 0.8752871 -0.4836037 -2.40209e-7 -6.28274e-7 4.1564e-6 -1 0.9238796 -0.3826833 -1.90081e-7 3.19004e-6 1.29479e-5 -1 0.8155552 -0.5786793 -2.87433e-7 3.12512e-6 1.29253e-5 -1 0.875287 -0.4836037 -2.40209e-7 4.89785e-7 5.0576e-6 -1 0.7459532 -0.6659985 -3.30807e-7 -5.81989e-6 1.47173e-6 -1 0.8155552 -0.5786793 -2.87435e-7 -2.24855e-6 2.38964e-6 -1 0.7849757 0.6195265 0 0.7459534 -0.6659982 0 4.01957e-5 4.82903e-5 -1 0.7162504 0.6978435 3.46624e-7 0.7849755 0.6195268 3.07724e-7 0.6397497 0.7685833 0 0.7162505 0.6978433 0 1.11573e-6 3.61332e-6 -1 -0.7071069 0.7071065 0 0.6397497 0.7685833 0 -0.7071067 -0.7071069 0 -0.7071069 0.7071065 0 -0.7071066 0.707107 0 -0.7071067 -0.7071069 0 0.7071065 0.707107 0 -0.7071066 0.7071071 0 -1.45751e-7 1 0 0.7071069 0.7071065 -7.02448e-7 0.0565344 0.9984007 0 -1.45751e-7 1 0 0.1674983 0.9858723 0 0.0565344 0.9984006 0 0.276961 0.9608812 0 0.1674983 0.9858724 0 0.3826832 0.9238796 4.58898e-7 0.2769606 0.9608813 4.77277e-7 0.4836035 0.8752872 4.34762e-7 0.3826833 0.9238796 4.58898e-7 0.5786779 0.8155562 0 0.4836038 0.8752869 0 0.6660001 0.7459516 7.4104e-7 0.5786772 0.8155567 8.10187e-7 -0.6195273 0.7849751 7.79806e-7 0.6660001 0.7459516 7.4104e-7 4.66832e-7 4.20506e-6 -1 -0.6978424 0.7162513 0 -2.83846e-5 -1.76844e-5 -1 -0.6195269 0.7849755 0 -5.16166e-6 4.29643e-6 -1 -0.768584 0.6397488 3.17768e-7 4.99136e-7 4.49605e-6 -1 -0.6978426 0.7162511 3.55767e-7 -0.7071064 -0.7071073 0 -0.7685839 0.6397491 0 0.707107 -0.7071065 -3.51225e-7 -0.7071065 -0.7071069 -3.51226e-7 -0.7071064 -0.7071073 0 0.7071071 -0.7071065 0 -0.7071066 0.7071071 0 -0.7071064 -0.7071073 0 -1 -2.91502e-7 0 -0.7071066 0.7071071 0 -0.9984006 0.05653488 0 -1 -2.91502e-7 0 -0.9858725 0.1674972 0 -0.9984007 0.05653488 0 -0.9608808 0.2769622 0 -0.9858725 0.1674972 0 -0.9238796 0.3826834 0 -0.9608808 0.2769622 0 -0.8752877 0.4836025 2.40208e-7 -0.9238795 0.3826833 1.90081e-7 -0.8155559 0.5786783 2.87433e-7 -0.8752877 0.4836025 2.40208e-7 4.89786e-7 5.0576e-6 -1 -0.7459529 0.6659987 0 -0.8155557 0.5786786 0 -2.24855e-6 2.38964e-6 -1 -0.7849757 -0.6195265 0 -0.7459529 0.6659987 0 -2.40328e-6 2.2223e-6 -1 -0.7162513 -0.6978424 -3.46622e-7 -0.7849759 -0.6195263 -3.07722e-7 -0.6397486 -0.7685843 0 -0.7162511 -0.6978427 0 -0.6397486 -0.7685843 0 1.6791e-6 -3.37852e-6 1 -1.28352e-5 -1.95787e-5 1 1.67233e-6 -5.07117e-6 1 3.12387e-6 -1.80177e-6 1 1.85005e-6 -3.20757e-6 1 4.59711e-6 0 1 0 -4.92564e-6 1 9.95846e-6 5.74378e-6 1 -6.26499e-6 -1.08621e-5 1 -1.31791e-5 -2.16762e-5 1 1.68755e-5 1.26608e-5 1 -3.4093e-6 -6.3923e-6 1 4.80435e-6 -1.65854e-6 1 4.20957e-7 -4.31424e-6 1 2.65607e-6 -3.23043e-6 1 8.85952e-5 -4.84315e-5 1 -6.97485e-7 -4.66404e-6 1 5.21674e-7 -4.24854e-6 1 5.94796e-6 1.81017e-6 1 4.98108e-6 -2.82056e-7 1 -2.77556e-5 -3.3758e-5 1 3.06108e-5 2.51681e-5 1 4.28139e-6 -1.16131e-6 1 2.23387e-5 1.74465e-5 1 6.65143e-6 6.49015e-7 1 3.19059e-6 -1.70169e-6 1 -8.3532e-6 -1.44827e-5 1 -1.75223e-6 -8.5499e-6 1 1.32779e-5 7.65837e-6 1 3.91875e-6 -1.70083e-6 1 0 -6.56753e-6 1 6.12948e-6 0 1 2.46673e-6 -4.27677e-6 1 4.16517e-6 -2.40236e-6 1 1.6791e-6 -3.37852e-6 1 1.67233e-6 -5.07116e-6 1 3.19059e-6 -1.70168e-6 1 1.75919e-6 -3.29843e-6 1 4.98857e-6 4.86753e-7 1 -5.28971e-7 -5.42125e-6 1 2.29587e-5 1.88766e-5 1 -2.0817e-5 -2.53188e-5 1 4.84311e-5 8.85943e-5 1 6.01917e-6 1.93714e-6 1 -8.05582e-6 -2.6648e-5 1 6.51934e-7 -4.462e-6 1 7.38958e-7 -4.32004e-6 1 2.54913e-6 -5.14385e-7 1 -1.51765e-5 -5.26529e-5 1 -3.06052e-6 -1.80138e-5 1 4.12059e-6 2.66614e-7 1 -1.53776e-5 -2.0015e-5 1 -5.39649e-6 -9.76725e-6 1 1.06794e-5 4.23381e-6 1 3.14915e-6 -2.58923e-6 1 3.59256e-6 -2.13071e-6 1 3.47034e-6 -2.25512e-6 1 4.42502e-6 -4.3177e-7 1 2.52249e-6 -3.19614e-6 1 7.75563e-6 4.13643e-6 1 -1.6276e-5 -2.47731e-5 1 2.9348e-5 1.1382e-5 1 2.08819e-6 -4.33163e-6 1 -1.91776e-5 -1.49501e-5 1 3.32053e-6 -4.03861e-6 1 -2.69392e-5 8.19855e-6 1 4.93018e-7 -5.24757e-6 1 -4.33628e-7 -5.09825e-6 1 -8.57116e-6 -2.40774e-5 1 6.41656e-7 -4.14182e-6 1 -1.19194e-5 -2.21159e-5 1 -3.821e-6 -1.25552e-5 1 1.86401e-6 -4.02597e-6 1 2.99438e-6 -3.37076e-6 1 3.39883e-6 -3.01626e-6 1 -3.408e-5 -9.47083e-5 1 -1.13281e-6 -1.46423e-5 1 1.238e-6 -9.2689e-6 1 6.41287e-6 5.16696e-7 1 1.35321e-6 -4.4464e-6 1 2.29147e-7 -5.67679e-6 1 1.14962e-6 -4.7696e-6 1 3.14915e-6 -2.58923e-6 1 4.42503e-6 -4.31761e-7 1 2.52249e-6 -3.19614e-6 1 7.75562e-6 4.13641e-6 1 2.32001e-6 -2.32001e-6 1 4.51994e-7 -5.89843e-6 1 1.42095e-5 9.21434e-6 1 2.40327e-6 -2.22231e-6 1 2.24855e-6 -2.38963e-6 1 -6.33426e-7 -9.69145e-6 1 -2.25524e-7 -4.56745e-6 1 -4.88223e-6 -1.11682e-5 1 1.12222e-6 -4.92768e-6 1 1.65236e-6 -3.66338e-6 1 1.29051e-6 -4.64607e-6 1 1.45275e-6 -4.44131e-6 1 3.32052e-6 -3.32052e-6 1 1.53503e-5 8.71943e-6 1 6.22052e-6 8.70386e-7 1 -2.65948e-6 -9.00386e-6 1 7.79306e-7 -5.562e-6 1 2.23146e-6 -7.22664e-6 1 0 0 1 -4.66831e-7 -4.20506e-6 1 2.83846e-5 1.76844e-5 1 2.33202e-6 -2.45266e-6 1 2.23076e-6 -3.38492e-6 1 2.90148e-6 -1.20183e-6 1 -9.12002e-7 -9.78829e-6 1 4.31251e-6 -2.3827e-6 1 2.33341e-5 2.08365e-5 1 -6.33435e-7 -9.69147e-6 1 0 -4.65375e-6 1 -3.50854e-7 -5.18163e-6 1 -4.01956e-5 -4.82902e-5 1 2.24854e-6 -2.38964e-6 1 1.11522e-6 -3.61383e-6 1 1.76615e-6 -5.72317e-6 1 2.15645e-6 -2.21333e-6 1 8.74722e-7 -8.69463e-6 1 -1.9853e-6 3.72236e-6 -1 -0.4705963 0.8823487 4.5288e-7 -4.01156e-7 5.4994e-6 -1 -0.7071068 0.7071067 1.70124e-7 -3.84816e-6 2.05239e-6 -1 -0.707107 0.7071067 5.26834e-7 5.6788e-7 5.82e-6 -1 0.09711271 0.9952734 6.93298e-7 -6.32479e-6 -6.17142e-7 -1 -0.4705982 0.8823477 8.87957e-7 2.51675e-5 3.06102e-5 -1 0.6350916 0.7724368 -1.23616e-7 4.52332e-5 5.04853e-5 -1 0.09711527 0.995273 1.9894e-7 4.25116e-6 1.20282e-5 -1 0.9566773 0.2911505 -4.02877e-7 -7.99983e-7 4.64272e-6 -1 -3.73383e-6 2.13763e-6 -1 -3.17488e-7 8.22896e-6 -1 0.6350916 0.7724368 -1.23616e-7 -3.54001e-6 5.09825e-6 -1 1 2.1243e-7 -4.96704e-7 0.9566773 0.2911505 -4.02877e-7 -5.96575e-6 1.81559e-6 -1 0.9566773 -0.2911505 -5.47495e-7 -9.31235e-7 3.78953e-6 -1 1 2.12429e-7 -4.96706e-7 -2.65606e-6 3.23044e-6 -1 0.6350949 -0.7724341 -5.07292e-7 0.9566773 -0.2911505 -5.47495e-7 -4.20957e-7 4.31424e-6 -1 0.09711247 -0.9952734 -2.95415e-7 0.6350949 -0.7724341 -5.07292e-7 3.4093e-6 6.3923e-6 -1 -0.4705961 -0.8823487 0 0.09711247 -0.9952734 -2.95415e-7 -1.58337e-6 3.51488e-6 -1 -0.7071066 -0.7071071 3.51224e-7 -0.4705951 -0.8823493 2.33747e-7 1.3356e-5 2.10178e-5 -1 -0.8662416 -0.4996254 0 1.05303e-5 1.82572e-5 -1 -1.1829e-5 -4.10205e-6 -1 -0.7071067 -0.707107 0 -8.2094e-6 0 -1 -1 0 0 0 7.66184e-6 -1 -0.8662418 -0.4996253 0 -5.34596e-6 3.08341e-6 -1 -0.8662416 0.4996252 0 -3.00294e-6 5.20646e-6 -1 -1 0 0 -2.94012e-6 5.48925e-6 -1 -0.8662418 0.4996252 1.20206e-7 3.64233e-6 9.59029e-6 -1 0.7071067 0.7071069 0 9.57297e-6 1.65974e-5 -1 0.4996252 0.8662418 0 -2.55773e-6 4.46675e-6 -1 0.4996252 0.8662418 0 -1.38758e-5 -7.40063e-6 -1 0.8823476 0.4705981 0 -2.79586e-6 4.03436e-6 -1 -6.0274e-6 -2.77472e-7 -1 0.7071067 0.7071069 0 4.82994e-6 9.8469e-6 -1 0.9952732 -0.09711402 0 0.8823476 0.4705981 0 -3.14525e-6 2.58603e-6 -1 0.7724341 -0.6350949 0 1.38018e-5 1.8536e-5 -1 0.9952732 -0.09711402 0 -1.30676e-6 4.29379e-6 -1 0.2911532 -0.9566765 0 -3.47033e-6 2.25512e-6 -1 0.7724341 -0.6350949 0 -1.69942e-6 3.23515e-6 -1 0 -1 0 -1.85937e-6 3.41498e-6 -1 -1.54197e-6 3.2683e-6 -1 -3.40361e-6 3.02002e-6 -1 -2.07274e-7 4.88673e-6 -1 -3.64754e-6 1.89048e-6 -1 0.2911532 -0.9566765 0 0 0 -1 -0.2911528 -0.9566766 0 -1.45751e-6 3.71736e-6 -1 0 -1 0 -5.064e-5 -4.16364e-5 -1 -0.7724327 -0.6350967 0 3.77519e-5 4.59159e-5 -1 -2.44488e-6 5.71918e-6 -1 -0.2911528 -0.9566766 0 2.39836e-6 1.05522e-5 -1 -0.9952734 -0.09711349 0 -1.04603e-5 -1.45667e-6 -1 -0.7724327 -0.6350967 0 -5.49737e-6 2.932e-6 -1 -0.8823482 0.4705972 0 -2.83615e-6 5.31765e-6 -1 -0.9952734 -0.09711349 0 -2.51865e-6 5.06778e-6 -1 -0.707107 0.7071067 0 -3.36498e-6 5.06439e-6 -1 -0.8823482 0.4705972 0 -3.00295e-6 5.20646e-6 -1 -0.4996253 0.8662418 4.76799e-7 3.63273e-6 1.12192e-5 -1 -0.707107 0.7071065 4.17078e-7 0 7.66184e-6 -1 -1.43591e-6 1 2.48353e-7 -8.20941e-6 0 -1 -0.4996241 0.8662423 2.61665e-7 -1.81035e-5 -1.04416e-5 -1 0 1 0 0.8662412 0.4996261 0 1.63954e-6 7.5875e-6 -1 0.7071068 0.7071068 -1.75612e-7 0.7071067 0.7071068 0 1 1.43591e-6 0 0.866241 0.4996263 1.23191e-7 0.8662405 -0.4996274 0 1 1.43591e-6 0 0.7071071 -0.7071066 -1.5366e-7 0.8662405 -0.4996273 0 0.4705972 -0.8823481 -4.5288e-7 0.707107 -0.7071066 -5.26834e-7 -0.09711372 -0.9952734 -1.98941e-7 0.4705972 -0.8823481 -4.5288e-7 -0.6350929 -0.7724358 1.23617e-7 -0.09711372 -0.9952734 -1.98941e-7 -8.05386e-6 -2.45107e-6 -1 -0.9566773 -0.2911505 4.75185e-7 -2.46982e-6 2.1926e-6 -1 -6.53571e-7 5.43096e-6 -1 -0.6350921 -0.7724364 3.15453e-7 -9.99328e-7 3.82369e-6 -1 -1 -2.12429e-7 4.96704e-7 -0.9566773 -0.2911505 4.75185e-7 6.46294e-6 8.76755e-6 -1 -0.9566773 0.2911505 4.75187e-7 -3.25653e-6 4.95604e-6 -1 -1 -2.12429e-7 4.96706e-7 -3.6526e-6 4.44247e-6 -1 -0.6350949 0.7724341 3.15455e-7 -0.9566773 0.2911505 4.75187e-7 -1.04309e-5 1.15504e-6 -1 -0.09711372 0.9952733 2.95416e-7 -0.6350957 0.7724335 5.07292e-7 5.11537e-6 9.5911e-6 -1 0.4705961 0.8823487 0 -0.09711372 0.9952733 2.95416e-7 0.4705961 0.8823487 0 -1.58707e-6 4.36089e-6 -1 -0.7071067 -0.707107 0 -0.4996252 -0.8662418 -1.68602e-7 -0.4996252 -0.8662418 -1.68602e-7 -1.85009e-5 -9.86731e-6 -1 -0.8823493 -0.4705952 0 -7.57631e-7 6.23631e-6 -1 -3.21779e-6 2.95372e-6 -1 -0.7071065 -0.707107 0 -7.05293e-6 6.88191e-7 -1 -0.9952732 0.09711402 0 -0.8823493 -0.4705952 0 3.22557e-6 1.06427e-5 -1 -0.7724375 0.6350908 0 -0.9952732 0.09711402 0 -1.65827e-6 5.44881e-6 -1 -0.2911505 0.9566773 0 -2.86653e-6 4.34292e-6 -1 -0.7724375 0.6350908 0 -1.69942e-6 4.22479e-6 -1 0 1 0 -1.16962e-6 3.30646e-6 -1 -6.38266e-6 7.69429e-6 -1 4.68299e-7 6.99589e-6 -1 -8.27605e-7 6.43706e-6 -1 0 7.07857e-6 -1 -0.2911505 0.9566773 0 1.88693e-6 6.20018e-6 -1 0.2911505 0.9566773 0 -1.37282e-6 4.64196e-6 -1 0 1 0 0.7724358 0.6350929 0 0.2911505 0.9566773 0 0.9952733 0.09711372 0 0.7724358 0.6350929 0 0.8823493 -0.4705953 0 0.9952733 0.09711372 0 0.707107 -0.7071067 0 0.8823493 -0.4705953 0 0.4996241 -0.8662423 0 0.7071069 -0.7071067 0 1.43591e-6 -1 0 0.4996241 -0.8662423 0 0 -1 -2.48352e-7 -1.93973e-6 4.30425e-6 -1 0.7071066 0.707107 3.51224e-7 0.707107 -0.7071065 -1.05367e-6 0.707107 -0.7071066 -1.05367e-6 -3.51423e-6 3.51423e-6 -1 0.7071067 -0.7071067 -3.51224e-7 3.16716e-7 4.84573e-6 -1 4.7763e-7 5.05069e-6 -1 0.7071068 0.7071068 -3.44935e-7 1.52131e-6 6.30599e-6 -1 -0.7071065 -0.7071069 3.51224e-7 -3.12162e-6 4.07075e-6 -1 0.7071067 -0.7071068 -3.51224e-7 -1.74944e-6 4.14168e-6 -1 2.1868e-7 -1 0 -7.06001e-7 4.31444e-6 -1 -3.95551e-7 4.3881e-6 -1 -2.91513e-6 3.43891e-6 -1 -0.7071065 -0.707107 3.51224e-7 -0.04202997 -0.9991164 0 2.1868e-7 -1 0 -0.1252129 -0.9921299 -4.85022e-7 -0.04203033 -0.9991163 -4.93657e-7 -0.2077736 -0.978177 0 -0.1252124 -0.9921299 0 -0.2887694 -0.9573987 0 -0.2077736 -0.9781769 0 -0.3677462 -0.9299262 -4.61899e-7 -0.2887697 -0.9573986 -4.75545e-7 -0.4442529 -0.8959015 2.20663e-7 -0.3677458 -0.9299263 1.82661e-7 -0.5174258 -0.855728 2.57008e-7 -0.4442529 -0.8959015 2.20663e-7 0.6195275 -0.7849751 -3.07722e-7 -0.5174258 -0.855728 2.57008e-7 -8.4446e-7 3.20884e-6 -1 0.6978425 -0.7162514 -3.46622e-7 -6.22056e-6 -8.70414e-7 -1 -1.32104e-5 -6.87968e-6 -1 0.6195275 -0.7849751 -3.07722e-7 -3.87125e-6 3.22232e-6 -1 0.7685841 -0.6397489 0 -8.31039e-7 3.32953e-6 -1 0.6978427 -0.7162512 0 0.7071066 0.707107 0 0.7685841 -0.6397489 0 -0.706954 0.7072595 3.51299e-7 0.7071064 0.7071073 3.51224e-7 0.707107 0.7071065 -3.51223e-7 -0.706954 0.7072595 3.51147e-7 -2.04991e-6 4.44126e-6 -1 0.7071071 -0.7071066 -3.51223e-7 -7.78253e-7 5.56293e-6 -1 0.707107 0.7071065 -3.51223e-7 1 2.18651e-7 -4.96705e-7 1.74476e-5 2.39563e-5 -1 0.7071071 -0.7071066 -3.51223e-7 0.9984007 -0.05653488 -5.0644e-7 1 2.18651e-7 -4.96704e-7 -4.00832e-6 4.8755e-6 -1 0.9858725 -0.1674973 -5.10486e-7 0.9984006 -0.05653488 -5.0293e-7 9.24575e-6 8.02025e-6 -1 0.9608809 -0.276962 -5.46057e-7 0.9858726 -0.1674973 -5.31285e-7 -2.91513e-6 3.43891e-6 -1 0.9238796 -0.3826832 -5.53937e-7 0.9608809 -0.276962 -5.46059e-7 2.2552e-7 4.56744e-6 -1 0.8752878 -0.4836024 -6.74969e-7 -5.24163e-6 1.93538e-6 -1 0.9238797 -0.3826833 -6.48977e-7 -9.61587e-7 3.21753e-6 -1 0.8155552 -0.5786793 -2.87433e-7 -6.50559e-7 3.32563e-6 -1 0.875288 -0.4836019 -2.40208e-7 -1.39057e-6 3.98897e-6 -1 0.7459524 -0.6659992 0 4.77628e-7 5.05069e-6 -1 0.8155554 -0.5786791 0 -6.37349e-6 -8.65897e-7 -1 0.7849755 0.6195269 0 0.7459524 -0.6659992 0 -1.36537e-5 -8.73894e-6 -1 0.7162507 0.697843 0 0.7849755 0.6195269 0 0.6397491 0.7685838 -3.17767e-7 0.716251 0.6978428 -3.55766e-7 -1.93973e-6 4.30425e-6 -1 -0.7071065 0.707107 3.51223e-7 0.6397491 0.7685838 -3.17766e-7 -0.7071067 -0.7071069 3.51223e-7 -0.7071065 0.707107 3.51223e-7 -0.7071068 0.7071068 7.02448e-7 -0.7071067 -0.7071067 0 0.7071069 0.7071065 -3.51224e-7 -0.7071066 0.7071071 3.51224e-7 -1.45751e-7 1 0 0.707107 0.7071065 -3.51224e-7 0.05653434 0.9984006 4.90644e-7 -2.18626e-7 1 4.96704e-7 0.1674973 0.9858726 0 0.05653488 0.9984006 0 0.2769618 0.960881 0 0.1674973 0.9858726 0 0.3826833 0.9238796 0 0.2769618 0.960881 0 0.4836031 0.8752874 4.34759e-7 0.3826829 0.9238798 4.58895e-7 0.578679 0.8155553 -2.87432e-7 0.4836037 0.8752871 -2.40208e-7 0.665999 0.7459526 -3.30804e-7 0.578679 0.8155553 -2.87432e-7 -0.6195274 0.7849751 1.08752e-6 0.6659985 0.7459531 4.10232e-7 -6.23838e-6 8.74504e-6 -1 -0.697843 0.7162507 3.46623e-7 4.47693e-5 4.74444e-5 -1 -0.6195269 0.7849755 3.07723e-7 3.22185e-6 7.95089e-6 -1 -0.7685831 0.63975 6.99527e-7 -6.36407e-6 7.61287e-6 -1 -0.6978433 0.7162505 7.02389e-7 -0.7071068 -0.7071068 -3.51223e-7 -0.7685829 0.6397503 3.17766e-7 0.7071067 -0.7071069 -7.02445e-7 -0.7071066 -0.707107 0 -0.707107 -0.7071065 3.51223e-7 0.7071068 -0.7071068 -3.51223e-7 -0.7071068 0.7071068 3.51223e-7 -0.707107 -0.7071065 3.51223e-7 -1 -1.45753e-7 4.96704e-7 -0.7071068 0.7071068 3.51223e-7 -0.9984007 0.05653488 5.06442e-7 -1 -1.45753e-7 4.96706e-7 -0.9858726 0.1674973 5.10486e-7 -0.9984007 0.05653488 5.0293e-7 -0.9608813 0.2769607 5.46057e-7 -0.9858726 0.1674972 5.31285e-7 -0.9238795 0.3826833 5.53935e-7 -0.9608813 0.2769607 5.46057e-7 -0.8752871 0.4836037 4.34758e-7 -0.9238795 0.3826834 4.58894e-7 -0.8155561 0.5786781 6.92521e-7 -0.8752872 0.4836035 6.74966e-7 -3.27092e-6 2.92034e-6 -1 -0.7459526 0.665999 3.30804e-7 -0.8155558 0.5786785 2.87432e-7 7.52106e-7 6.83997e-6 -1 -0.7849758 -0.6195266 0 -0.7459524 0.6659993 0 7.64544e-6 1.42947e-5 -1 -0.716251 -0.6978428 -3.46623e-7 -0.7849759 -0.6195263 -3.07722e-7 -0.6397492 -0.7685837 3.17767e-7 -0.7162505 -0.6978433 3.55766e-7 -0.6397497 -0.7685834 -4.45752e-7 1.67233e-6 -5.07116e-6 1 2.63881e-6 -4.94763e-6 1 1.66895e-6 -5.91749e-6 1 4.16517e-6 -2.40236e-6 1 2.46672e-6 -4.27677e-6 1 6.12948e-6 0 1 0 -6.56752e-6 1 -1.65217e-5 -2.28437e-5 1 -8.35326e-6 -1.44827e-5 1 1.2223e-5 7.12478e-6 1 3.63434e-6 -2.68768e-6 1 -4.26161e-6 -7.99036e-6 1 1.76342e-6 -4.51797e-6 1 5.26196e-7 -5.3928e-6 1 3.32008e-6 -4.03804e-6 1 -1.6837e-5 5.12409e-6 1 2.53763e-6 -4.37253e-6 1 1.84622e-6 -4.24854e-6 1 -1.3116e-6 -1.11336e-5 1 1.88693e-6 -4.21234e-6 1 -3.1225e-5 -3.79778e-5 1 -3.65086e-5 -4.3312e-5 1 2.54362e-6 -4.25976e-6 1 -7.93482e-7 -8.1319e-6 1 7.48286e-6 7.3014e-7 1 4.78589e-6 -2.55252e-6 1 -8.35326e-6 -1.44827e-5 1 5.43501e-6 -5.12954e-7 1 1.3278e-5 7.65841e-6 1 7.01574e-6 1.39616e-6 1 0 -6.56752e-6 1 6.12949e-6 0 1 2.15838e-6 -3.74218e-6 1 -4.27893e-6 -1.08465e-5 1 2.09719e-6 -4.64631e-6 1 2.10057e-6 -3.79999e-6 1 4.25412e-6 -2.26892e-6 1 2.3456e-6 -4.39789e-6 1 -3.1195e-6 -1.06225e-5 1 1.07285e-5 4.20548e-6 1 3.82648e-5 3.14615e-5 1 -3.46946e-5 -4.21977e-5 1 -7.17389e-6 -2.35721e-5 1 -2.64509e-7 -7.06789e-6 1 -1.52103e-6 -1.20394e-5 1 6.18073e-7 -6.58928e-6 1 1.88937e-6 -4.5155e-6 1 1.69942e-6 -6.01841e-6 1 7.21916e-6 1.02175e-5 1 6.35077e-7 -8.60619e-6 1 1.72211e-6 -5.83902e-6 1 1.63345e-6 -5.36724e-6 1 1.84871e-6 -5.14623e-6 1 -8.87198e-7 -7.52903e-6 1 3.41158e-6 -2.805e-6 1 -3.78751e-5 -4.54993e-5 1 5.12991e-7 -6.42302e-6 1 -1.49193e-6 -1.01726e-5 1 3.9128e-6 -2.31957e-6 1 9.69457e-6 5.17058e-6 1 -7.21561e-6 -1.4863e-5 1 -4.68909e-6 -8.79185e-6 1 1.38315e-6 -5.29157e-6 1 1.03782e-5 -6.15655e-7 1 3.32055e-6 -4.03861e-6 1 3.0828e-5 -2.01165e-5 1 4.93018e-7 -5.24757e-6 1 0 -4.6734e-6 1 4.46097e-6 1.35763e-6 1 2.81137e-6 -2.21194e-6 1 -2.74553e-6 -1.03929e-5 1 -3.18416e-6 -1.04627e-5 1 3.58053e-6 -3.031e-6 1 1.3871e-6 -4.30241e-6 1 1.69942e-6 -5.04923e-6 1 -8.23474e-6 -2.93532e-5 1 -4.40347e-6 -2.00427e-5 1 8.24611e-6 8.62732e-6 1 9.29629e-7 -5.20805e-6 1 1.57873e-6 -5.18748e-6 1 3.87696e-6 -2.67185e-6 1 5.77136e-7 -5.92409e-6 1 -3.488e-6 -1.0427e-5 1 4.79377e-6 -4.67753e-7 1 7.92899e-7 -6.28099e-6 1 8.40192e-6 4.48111e-6 1 2.66903e-6 -5.03355e-6 1 3.61283e-6 -3.2256e-6 1 9.64726e-6 3.40328e-6 1 -7.64558e-6 -1.42948e-5 1 -1.50032e-5 -2.22516e-5 1 1.92318e-6 -6.43505e-6 1 5.27787e-6 -5.26209e-6 1 5.27135e-6 -5.27135e-6 1 2.7344e-6 -3.36405e-6 1 1.09393e-6 -7.27637e-6 1 1.86872e-6 -4.81272e-6 1 2.07874e-6 -4.54767e-6 1 8.53719e-7 -5.6384e-6 1 1.42803e-5 7.79952e-6 1 6.22056e-6 8.70414e-7 1 -5.20774e-7 -7.16525e-6 1 2.12538e-6 -4.51673e-6 1 1.74012e-6 -2.98892e-6 1 3.75127e-6 -9.50207e-6 1 4.08112e-6 -6.53087e-6 1 -2.88107e-5 -3.14858e-5 1 2.04052e-6 -5.1365e-6 1 2.23076e-6 -3.38491e-6 1 2.29331e-6 -3.18134e-6 1 6.50557e-7 -3.32563e-6 1 -2.25521e-7 -4.56744e-6 1 -1.57066e-5 -2.44481e-5 1 9.61589e-7 -3.21753e-6 1 2.28236e-6 -4.64689e-6 1 2.23312e-6 -4.74121e-6 1 3.61544e-5 3.06614e-5 1 1.46234e-5 7.37694e-6 1 2.29722e-6 -4.79635e-6 1 1.09952e-6 -9.15207e-7 1 8.4446e-7 -3.20884e-6 1 1.74944e-6 -3.03524e-6 1 0 0 -1 -0.3814387 0.9243942 4.59152e-7 0 0 -1 -0.9243937 0.3814398 1.43407e-4 -0.9238891 0.3826603 1.9007e-7 3.44401e-6 8.28621e-6 -1 0.3838004 0.923416 -6.12e-6 5.60985e-6 6.5249e-6 -1 -0.3826563 0.9238908 1.43533e-4 1.11055e-5 4.61585e-6 -1 0.9234148 0.3838033 1.2226e-4 0.3827044 0.9238708 1.22468e-4 -1.1147e-5 4.59967e-6 -1 0.9243937 -0.3814398 1.42683e-4 0 7.94729e-6 -1 0.9238697 0.3827074 -6.14162e-6 -3.42424e-6 8.29842e-6 -1 0.381439 -0.924394 -4.59152e-7 0.9238904 -0.3826574 -1.90068e-7 6.96599e-6 1.67597e-5 -1 -0.3838067 -0.9234135 -6.89575e-6 0.3826555 -0.9238911 1.42471e-4 0 0 -1 -0.9234148 -0.3838037 1.21878e-4 -1.99949e-6 4.82717e-6 -1 2.97837e-5 2.51269e-5 -1 3.78538e-6 9.1387e-6 -1 -4.31266e-5 -2.84674e-5 -1 -5.47363e-6 5.40476e-6 -1 1.39041e-6 8.77895e-6 -1 9.6969e-5 9.69689e-5 -1 -5.676e-5 -4.56638e-5 -1 0 0 -1 -0.3827119 -0.9238678 1.2155e-4 -0.9238682 -0.3827105 -6.17837e-6 0 0 -1 -0.3814395 0.9243938 0 0 0 -1 -0.9243925 0.3814427 1.42798e-4 -0.9238898 0.3826587 0 0 0 -1 0.3838025 0.9234152 -6.5791e-6 -0.3826567 0.9238906 1.43073e-4 -3.9684e-5 -1.64941e-5 -1 0.9234142 0.3838049 1.22757e-4 -1.25515e-5 0 -1 -5.60984e-6 -5.4952e-6 -1 0.382704 0.923871 1.22294e-4 -8.85483e-6 3.65382e-6 -1 0.9243943 -0.3814385 1.43406e-4 0.9238709 0.3827044 -6.17695e-6 -5.41093e-6 1.31131e-5 -1 0.3814383 -0.9243943 0 2.04459e-5 3.25858e-5 -1 0.923889 -0.3826606 0 4.3756e-6 1.05276e-5 -1 -0.3838016 -0.9234156 -5.61393e-6 -1.17306e-4 -1.02859e-4 -1 -6.48648e-5 -5.02437e-5 -1 0.3826633 -0.9238879 1.43944e-4 1.11055e-5 4.61588e-6 -1 -0.9234131 -0.3838075 1.22871e-4 2.4827e-6 8.74672e-6 -1 -0.3827111 -0.9238681 1.22341e-4 1.32443e-5 3.97365e-6 -1 -0.9238696 -0.3827073 -6.02687e-6 -2.15263e-5 -1.43835e-5 -1 0.831468 0.5555728 -1.37038e-7 1.59019e-5 2.3799e-5 -1 0.555567 0.8314717 1.23416e-5 -6.05082e-6 0 -1 1.94083e-5 2.55635e-5 -1 0.5556923 0.8313881 1.36939e-7 -7.65954e-6 -1.52352e-6 -1 0.9807868 0.1950831 -6.98587e-5 0.8313881 0.5556923 1.15479e-5 -4.97881e-6 9.90302e-7 -1 0.980787 -0.195082 2.60328e-5 0.9806256 0.1958913 -2.71046e-6 -3.53859e-6 2.36441e-6 -1 0.8314699 -0.55557 -1.82263e-4 0.9804435 -0.196801 -1.16349e-4 -2.35211e-6 3.52022e-6 -1 0.555567 -0.8314717 2.87988e-5 0.832909 -0.5534102 2.90596e-5 -1.1402e-6 5.73226e-6 -1 0.1950878 -0.9807857 -1.15325e-4 4.72989e-6 1.14189e-5 -1 1.97356e-4 2.02173e-4 -1 0.5534201 -0.8329024 -1.80945e-4 -5.98018e-5 -5.00706e-5 -1 -0.1950913 -0.9807851 -1.67543e-6 -2.01248e-6 4.85854e-6 -1 0.1968104 -0.9804416 2.71297e-5 1.54189e-5 2.30757e-5 -1 -0.5555756 -0.8314661 1.20697e-5 -0.1959088 -0.9806222 -6.94967e-5 0 0 -1 -0.8314594 -0.5555854 1.37028e-7 -5.70808e-6 2.36436e-6 -1 -1.48297e-5 -6.1427e-6 -1 1.68634e-6 8.97749e-6 -1 -0.5557008 -0.8313824 -1.36932e-7 0 0 -1 -0.9807848 -0.1950925 -6.90763e-5 -0.8313795 -0.555705 1.18244e-5 -1.47726e-4 2.93854e-5 -1 -0.9807842 0.195096 2.74952e-5 0 6.11446e-6 -1 -0.9806221 -0.1959089 -1.25056e-6 -1.34838e-5 9.0096e-6 -1 -0.8314699 0.55557 -1.80885e-4 -0.9804399 0.1968187 -1.15183e-4 -5.58504e-6 8.35867e-6 -1 -0.555567 0.8314717 3.03137e-5 -0.832908 0.5534116 3.0298e-5 -5.09894e-5 5.76794e-6 -1 -0.1950972 0.9807839 -1.14256e-4 -0.5534158 0.8329051 -1.79842e-4 3.75481e-6 1.88763e-5 -1 0.1950937 0.9807847 -1.28536e-6 -0.196814 0.9804408 2.77147e-5 0.1959065 0.9806225 -6.87176e-5 0 0 -1 0.831468 0.5555728 -4.12993e-7 0 0 -1 0.555567 0.8314717 1.13767e-5 0.5556867 0.8313919 -2.76012e-7 -2.50207e-6 -4.97668e-7 -1 0.9807872 0.1950808 -7.09304e-5 -2.47508e-6 -5.61455e-7 -1 0.8313937 0.5556838 1.04449e-5 -2.2466e-5 4.46889e-6 -1 0.9807842 -0.195096 2.6424e-5 -5.30359e-6 5.30359e-6 -1 0.9806222 0.1959088 -2.12741e-6 7.02399e-5 1.18602e-5 -1 0.8314774 -0.5555587 -1.81159e-4 0.9804423 -0.1968069 -1.15278e-4 0 0 -1 0.5555629 -0.8314745 2.92117e-5 0.8329108 -0.5534073 2.93345e-5 0 0 -1 0.1950948 -0.9807844 -1.1513e-4 0.5534073 -0.8329107 -1.81354e-4 0 0 -1 -0.1950937 -0.9807847 -1.57871e-6 0.196814 -0.9804408 2.70322e-5 0 0 -1 -0.5555756 -0.8314661 1.16548e-5 -0.19591 -0.9806219 -6.93013e-5 3.26736e-5 8.06243e-5 -1 -0.831468 -0.5555728 4.12993e-7 -1.20841e-5 -8.31769e-6 -1 -0.5556923 -0.8313881 2.76014e-7 0 0 -1 -0.9807833 -0.1951007 -6.89777e-5 -0.8313881 -0.5556923 1.20972e-5 0 0 -1 -0.9807835 0.1950995 2.71052e-5 -0.9806222 -0.1959088 -1.83494e-6 0 0 -1 -0.8314661 0.5555756 -1.79923e-4 0 0 -1 -0.9804434 0.196801 -1.13816e-4 0 0 -1 -0.555584 0.8314604 3.05898e-5 -0.8329005 0.5534228 3.07118e-5 0 0 -1 -0.1950878 0.9807857 -1.14935e-4 -0.55342 0.8329024 -1.80807e-4 0 0 -1 0.195089 0.9807856 -1.3819e-6 -0.196814 0.9804408 2.78124e-5 0.1959088 0.9806222 -6.93989e-5 -2.69168e-6 4.02837e-6 -1 0.5555714 -0.8314689 -6.88951e-7 9.91608e-4 -6.03774e-4 -0.9999994 0.8314716 -0.5555671 1.12397e-5 0.8313899 -0.5556894 -6.8897e-7 -5.51553e-7 2.77288e-6 -1 0.1950878 -0.9807857 -7.01487e-5 0.555688 -0.8313909 1.0716e-5 4.4406e-7 2.23246e-6 -1 -0.1950889 -0.9807855 2.66174e-5 0.1959041 -0.9806231 -2.32167e-6 1.23392e-6 1.84672e-6 -1 -0.5555643 -0.8314735 -1.80746e-4 -0.1968045 -0.9804428 -1.15472e-4 1.61598e-4 1.66768e-4 -1 -0.8314699 -0.55557 2.92119e-5 1.45488e-5 2.1774e-5 -1 -4.46888e-6 2.7563e-6 -1 -4.21469e-6 4.21469e-6 -1 -0.5534172 -0.8329043 2.93347e-5 -6.88163e-6 -1.36875e-6 -1 -0.9807879 -0.1950772 -1.15421e-4 1.28373e-6 6.45381e-6 -1 -0.8329051 -0.5534158 -1.8122e-4 -4.81146e-6 9.56997e-7 -1 -0.9807877 0.1950784 -1.0904e-6 -9.14618e-7 4.59827e-6 -1 -0.9804425 -0.1968057 2.75187e-5 -3.51515e-6 2.34876e-6 -1 -0.831468 0.5555728 1.2482e-5 -2.31051e-6 3.45794e-6 -1 -0.9806244 0.1958971 -6.90123e-5 -2.31054e-6 3.45791e-6 -1 -0.555577 0.8314651 6.88952e-7 -3.51516e-6 2.34875e-6 -1 -0.8313871 0.5556937 6.88971e-7 -9.14676e-7 4.59821e-6 -1 -0.1950972 0.9807839 -6.84915e-5 -4.8114e-6 9.57058e-7 -1 -0.5556979 0.8313843 1.25116e-5 1.28386e-6 6.45394e-6 -1 0.1951031 0.9807828 2.70087e-5 -6.8818e-6 -1.36892e-6 -1 -0.1959006 0.9806238 -1.73702e-6 9.69918e-6 1.4516e-5 -1 0.5555671 0.8314716 -1.80472e-4 -1.55809e-5 -1.04108e-5 -1 0.196814 0.9804409 -1.14696e-4 -2.59653e-5 -1.73494e-5 -1 0.8314699 0.55557 3.01768e-5 6.29808e-6 1.11149e-5 -1 -3.42897e-5 -2.56025e-5 -1 0.5534116 0.8329079 3.04369e-5 -1.15687e-5 -2.30131e-6 -1 0.980783 0.1951019 -1.15719e-4 0.8329107 0.5534073 -1.81083e-4 -8.3969e-6 1.67034e-6 -1 0.9807832 -0.1951007 -2.84429e-6 0.9804396 0.1968199 2.6352e-5 -4.94472e-6 7.61392e-6 -1 0.9806224 -0.1959077 -6.97892e-5 0.5555686 -0.8314708 -2.75954e-7 0.8314699 -0.55557 1.17905e-5 0.8313862 -0.5556951 -4.12954e-7 0.1950831 -0.9807867 -6.9859e-5 0.5556895 -0.83139 1.1545e-5 -0.1950878 -0.9807857 2.76886e-5 0.1959065 -0.9806226 -1.445e-6 -0.5555672 -0.8314717 -1.81161e-4 -0.196814 -0.9804409 -1.1528e-4 0 0 -1 -0.8314735 -0.5555643 3.04508e-5 5.54635e-6 8.37446e-6 -1 -0.5534073 -0.8329107 3.01592e-5 0 0 -1 -0.9807832 -0.1951007 -1.1338e-4 -0.8329043 -0.5534172 -1.79291e-4 -1.65251e-5 3.28724e-6 -1 -0.980783 0.1951019 -1.67625e-6 3.18065e-6 7.05102e-6 -1 -0.9804437 -0.1967998 2.7129e-5 -8.06936e-6 5.39181e-6 -1 -0.831468 0.5555728 1.23431e-5 -0.9806219 0.19591 -6.87172e-5 -4.50905e-6 6.7481e-6 -1 -0.5555798 0.8314632 2.7596e-7 -0.8313862 0.5556951 4.12954e-7 -1.67033e-6 8.3969e-6 -1 -0.1950995 0.9807834 -6.94654e-5 -0.5556965 0.8313852 1.16854e-5 2.30129e-6 1.15687e-5 -1 0.1951007 0.9807832 2.64244e-5 -0.19591 0.9806219 -2.1275e-6 1.73499e-5 2.59658e-5 -1 0.5555728 0.831468 -1.81438e-4 0.1968128 0.9804412 -1.15378e-4 0.8314699 0.55557 2.99008e-5 -3.20375e-6 5.23436e-6 -1 0.5534116 0.8329079 3.00232e-5 0.9807842 0.195096 -1.1484e-4 0.8329051 0.5534158 -1.80532e-4 0.9807849 -0.1950925 -2.06579e-6 0.9804425 0.1968057 2.65447e-5 0.9806243 -0.1958982 -6.89142e-5 -2.25169e-5 -1.50493e-5 -1 -0.8314011 -0.5556728 4.1296e-7 0 0 -1 -0.5556714 -0.831402 2.30841e-6 3.45862e-6 9.83298e-6 -1 -1.26008e-5 -6.34104e-6 -1 -0.5556923 -0.8313881 2.76014e-7 5.69291e-5 6.12039e-5 -1 -0.9807265 -0.1953849 -3.20132e-5 -0.8313881 -0.5556923 2.309e-6 -5.34608e-6 1.06186e-6 -1 -0.9808394 0.194818 9.37454e-5 -0.9806202 -0.1959182 1.22199e-5 -3.81863e-6 2.55099e-6 -1 -0.831523 0.5554905 -1.01455e-4 -0.9804475 0.196781 -6.86454e-5 -2.5438e-6 3.80791e-6 -1 -0.5554848 0.8315267 1.00034e-4 -0.8328976 0.5534271 1.00398e-4 -1.05536e-6 5.31331e-6 -1 -0.1948191 0.9808391 -6.92267e-5 -2.73134e-5 -2.08913e-5 -1 4.45616e-6 1.07582e-5 -1 -0.5534229 0.8329004 -1.01568e-4 1.56789e-6 7.86987e-6 -1 0.1953873 0.9807262 1.17522e-5 -1.86519e-6 4.50295e-6 -1 -0.1967868 0.9804462 9.37456e-5 1.24633e-5 1.86479e-5 -1 0.5556686 0.8314039 2.58411e-6 0.1959123 0.9806214 -3.1871e-5 -5.94137e-6 -3.97089e-6 -1 0.8314058 0.5556659 -4.12962e-7 -1.1089e-5 -4.5932e-6 -1 -4.94411e-6 1.3382e-6 -1 -4.46608e-6 1.84992e-6 -1 0.555698 0.8313844 -2.76017e-7 -5.63999e-6 -1.12372e-6 -1 0.9807234 0.1954014 -3.20118e-5 0.8313871 0.5556937 2.3108e-6 0.001061916 -1.61115e-4 -0.9999994 0.980839 -0.1948203 9.11164e-5 -5.6805e-6 7.00263e-6 -1 0.9806223 0.1959076 9.98143e-6 0 0 -1 0.8315249 -0.5554876 -1.0352e-4 0.9804475 -0.196781 -7.10804e-5 0 0 -1 0.5554777 -0.8315314 9.98952e-5 0.8329098 -0.5534088 9.98455e-5 0 0 -1 0.194832 -0.9808366 -6.93247e-5 0.5534144 -0.8329061 -1.01842e-4 0 0 -1 -0.1953955 -0.9807245 1.04831e-5 0.1967809 -0.9804474 9.2088e-5 -0.1959065 -0.9806225 -3.19688e-5 1.0812e-5 7.22643e-6 -1 -0.8313954 -0.5556813 1.36948e-7 3.97102e-6 5.9414e-6 -1 -0.5556771 -0.8313983 1.89606e-6 -0.555698 -0.8313844 -1.36934e-7 -2.5017e-6 -4.98397e-7 -1 -0.9807268 -0.1953837 -3.21103e-5 -4.31846e-6 3.79481e-6 -1 -0.8313824 -0.5557008 2.03477e-6 -2.24828e-5 4.46592e-6 -1 -0.9808368 0.1948308 9.38448e-5 -5.30232e-6 5.30232e-6 -1 -0.9806205 -0.195917 1.21228e-5 -8.37029e-6 5.59146e-6 -1 -0.8315333 0.5554749 -1.01591e-4 -0.9804437 0.1967998 -6.90366e-5 -4.20521e-6 6.29506e-6 -1 -0.5554777 0.8315314 1.0086e-4 -0.8329126 0.5534046 1.00948e-4 -1.42341e-6 7.16611e-6 -1 -0.194825 0.9808381 -6.92272e-5 -0.5534074 0.8329107 -1.01567e-4 1.72953e-6 8.68107e-6 -1 0.1953896 0.9807257 1.22388e-5 -0.1967986 0.9804439 9.4235e-5 8.67238e-6 1.29754e-5 -1 0.5556799 0.8313964 2.72228e-6 0.1959158 0.9806208 -3.1481e-5 0 0 -1 0.8313973 0.5556785 -1.36951e-7 5.39394e-6 1.07188e-5 -1 0.5557065 0.8313786 1.36927e-7 0 0 -1 0.9807252 0.1953919 -3.14284e-5 0.8313758 0.5557106 3.00159e-6 0 0 -1 0.9808394 -0.194818 9.21871e-5 0.9806235 0.1959018 1.08596e-5 -1.10361e-5 7.37253e-6 -1 0.831523 -0.5554905 -1.0297e-4 2.69777e-7 4.70948e-6 -1 0.9804474 -0.1967809 -7.02041e-5 -3.99748e-6 5.98383e-6 -1 0.5554947 -0.8315201 9.94826e-5 0.8329023 -0.55342 9.95709e-5 -1.12245e-6 5.65119e-6 -1 0.1948168 -0.9808397 -7.06846e-5 0.5534158 -0.8329051 -1.03769e-4 1.12365e-6 5.64e-6 -1 -0.1953896 -0.9807257 1.05815e-5 0.1967809 -0.9804474 9.19903e-5 -0.1959076 -0.9806223 -3.24558e-5 -5.38587e-6 8.05828e-6 -1 -0.5556771 0.8313983 2.76008e-7 -8.34964e-5 5.58063e-5 -1 -0.8313973 0.5556785 2.03317e-6 -0.8313862 0.5556951 4.12954e-7 -1.10505e-6 5.54678e-6 -1 -0.1953837 0.980727 -3.29877e-5 -0.5556895 0.83139 1.48324e-6 8.86989e-7 4.46534e-6 -1 0.194832 0.9808366 9.20935e-5 -0.1959135 0.9806212 1.09544e-5 2.46731e-6 3.69349e-6 -1 0.5554764 0.8315324 -1.01867e-4 0.1967809 0.9804474 -6.91327e-5 -1.55745e-5 -1.04042e-5 -1 0.8315286 0.555482 9.93456e-5 9.69271e-6 1.45095e-5 -1 1.0162e-6 5.83298e-6 -1 7.71839e-7 4.43037e-6 -1 0.5534158 0.8329051 9.971e-5 -6.87977e-6 -1.3665e-6 -1 0.980839 0.1948203 -7.06886e-5 1.28161e-6 6.45197e-6 -1 0.8329061 0.5534144 -1.02809e-4 -2.40515e-6 4.79179e-7 -1 0.9807254 -0.1953908 1.08743e-5 -4.24944e-5 -3.69812e-5 -1 0.9804452 0.1967927 9.26755e-5 -1.75738e-6 1.17457e-6 -1 0.8313973 -0.5556785 1.75927e-6 -1.15549e-6 1.72884e-6 -1 0.9806204 -0.195917 -3.28449e-5 -1.1555e-6 1.72883e-6 -1 0.5556799 -0.8313964 -2.76009e-7 -1.75739e-6 1.17456e-6 -1 0.8313824 -0.5557008 -4.12952e-7 -4.57963e-7 2.29867e-6 -1 0.1953896 -0.9807257 -3.17199e-5 -2.40516e-6 4.79162e-7 -1 0.555705 -0.8313795 2.17293e-6 1.2815e-6 6.45186e-6 -1 -0.1948191 -0.9808391 9.20909e-5 5.87274e-5 6.14841e-5 -1 0.1959041 -0.9806231 1.09564e-5 9.69334e-6 1.45101e-5 -1 -0.5554904 -0.831523 -1.01729e-4 -1.55746e-5 -1.04043e-5 -1 -0.1967715 -0.9804494 -6.94232e-5 -2.59398e-5 -1.73289e-5 -1 -0.8315219 -0.5554918 1.00585e-4 6.29389e-6 1.11107e-5 -1 -3.4199e-5 -2.55191e-5 -1 -0.5534229 -0.8329005 1.00535e-4 -1.15631e-5 -2.29672e-6 -1 -0.9808391 -0.1948191 -6.99077e-5 -0.8329061 -0.5534144 -1.02531e-4 -8.39492e-6 1.67245e-6 -1 -0.9807271 0.1953825 1.09731e-5 -0.9804475 -0.1967809 9.25754e-5 -4.9455e-6 7.6147e-6 -1 -0.9806238 0.1959006 -3.20668e-5 -0.5556757 0.8313992 6.88968e-7 -0.8314011 0.5556728 2.85849e-6 -0.8313862 0.5556951 6.88971e-7 -0.1953837 0.980727 -3.26965e-5 -0.5556923 0.831388 2.31212e-6 0.194832 0.9808366 9.26774e-5 -0.1959146 0.9806209 1.13439e-5 0.555482 0.8315286 -1.02419e-4 0.1967904 0.9804456 -6.93291e-5 -1.25618e-5 -8.39142e-6 -1 0.8315333 0.5554749 1.00447e-4 -5.60066e-6 2.12153e-6 -1 0.553406 0.8329117 1.00673e-4 -8.62211e-6 -1.71275e-6 -1 0.9808352 0.1948391 -6.91322e-5 0.8329079 0.5534116 -1.01293e-4 1.11231e-4 2.77021e-5 -1 0.980727 -0.1953837 1.08758e-5 -5.41091e-6 5.41091e-6 -1 0.9804452 0.1967927 9.26755e-5 0 0 -1 0.8313973 -0.5556785 1.0703e-6 0.9806204 -0.195917 -3.34293e-5 0 0 -1 0.5556771 -0.8313983 -6.88968e-7 0.8313853 -0.5556966 -6.88972e-7 0 0 -1 0.1953896 -0.9807257 -3.2207e-5 0.5557022 -0.8313815 1.75968e-6 -5.92055e-5 -4.72576e-5 -1 -0.1948168 -0.9808397 9.18936e-5 0.1959006 -0.9806237 1.01782e-5 1.73289e-5 2.59399e-5 -1 -0.5554904 -0.831523 -1.03107e-4 -0.1967809 -0.9804474 -7.05937e-5 -0.8315277 -0.5554835 9.94828e-5 -3.20368e-6 5.23421e-6 -1 -0.5534186 -0.8329033 9.95713e-5 -0.9808394 -0.194818 -6.85427e-5 -0.8328977 -0.5534272 -1.01566e-4 -0.9807271 0.1953825 1.25316e-5 -0.9804477 -0.1967798 9.39384e-5 -0.9806224 0.1959077 -3.1092e-5 -2.73235e-6 5.36257e-6 -1 -0.4539877 0.891008 2.25498e-7 -5.50574e-6 2.80528e-6 -1 -0.8910086 0.4539865 4.42569e-7 -0.8910086 0.4539865 4.42569e-7 1.49741e-6 9.45434e-6 -1 0.1564337 0.9876884 0 -0.4539877 0.891008 2.28914e-7 0.002064466 0.002064466 -0.9999958 0.7071052 0.7071084 -3.51223e-7 0.1564337 0.9876884 0 0 0 -1 0.9876886 0.1564327 -4.90591e-7 1.11482e-5 1.88799e-5 -1 0.7071052 0.7071084 -3.51223e-7 -6.51727e-6 3.32068e-6 -1 0.8910086 -0.4539865 -4.42569e-7 1.69442e-6 4.09379e-6 -1 0.9876886 0.1564327 -4.90591e-7 -2.11665e-6 4.15422e-6 -1 0.4539851 -0.8910092 -2.25497e-7 0.8910086 -0.4539864 -4.42569e-7 8.3445e-7 5.26854e-6 -1 -0.1564337 -0.9876884 0 0.4539851 -0.8910092 -2.25497e-7 1.07146e-5 1.07147e-5 -1 -0.7071052 -0.7071084 3.51223e-7 -0.1564337 -0.9876884 0 -1.06022e-5 -1.67921e-6 -1 -0.9876886 -0.1564332 4.90591e-7 -3.98903e-6 3.98903e-6 -1 -9.36036e-6 -1.40309e-6 -1 -0.7071052 -0.7071084 3.51223e-7 -0.9876886 -0.1564332 4.90591e-7 -2.24591e-6 3.20878e-6 -1 -0.5734229 0.8192596 3.86555e-7 -3.31911e-6 2.32314e-6 -1 -0.8192594 0.5734232 5.13739e-7 -0.8192594 0.5734232 4.78137e-7 -1.23269e-6 4.59814e-6 -1 -0.2589415 0.965893 2.48559e-7 -4.78629e-7 5.03507e-6 -1 -0.5734229 0.8192596 3.95816e-7 5.1199e-7 5.84223e-6 -1 0.08730143 0.996182 2.04042e-7 -0.2589418 0.9658929 3.685e-7 4.10285e-6 8.79958e-6 -1 0.4225791 0.9063261 1.27736e-7 0.08730107 0.996182 3.27744e-7 -9.73691e-5 -8.11669e-5 -1 0.7071061 0.7071075 1.75612e-7 0.4225789 0.9063262 2.25089e-7 -1.18286e-5 -5.51513e-6 -1 0.9063266 0.4225779 1.31186e-7 -1.25982e-6 4.8489e-6 -1 5.15931e-7 6.60904e-6 -1 -1.78872e-6 4.30926e-6 -1 0.7071061 0.7071076 2.19515e-7 4.80575e-6 1.19187e-5 -1 0.996182 0.08730173 0 7.02849e-4 7.05519e-4 -0.9999995 9.98231e-6 1.63093e-5 -1 0.9063266 0.4225779 1.31186e-7 -5.29184e-6 1.41866e-6 -1 0.965893 -0.2589416 0 -5.33349e-6 1.38292e-6 -1 0.9961819 0.08730173 0 -1.25399e-5 -5.19192e-6 -1 0.8192598 -0.5734225 -1.82463e-7 0.965893 -0.2589416 0 5.33665e-6 1.23331e-5 -1 0.5734226 -0.8192598 -2.5433e-7 0.8192598 -0.5734224 -1.78013e-7 -1.38696e-6 5.17356e-6 -1 0.2589423 -0.9658928 -2.9985e-7 -1.78322e-6 4.82912e-6 -1 0.5734226 -0.8192598 -2.5433e-7 6.1677e-7 7.03786e-6 -1 -0.08730143 -0.996182 -2.65891e-7 0.258942 -0.9658929 -4.28467e-7 5.51142e-6 1.18207e-5 -1 -0.422578 -0.9063266 0 -0.08730125 -0.996182 -2.04042e-7 -7.75191e-5 -6.13168e-5 -1 -0.7071065 -0.7071071 1.31709e-7 -3.77945e-7 5.92028e-6 -1 -0.4225781 -0.9063265 0 -1.27282e-5 -5.93458e-6 -1 -0.9063265 -0.422578 3.18992e-7 1.49635e-7 6.78995e-6 -1 -3.96643e-6 1.14138e-6 -1 -0.7071065 -0.7071071 1.31709e-7 -6.42246e-6 -5.62837e-7 -1 -0.996182 -0.08730107 4.67369e-7 -0.9063266 -0.422578 3.17352e-7 4.90495e-6 1.0523e-5 -1 -0.9658933 0.2589401 5.19958e-7 -0.9961819 -0.08730107 4.81258e-7 0 4.47936e-6 -1 -0.9658933 0.2589401 5.27996e-7 -1.12449e-5 -3.89188e-6 -1 -0.5734229 0.8192595 4.06931e-7 5.62969e-6 1.00286e-5 -1 -0.81926 0.5734224 2.84822e-7 -1.13493e-6 2.6978e-6 -1 -0.81926 0.5734224 2.84822e-7 -1.23247e-6 4.59727e-6 -1 -0.2589429 0.9658927 4.79765e-7 -0.5734229 0.8192595 4.07458e-7 4.92991e-7 5.62545e-6 -1 0.08730113 0.9961819 0 -1.37987e-6 4.44227e-6 -1 -0.2589417 0.965893 0 3.82883e-6 8.21188e-6 -1 0.4225791 0.906326 0 0.08730107 0.9961819 0 3.47965e-5 3.47965e-5 -1 0.7071059 0.7071077 3.01834e-7 0.422578 0.9063266 4.20661e-7 1.20627e-5 1.82347e-5 -1 0.9063265 0.4225782 1.46591e-7 -4.52676e-5 -3.49783e-5 -1 0.7071059 0.7071077 3.01834e-7 -7.88186e-6 -6.90737e-7 -1 0.996182 0.08730173 0 0.9063267 0.4225776 0 -5.65942e-6 1.5172e-6 -1 0.9658931 -0.2589411 -1.88587e-7 0.996182 0.08730185 0 4.33229e-6 1.09367e-5 -1 0.8192595 -0.573423 -3.35686e-7 -2.054e-6 5.33979e-6 -1 0.9658931 -0.2589411 -1.88587e-7 -2.89515e-6 4.13635e-6 -1 0.573423 -0.8192594 -6.47663e-7 0.8192592 -0.5734233 -4.80481e-7 -1.26207e-6 4.70771e-6 -1 0.2589417 -0.965893 -7.35718e-7 -7.37632e-6 -3.93137e-7 -1 0.573423 -0.8192594 -6.45994e-7 5.54065e-7 6.32232e-6 -1 -0.08730173 -0.9961819 -7.42208e-7 0.2589417 -0.965893 -7.19641e-7 -1.75048e-5 -1.04972e-5 -1 -0.422578 -0.9063266 -4.50178e-7 -0.08730101 -0.996182 -4.94809e-7 1.36833e-4 1.36833e-4 -1 -0.7071065 -0.7071071 0 -0.4225768 -0.9063271 0 1.29723e-5 1.86588e-5 -1 -0.9063266 -0.422578 0 5.19467e-7 6.6544e-6 -1 -2.13706e-5 -1.51426e-5 -1 -1.27656e-5 -6.18341e-6 -1 -0.7071068 -0.7071068 -1.75612e-7 -5.05513e-6 -4.43007e-7 -1 -0.996182 -0.08730065 0 -1.99417e-4 -1.9141e-4 -0.9999999 8.96376e-6 1.46452e-5 -1 -0.9063265 -0.4225779 0 -4.56332e-6 1.22336e-6 -1 -0.9658931 0.2589413 0 -1.75395e-6 3.24644e-6 -1 -0.996182 -0.08730071 0 -0.9658932 0.258941 1.28618e-7 1.12392e-4 1.12392e-4 -1 -0.7071067 -0.707107 0 0.7071069 -0.7071066 -1.86586e-7 0.707107 -0.7071066 -1.75611e-7 -3.03747e-6 3.03747e-6 -1 -0.7071069 0.7071067 2.25001e-7 1.54224e-7 5.64176e-6 -1 1.15212e-5 1.77093e-5 -1 -0.7071066 -0.707107 0 8.99127e-5 8.99128e-5 -1 0.7071065 0.7071071 1.20732e-7 -0.707107 0.7071067 2.08538e-7 -1.24121e-5 -6.13471e-6 -1 0.7071065 0.7071071 0 -2.30215e-6 5.55792e-6 -1 -0.3826814 0.9238803 3.33485e-7 -6.67359e-6 2.7643e-6 -1 -0.9238793 0.3826841 5.18297e-7 -0.9238793 0.3826841 5.18297e-7 4.42773e-6 1.06895e-5 -1 0.3826835 0.9238795 0 -0.3826814 0.9238803 3.34487e-7 0 0 -1 0.9238808 0.3826804 -3.99497e-7 3.83655e-5 3.87454e-5 -1 0.3826835 0.9238795 0 0 0 -1 0.9238804 -0.3826813 -5.18297e-7 0 0 -1 0.9238808 0.3826804 -3.99497e-7 0 0 -1 0.3826835 -0.9238795 -3.33486e-7 0 0 -1 0.9238804 -0.3826813 -5.18297e-7 0 0 -1 -0.3826833 -0.9238797 0 0.3826835 -0.9238795 -3.33486e-7 -4.77745e-5 -1.97889e-5 -1 -0.9238793 -0.382684 3.99496e-7 0 0 -1 -6.51007e-6 -4.43079e-6 -1 -2.56804e-6 4.53679e-6 -1 -0.3826833 -0.9238797 0 -0.9238793 -0.382684 3.99496e-7 -1.88426e-6 4.54898e-6 -1 -0.382685 0.9238789 4.19527e-7 -4.75254e-6 1.96855e-6 -1 -0.9238807 0.3826807 5.53932e-7 -4.45244e-6 2.26865e-6 -1 -0.9238807 0.3826807 5.53932e-7 4.39547e-6 1.06115e-5 -1 0.3826853 0.9238788 0 -0.3826841 0.9238793 3.03679e-7 -1.4491e-5 -6.0025e-6 -1 0.9238764 0.382691 -4.1137e-7 -2.65892e-6 5.21844e-6 -1 -7.40495e-6 -1.17282e-6 -1 0.3826853 0.9238788 0 -5.77107e-6 2.3905e-6 -1 0.923877 -0.3826896 -5.53933e-7 0.9238762 0.3826913 -3.63849e-7 -2.34276e-6 5.65584e-6 -1 0.3826878 -0.9238778 -4.19528e-7 -5.40671e-6 2.75485e-6 -1 0.923877 -0.3826896 -5.53933e-7 5.56523e-6 1.34356e-5 -1 -0.3826844 -0.9238792 0 0.3826878 -0.9238778 -4.19528e-7 -1.25336e-5 -5.19158e-6 -1 -0.9238795 -0.3826836 3.63853e-7 -9.36301e-6 -1.48298e-6 -1 -2.1021e-6 4.12557e-6 -1 -0.3826844 -0.9238792 0 -0.9238795 -0.3826836 3.63853e-7 -1.22527e-6 2.95807e-6 -1 -0.3826844 0.9238792 4.1953e-7 -3.42897e-6 1.42033e-6 -1 -0.9238789 0.3826851 5.53937e-7 -0.9238789 0.3826851 5.53937e-7 2.36157e-6 5.70132e-6 -1 0.3826844 0.9238792 0 -0.3826844 0.9238792 4.22511e-7 -1.16711e-5 -4.83431e-6 -1 0.9238795 0.3826836 -3.63856e-7 4.54131e-6 1.09637e-5 -1 -1.30191e-5 -6.59669e-6 -1 0.3826844 0.9238792 0 -4.96705e-6 2.05743e-6 -1 0.9238792 -0.3826844 -5.53937e-7 -2.00244e-6 4.83431e-6 -1 0.9238795 0.3826836 -3.63856e-7 -2.00244e-6 4.83431e-6 -1 0.3826844 -0.9238792 -4.1953e-7 -4.96706e-6 2.05742e-6 -1 0.9238791 -0.3826844 -5.53937e-7 4.54133e-6 1.09637e-5 -1 -0.3826844 -0.9238792 0 -1.1671e-5 -4.83427e-6 -1 0.3826844 -0.9238791 -4.1953e-7 -1.57939e-5 -6.54202e-6 -1 -0.9238799 -0.3826829 3.63856e-7 -2.45405e-6 1.90658e-6 -1 -0.3826844 -0.9238791 0 -0.9238799 -0.3826829 3.63856e-7 -0.3826837 0.9238794 1.43404e-7 -0.9238798 0.3826827 0 -0.9238798 0.3826827 0 0.3826835 0.9238795 1.43404e-7 -0.3826837 0.9238794 1.45237e-7 0.9238793 0.3826841 0 -9.36481e-6 -3.27726e-6 -1 0.3826835 0.9238795 1.43404e-7 0.923879 -0.3826848 0 0.9238793 0.3826841 0 0.3826848 -0.9238789 -1.43404e-7 0.923879 -0.3826848 0 -0.3826819 -0.9238802 -1.43404e-7 0.3826848 -0.9238789 -1.43404e-7 -0.9238802 -0.382682 0 -0.3826819 -0.9238802 -1.43404e-7 -0.9238802 -0.382682 0 -0.3826844 0.9238792 0 -0.9238792 0.3826844 0 -0.9238792 0.3826844 0 0.3826844 0.9238792 0 -0.3826844 0.9238792 0 -8.75333e-6 -3.62577e-6 -1 0.9238787 0.3826854 0 3.40596e-6 8.22275e-6 -1 0.3826844 0.9238792 0 -3.72528e-6 1.54308e-6 -1 0.9238781 -0.382687 0 -1.50183e-6 3.62573e-6 -1 0.9238784 0.3826862 0 -1.50183e-6 3.62573e-6 -1 0.3826851 -0.9238789 -2.29448e-7 -3.72528e-6 1.54306e-6 -1 0.9238781 -0.382687 0 4.54133e-6 1.09637e-5 -1 -0.3826844 -0.9238792 -2.29448e-7 5.52015e-5 6.03291e-5 -1 0.3826851 -0.9238789 -2.29448e-7 -0.9238784 -0.3826861 0 -7.58796e-6 -1.16558e-6 -1 -6.92021e-6 -5.28276e-7 -1 -0.3826825 -0.9238799 0 -0.9238784 -0.3826861 0 -0.3826851 0.9238789 0 -0.9238794 0.3826837 1.90081e-7 -0.9238792 0.3826844 0 0.382684 0.9238793 0 -0.3826848 0.923879 0 3.75658e-5 5.30242e-5 -1 0.9238788 0.3826853 0 0.3826844 0.9238792 0 0 0 -1 0.9238805 -0.382681 0 0 0 -1 0.9238788 0.3826853 0 0 0 -1 0.3826803 -0.9238809 0 0 0 -1 0.9238809 -0.38268 0 0 0 -1 -0.3826803 -0.9238809 0 0.3826803 -0.9238809 0 -1.82339e-5 -7.55277e-6 -1 -0.9238788 -0.3826853 0 -5.73578e-5 -5.67954e-5 -1 1.52028e-5 2.46141e-5 -1 -0.3826803 -0.9238809 0 -0.9238794 -0.3826837 -1.90081e-7 -1.88426e-6 4.54898e-6 -1 -0.3826851 0.9238789 0 -4.75252e-6 1.96857e-6 -1 -0.9238784 0.382686 0 -4.45245e-6 2.26864e-6 -1 -0.9238781 0.3826868 0 4.39546e-6 1.06115e-5 -1 0.3826851 0.9238789 0 -0.3826851 0.9238789 0 -1.26795e-5 -5.2521e-6 -1 0.9238777 0.3826881 0 -7.40498e-6 -1.17285e-6 -1 -2.32656e-6 4.56613e-6 -1 0.3826851 0.9238789 0 -5.04972e-6 2.09166e-6 -1 0.9238799 -0.3826826 0 0.9238772 0.3826888 0 -2.04988e-6 4.94889e-6 -1 0.3826814 -0.9238804 -2.29447e-7 -4.73089e-6 2.41049e-6 -1 0.9238799 -0.3826827 0 4.86965e-6 1.17562e-5 -1 -0.382687 -0.9238781 -2.29446e-7 0.3826814 -0.9238804 -2.29447e-7 -1.25337e-5 -5.19164e-6 -1 -0.9238788 -0.3826853 0 -2.10207e-6 4.12559e-6 -1 -8.19262e-6 -1.2976e-6 -1 -0.382687 -0.9238781 -2.29446e-7 -0.9238788 -0.3826853 0 -0.3826847 0.923879 1.62243e-7 -0.923879 0.3826847 0 -0.9238793 0.3826838 1.62243e-7 0.3826821 0.92388 0 -0.3826844 0.9238792 0 -1.36769e-5 -5.66515e-6 -1 0.9238799 0.3826826 0 -7.02239e-7 5.72536e-6 -1 0.3826825 0.9238799 0 2.38754e-5 2.75744e-5 -1 0.9238795 -0.3826834 0 0.9238793 0.3826839 0 -1.79169e-6 4.32553e-6 -1 0.382683 -0.9238796 -1.62243e-7 0.9238793 -0.3826839 -1.62243e-7 4.02825e-6 9.72504e-6 -1 -0.3826838 -0.9238794 0 0.3826834 -0.9238795 0 -0.9238793 -0.3826839 0 -0.3826834 -0.9238795 0 -0.9238796 -0.382683 0 -0.4539896 0.891007 0 -0.8910065 0.4539905 0 -0.8910067 0.4539902 0 1.34121e-6 8.46799e-6 -1 0.1564355 0.9876882 0 -3.23209e-5 -2.44627e-5 -1 -0.4539896 0.891007 0 8.52275e-4 8.52273e-4 -0.9999992 0.7071073 0.7071062 0 -4.89912e-5 -4.18645e-5 -1 0.1564355 0.9876882 0 -1.00489e-5 -1.5916e-6 -1 0.9876883 0.1564348 0 -1.09853e-6 4.757e-6 -1 0.7071073 0.7071062 0 -4.83315e-6 2.46262e-6 -1 0.8910061 -0.4539913 0 0.9876883 0.1564348 0 1.64843e-5 2.24691e-5 -1 0.4539912 -0.8910062 0 0.8910061 -0.4539913 0 -2.54971e-5 -1.88488e-6 -1 -0.1564298 -0.9876891 0 -3.37196e-7 3.3547e-6 -1 0.4539912 -0.8910062 0 1.01126e-5 1.01126e-5 -1 -0.7071074 -0.7071062 0 -0.1564298 -0.9876891 0 4.00753e-5 4.63604e-5 -1 -0.9876881 -0.1564365 0 1.34119e-6 8.46797e-6 -1 -1.65914e-6 5.46764e-6 -1 -0.7071074 -0.7071062 0 -0.9876881 -0.1564361 0 -0.4539927 0.8910055 3.63803e-7 -0.8910037 0.453996 5.1656e-7 -0.8910037 0.4539961 5.13036e-7 1.04559e-6 6.60159e-6 -1 0.1564341 0.9876884 0 -0.4539927 0.8910055 3.67109e-7 1.31083e-4 1.31083e-4 -1 0.7071061 0.7071075 -2.41466e-7 0.1564341 0.9876884 0 0.9876886 0.1564328 -4.66081e-7 0.7071061 0.7071075 -2.40437e-7 0.8910049 -0.4539936 -5.13036e-7 0.9876886 0.1564328 -4.66309e-7 0.4539927 -0.8910055 -3.63803e-7 0.8910049 -0.4539935 -5.13036e-7 -0.1564337 -0.9876885 0 0.4539927 -0.8910055 -3.63803e-7 6.57336e-5 6.57334e-5 -1 -0.7071076 -0.7071059 2.41467e-7 -0.1564337 -0.9876885 0 -0.9876881 -0.1564359 4.6388e-7 3.54654e-6 1.00244e-5 -1 -0.7071077 -0.7071059 2.30491e-7 -0.9876881 -0.1564358 4.65094e-7 -0.4539912 0.8910062 0 -0.8910061 0.4539913 0 -0.8910063 0.453991 0 0.1564298 0.9876891 0 -0.4539912 0.8910062 0 0.7071074 0.7071062 0 0.1564298 0.9876891 0 -1.73774e-5 -1.04944e-5 -1 0.9876881 0.1564363 0 1.21928e-6 7.69817e-6 -1 -4.32618e-6 2.15273e-6 -1 0.7071074 0.7071062 0 0.8910067 -0.4539903 0 0.9876881 0.1564363 0 0.453987 -0.8910083 0 0.8910067 -0.4539903 0 1.21925e-6 7.69814e-6 -1 -0.1564325 -0.9876887 0 1.19031e-5 1.81499e-5 -1 0.453987 -0.8910083 0 8.63373e-4 8.63371e-4 -0.9999993 -0.7071074 -0.7071062 0 3.34201e-5 3.98989e-5 -1 -0.1564325 -0.9876887 0 -6.43742e-6 -1.01959e-6 -1 -0.9876883 -0.1564349 0 4.3352e-4 4.36826e-4 -0.9999998 -0.7071074 -0.7071062 0 -0.9876883 -0.1564345 0 -0.4539902 0.8910066 3.70717e-7 -0.8910075 0.4539886 5.1656e-7 -0.8910074 0.4539887 5.1656e-7 0.1564351 0.9876882 0 -0.4539903 0.8910068 3.60777e-7 -0.001864969 -0.001829743 -0.9999966 0.7071061 0.7071075 -2.41466e-7 0.1564351 0.9876882 0 -1.08665e-5 -1.72117e-6 -1 0.9876872 0.1564419 -4.66079e-7 -4.96184e-7 4.21655e-6 -1 4.21467e-6 1.09932e-5 -1 0.7071061 0.7071075 -2.40437e-7 -4.40183e-6 2.24286e-6 -1 0.8910049 -0.4539936 -5.13036e-7 0.9876872 0.1564419 -4.66307e-7 -2.2439e-5 -1.07825e-5 -1 0.4539927 -0.8910055 -3.63803e-7 0.8910049 -0.4539935 -5.13036e-7 1.56924e-6 9.90781e-6 -1 -0.1564337 -0.9876885 0 0.4539927 -0.8910055 -3.63803e-7 1.992e-4 1.992e-4 -1 -0.7071076 -0.7071059 2.41467e-7 -0.1564337 -0.9876885 0 -0.9876881 -0.1564358 4.66308e-7 -0.7071076 -0.7071059 2.41467e-7 -0.9876881 -0.1564358 4.65094e-7 1 1.34872e-7 0 -1.40246e-6 -1 0 -1.40246e-6 -1 0 0.9758974 -0.21823 0 1 1.34872e-7 0 -3.64493e-6 2.82334e-6 -1 0.7905712 -0.6123701 -3.04168e-7 0.9758974 -0.21823 0 -2.21511e-6 4.33198e-6 -1 0.4552711 -0.8903528 -4.42243e-7 -1.73932e-6 4.75744e-6 -1 0.7905713 -0.6123701 -3.04168e-7 0.2966415 -0.9549889 0 0.4552738 -0.8903514 0 0.3877705 -0.9217559 0 0.2966415 -0.9549889 0 0.475333 -0.879806 0 0.3877705 -0.9217559 0 -0.7071064 -0.7071071 3.51224e-7 0.4753328 -0.8798062 -2.36101e-7 -0.522041 -0.8529204 -1.64349e-7 -0.7071065 -0.707107 0 -0.07782679 -0.9969668 -1.36824e-4 -0.5222573 -0.852788 -3.96284e-5 0.383372 -0.923594 -3.90039e-5 -0.07781916 -0.9969676 -1.35632e-4 0.6299823 -0.7766096 -6.9866e-7 0.3835993 -0.9234996 -6.49241e-7 -1.51329e-6 6.92604e-6 -1 0.7071068 -0.7071068 -3.51223e-7 1.00492e-4 1.06019e-4 -1 7.39883e-5 7.99458e-5 -1 0.6299826 -0.7766093 -3.12915e-7 0.7766101 -0.6299815 -3.85745e-7 0.7071068 -0.7071068 -3.51223e-7 -3.54629e-6 1.47202e-6 -1 0.9235938 -0.3833724 0 -1.7159e-6 2.97499e-6 -1 0.7766104 -0.6299812 0 2.71323e-5 2.76543e-5 -1 0.9969668 0.07782757 -1.35557e-4 0 5.20977e-6 -1 0.9234969 -0.3836059 -3.93287e-5 0 0 -1 0.8529199 0.5220419 -3.86732e-5 0 0 -1 0.9969668 0.0778287 -1.35377e-4 0.7071068 0.7071068 -3.51223e-7 0.8527916 0.5222513 -4.23585e-7 0.4996235 0.8662426 -2.48165e-7 0.7071068 0.7071068 -3.51223e-7 0 1 -2.04642e-4 0.4999167 0.8660734 -5.85425e-5 -0.4996266 0.8662407 -5.79672e-5 -2.87973e-6 1 -2.04145e-4 -0.7071068 0.7071068 3.51223e-7 -0.4999189 0.8660722 2.48312e-7 0.7071068 0.7071068 0 -0.7071069 0.7071067 7.02445e-7 0.7057796 -0.7084316 -7.02447e-7 0.7071068 0.7071068 0 0.7896845 -0.6135131 -6.96976e-7 -1.16943e-4 -1.10273e-4 -1 0.7057794 -0.7084316 -7.02447e-7 0.8609147 -0.5087493 -4.27621e-7 0.7896847 -0.6135129 -3.92241e-7 0.9183277 -0.395821 -5.54442e-7 0.8609147 -0.5087494 -5.53971e-7 0.9610031 -0.2765378 -4.77336e-7 0.9183277 -0.3958209 -4.56139e-7 0.988255 -0.1528134 -5.28824e-7 0.961003 -0.2765379 -5.46015e-7 -2.63587e-6 4.16263e-6 -1 0.9996452 -0.02663362 -5.01491e-7 0.9882551 -0.1528134 -5.19336e-7 -3.43652e-6 3.76609e-6 -1 0.9949898 0.09997594 -4.78695e-7 1.91625e-7 7.20612e-6 -1 0.9996452 -0.02663362 -5.0066e-7 -3.02635e-6 3.49944e-6 -1 0.9743612 0.2249897 -4.28091e-7 -8.5485e-6 -1.73651e-6 -1 0.9949899 0.099976 -4.69384e-7 -4.76346e-6 2.60158e-6 -1 0.93809 0.3463919 -4.65951e-7 2.81589e-6 9.78826e-6 -1 0.9743611 0.2249897 -4.83967e-7 1.49357e-5 2.16226e-5 -1 0.886753 0.4622435 -3.25653e-7 -2.0967e-6 5.47226e-6 -1 0.9380899 0.346392 -3.79924e-7 0.7071068 -0.7071067 -5.26836e-7 -4.21468e-6 4.21469e-6 -1 1.05404e-5 1.50188e-5 -1 -4.05502e-6 1.17889e-6 -1 0.8867531 0.4622436 -3.25656e-7 1.56675e-5 2.03585e-5 -1 0.8529247 -0.5220341 -4.23653e-7 0.7071069 -0.7071067 -3.51224e-7 -4.61163e-6 3.60004e-7 -1 0.9969668 -0.07782757 -1.36407e-4 -3.39668e-7 4.3513e-6 -1 0.8527927 -0.5222495 -3.97258e-5 -6.19149e-6 -2.56999e-6 -1 0.9235951 0.3833692 -3.90047e-5 -4.3754e-5 -3.87824e-5 -1 0.9969672 -0.07782262 -1.35634e-4 2.61028e-5 2.61028e-5 -1 0.7766097 0.6299821 0 -1.0543e-5 -6.92154e-6 -1 0.9234992 0.3836005 0 0.7071068 0.7071068 -3.51224e-7 0.77661 0.6299818 -3.85747e-7 0.6299818 0.77661 -3.12916e-7 0.7071068 0.7071068 -3.51224e-7 0.3833724 0.9235939 2.68331e-7 0.6299814 0.7766102 0 -0.07782441 0.9969671 -1.34566e-4 0.383602 0.9234985 -3.84124e-5 -0.5220433 0.852919 -3.82493e-5 -0.07782238 0.9969673 -1.34883e-4 -0.7071063 0.7071073 7.02448e-7 -0.5222564 0.8527885 6.82993e-7 -4.76541e-6 2.74797e-6 -1 -0.8662887 0.4995437 6.78417e-7 -0.7071063 0.7071073 7.02448e-7 1.87437e-5 2.30669e-5 -1 -1 0 -2.33452e-5 -0.8660729 0.4999176 -7.3854e-5 -1.32741e-5 -7.65454e-6 -1 -0.8662872 -0.4995462 -7.33889e-5 -1 -2.87924e-6 -2.28488e-5 -0.7071065 -0.7071071 0 -0.8660742 -0.4999154 1.81873e-7 -0.7071063 0.7071073 3.51224e-7 -0.7071064 -0.7071071 3.51224e-7 1.98383e-5 2.55378e-5 -1 0.7084158 0.7057953 0 -0.7071065 0.707107 7.02448e-7 0.6134694 0.7897185 0 0.7084158 0.7057953 0 0.5086915 0.860949 -2.5267e-7 0.6134698 0.7897182 -3.04714e-7 0.3957512 0.9183577 0 0.5086913 0.860949 0 0.2764674 0.9610232 0 0.3957512 0.9183577 0 0.1527513 0.9882647 4.90875e-7 0.2764669 0.9610235 4.77344e-7 0.02658259 0.9996466 4.93227e-7 0.1527513 0.9882647 4.71907e-7 -0.1000104 0.9949865 0 0.02658307 0.9996466 0 -0.2250074 0.974357 0 -0.1000104 0.9949864 0 -0.346402 0.9380862 0 -0.2250074 0.974357 0 -0.4622473 0.8867511 4.40454e-7 -0.3464024 0.938086 4.65953e-7 0.7071065 0.707107 0 -0.4622468 0.8867513 0 0.522041 0.8529204 -2.593e-7 0.7071066 0.7071069 -3.51223e-7 0.07782757 0.9969668 -1.36445e-4 0.5222588 0.8527871 -3.99827e-5 -0.383372 0.923594 -3.81643e-5 0.0778197 0.9969675 -1.35215e-4 -0.6299818 0.7766099 3.12914e-7 -0.3835994 0.9234995 1.90535e-7 -4.25885e-6 4.25885e-6 -1 -0.7071068 0.7071068 7.02445e-7 2.94123e-4 2.94123e-4 -0.9999999 -0.6299821 0.7766096 6.9866e-7 -0.7766109 0.6299808 6.98659e-7 -0.7071068 0.7071067 7.02445e-7 -3.54716e-6 1.47237e-6 -1 -0.923595 0.3833697 4.58753e-7 -1.71567e-6 2.97524e-6 -1 -0.7766107 0.6299809 3.85746e-7 -6.95002e-6 -5.42482e-7 -1 -0.9969676 -0.07781803 -1.3506e-4 0 5.20855e-6 -1 -0.923498 0.3836032 -3.88707e-5 7.71975e-5 7.71976e-5 -1 -0.8529199 -0.5220419 -3.82495e-5 9.15557e-6 1.58773e-5 -1 -0.9969675 -0.07781916 -1.34883e-4 -0.7071064 -0.7071073 3.51222e-7 -0.8527903 -0.5222536 4.23584e-7 -0.4995415 -0.8662899 -1.82165e-7 -0.7071068 -0.7071068 0 0 -1 -2.43385e-5 -0.4999129 -0.8660756 -7.4217e-5 0.4995459 -0.8662875 -7.42491e-5 2.87979e-6 -1 -2.38421e-5 0.7071069 -0.7071067 -7.02445e-7 0.4999151 -0.8660744 -6.78492e-7 -0.7071068 -0.7071068 3.51223e-7 0.707107 -0.7071066 -3.51223e-7 -0.7057932 0.7084179 3.50572e-7 -0.7071068 -0.7071068 3.51224e-7 -0.789717 0.6134713 3.92257e-7 -0.7057933 0.7084179 3.50572e-7 -0.8609505 0.5086889 4.27639e-7 -0.789717 0.6134713 3.92257e-7 -0.9183604 0.395745 4.56155e-7 -0.8609505 0.5086889 4.27639e-7 -0.961027 0.2764548 4.77348e-7 -0.9183604 0.3957451 4.56155e-7 -0.9882674 0.1527333 5.09844e-7 -0.961027 0.2764548 5.11677e-7 6.80625e-6 1.20975e-5 -1 -0.9996472 0.02656143 4.99829e-7 0 6.65813e-6 -1 -0.9882674 0.1527333 5.09844e-7 -2.23897e-6 3.8868e-6 -1 -0.9949839 -0.1000355 4.78683e-7 -0.9996473 0.02656143 5.0065e-7 -2.33003e-6 3.66072e-6 -1 -0.9743515 -0.2250311 4.56019e-7 5.56379e-6 1.08808e-5 -1 -0.9949839 -0.1000355 4.81788e-7 -3.74032e-6 2.97975e-6 -1 -0.9380801 -0.3464183 3.79913e-7 2.95492e-6 9.14866e-6 -1 -0.9743516 -0.2250311 4.28076e-7 -4.70863e-6 2.15855e-6 -1 -0.8867481 -0.4622529 2.10848e-7 -3.08413e-6 3.66615e-6 -1 -0.9380802 -0.3464182 2.9388e-7 -0.707107 0.7071065 5.26836e-7 -4.21469e-6 4.21469e-6 -1 1.05736e-5 1.50431e-5 -1 -1.64884e-5 -1.02524e-5 -1 -0.8867481 -0.462253 3.25651e-7 -3.87988e-6 2.37475e-6 -1 -0.852919 0.5220433 4.2365e-7 -0.707107 0.7071065 3.51224e-7 1.90755e-5 2.40471e-5 -1 -0.9969671 0.07782417 -1.35873e-4 -4.5289e-7 5.80174e-6 -1 -0.8527866 0.5222597 -3.90402e-5 -9.28729e-6 -3.85503e-6 -1 -0.923594 -0.383372 -3.83549e-5 3.52815e-6 8.49979e-6 -1 -0.9969674 0.0778197 -1.35176e-4 -2.86687e-5 -2.32559e-5 -1 -0.7766094 -0.6299824 3.85746e-7 -2.88658e-5 -2.34335e-5 -1 -0.9234985 -0.383602 4.58707e-7 -0.707107 -0.7071065 0 -0.7766097 -0.6299821 0 -0.6299813 -0.7766103 0 -0.7071071 -0.7071065 0 -0.383372 -0.923594 1.90423e-7 -0.629981 -0.7766106 3.12915e-7 0.07782441 -0.9969671 -1.34605e-4 -0.3836 -0.9234994 -3.82223e-5 0.5220405 -0.8529208 -3.87687e-5 0.07782214 -0.9969673 -1.34961e-4 0.7071073 -0.7071063 -3.51224e-7 0.5222513 -0.8527916 -2.59405e-7 -3.17694e-6 1.83198e-6 -1 0.866288 -0.499545 -4.3029e-7 0.7071073 -0.7071063 -3.51224e-7 -5.29655e-6 0 -1 1 0 -2.38419e-5 0.8660742 -0.4999155 -7.4284e-5 -1.32743e-5 -7.65475e-6 -1 0.8662848 0.4995505 -7.40017e-5 1 0 -2.38419e-5 0.7071066 0.707107 -3.51224e-7 0.8660717 0.4999198 -4.30183e-7 0.7071068 -0.7071068 -7.02448e-7 0.7071064 0.7071071 0 2.25848e-5 2.84371e-5 -1 -0.7109412 -0.7032516 3.53129e-7 0.707107 -0.7071065 -3.51224e-7 -0.6219225 -0.7830789 3.08913e-7 -0.7109412 -0.7032516 3.53129e-7 -0.5240248 -0.8517031 0 -0.6219227 -0.7830786 0 -0.4186444 -0.9081503 -4.51084e-7 -0.5240252 -0.8517029 -4.23046e-7 -0.3073548 -0.951595 -4.72661e-7 -0.4186444 -0.9081503 -4.51082e-7 -0.4552718 -0.8903524 0 -0.3073543 -0.9515951 0 -0.7905712 -0.6123701 0 -0.4552718 -0.8903524 0 -0.9758979 -0.2182275 0 -0.7905712 -0.6123701 0 -1 -1.34872e-7 0 -0.9758979 -0.2182275 0 1.40246e-6 -1 0 -1 -1.34872e-7 0 1 3.7253e-7 -1.24176e-7 1.40246e-6 -1 0 2.59151e-7 -1 0 1 3.7253e-7 -1.24176e-7 -1 2.48353e-7 0 0 -1 -4.96706e-7 -1 2.48353e-7 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -2.71353e-6 -6.55046e-6 1 3.6677e-5 -3.62155e-5 1 1.73583e-6 -4.19102e-6 1 -3.24726e-5 2.5153e-5 1 -1.98578e-4 1.91766e-4 1 1.11277e-5 -4.6089e-6 1 5.08811e-6 -7.50153e-6 1 0 0 1 1.32453e-5 -3.97365e-6 1 0 0 1 0 0 1 0 0 1 -1.1127e-5 -4.60927e-6 1 -1.32457e-5 -3.97365e-6 1 -3.43539e-6 -8.29306e-6 1 6.92891e-6 -1.67289e-5 1 5.85127e-5 -2.4235e-5 1 4.72674e-6 -9.27673e-6 1 -1.15428e-4 1.03184e-4 1 -2.8151e-6 -2.81509e-6 1 4.6995e-6 -7.75685e-6 1 -7.04961e-7 -4.45109e-6 1 1.25552e-5 0 1 8.24206e-6 3.41419e-6 1 3.10029e-6 7.4843e-6 1 5.60984e-6 4.56628e-6 1 -4.51011e-6 -6.74771e-6 1 -8.06778e-6 -5.39243e-6 1 -1.67652e-6 -8.39192e-6 1 6.19024e-5 -5.91805e-5 1 0 0 1 -7.70422e-6 5.11894e-6 1 4.76899e-6 -7.17737e-6 1 -6.31249e-6 3.90409e-6 1 0 0 1 -3.44863e-6 6.92296e-7 1 6.49313e-7 -3.23459e-6 1 -2.40409e-6 -4.8029e-7 1 -4.58967e-7 -2.29736e-6 1 -1.75733e-6 -1.17462e-6 1 -1.15553e-6 -1.72885e-6 1 -1.15556e-6 -1.72883e-6 1 -1.75737e-6 -1.17458e-6 1 4.14098e-5 -4.14098e-5 1 -2.40409e-6 -4.8029e-7 1 0 0 1 0 0 1 4.76899e-6 -7.17737e-6 1 1.74589e-4 -1.74589e-4 0.9999999 1.00986e-5 -6.70979e-6 1 -7.13297e-6 4.72457e-6 1 5.99434e-6 -5.99434e-6 1 1.73769e-6 -3.01042e-6 1 0 -1.72517e-6 1 -6.77345e-7 -1.17346e-6 1 4.65875e-6 -9.35135e-7 1 -3.764e-6 -3.764e-6 1 -1.64895e-5 -3.29396e-6 1 -8.1031e-6 -4.8954e-6 1 -2.56755e-5 1.70601e-5 1 -7.58767e-5 6.68264e-5 1 -1.15895e-5 2.32632e-6 1 -2.44186e-5 -4.87835e-6 1 -5.40973e-6 -5.40973e-6 1 7.26686e-5 -1.0379e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 3.27978e-5 -8.08713e-5 1 5.27445e-6 -7.89135e-6 1 -1.31155e-5 1.03673e-5 1 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.05369e-5 7.04281e-6 1 -3.84944e-6 7.23082e-7 1 -3.9246e-6 7.84008e-7 1 -2.56042e-6 -5.13957e-7 1 3.42579e-5 -3.58251e-5 1 -1.0733e-6 -1.61533e-6 1 -4.47123e-7 -2.22748e-6 1 6.63712e-7 -3.32229e-6 1 5.94144e-6 -3.97124e-6 1 2.82665e-6 -4.22906e-6 1 5.78647e-6 -3.14624e-6 1 5.64006e-6 -1.12671e-6 1 -1.41661e-4 -2.84357e-5 1 5.6184e-6 -5.2247e-6 1 -1.35721e-5 -9.01786e-6 1 -5.55239e-6 -8.35658e-6 1 -1.72172e-6 -8.57691e-6 1 1.88597e-6 -9.44019e-6 1 7.95493e-6 -1.19015e-5 1 0 0 1 8.31766e-6 -1.2084e-5 1 0 0 1 0 0 1 -5.08728e-5 -3.38021e-5 1 1.34062e-6 -4.27896e-6 1 -5.57503e-6 -8.39074e-6 1 -1.21924e-6 -6.07372e-6 1 9.99331e-7 -5.00221e-6 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.70413e-6 5.11884e-6 1 4.76883e-6 -7.17722e-6 1 -6.31246e-6 3.90406e-6 1 0 0 1 6.25802e-5 -6.25802e-5 1 6.49172e-7 -3.23445e-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 1.00979e-5 -6.70968e-6 1 2.07509e-5 -2.07508e-5 1 5.99434e-6 -5.99433e-6 1 1.73766e-6 -3.0104e-6 1 0 -1.72517e-6 1 -6.7734e-7 -1.17346e-6 1 9.31789e-6 -1.87015e-6 1 7.94728e-7 -4.73272e-6 1 1.10666e-4 -2.75751e-5 1 -3.35372e-6 -5.80239e-6 1 -2.5675e-5 1.70597e-5 1 -7.58745e-5 6.68243e-5 1 -1.15892e-5 2.32601e-6 1 -2.44194e-5 -4.87832e-6 1 -5.40976e-6 -5.40976e-6 1 -8.63608e-6 -5.77256e-6 1 -4.27483e-6 -6.39547e-6 1 -1.43879e-6 -7.20162e-6 1 1.73281e-6 -8.63278e-6 1 8.31412e-6 -1.25132e-5 1 0 0 1 6.91116e-6 -1.03401e-5 1 -1.02249e-6 -2.4685e-6 1 3.31236e-6 -6.58228e-6 1 0 0 1 0 0 1 -1.1125e-5 -7.39185e-6 1 2.70837e-7 -4.70862e-6 1 -3.97345e-6 -5.98004e-6 1 -1.13433e-6 -5.65201e-6 1 1.12675e-6 -5.64007e-6 1 3.97134e-6 -5.94145e-6 1 -1.01426e-5 6.77935e-6 1 2.94502e-6 -5.74867e-6 1 -3.8809e-6 7.7536e-7 1 -2.54625e-6 -5.11079e-7 1 -1.82454e-6 -1.2123e-6 1 -1.2076e-6 -1.81747e-6 1 -5.04526e-7 -2.51376e-6 1 8.70687e-7 -4.35812e-6 1 1.26541e-4 -1.28146e-4 1 3.11685e-4 -3.11684e-4 1 -1.40229e-4 1.37018e-4 1 -1.48797e-4 1.45541e-4 1 2.47034e-6 -5.96385e-6 1 0 0 1 1.41333e-6 -2.11453e-6 1 4.62538e-7 -2.46237e-6 1 0 0 1 0.001018583 1.54419e-4 0.9999995 0 -6.1152e-6 1 0 0 1 0 0 1 4.94491e-5 -2.84439e-6 1 -1.88588e-6 9.44018e-6 1 -7.95516e-6 1.19016e-5 1 -1.29759e-5 8.67306e-6 1 -1.90365e-5 1.74781e-5 1 2.63863e-5 -5.49565e-5 1 0 0 1 -5.08775e-5 -3.38047e-5 1 1.34062e-6 -4.27896e-6 1 -5.57499e-6 -8.39072e-6 1 -1.21907e-6 -6.07363e-6 1 4.63114e-5 1.68821e-5 1 -4.35956e-6 2.22128e-6 1 2.92238e-6 -5.73554e-6 1 1.60237e-6 -4.38751e-6 1 6.34229e-6 -8.2035e-6 1 4.04674e-7 -1.75237e-6 1 -1.47426e-6 -2.33498e-7 1 -8.25304e-7 -8.25307e-7 1 -2.25575e-7 -1.42423e-6 1 1.6745e-6 -3.28645e-6 1 1.0189e-6 -2.75926e-6 1 -8.41432e-6 4.28726e-6 1 3.51932e-6 -5.26949e-6 1 9.32945e-7 -2.6617e-6 1 -2.63322e-6 -4.17057e-7 1 -1.44429e-6 -1.44429e-6 1 -3.85633e-7 -2.43481e-6 1 0 0 1 7.37317e-6 -1.05342e-5 1 -2.89601e-5 2.57991e-5 1 0 0 1 1.64944e-5 -1.85154e-5 1 1.7196e-5 -1.64479e-5 1 0 0 1 -4.9629e-6 -4.34927e-7 1 2.08619e-5 -2.11962e-5 1 -3.62205e-6 -1.68879e-6 1 6.42591e-6 -9.77647e-6 1 -9.87124e-7 -4.725e-6 1 -1.48241e-6 -3.17941e-6 1 2.14225e-5 -1.79448e-5 1 0 -4.63208e-6 1 7.82324e-7 -2.91819e-6 1 -2.83662e-5 2.05696e-5 1 -5.46077e-5 5.21904e-5 1 2.45773e-6 -3.5114e-6 1 1.36629e-5 -1.47165e-5 1 -3.79391e-6 1.01709e-6 1 8.85407e-7 -3.30271e-6 1 3.02788e-5 -3.18391e-5 1 2.09185e-5 -2.36953e-5 1 -2.2788e-6 -1.0625e-6 1 8.10432e-6 -9.66464e-6 1 7.26586e-6 -8.93651e-6 1 -1.67065e-6 -1.67065e-6 1 -9.9233e-7 -2.1283e-6 1 7.46108e-6 -9.13172e-6 1 -2.23741e-7 -2.55308e-6 1 -2.86919e-6 -2.51442e-7 1 8.85407e-7 -3.30271e-6 1 -3.79391e-6 1.01709e-6 1 3.84963e-5 -4.09136e-5 1 5.33194e-5 -5.62207e-5 1 0 0 1 2.5252e-5 -3.16436e-5 1 -4.23668e-5 3.6878e-5 1 -1.14545e-5 3.07077e-6 1 -1.6509e-6 -3.58123e-6 1 2.1907e-5 -2.10753e-5 1 7.47081e-6 -9.12717e-6 1 -8.33814e-7 -8.33816e-7 1 -5.7201e-7 -1.22682e-6 1 -4.29605e-7 -1.3301e-6 1 -1.41844e-7 -1.61856e-6 1 1.52039e-6 -5.67128e-6 1 1.27325e-5 -1.43275e-5 1 -5.84081e-7 -1.14226e-6 1 4.45048e-6 -8.73464e-6 1 5.07087e-5 -5.07086e-5 1 -1.51836e-6 -1.51837e-6 1 -2.27657e-6 -2.27657e-6 1 1.0524e-6 -5.05558e-6 1 -9.33875e-6 6.0622e-6 1 1.01089e-4 -1.01089e-4 1 1.63536e-5 -1.98549e-5 1 1.65284e-6 -4.12617e-6 1 -1.75539e-4 7.27106e-5 1 2.27063e-6 -5.48182e-6 1 -2.29971e-6 -9.11479e-7 1 -2.31885e-5 1.60562e-5 1 -4.7656e-6 -4.59024e-6 1 -8.25742e-6 -3.42034e-6 1 -2.61832e-6 -6.3212e-6 1 4.34863e-6 -1.04985e-5 1 -5.8355e-6 2.41713e-6 1 2.27066e-6 -5.48185e-6 1 -1.60559e-6 -1.60559e-6 1 -4.64488e-6 -4.64488e-6 1 -2.48353e-6 -1.0287e-6 1 -1.00122e-6 -2.41715e-6 1 -1.00122e-6 -2.41715e-6 1 -2.48353e-6 -1.02871e-6 1 -5.83555e-6 2.41718e-6 1 -5.50809e-6 2.28151e-6 1 1.13533e-6 -2.74092e-6 1 2.21161e-5 -2.37216e-5 1 4.57732e-6 -7.80248e-6 1 -2.19697e-6 -9.12572e-7 1 -2.23505e-6 -9.25788e-7 1 -2.91781e-6 1.20862e-6 1 1.13533e-6 -2.74093e-6 1 -1.24175e-6 -5.14364e-7 1 -5.00608e-7 -1.20858e-6 1 -5.00611e-7 -1.20858e-6 1 -1.24177e-6 -5.14354e-7 1 -2.91776e-6 1.20857e-6 1 0 0 1 8.88428e-6 -8.88427e-6 1 0 0 1 0 0 1 3.21119e-5 -3.21119e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.16744e-6 -5.23267e-6 1 1.07983e-5 -1.38635e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.01526e-6 -2.45105e-6 1 2.6491e-5 -2.64909e-5 1 -5.91736e-6 2.45106e-6 1 2.27066e-6 -5.48185e-6 1 8.0274e-7 -4.01393e-6 1 -2.91779e-6 1.2086e-6 1 1.13531e-6 -2.7409e-6 1 6.84286e-6 -8.44845e-6 1 -1.24176e-6 -5.14358e-7 1 -5.00606e-7 -1.20858e-6 1 -5.0061e-7 -1.20858e-6 1 -1.24176e-6 -5.14356e-7 1 6.10373e-5 -6.27464e-5 1 1.51815e-6 -3.66512e-6 1 -4.94691e-6 2.04906e-6 1 -9.74039e-6 7.49049e-6 1 2.06259e-5 -2.89203e-5 1 -2.60443e-6 -6.28764e-6 1 2.07321e-6 -2.90692e-6 1 -2.91779e-6 1.2086e-6 1 4.6253e-6 -1.11664e-5 1 1.13533e-6 -2.74093e-6 1 1.97646e-5 -2.13702e-5 1 -1.24176e-6 -5.14357e-7 1 -5.00608e-7 -1.20858e-6 1 -5.00613e-7 -1.20857e-6 1 -1.24176e-6 -5.14356e-7 1 2.27063e-6 -5.48182e-6 1 6.10371e-5 -6.27463e-5 1 -5.82222e-5 2.41164e-5 1 4.21556e-6 -9.69481e-6 1 -8.0307e-6 -3.32648e-6 1 -2.68098e-6 -6.47242e-6 1 -5.36632e-6 2.73427e-6 1 2.64354e-6 -5.18826e-6 1 -1.57134e-6 -9.7338e-7 1 -3.263e-6 5.68755e-7 1 -1.80574e-5 -2.86003e-6 1 6.67849e-6 -1.0362e-5 1 -6.88702e-6 -6.88701e-6 1 2.18631e-5 -2.10605e-5 1 -3.62306e-5 1.62852e-5 1 -5.37301e-6 2.73769e-6 1 5.89339e-5 -6.08424e-5 1 2.86772e-5 -3.05858e-5 1 -2.32618e-6 -3.68432e-7 1 -3.60322e-7 -2.275e-6 1 -1.34731e-6 -1.3473e-6 1 -1.34731e-6 -1.3473e-6 1 -3.60326e-7 -2.27499e-6 1 -2.32618e-6 -3.68434e-7 1 -5.37297e-6 2.73765e-6 1 -2.93241e-5 1.49416e-5 1 1.98269e-6 -3.89123e-6 1 1.66289e-5 -1.85375e-5 1 -9.40722e-6 -1.48997e-6 1 -5.3722e-6 -5.37219e-6 1 -1.1874e-6 -7.49701e-6 1 -5.32502e-6 -5.42785e-6 1 5.961e-6 -1.16991e-5 1 -1.01048e-6 -1.01048e-6 1 -1.01048e-6 -1.01048e-6 1 -2.70242e-7 -1.70625e-6 1 -1.74464e-6 -2.76323e-7 1 -4.02976e-6 2.05327e-6 1 0 0 1 0 0 1 -2.40031e-6 -3.80176e-7 1 2.231e-5 -2.30249e-5 1 1.48992e-6 -2.92413e-6 1 -9.78092e-6 4.98367e-6 1 1.49406e-6 -3.9617e-6 1 1.88549e-6 -4.99961e-6 1 -3.13573e-6 -4.96675e-7 1 1.61514e-5 -1.9046e-5 1 -2.9682e-7 -1.87404e-6 1 2.97756e-6 -3.51117e-6 1 2.08355e-6 -4.07468e-6 1 -3.04962e-6 8.77559e-7 1 1.15943e-6 -3.73258e-6 1 1.07478e-5 -1.25636e-5 1 2.32026e-6 -4.49848e-6 1 1.94009e-5 -2.17486e-5 1 -1.46361e-6 -1.84286e-6 1 3.05631e-5 -3.05631e-5 1 -1.07085e-5 6.70169e-6 1 2.70333e-5 -2.70332e-5 1 -1.44532e-6 -1.86055e-6 1 2.66719e-6 -2.74556e-6 1 2.13011e-5 -2.1927e-5 1 -2.97409e-6 -1.71672e-6 1 -5.20967e-6 0 1 -1.4729e-6 -3.54595e-6 1 -2.4201e-5 1.39693e-5 1 9.84576e-6 -1.60773e-5 1 5.42488e-7 -6.94973e-6 1 -2.35946e-6 -9.8007e-7 1 1.89118e-6 -4.84115e-6 1 2.6e-5 -2.76249e-5 1 3.97736e-5 -3.98898e-5 1 -6.88677e-6 4.21756e-6 1 7.51366e-6 -9.92257e-6 1 1.28404e-6 -3.88681e-6 1 5.53364e-6 -7.83445e-6 1 -5.59002e-7 -1.94314e-6 1 1.20946e-6 -4.12491e-6 1 0 -2.929e-6 1 -4.27912e-6 1.66345e-6 1 5.3404e-6 -6.75599e-6 1 -2.16708e-5 1.75555e-5 1 1.15457e-5 -1.33002e-5 1 -2.70903e-6 -3.07541e-6 1 1.00598e-6 -6.35917e-6 1 1.49254e-7 -5.18915e-6 1 1.75799e-5 -1.91435e-5 1 -1.53702e-6 -1.19974e-7 1 0 -1.45045e-6 1 -3.09732e-6 1.28657e-6 1 1.1773e-6 -2.83429e-6 1 2.61024e-5 -2.61024e-5 1 7.77983e-6 -9.59058e-6 1 -2.12943e-6 -2.12943e-6 1 0 0 1 1.90682e-5 -2.30381e-5 1 1.83378e-5 -2.2345e-5 1 0 0 1 0 0 1 0 0 1 -5.50563e-6 4.29766e-7 1 7.028e-5 -7.29492e-5 1 3.6175e-6 -6.01431e-6 1 1.86546e-6 -4.43432e-6 1 6.43897e-6 -8.55728e-6 1 2.79359e-6 -5.17073e-6 1 -2.55525e-5 1.9852e-5 1 5.67909e-6 -7.75587e-6 1 2.2566e-6 -3.08181e-6 1 -1.93955e-6 -1.18779e-6 1 2.22048e-5 -2.38618e-5 1 -2.26433e-7 -2.9009e-6 1 -6.19469e-6 2.57318e-6 1 4.84204e-5 -5.00773e-5 1 -2.86682e-5 2.32554e-5 1 -1.05431e-5 6.92154e-6 1 -7.03819e-6 3.84096e-6 -1 0.6331905 -0.773996 -2.0707e-7 -5.06471e-7 4.31031e-6 -1 0.7739961 -0.6331905 -1.86968e-7 -1.35472e-6 3.46206e-6 -1 0.7739959 -0.6331906 -1.94831e-7 1.40825e-6 3.88991e-6 -1 0.4709635 -0.8821527 -2.111e-7 0.6331905 -0.7739959 -2.06136e-7 -4.18249e-6 3.35398e-6 -1 0.2907204 -0.9568081 -2.18981e-7 0.4709632 -0.8821529 -2.22054e-7 -4.0039e-7 4.11347e-6 -1 0.09687846 -0.9952962 -1.95012e-7 0.2907207 -0.956808 -2.071e-7 -2.73171e-6 3.39229e-6 -1 -0.09687727 -0.9952962 -1.75764e-7 0.09687846 -0.9952962 -1.95012e-7 1.56842e-6 5.16194e-6 -1 -0.2907204 -0.956808 -1.49339e-7 -0.09687727 -0.9952962 -1.75764e-7 -6.24668e-6 1.26938e-6 -1 -0.4718012 -0.8817049 0 -0.29072 -0.9568082 -1.37458e-7 7.23479e-6 8.83654e-6 -1 -0.6334944 -0.7737472 0 -0.4718015 -0.8817048 0 2.61389e-6 6.064e-6 -1 -0.773747 -0.6334947 0 -0.6334944 -0.7737473 0 3.64232e-5 2.9879e-5 -1 -0.8817042 -0.4718025 0 -1.12608e-4 -6.47532e-5 -1 -0.7737472 -0.6334946 0 -1.06162e-5 0 -1 -0.9568088 -0.2907182 0 7.26413e-5 5.31283e-5 -1 -0.8817042 -0.4718028 0 -6.96504e-6 2.38396e-6 -1 -0.9952964 -0.09687691 0 -0.9568087 -0.2907181 0 9.46257e-6 1.43885e-5 -1 -0.9952964 0.09687691 0 -0.9952964 -0.09687691 0 -1.9116e-7 6.38489e-6 -1 -0.9568087 0.2907185 1.49878e-7 -0.9952964 0.09687691 0 -4.53578e-6 2.42157e-6 -1 -0.882152 0.4709648 1.7682e-7 -5.99691e-7 5.9861e-6 -1 -0.9568087 0.2907185 1.50103e-7 -1.04838e-6 4.75365e-6 -1 -0.773995 0.6331918 1.94831e-7 -8.09684e-6 -1.59531e-6 -1 -0.8821521 0.4709649 1.75358e-7 0 4.90502e-6 -1 -0.6331922 0.7739946 2.11875e-7 -2.53662e-6 2.9749e-6 -1 -0.773995 0.6331917 1.98762e-7 -4.23181e-6 1.39883e-6 -1 -0.4709638 0.8821525 2.22054e-7 -1.93644e-6 2.89857e-6 -1 -0.6331923 0.7739945 2.16681e-7 1.23291e-6 6.35357e-6 -1 -0.290721 0.9568079 1.95219e-7 -0.4709632 0.8821529 2.00146e-7 -3.28919e-6 2.33507e-6 -1 -0.0968784 0.9952962 2.07372e-7 -1.56078e-7 4.70309e-6 -1 -0.2907217 0.9568077 2.18981e-7 5.84291e-7 6.00278e-6 -1 0.09687882 0.9952962 1.75764e-7 -0.09687805 0.9952962 1.95012e-7 -5.88631e-6 1.44976e-6 -1 0.2907196 0.9568083 1.37458e-7 3.34791e-6 9.05852e-6 -1 0.09687918 0.9952961 1.63405e-7 7.23058e-6 1.35126e-5 -1 0.4717997 0.8817058 1.2831e-7 0.2907189 0.9568085 1.6122e-7 -1.27032e-5 -5.93029e-6 -1 0.6334946 0.7737471 0 0.4718 0.8817057 0 -1.47236e-5 -8.13077e-6 -1 0.7737477 0.6334939 0 7.50276e-6 1.39565e-5 -1 3.60161e-5 4.247e-5 -1 0.6334946 0.773747 0 -7.02907e-6 -2.98295e-7 -1 0.8817056 0.4718001 0 1.39477e-7 6.73227e-6 -1 0.7737476 0.633494 0 1.85637e-5 2.46209e-5 -1 0.9568075 0.2907221 0 -1.60638e-6 5.1244e-6 -1 0.8817056 0.4718 0 2.2911e-7 6.14611e-6 -1 0.9952963 0.09687709 0 -2.73891e-6 3.31827e-6 -1 0.9568075 0.2907221 0 -5.67499e-6 5.52374e-7 -1 0.9952964 -0.09687691 0 -5.24853e-7 5.39215e-6 -1 0.9952964 0.09687709 0 -2.06625e-6 3.79122e-6 -1 0.9568079 -0.2907209 -1.49201e-7 -1.45121e-6 4.77615e-6 -1 6.31639e-6 1.19837e-5 -1 -1.9592e-5 -1.11627e-5 -1 0.9952964 -0.09687691 0 1.17705e-6 6.3416e-6 -1 0.8821525 -0.4709637 -1.75358e-7 -7.89958e-6 -2.15395e-6 -1 0 5.41552e-6 -1 0.9568079 -0.2907209 -1.49201e-7 -1.88463e-6 3.26754e-6 -1 0.8821526 -0.4709635 -1.6951e-7 -1.27867e-7 4.91866e-6 -1 0.63319 -0.7739964 -1.93093e-7 -1.14412e-6 4.83196e-6 -1 0.7739959 -0.6331908 -1.7386e-7 -2.9749e-6 2.53662e-6 -1 0.7739959 -0.6331908 -1.7386e-7 -1.88775e-6 3.5359e-6 -1 0.4709645 -0.8821521 -2.05971e-7 -2.98351e-6 2.60563e-6 -1 8.4944e-7 6.00364e-6 -1 0.6331899 -0.7739964 -1.95093e-7 -7.31363e-7 2.40703e-6 -1 0.2907209 -0.9568079 -2.08828e-7 1.84502e-5 -2.76173e-5 -1 -1.68265e-6 3.74601e-6 -1 0.4709645 -0.8821521 -2.05606e-7 -3.73214e-6 6.88594e-6 -1 0.09687691 -0.9952964 -3.02937e-7 0.2907181 -0.9568087 -3.04104e-7 1.52777e-7 1.56961e-6 -1 -0.09687691 -0.9952964 -1.91733e-7 0.09687995 -0.9952961 -2.03763e-7 -1.92501e-6 4.07578e-6 -1 -0.2907184 -0.9568087 -1.72051e-7 -0.09687691 -0.9952964 -1.91733e-7 -1.50967e-6 3.6503e-6 -1 -0.4718024 -0.8817043 -1.40027e-7 -0.2907183 -0.9568086 -1.68441e-7 -3.48681e-6 5.32653e-6 -1 -0.6334949 -0.7737469 0 -0.4718024 -0.8817043 -1.40027e-7 -4.7612e-6 0 -1 -0.7737467 -0.6334951 0 2.79994e-5 -1.64062e-5 -1 -1.06005e-6 3.67894e-6 -1 -1.92136e-6 4.75881e-6 -1 -1.72123e-6 4.23213e-6 -1 -0.6334931 -0.7737483 0 -4.04758e-6 1.2971e-6 -1 -0.8817051 -0.4718009 0 -0.7737467 -0.6334951 0 8.76483e-6 8.98995e-6 -1 -0.956808 -0.2907209 0 -2.2573e-6 4.89147e-6 -1 -0.8817055 -0.4718003 0 -9.27754e-6 2.15887e-6 -1 -0.9952963 -0.09687769 0 -0.9568082 -0.2907201 0 1.83755e-5 1.35209e-5 -1 -0.9952961 0.09687995 0 -0.9952963 -0.09687769 0 -6.09911e-6 1.85317e-6 -1 -0.9568087 0.2907186 0 -0.9952961 0.09687995 0 -1.74467e-6 4.41645e-6 -1 -0.8821526 0.4709638 1.60782e-7 -0.9568087 0.2907181 1.19726e-7 -1.16882e-6 4.85216e-6 -1 -0.7739959 0.6331908 2.14922e-7 -0.8821529 0.4709632 1.82691e-7 -2.574e-6 3.14639e-6 -1 -0.633191 0.7739956 2.16681e-7 -3.81854e-6 2.20243e-6 -1 -0.7739956 0.633191 2.02693e-7 -1.9377e-6 3.62948e-6 -1 -0.470963 0.882153 1.66541e-7 -2.84968e-6 2.87181e-6 -1 -0.6331897 0.7739967 1.62511e-7 -0.290722 0.9568076 2.11761e-7 2.15398e-6 7.8996e-6 -1 -0.4709642 0.8821523 2.10358e-7 -0.09687858 0.9952962 2.03763e-7 -0.2907219 0.9568076 2.08151e-7 0.0968784 0.9952962 1.42296e-7 -0.09687709 0.9952964 1.54326e-7 0.2907209 0.9568079 1.71148e-7 0.09687691 0.9952964 1.91432e-7 0.4717999 0.8817058 1.88582e-7 0.2907195 0.9568083 2.18899e-7 0.6334941 0.7737475 1.50863e-7 0.4717999 0.8817058 1.88216e-7 -1.49575e-5 -8.32232e-6 -1 0.7737469 0.633495 0 -2.57625e-5 -1.91986e-5 -1 0.6334959 0.773746 0 4.23883e-5 3.99968e-5 -1 0.8817054 0.4718004 0 -2.77407e-6 4.16865e-6 -1 0.7737463 0.6334958 0 -3.60615e-6 2.06769e-6 -1 0.956808 0.2907206 0 0.8817058 0.4717998 0 9.84675e-7 6.21965e-6 -1 0.9952962 0.0968784 0 0.9568082 0.2907203 0 -2.37254e-6 3.29283e-6 -1 0.9952963 -0.09687769 0 -6.80721e-7 4.46082e-6 -1 0.9952962 0.0968784 0 -1.85619e-6 3.72738e-6 -1 0.9568085 -0.2907188 0 0.9952963 -0.09687769 0 -4.07381e-6 2.17493e-6 -1 0.8821521 -0.4709647 -1.9513e-7 -1.96229e-6 3.61036e-6 -1 0.9568083 -0.2907197 -1.46048e-7 0.8821528 -0.4709634 -1.48343e-7 -2.47435e-6 3.02457e-6 -1 0.6331929 -0.773994 -2.16681e-7 -2.65201e-6 2.16957e-6 -1 0.7739936 -0.6331936 -1.94831e-7 -8.58031e-7 4.31375e-6 -1 0.7739934 -0.6331937 -2.02694e-7 -2.11896e-6 3.96897e-6 -1 0.4709638 -0.8821526 -2.111e-7 -8.89014e-7 4.77259e-6 -1 0.6331931 -0.7739939 -2.07363e-7 -1.40315e-6 4.61798e-6 -1 0.290721 -0.9568079 -2.18981e-7 0.4709635 -0.8821527 -2.22054e-7 -3.33775e-6 2.83404e-6 -1 0.09687829 -0.9952962 -2.07372e-7 -2.14718e-6 3.73387e-6 -1 0.2907211 -0.9568079 -2.18981e-7 6.42723e-7 6.60306e-6 -1 -0.09687918 -0.9952961 -1.75764e-7 0.09687864 -0.9952961 -1.95012e-7 -1.49618e-6 5.48711e-6 -1 -0.290718 -0.9568088 -1.49339e-7 2.9373e-6 9.14019e-6 -1 -0.09687918 -0.9952961 -1.75764e-7 4.12421e-7 7.24234e-6 -1 -0.4718006 -0.8817052 0 -0.290718 -0.9568088 -1.49339e-7 8.32233e-6 1.49575e-5 -1 -0.6334946 -0.7737471 0 -0.4718003 -0.8817055 0 -1.39497e-5 -7.49722e-6 -1 -0.7737475 -0.6334942 0 -1.41448e-5 -7.69108e-6 -1 3.60228e-5 4.24765e-5 -1 -0.6334947 -0.7737471 0 7.41456e-7 7.32266e-6 -1 -0.8817063 -0.4717988 0 7.42683e-6 1.38794e-5 -1 -0.7737478 -0.6334939 0 9.47549e-6 1.55327e-5 -1 -0.9568075 -0.2907221 0 -6.21577e-6 3.65434e-7 -1 -0.8817062 -0.4717989 0 -3.53754e-6 2.71758e-6 -1 -0.9952964 -0.09687709 0 6.5316e-7 6.71035e-6 -1 -0.9568076 -0.2907221 0 -2.88469e-6 3.34268e-6 -1 -0.9952964 0.09687691 0 -3.34515e-6 2.90996e-6 -1 -0.9952964 -0.09687709 0 6.67666e-7 6.12393e-6 -1 -0.9568079 0.2907209 1.49878e-7 9.74999e-7 7.20237e-6 -1 9.59906e-6 1.52046e-5 -1 -2.6772e-5 -1.72889e-5 -1 -0.9952964 0.09687691 0 -1.46177e-6 4.26542e-6 -1 -0.8821507 0.4709672 1.7682e-7 0 5.41551e-6 -1 -4.58458e-7 4.97622e-6 -1 -0.9568079 0.2907209 1.50104e-7 -5.06472e-7 4.31031e-6 -1 -0.7739988 0.6331869 3.10165e-7 -4.20194e-6 1.51418e-6 -1 -0.8821526 0.4709637 3.06809e-7 -3.16058e-6 3.86343e-6 -1 -0.633189 0.7739972 2.11875e-7 -1.0913e-6 3.72548e-6 -1 -0.7739967 0.6331896 1.98762e-7 -2.06601e-6 3.86978e-6 -1 -0.4709655 0.8821517 2.111e-7 -0.6331889 0.7739973 2.0707e-7 -1.201e-6 3.9527e-6 -1 -0.2907191 0.9568085 2.18981e-7 -0.4709658 0.8821514 2.22054e-7 -4.0039e-7 4.11347e-6 -1 -0.09687846 0.9952962 2.07372e-7 -0.2907191 0.9568085 2.18981e-7 -2.73171e-6 3.39229e-6 -1 0.0968768 0.9952964 1.75765e-7 -0.09687805 0.9952962 1.95012e-7 -2.04708e-6 3.67403e-6 -1 0.2907216 0.9568077 1.49339e-7 0.0968768 0.9952964 1.75765e-7 -1.29709e-6 4.04759e-6 -1 0.4718 0.8817057 0 0.2907216 0.9568077 1.49339e-7 0 4.7612e-6 -1 0.6334945 0.7737472 0 0.4718002 0.8817054 0 -1.40406e-5 -3.64772e-6 -1 0.7737471 0.6334946 0 0.6334943 0.7737473 0 -2.84131e-5 -1.1741e-5 -1 0.8817042 0.4718027 0 -6.47634e-5 -3.48228e-5 -1 0.7737471 0.6334947 0 -1.17397e-6 5.9701e-6 -1 0.9568079 0.2907209 0 7.26474e-5 5.31322e-5 -1 0.8817042 0.4718026 0 -6.45201e-6 2.43392e-6 -1 0.9952967 0.09687387 0 0.9568079 0.290721 0 6.15743e-6 1.16483e-5 -1 0.9952967 -0.09687387 0 0.9952967 0.09687387 0 -2.98344e-6 4.06991e-6 -1 0.9568077 -0.2907211 -1.49201e-7 0.9952967 -0.09687387 0 0 6.97948e-6 -1 0.8821532 -0.4709624 -1.78282e-7 1.89109e-7 7.16681e-6 -1 0.9568078 -0.2907212 -1.51006e-7 -1.07424e-5 -5.11793e-6 -1 0.8821533 -0.4709624 -1.75358e-7 0 4.65527e-6 -1 0.633192 -0.7739949 -1.54648e-7 -8.3764e-7 4.58124e-6 -1 0.7739951 -0.6331916 -1.90465e-7 -3.4367e-6 1.98219e-6 -1 0.7739961 -0.6331904 -1.42409e-7 -4.17575e-6 1.29383e-6 -1 0.4709633 -0.8821528 -2.80492e-7 1.18035e-6 5.74363e-6 -1 0.633189 -0.7739972 -2.74848e-7 0.2907207 -0.956808 -2.08828e-7 2.15395e-6 7.89957e-6 -1 0.4709653 -0.8821517 -2.05606e-7 0.09687858 -0.9952962 -1.54627e-7 0.290722 -0.9568075 -1.61528e-7 -0.0968784 -0.9952962 -2.4117e-7 0.0968756 -0.9952965 -2.53199e-7 -0.290721 -0.9568079 -1.24525e-7 -0.09687542 -0.9952966 -1.42296e-7 -0.4718 -0.8817056 0 -0.2907209 -0.9568079 -1.20915e-7 -0.6334958 -0.7737461 0 -0.4718 -0.8817057 0 -1.30709e-5 -6.77771e-6 -1 -0.7737465 -0.6334954 0 1.65459e-5 2.30344e-5 -1 -0.6334958 -0.7737461 0 2.75263e-5 2.85811e-5 -1 -0.8817055 -0.4718002 0 5.21191e-7 7.15751e-6 -1 -0.7737465 -0.6334954 0 6.92876e-6 1.15955e-5 -1 -0.9568083 -0.2907197 0 -0.8817058 -0.4717997 0 -2.80918e-6 2.78847e-6 -1 -0.9952962 -0.09687936 0 -0.9568084 -0.2907193 0 -2.37254e-6 3.29283e-6 -1 -0.9952964 0.09687614 0 -2.25435e-6 3.37443e-6 -1 -0.9952961 -0.09687918 0 -4.61798e-6 1.40314e-6 -1 -0.9568082 0.2907201 1.34167e-7 -0.9952964 0.09687602 0 1.21638e-6 6.32061e-6 -1 -0.8821521 0.4709644 0 -2.36987e-6 3.88265e-6 -1 -0.9568077 0.2907213 0 -7.66048e-7 4.52267e-6 -1 -0.773996 0.6331906 1.83471e-7 -0.8821529 0.4709632 1.59298e-7 -4.75365e-6 1.04839e-6 -1 -0.6331915 0.7739952 2.00955e-7 -1.09684e-6 4.10795e-6 -1 -0.7739959 0.6331905 1.83471e-7 3.65113e-7 5.84379e-6 -1 -0.4709651 0.8821519 1.22724e-7 -5.1685e-6 1.1459e-6 -1 -2.67319e-6 3.35805e-6 -1 -0.6331897 0.7739967 1.24066e-7 -6.76369e-6 1.18492e-5 -1 -0.2907182 0.9568087 0 -1.68265e-6 3.74601e-6 -1 1.84498e-5 -2.76165e-5 -1 -0.4709651 0.8821519 1.22724e-7 -1.99738e-7 2.05201e-6 -1 -0.09687989 0.9952961 0 -0.2907181 0.9568088 0 -2.54921e-6 5.26715e-6 -1 0.09687989 0.9952961 1.91732e-7 -0.09688293 0.9952958 2.03763e-7 4.87475e-7 1.60437e-6 -1 0.2907184 0.9568087 1.71148e-7 0.09687995 0.9952961 1.91432e-7 -3.74647e-6 5.94173e-6 -1 0.4718022 0.8817045 1.44787e-7 0.2907184 0.9568087 1.71374e-7 1.33648e-6 1.63238e-6 -1 0.6334933 0.7737482 0 0.4718022 0.8817045 1.44421e-7 -5.31348e-6 -4.26434e-7 -1 0.7737474 0.6334942 0 -2.93811e-6 5.25026e-6 -1 -2.34992e-6 4.51283e-6 -1 1.32828e-6 1.68068e-6 -1 1.15279e-5 -5.402e-6 -1 0.6334932 0.7737482 0 1.08219e-6 1.0968e-5 -1 0.8817055 0.4718003 0 0.773748 0.6334935 0 -2.93302e-5 -5.74841e-6 -1 0.956808 0.2907205 0 -2.22358e-6 4.33093e-6 -1 0.8817051 0.4718009 0 -8.15738e-6 2.26789e-6 -1 0.9952962 0.09687858 0 0.956808 0.2907206 0 1.30418e-5 1.09782e-5 -1 0.9952962 -0.09687846 0 0.9952962 0.09687829 0 2.00626e-6 5.71722e-6 -1 0.9568084 -0.2907193 0 0.9952962 -0.0968784 0 -4.04104e-6 2.15743e-6 -1 0.8821528 -0.4709632 -1.2495e-7 0.9568085 -0.2907189 0 0.882152 -0.4709647 -1.79722e-7 0.5555067 -0.8315121 -2.75402e-7 0.8315116 -0.5555073 0 0.8315106 -0.555509 -2.06856e-7 2.79258e-6 -4.26177e-6 -1 0.1950857 -0.9807862 -2.04555e-7 -1.69545e-6 4.03632e-6 -1 0.555508 -0.8315112 -1.92941e-7 -2.98399e-6 4.55387e-6 -1 -0.1950841 -0.9807865 -1.75485e-7 0.1950855 -0.9807862 -2.14245e-7 -2.10058e-6 3.7395e-6 -1 -0.555507 -0.8315119 -1.92625e-7 -0.195086 -0.9807862 -2.72917e-7 -6.34134e-6 3.62367e-7 -1 -0.8315114 -0.5555076 -1.38136e-7 -6.2785e-7 5.94395e-6 -1 -2.61594e-6 3.95586e-6 -1 -0.5555083 -0.831511 -2.75228e-7 -8.76579e-7 5.66032e-6 -1 -0.9807863 -0.1950854 0 -3.1911e-6 3.5126e-6 -1 -0.8315103 -0.5555093 0 -4.12494e-6 2.76536e-6 -1 -0.9807866 0.1950837 1.36192e-7 -1.08452e-6 5.45238e-6 -1 -0.9807863 -0.1950854 0 -2.75153e-6 4.13762e-6 -1 -0.831512 0.5555067 2.48157e-7 -2.75959e-6 4.13071e-6 -1 -0.9807866 0.1950833 1.55572e-7 -1.29748e-6 5.38402e-6 -1 -0.555507 0.8315119 2.20391e-7 -2.75153e-6 4.13762e-6 -1 -0.8315114 0.5555076 1.92973e-7 -2.73864e-6 3.99053e-6 -1 -0.195086 0.9807862 3.11677e-7 -2.32856e-6 4.35294e-6 -1 -0.5555083 0.831511 3.02994e-7 1.57912e-6 7.93904e-6 -1 0.1950837 0.9807866 1.75485e-7 -3.54439e-6 3.18478e-6 -1 -0.1950841 0.9807865 2.14245e-7 -7.86285e-6 -1.44388e-6 -1 0.555508 0.8315111 1.37614e-7 -5.30566e-6 1.05427e-6 -1 0.1950836 0.9807865 1.85175e-7 1.34185e-5 1.35633e-5 -1 0.8315114 0.5555076 0 7.76657e-6 1.41855e-5 -1 -1.19873e-7 5.9789e-6 -1 -2.87182e-6 4.04708e-6 -1 7.14661e-7 7.01014e-6 -1 -2.56284e-5 -1.61453e-5 -1 0.555508 0.8315111 1.37614e-7 0.9807865 0.1950845 0 0.8315114 0.5555076 0 0.9807867 -0.1950837 0 0.9807865 0.1950841 0 0.9807867 -0.1950837 0 -2.58126e-6 3.86374e-6 -1 0.5555096 -0.8315101 -1.37788e-7 -2.41102e-6 3.91014e-6 -1 0.8315114 -0.5555076 -1.37788e-7 -1.14656e-6 5.179e-6 -1 0.8315114 -0.5555076 -1.37788e-7 7.343e-7 6.08618e-6 -1 0.1950858 -0.9807862 -2.04555e-7 -1.18498e-5 -5.51444e-6 -1 -1.41619e-5 -7.78128e-6 -1 0.5555087 -0.8315108 -1.92941e-7 -4.45182e-6 2.65079e-5 -1 -0.1950858 -0.9807862 -1.85175e-7 -1.8874e-6 2.0852e-6 -1 0.1950858 -0.9807862 -2.04555e-7 -1.73581e-6 4.28549e-6 -1 -0.5555083 -0.831511 -1.37614e-7 -0.1950858 -0.9807863 -1.85175e-7 -0.8315112 -0.555508 0 -0.5555083 -0.831511 -1.37614e-7 -0.980786 -0.1950863 0 -0.8315112 -0.555508 0 -0.9807863 0.1950856 0 -0.980786 -0.1950863 0 -0.8315114 0.5555076 1.51671e-7 -0.9807863 0.1950856 0 -0.555507 0.8315119 1.92799e-7 -0.8315114 0.5555076 1.51671e-7 -0.195086 0.9807861 2.04555e-7 -0.555507 0.8315119 1.92799e-7 1.59316e-6 8.00954e-6 -1 0.1950856 0.9807863 1.85175e-7 -3.3381e-6 3.22581e-6 -1 -0.195086 0.9807861 2.04555e-7 -7.82042e-6 -1.38039e-6 -1 0.5555059 0.8315127 1.37614e-7 -5.47575e-6 9.40631e-7 -1 0.1950856 0.9807863 1.85175e-7 -6.36288e-6 3.47972e-7 -1 0.8315114 0.5555076 0 9.19966e-7 7.36024e-6 -1 -1.66914e-6 4.81427e-6 -1 -4.67627e-6 1.78421e-6 -1 0.5555076 0.8315115 0 -3.37624e-6 3.21822e-6 -1 0.9807865 0.1950846 0 0.8315114 0.5555076 0 2.7246e-6 9.18253e-6 -1 0.9807865 -0.1950845 0 4.23755e-7 6.9894e-6 -1 0.9807865 0.1950846 0 -7.77474e-6 -1.04493e-6 -1 3.44993e-6 9.88165e-6 -1 1.73792e-4 1.78404e-4 -1 -3.52545e-6 2.90683e-6 -1 0.9807865 -0.1950845 0 0.555507 -0.8315119 0 0.8315117 -0.5555073 0 0.8315117 -0.5555073 0 0.1950878 -0.9807858 0 0.555507 -0.8315119 0 -3.24453e-6 3.24395e-6 -1 -0.1950858 -0.9807863 -1.75485e-7 -3.24391e-6 3.24455e-6 -1 0.1950858 -0.9807862 -2.14245e-7 -8.93049e-7 5.54699e-6 -1 -0.555507 -0.8315119 0 -5.69291e-6 7.95569e-7 -1 -0.1950858 -0.9807862 -1.75485e-7 -6.36288e-6 3.47975e-7 -1 -0.8315114 -0.5555076 0 1.06085e-5 1.70488e-5 -1 -1.53578e-6 4.9487e-6 -1 -1.66915e-6 4.81425e-6 -1 -0.555507 -0.8315119 0 -8.24287e-7 5.67071e-6 -1 -0.9807862 -0.195086 0 -0.8315114 -0.5555076 0 1.17933e-6 7.54497e-6 -1 -0.9807865 0.1950847 1.36192e-7 -1.73079e-6 4.77108e-6 -1 -0.9807861 -0.195086 0 -2.34217e-6 3.86414e-6 -1 -0.831512 0.5555067 1.92973e-7 -9.98299e-6 -3.19453e-6 -1 3.45014e-6 9.88186e-6 -1 1.73708e-4 1.78321e-4 -1 2.45671e-6 8.82759e-6 -1 -0.9807865 0.1950846 1.36192e-7 -2.53064e-6 3.78799e-6 -1 -0.555507 0.8315119 2.20391e-7 -1.22815e-6 4.98204e-6 -1 -0.831512 0.5555067 1.92973e-7 -1.06076e-6 5.33295e-6 -1 -0.1950859 0.9807861 2.14245e-7 -1.39232e-7 6.19269e-6 -1 -3.14012e-7 6.02134e-6 -1 -0.555507 0.831512 2.20391e-7 -3.64337e-6 2.07947e-5 -1 0.1950839 0.9807866 1.75485e-7 -1.8874e-6 4.07142e-6 -1 -0.195086 0.9807862 2.14245e-7 -1.64267e-6 4.42492e-6 -1 0.5555068 0.8315121 0 0.1950856 0.9807862 0 0.831512 0.5555067 0 -1.73872e-6 5.01787e-6 -1 0.5555068 0.8315121 0 0.9807864 0.1950851 0 0.831512 0.5555067 0 0.9807863 -0.1950855 0 0.9807864 0.1950851 0 0.9807863 -0.1950855 0 -2.84322e-6 4.25588e-6 -1 0.555507 -0.8315119 -2.75576e-7 -2.8806e-6 4.22383e-6 -1 0.8315134 -0.5555047 -1.37788e-7 -2.88059e-6 4.22384e-6 -1 0.8315119 -0.555507 -2.75576e-7 5.05799e-7 7.23497e-6 -1 0.1950863 -0.9807861 -2.04555e-7 -2.67689e-6 4.42221e-6 -1 0.5555083 -0.831511 -1.92941e-7 -3.19108e-6 3.51262e-6 -1 -0.1950853 -0.9807863 -2.82607e-7 -3.54437e-6 3.1848e-6 -1 0.1950845 -0.9807865 -3.01987e-7 -3.20272e-7 6.40436e-6 -1 -0.555507 -0.8315119 -1.37614e-7 5.86049e-7 7.28975e-6 -1 -0.1950834 -0.9807867 -1.85175e-7 1.34186e-5 1.35634e-5 -1 -0.8315112 -0.555508 -1.24253e-7 7.21111e-6 1.39357e-5 -1 -3.43365e-5 -2.37998e-5 -1 -1.19867e-7 5.97891e-6 -1 -2.87182e-6 4.04709e-6 -1 7.14645e-7 7.01013e-6 -1 -0.5555083 -0.831511 -2.20217e-7 -0.9807866 -0.1950836 0 -0.8315112 -0.555508 -1.24253e-7 -0.9807866 0.1950833 0 -0.9807865 -0.195084 0 -0.831512 0.5555067 2.6204e-7 -0.9807868 0.1950826 1.26235e-7 -0.5555072 0.8315118 1.92799e-7 -0.8315109 0.5555085 1.51671e-7 -5.67269e-7 2.85193e-6 -1 -0.1950856 0.9807863 2.04555e-7 -0.5555072 0.8315118 1.92799e-7 -1.18892e-6 3.80062e-6 -1 0.195086 0.9807861 1.85175e-7 -0.1950856 0.9807863 2.04555e-7 -1.72785e-6 4.29744e-6 -1 0.5555056 0.8315128 1.37614e-7 0.195086 0.9807861 1.85175e-7 -6.34133e-6 3.62372e-7 -1 0.831512 0.5555067 0 -6.2786e-7 5.94393e-6 -1 -2.11277e-6 4.45903e-6 -1 0.5555074 0.8315116 0 -3.7844e-6 3.13703e-6 -1 0.980786 0.1950868 0 -7.63316e-7 5.94039e-6 -1 0.8315109 0.5555085 0 -2.50271e-6 4.38759e-6 -1 0.9807862 -0.195086 -1.36192e-7 -2.77053e-6 4.1509e-6 -1 0.980786 0.1950865 0 -1.3811e-6 5.50919e-6 -1 0.9807863 -0.1950856 0 0.5555061 -0.8315125 -2.75576e-7 0.8315122 -0.5555065 -1.6538e-7 0.8315111 -0.5555084 -2.75576e-7 0.195086 -0.9807862 -2.14245e-7 0.555507 -0.8315119 -2.20949e-7 -0.1950841 -0.9807865 -2.24201e-7 0.1950851 -0.9807864 -2.62961e-7 -0.5555067 -0.831512 -1.51324e-7 -0.1950841 -0.9807865 -2.24201e-7 -1.95945e-7 2.16851e-6 -1 -0.831511 -0.5555083 0 -1.34602e-6 4.90803e-6 -1 -0.5555061 -0.8315125 0 -1.50647e-6 3.59013e-6 -1 -0.9807861 -0.1950859 0 -0.831511 -0.5555082 0 -3.32763e-6 4.55166e-6 -1 -0.9807866 0.1950839 1.36192e-7 -3.02272e-6 4.58367e-6 -1 -0.9807861 -0.195086 0 -4.54947e-7 4.90276e-6 -1 -0.8315112 0.5555081 1.92973e-7 -0.9807866 0.1950838 1.36192e-7 -2.99995e-6 4.49048e-6 -1 -0.5555067 0.831512 2.20391e-7 -0.8315111 0.555508 1.92973e-7 -9.81405e-7 4.93398e-6 -1 -0.1950855 0.9807862 2.14245e-7 -0.5555067 0.831512 2.20391e-7 -3.02408e-6 4.35227e-6 -1 0.1950851 0.9807864 1.75485e-7 -0.1950855 0.9807862 2.14245e-7 -1.29518e-6 4.94505e-6 -1 0.5555077 0.8315116 0 0.1950855 0.9807863 1.51127e-7 0.8315112 0.5555081 0 3.5391e-6 6.79014e-6 -1 0 5.61575e-6 -1 -3.60361e-6 1.25015e-6 -1 0.5555077 0.8315116 0 0.9807861 0.1950861 0 0.8315109 0.5555085 0 0.9807866 -0.1950839 -1.26502e-7 0.9807862 0.1950858 0 0.9807865 -0.1950839 -1.26502e-7 0.5555076 -0.8315114 -1.7909e-7 0.8315111 -0.555508 -1.79177e-7 0.8315113 -0.5555079 -1.6538e-7 0.1950845 -0.9807865 -1.65529e-7 0.5555076 -0.8315114 -1.78938e-7 -0.1950829 -0.9807868 -1.26769e-7 0.1950845 -0.9807865 -1.65529e-7 -0.5555085 -0.8315109 0 -0.1950834 -0.9807866 -1.51127e-7 -0.8315113 -0.5555081 0 -0.5555085 -0.8315109 0 -2.8842e-6 3.31609e-6 -1 -0.9807863 -0.1950858 0 -4.89185e-6 2.87181e-6 -1 8.03043e-7 6.19404e-6 -1 -0.831511 -0.5555083 0 -1.54094e-6 4.19628e-6 -1 -0.9807865 0.1950841 1.26502e-7 -0.9807863 -0.1950858 0 -1.02186e-6 5.28149e-6 -1 -0.831511 0.5555083 1.6538e-7 4.75986e-6 1.10313e-5 -1 -0.9807865 0.1950841 1.26502e-7 -2.53182e-6 3.78975e-6 -1 -0.5555085 0.8315109 1.7909e-7 2.00447e-5 2.50932e-5 -1 -4.51276e-6 1.6958e-6 -1 -2.15558e-6 4.0448e-6 -1 -0.831511 0.5555083 1.6538e-7 -2.66342e-6 3.6124e-6 -1 -0.195085 0.9807863 1.65528e-7 -4.51739e-6 1.83587e-6 -1 -9.47794e-7 5.39089e-6 -1 -0.5555085 0.8315109 1.7909e-7 -8.25599e-7 5.6272e-6 -1 0.1950846 0.9807865 1.75485e-7 2.01388e-6 8.32543e-6 -1 -0.195086 0.9807862 2.14245e-7 -8.65889e-7 5.58766e-6 -1 0.5555063 0.8315123 0 0.1950846 0.9807865 1.75485e-7 0.8315113 0.5555078 0 0.555507 0.8315119 0 0.9807862 0.195086 0 0.8315113 0.5555078 0 0.9807866 -0.1950839 -1.31347e-7 0.9807861 0.195086 0 0.9807865 -0.1950838 -1.31347e-7 -2.93019e-6 4.38605e-6 -1 0.5555085 -0.8315109 -2.20391e-7 -3.1552e-7 4.80961e-6 -1 0.8315119 -0.555507 -1.92973e-7 0.8315119 -0.555507 -1.92973e-7 -2.82203e-6 4.40981e-6 -1 0.1950851 -0.9807863 -1.89887e-7 0.5555089 -0.8315107 -1.99166e-7 -9.62409e-7 4.93939e-6 -1 -0.1950855 -0.9807862 -1.51127e-7 0.1950851 -0.9807863 -1.89887e-7 1.58363e-6 5.81234e-6 -1 -0.5555064 -0.8315123 0 -0.1950855 -0.9807862 -1.51127e-7 -0.831511 -0.5555082 0 2.08505e-6 6.00371e-6 -1 -8.33956e-7 5.03423e-6 -1 -4.28492e-6 8.57183e-7 -1 -0.5555067 -0.831512 0 -0.9807873 -0.1950805 0 -0.831511 -0.5555083 0 -0.9807876 0.1950784 2.28779e-7 -0.9807869 -0.1950823 1.6095e-7 -0.8315113 0.5555078 1.92973e-7 -0.9807873 0.1950802 1.36191e-7 -0.5555061 0.8315125 1.7909e-7 -0.831511 0.5555083 1.6538e-7 -0.1950841 0.9807865 2.14245e-7 -0.5555067 0.831512 2.20391e-7 0.1950828 0.9807868 2.72918e-7 -0.195086 0.9807862 3.11677e-7 0.5555085 0.8315109 0 0.1950847 0.9807865 1.75485e-7 -1.50776e-6 3.59154e-6 -1 0.8315119 0.555507 0 -1.92959e-6 4.59637e-6 -1 0.5555085 0.8315109 0 -1.50646e-6 3.59013e-6 -1 0.9807859 0.1950878 0 0.8315119 0.555507 0 -2.98449e-6 4.48341e-6 -1 0.9807862 -0.1950857 -1.36192e-7 -2.88555e-6 4.4938e-6 -1 0.9807859 0.1950878 0 0.9807863 -0.1950857 -1.36192e-7 -2.6074e-6 3.90288e-6 -1 0.5555085 -0.8315109 -1.7909e-7 -2.40493e-6 3.90607e-6 -1 0.8315119 -0.555507 -1.6538e-7 2.90955e-5 3.3818e-5 -1 -4.81132e-6 1.51296e-6 -1 -2.35253e-6 3.96322e-6 -1 0.8315119 -0.555507 -1.6538e-7 -1.04326e-6 5.24493e-6 -1 0.1950865 -0.980786 -1.65529e-7 -4.66456e-6 1.77491e-6 -1 -7.92893e-6 -1.47612e-6 -1 0.5555085 -0.8315109 -1.78938e-7 -3.20527e-6 3.44134e-6 -1 -0.195086 -0.9807862 -1.75485e-7 3.3284e-6 9.64999e-6 -1 0.1950856 -0.9807863 -2.14245e-7 6.10289e-6 1.2577e-5 -1 -0.555507 -0.8315119 0 -0.195085 -0.9807863 -1.26769e-7 -0.8315122 -0.5555065 0 -0.555507 -0.8315119 0 -0.9807865 -0.1950843 0 -0.8315122 -0.5555065 0 -0.9807869 0.1950819 1.26502e-7 -0.9807865 -0.1950843 0 -0.8315121 0.5555067 1.79176e-7 -0.9807869 0.1950818 1.31347e-7 -0.555508 0.8315112 1.9974e-7 -0.8315121 0.5555067 1.79176e-7 -0.1950841 0.9807865 1.65528e-7 -0.5555076 0.8315114 1.7909e-7 0.1950837 0.9807867 1.26769e-7 -0.1950841 0.9807865 1.65528e-7 0.5555085 0.8315109 0 0.1950837 0.9807866 1.26769e-7 0.831512 0.5555067 0 0.5555081 0.8315111 0 -2.88421e-6 3.31608e-6 -1 0.9807858 0.1950877 0 -4.69153e-6 2.87183e-6 -1 -1.96538e-6 4.46218e-6 -1 0.8315121 0.5555068 0 -1.54093e-6 4.19628e-6 -1 0.9807862 -0.195086 -1.26502e-7 0.9807859 0.1950876 0 4.75991e-6 1.10313e-5 -1 0.9807861 -0.195086 -1.26502e-7 4.30184e-4 4.35804e-4 -0.9999998 0.7071067 0.707107 0 9.69321e-7 7.45169e-6 -1 0.4996246 0.8662421 1.28778e-7 0.4996249 0.8662419 0 0.7071067 0.7071069 0 -8.04801e-6 -1.31327e-6 -1 0.8662417 0.4996252 0 -5.20485e-6 1.23389e-6 -1 -2.38711e-6 4.05733e-6 -1 -9.89857e-7 5.74364e-6 -1 1 0 0 -1.07239e-5 -3.86834e-6 -1 1.17529e-5 1.70212e-5 -1 0.8662417 0.4996252 0 -2.01272e-6 4.48949e-6 -1 0.866243 -0.499623 -1.52949e-7 -6.55566e-6 1.76107e-7 -1 1 0 0 -2.35722e-6 4.46457e-6 -1 0.7071068 -0.7071068 -1.68155e-7 -6.28285e-6 3.62378e-6 -1 -1.75612e-6 4.91713e-6 -1 -2.4951e-6 4.32595e-6 -1 0 6.8201e-6 -1 0.707107 -0.7071065 -2.32686e-7 0.8662419 -0.4996247 -2.1904e-7 -2.41878e-6 4.19364e-6 -1 0.4996247 -0.8662421 -1.82778e-7 -3.94937e-6 2.87182e-6 -1 0 6.73172e-6 -1 0 -1 -1.49012e-7 -1.76138e-7 6.55563e-6 -1 0.4996252 -0.8662417 -1.61652e-7 -6.87403e-6 -3.75889e-7 -1 -0.4996247 -0.8662421 0 -2.09877e-6 4.36029e-6 -1 0 -1 -1.49012e-7 7.79605e-4 7.84523e-4 -0.9999994 -0.7071067 -0.707107 0 -0.7071066 -0.707107 0 -0.4996252 -0.8662417 -1.19573e-7 -8.04801e-6 -1.31327e-6 -1 -0.8662417 -0.4996252 0 -4.14565e-5 -3.49946e-5 -1 -4.19319e-6 2.34388e-6 -1 -1.36384e-6 5.74364e-6 -1 -1 0 0 5.2379e-6 1.13729e-5 -1 1.00496e-5 1.58448e-5 -1 -0.8662417 -0.4996252 0 -2.53692e-6 4.79184e-6 -1 -0.866242 0.4996246 1.545e-7 1.82256e-6 8.93103e-6 -1 -1 0 0 -2.00607e-6 4.81586e-6 -1 -0.7071069 0.7071067 2.06961e-7 -6.63189e-6 3.8251e-6 -1 -1.99027e-6 5.15128e-6 -1 -4.93909e-6 2.79222e-6 -1 0 7.72945e-6 -1 -0.707107 0.7071065 1.63539e-7 -0.8662417 0.4996252 1.33763e-7 -4.79184e-6 2.53692e-6 -1 -0.499625 0.8662418 2.10983e-7 -1.07864e-6 5.74363e-6 -1 0 7.47968e-6 -1 -3.58978e-7 1 1.98682e-7 -1.94473e-6 5.53555e-6 -1 -0.4996253 0.8662416 2.18638e-7 -7.16417e-6 -6.15185e-7 -1 0 1 1.86265e-7 0.7071067 0.707107 0 -2.69628e-7 1 1.98682e-7 -1.79752e-7 1 0 6.98801e-6 1.17685e-5 -1 0.8528587 0.5221419 0 -9.12344e-7 5.96661e-6 -1 0.7071066 0.707107 0 -3.34454e-6 3.99752e-6 -1 0.9969042 0.07862615 0 0.8528597 0.52214 0 -1.80602e-6 5.3665e-6 -1 0.9238791 -0.3826847 0 0.9969042 0.07862615 0 -3.70953e-6 4.34469e-6 -1 0.6493274 -0.7605089 0 -1.86495e-6 5.29619e-6 -1 0.9238791 -0.3826847 0 -3.31726e-6 4.68637e-6 -1 0.2338514 -0.9722723 -2.16404e-7 0.649325 -0.760511 -2.15605e-7 -1.77562e-6 3.76732e-6 -1 1.22456e-7 -1 -1.98682e-7 -1.97219e-6 6.4114e-6 -1 0.2338513 -0.9722723 -2.16404e-7 -1.3999e-6 3.28546e-6 -1 -0.2338485 -0.972273 -1.69943e-7 1.22456e-7 -1 -1.98682e-7 -5.90063e-7 2.58008e-6 -1 -0.6493239 -0.7605119 0 -0.2338486 -0.972273 -1.69943e-7 -5.00183e-6 4.85581e-6 -1 -0.923879 -0.3826846 0 -0.6493239 -0.7605119 0 -2.11018e-6 4.42772e-6 -1 -0.9969045 0.07862192 0 -3.23507e-6 4.26926e-6 -1 -0.9238791 -0.3826847 0 -2.93719e-6 4.29496e-6 -1 -0.8528595 0.5221406 1.88464e-7 -0.9969046 0.07862192 0 -1.33583e-6 4.65434e-6 -1 -0.7071068 0.7071066 1.4049e-7 -0.8528588 0.5221416 1.36594e-7 -1.19529e-6 5.05876e-6 -1 -0.707107 0.7071065 2.10734e-7 -8.9472e-7 4.53089e-6 -1 -1 0 0 2.6209e-7 4.44323e-6 -1 -0.9722714 -0.2338554 0 0 4.60178e-6 -1 -0.9722715 -0.2338549 0 -8.31494e-7 4.58019e-6 -1 -0.9722731 0.2338483 0 -1 0 0 -3.99193e-6 3.40829e-6 -1 -0.7605131 0.6493226 0 5.16507e-7 6.1278e-6 -1 -0.972273 0.2338485 0 -3.62521e-7 6.45008e-6 -1 -0.3826864 0.9238783 0 -0.7605131 0.6493226 0 -1.76461e-6 4.64136e-6 -1 0.07862192 0.9969045 0 -2.44951e-6 4.10462e-6 -1 -0.3826864 0.9238783 0 -2.64508e-6 3.83587e-6 -1 0.5221441 0.8528574 1.69448e-7 0.07861983 0.9969046 1.98067e-7 1.37186e-6 7.70722e-6 -1 0.7071064 0.7071071 1.4049e-7 0.5221441 0.8528574 1.69448e-7 1 3.59504e-7 0 0.7071066 0.7071069 0 -1.4148e-6 4.73332e-6 -1 0.707107 -0.7071065 -2.45857e-7 -2.75789e-6 4.26659e-6 -1 1 3.59505e-7 0 -2.81333e-6 4.59527e-6 -1 0.5221394 -0.8528602 -1.69448e-7 -1.54592e-6 4.1491e-6 -1 0.7071072 -0.7071065 -1.40489e-7 -2.48489e-6 4.49123e-6 -1 0.07862824 -0.996904 -1.98067e-7 0.5221394 -0.8528602 -1.69448e-7 -6.89234e-6 5.66003e-6 -1 -0.3826849 -0.9238789 0 0.07863038 -0.9969038 0 -4.2048e-7 5.22687e-6 -1 -0.7605111 -0.649325 0 1.23639e-7 4.17203e-6 -1 -0.382685 -0.923879 0 -0.760511 -0.649325 0 0.07862448 0.9969044 0 -3.03414e-7 1 1.98682e-7 -2.02276e-7 1 0 0.2337464 0.9722976 0 0.07862448 0.9969044 0 0.3826837 0.9238794 1.45542e-7 0.2337449 0.9722979 1.69958e-7 0.5222328 0.8528029 0 0.3826837 0.9238794 1.45542e-7 0.6493213 0.7605142 0 0.5222329 0.8528029 0 0.7071084 0.7071052 0 0.7071084 0.7071051 0 0.6493214 0.7605142 0 0.6087623 0.7933527 0 0.382686 0.9238785 1.45542e-7 0.6087623 0.7933527 0 0.1305235 0.9914453 1.96982e-7 0.3826856 0.9238787 1.83558e-7 -1.76672e-6 4.67328e-6 -1 -0.1305243 0.9914451 1.96982e-7 -2.65635e-6 3.80414e-6 -1 0.1305235 0.9914453 1.96982e-7 -1.89269e-6 4.56932e-6 -1 -0.3826856 0.9238787 1.83558e-7 -1.05873e-6 5.38127e-6 -1 -0.1305243 0.9914451 1.96982e-7 -2.12873e-6 4.64955e-6 -1 -0.6087595 0.7933549 1.57625e-7 -1.03493e-6 5.41107e-6 -1 1.41499e-6 7.6467e-6 -1 6.68869e-7 6.93077e-6 -1 -3.40025e-5 -2.66268e-5 -1 -0.3826856 0.9238787 1.83558e-7 -2.01954e-6 4.54834e-6 -1 -0.707108 0.7071056 1.47459e-7 -2.32685e-6 4.4342e-6 -1 -0.707108 0.7071056 1.40489e-7 -0.6087595 0.7933549 1.57625e-7 -2.09109e-6 4.48253e-6 -1 -0.7933534 0.6087613 1.2095e-7 -1.91587e-6 4.50063e-6 -1 -0.923879 0.3826848 0 -2.75963e-6 3.67913e-6 -1 -0.7933534 0.6087614 1.2095e-7 -3.69501e-6 2.78941e-6 -1 -0.9914445 0.1305286 0 -7.46463e-7 5.67003e-6 -1 -0.923879 0.3826848 0 -0.9914445 -0.1305286 0 -0.9914445 0.1305286 0 -0.923879 -0.3826848 0 -0.9914446 -0.1305286 0 -1.11839e-5 -4.26473e-6 -1 -0.7933547 -0.6087597 -1.2095e-7 -0.923879 -0.3826848 0 -0.7071052 -0.7071085 0 -0.7071052 -0.7071084 0 -0.7933543 -0.6087603 0 -0.7605142 -0.6493213 0 -0.8528016 -0.5222349 0 -0.7605146 -0.649321 -1.29008e-7 -0.9238792 -0.3826842 0 -0.8528016 -0.5222349 0 -2.4495e-6 4.10463e-6 -1 -0.972298 -0.2337446 0 -1.7646e-6 4.64137e-6 -1 -2.64509e-6 3.83586e-6 -1 1.37193e-6 7.70727e-6 -1 -0.9238792 -0.3826842 0 5.16512e-7 6.12781e-6 -1 -0.9969042 -0.07862597 0 -3.99192e-6 3.4083e-6 -1 -3.62521e-7 6.45008e-6 -1 -0.9722981 -0.2337446 0 8.03807e-7 4.60178e-6 -1 -1 -3.03414e-7 0 -9.73246e-7 4.46967e-6 -1 -8.31494e-7 4.58019e-6 -1 -0.9969041 -0.07862597 0 -6.27445e-6 4.29928e-6 -1 -0.9969043 0.07862448 0 8.31502e-7 4.58019e-6 -1 0 5.5641e-6 -1 6.98462e-7 4.1606e-6 -1 -1 -3.03414e-7 0 -4.81611e-6 4.28682e-6 -1 -0.9722977 0.2337461 0 -0.9969043 0.07862448 0 -2.63808e-6 4.3845e-6 -1 -0.9238794 0.3826836 0 -0.9722977 0.2337461 0 6.47753e-7 4.95449e-6 -1 -0.8528028 0.5222331 0 -0.9238794 0.3826836 0 -1.28526e-6 4.08951e-6 -1 -0.7605137 0.6493219 1.93513e-7 -0.8528029 0.5222327 1.55637e-7 -2.13425e-6 4.44066e-6 -1 -0.7071068 0.7071068 0 2.81573e-6 8.71629e-6 -1 1.29195e-5 1.882e-5 -1 -0.7071068 0.7071068 0 -0.760513 0.6493226 0 -1.99995e-6 4.41259e-6 -1 -0.7933531 0.6087617 0 -2.85465e-6 3.72026e-6 -1 -1.91839e-6 4.50168e-6 -1 -0.9238787 0.3826856 0 -1.87819e-6 4.53434e-6 -1 -0.7933531 0.6087617 0 -3.60733e-6 2.77785e-6 -1 -0.9914452 0.1305238 0 -3.79943e-6 2.62064e-6 -1 -0.9238788 0.3826852 0 -2.78525e-6 4.23923e-6 -1 -0.991445 -0.1305243 0 9.68072e-7 7.35325e-6 -1 -0.9914453 0.1305238 0 5.57483e-6 1.0959e-5 -1 -0.923879 -0.3826848 -1.52065e-7 -5.58017e-6 1.4443e-6 -1 -0.9914451 -0.130524 0 -6.80616e-6 -9.056e-7 -1 -0.7933531 -0.6087617 -1.2095e-7 -7.97614e-7 4.58651e-6 -1 -0.9238787 -0.3826856 0 -0.707108 -0.7071056 0 -0.7071068 -0.7071068 -2.80979e-7 -0.793354 -0.6087607 -2.419e-7 -0.6087603 -0.7933543 0 -0.3826836 -0.9238794 -1.83558e-7 -0.6087614 -0.7933534 -1.57625e-7 -0.130526 -0.9914449 -3.68032e-7 -0.3826848 -0.923879 -2.91084e-7 0.130524 -0.9914451 -3.93965e-7 -0.1305263 -0.9914449 -3.93965e-7 0.3826848 -0.923879 -1.83558e-7 0.1305263 -0.9914448 -1.96982e-7 0.6087611 -0.7933535 -2.181e-7 0.3826844 -0.9238791 -2.21575e-7 0.7071084 -0.7071052 -2.12354e-7 0.70711 -0.7071035 -3.51223e-7 0.6087597 -0.7933546 -3.75726e-7 -1.90144e-6 3.39523e-6 -1 0.6493226 -0.7605131 -2.15605e-7 -6.99934e-5 -6.22663e-5 -1 -1.70126e-6 4.23453e-6 -1 0.5222342 -0.8528021 -2.21316e-7 -1.55848e-6 4.16166e-6 -1 0.6493225 -0.7605131 -2.15605e-7 -1.7652e-6 4.26158e-6 -1 0.3826836 -0.9238794 -2.21575e-7 0.5222342 -0.8528022 -2.21316e-7 -1.81003e-6 4.27513e-6 -1 0.2337477 -0.9722973 -2.16399e-7 0.3826836 -0.9238794 -2.21575e-7 -1.85954e-6 4.28278e-6 -1 0.07862442 -0.9969044 -2.05878e-7 0.2337477 -0.9722973 -2.16399e-7 -1.92162e-6 6.47624e-6 -1 2.02276e-7 -1 -1.98682e-7 -1.77562e-6 4.51237e-6 -1 -1.26294e-6 3.85487e-6 -1 -1.8546e-6 4.37022e-6 -1 -1.29549e-6 4.08181e-6 -1 -1.89965e-6 4.28238e-6 -1 0.07862442 -0.9969044 -2.05878e-7 -1.02502e-6 6.29837e-6 -1 -0.07862454 -0.9969043 -1.90256e-7 -2.10776e-6 5.73986e-6 -1 -3.31725e-6 4.68637e-6 -1 2.02276e-7 -1 -1.98682e-7 -1.09687e-6 5.19904e-6 -1 -0.2337459 -0.9722978 -1.69958e-7 -8.27628e-6 0 -1 -2.80709e-6 4.03991e-6 -1 -3.24263e-6 3.65236e-6 -1 -0.07862454 -0.9969043 -1.90256e-7 -0.3826824 -0.92388 -1.45542e-7 -0.2337459 -0.9722977 -1.69958e-7 -0.5222342 -0.8528022 0 -0.3826823 -0.92388 -1.45542e-7 -0.6493226 -0.760513 0 -0.5222342 -0.8528022 0 -0.7071068 -0.7071068 -1.40685e-7 -0.7071076 -0.7071059 0 -0.6493226 -0.760513 0 -0.608762 -0.7933529 -1.57625e-7 -0.3826848 -0.923879 -1.83558e-7 -0.608762 -0.7933529 -1.57625e-7 -0.130524 -0.9914452 -1.96982e-7 -0.3826848 -0.923879 -1.83558e-7 0.1305243 -0.991445 -1.96982e-7 -0.130524 -0.9914452 -1.96982e-7 0.3826848 -0.923879 -1.83558e-7 0.1305243 -0.9914451 -1.96982e-7 -2.28208e-6 4.84937e-6 -1 0.608762 -0.7933529 -1.57625e-7 7.90319e-7 6.98839e-6 -1 -4.63215e-7 5.8445e-6 -1 6.68872e-7 6.93077e-6 -1 -1.76024e-5 -1.07536e-5 -1 0.3826848 -0.923879 -1.83558e-7 -2.19515e-6 4.72396e-6 -1 0.7071068 -0.7071068 0 -2.50247e-6 4.60981e-6 -1 0.7071073 -0.7071061 -1.40489e-7 0.6087621 -0.7933529 -1.57625e-7 -3.14373e-6 3.85126e-6 -1 0.7933534 -0.6087613 0 0.923879 -0.3826848 0 0.7933533 -0.6087613 0 0.9914448 -0.1305263 0 0.923879 -0.3826848 0 0.991445 0.130526 0 0.9914448 -0.1305263 0 0.923879 0.3826848 0 0.991445 0.130526 0 -4.99944e-6 1.91975e-6 -1 0.7933543 0.6087603 1.2095e-7 0.9238786 0.3826856 0 0.7071036 0.7071101 1.40684e-7 0.7071036 0.7071101 1.4049e-7 0.7933542 0.6087602 1.2095e-7 0.7605135 0.6493222 1.29009e-7 0.8528023 0.5222338 0 0.7605134 0.6493222 1.29009e-7 0.9238797 0.3826829 0 0.8528025 0.5222336 0 0.9722973 0.2337475 0 0.9238797 0.3826829 0 0.9969042 0.07862591 0 0.9722973 0.2337475 0 1 2.02276e-7 0 0.9969042 0.07862591 0 -6.27462e-6 4.29928e-6 -1 0.9969044 -0.07862299 0 1 2.02276e-7 0 -4.81607e-6 4.28682e-6 -1 0.9722973 -0.2337477 0 0.9969044 -0.07862305 0 -2.63808e-6 4.3845e-6 -1 0.9238798 -0.3826826 0 0.9722973 -0.2337475 0 6.4774e-7 4.95449e-6 -1 0.8528019 -0.5222346 0 0.9238799 -0.3826823 0 -1.28526e-6 4.08951e-6 -1 0.7605138 -0.6493218 -1.29009e-7 0.8528016 -0.5222349 0 -2.13425e-6 4.44066e-6 -1 0.7071068 -0.7071068 -1.40685e-7 2.81574e-6 8.7163e-6 -1 1.29197e-5 1.88202e-5 -1 0.7071068 -0.7071068 -1.4049e-7 0.7605138 -0.6493218 -1.29009e-7 -3.01028e-6 3.74887e-6 -1 0.7933516 -0.6087637 -1.2095e-7 -2.04044e-6 4.53448e-6 -1 -2.05192e-6 4.55698e-6 -1 0.9238799 -0.3826829 0 -2.85348e-6 3.90568e-6 -1 0.7933525 -0.6087626 0 -1.37772e-6 4.78727e-6 -1 0.9914452 -0.130524 0 -3.8214e-6 2.78749e-6 -1 0.9238799 -0.3826829 0 -4.43488e-6 2.87057e-6 -1 0.9914452 0.130524 0 2.26074e-6 8.42574e-6 -1 0.9914452 -0.130524 0 2.75837e-6 8.55666e-6 -1 0.9238795 0.3826836 0 -7.49091e-6 -1.85457e-7 -1 0.9914452 0.130524 0 -6.21724e-7 5.27885e-6 -1 0.7933537 0.608761 0 5.68251e-7 6.36654e-6 -1 0.9238795 0.3826836 0 0.7071056 0.707108 1.39698e-7 0.7071049 0.7071086 0 0.7933537 0.608761 0 0.6087613 0.7933534 1.57625e-7 0.3826848 0.923879 1.83558e-7 0.6087614 0.7933534 1.57625e-7 0.130526 0.9914449 1.96982e-7 0.3826848 0.923879 1.83558e-7 -0.1305263 0.9914448 2.22916e-7 0.1305263 0.9914448 1.71049e-7 -0.3826848 0.923879 1.83558e-7 -0.130526 0.9914449 1.96982e-7 -0.6087614 0.7933534 1.57625e-7 -0.3826848 0.923879 1.83558e-7 -0.7071052 0.7071084 3.50383e-7 -0.7071076 0.7071059 1.40489e-7 -0.6087614 0.7933534 1.57625e-7 -1.90144e-6 3.39523e-6 -1 -0.6493218 0.7605139 3.66705e-7 -6.99941e-5 -6.22671e-5 -1 -1.79496e-6 4.38755e-6 -1 -0.5222339 0.8528023 2.21316e-7 -1.52015e-6 4.2473e-6 -1 -0.649321 0.7605146 2.15605e-7 -1.82215e-6 4.39905e-6 -1 -0.3826842 0.9238792 2.21575e-7 -0.5222339 0.8528024 2.21316e-7 -1.8412e-6 4.40481e-6 -1 -0.2337473 0.9722974 2.16399e-7 -0.3826842 0.9238792 2.21575e-7 -1.09925e-6 4.29025e-6 -1 -0.07862454 0.9969043 2.05878e-7 -0.2337474 0.9722974 2.16399e-7 -0.07862454 0.9969043 2.05878e-7 1 2.44913e-7 0 0.9722723 0.2338516 0 0.9722723 0.2338513 0 0.9722731 -0.2338483 0 1 2.44913e-7 0 0.760511 -0.649325 -1.29009e-7 0.972273 -0.2338485 0 0.3826857 -0.9238786 -1.83558e-7 0.760511 -0.649325 -1.29009e-7 -0.07862174 -0.9969046 -1.90257e-7 0.3826849 -0.9238789 -2.21575e-7 -0.522145 -0.8528567 0 -0.07862174 -0.9969046 -1.90257e-7 -0.7071067 -0.7071068 0 -0.5221434 -0.8528577 0 -1 -1.79752e-7 0 -0.7071068 -0.7071068 0 -1.19092e-6 4.81112e-6 -1 -0.707107 0.7071067 1.75612e-7 -1.05047e-6 5.47549e-6 -1 -4.91099e-6 3.51837e-6 -1 -1 -1.79753e-7 0 -2.81335e-6 4.59528e-6 -1 -0.5221419 0.8528586 2.21318e-7 -1.35461e-6 4.08176e-6 -1 -0.707107 0.7071065 2.10734e-7 -2.48487e-6 4.49123e-6 -1 -0.07862597 0.9969042 2.05878e-7 -0.5221419 0.8528586 2.21318e-7 -8.97309e-6 6.21181e-6 -1 0.3826887 0.9238773 1.45541e-7 -0.07862597 0.9969042 2.05878e-7 0.7605111 0.649325 1.29009e-7 0.3826879 0.9238776 1.83558e-7 0.7605111 0.649325 1.29009e-7 -0.7071067 -0.707107 0 3.59504e-7 -1 0 2.69628e-7 -1 -1.98682e-7 -0.8528602 -0.5221394 0 -0.7071065 -0.7071071 0 -0.9969042 -0.07862615 0 -0.8528602 -0.5221394 0 -0.9238783 0.3826864 1.67812e-7 -0.9969042 -0.07862597 0 -0.649325 0.760511 2.15605e-7 -0.9238783 0.3826864 1.67812e-7 -0.2338476 0.9722732 2.16404e-7 -0.649325 0.7605111 2.15605e-7 -1.22456e-7 1 1.98682e-7 -0.2338476 0.9722732 2.16404e-7 0.2338485 0.972273 3.63116e-7 -2.44912e-7 1 3.97364e-7 0.6493215 0.760514 0 0.2338526 0.9722721 1.69942e-7 0.9238775 0.3826882 0 0.6493214 0.760514 0 -1.31383e-6 4.36491e-6 -1 0.9969046 -0.07862174 0 0.9238781 0.3826867 0 -5.92136e-6 3.62525e-6 -1 0.8528562 -0.5221458 -1.88465e-7 0.9969045 -0.0786221 0 -1.33583e-6 4.65434e-6 -1 0.7071068 -0.7071068 -2.10734e-7 0.8528563 -0.5221458 -1.88465e-7 0.7071069 -0.7071067 -1.4049e-7 -0.707107 0.7071067 1.40489e-7 -0.7071073 -0.7071063 -1.42285e-7 0.7071065 0.707107 0 -0.707107 0.7071067 1.4609e-7 0.7071065 0.707107 0 0.7071068 -0.7071067 -1.4049e-7 -0.7071068 -0.7071068 -2.80979e-7 0.7071068 -0.7071068 -2.80979e-7 -0.7071063 0.7071073 1.42286e-7 -6.04719e-6 2.74808e-7 -1 -0.7071067 -0.707107 0 1.80446e-5 2.37221e-5 -1 -0.7071067 -0.7071068 -1.4049e-7 -0.7071063 0.7071073 1.4049e-7 0.7071065 0.707107 1.4049e-7 -1.6576e-6 4.46739e-6 -1 0.7071068 -0.7071068 -1.35818e-7 -1.2917e-7 5.99504e-6 -1 -2.10734e-6 4.21468e-6 -1 -2.87181e-6 3.25289e-6 -1 -1.82343e-6 4.3803e-6 -1 0.7071068 -0.7071068 -1.40489e-7 0.7071067 0.707107 0 -3.25288e-6 2.87183e-6 -1 0.7071063 -0.7071073 -1.4049e-7 -3.16856e-6 3.15346e-6 -1 0.7071065 0.707107 0 2.62462e-5 3.17814e-5 -1 0.7071066 0.707107 1.4049e-7 -0.7071065 -0.707107 -1.4049e-7 0.7071063 -0.7071073 -1.42286e-7 -2.46936e-6 3.87425e-6 -1 -0.7071068 0.7071068 2.13428e-7 -1.99643e-6 4.10377e-6 -1 -1.67206e-6 4.29299e-6 -1 0 5.85632e-6 -1 -2.87181e-6 3.03417e-6 -1 -0.7071068 0.7071068 2.10734e-7 -0.7071065 -0.7071071 0 -3.47161e-6 2.87182e-6 -1 -0.707107 0.7071067 2.10734e-7 -0.7071065 -0.707107 0 0.7071073 0.7071064 1.42286e-7 -0.7071068 0.7071067 1.4609e-7 0.7071073 0.7071063 1.40489e-7 0.7071071 -0.7071065 -1.40489e-7 -0.7071066 -0.707107 0 0.7071071 -0.7071065 -2.10734e-7 0.7071067 0.707107 0 0.4996258 0.8662413 1.22473e-7 0.4996259 0.8662414 1.22473e-7 0.7071065 0.7071071 0 0.8662412 0.4996259 0 1 0 0 0.8662417 0.4996253 0 0.8662417 -0.4996253 0 1 7.17954e-7 0 0.707107 -0.7071067 -1.75612e-7 0.8662413 -0.4996259 -1.42293e-7 0.499627 -0.8662406 -1.78713e-7 0.707107 -0.7071066 -1.75612e-7 0 -1 -1.49012e-7 0.4996271 -0.8662406 -1.78713e-7 -0.4996258 -0.8662413 -1.22473e-7 -1.43591e-6 -1 -1.98682e-7 -0.7071064 -0.7071071 0 -0.7071064 -0.7071071 0 -0.4996247 -0.866242 0 -0.8662423 -0.4996242 0 -1 -1.43591e-6 1.49011e-7 -0.8662416 -0.4996253 0 -0.866242 0.4996247 1.8532e-7 -1 0 0 -0.7071069 0.7071066 1.75612e-7 -0.8662416 0.4996253 1.60503e-7 -0.4996258 0.8662413 2.2174e-7 -0.707107 0.7071065 2.10734e-7 0 1 1.49012e-7 -0.4996247 0.866242 1.78713e-7 -1.43591e-6 1 1.98682e-7 0.8662417 0.4996253 0 0.7071066 0.707107 0 1 0 0 0.8662417 0.4996253 0 0.8662424 -0.4996241 -1.60503e-7 1 0 0 0.7071068 -0.7071066 -2.45857e-7 0.8662417 -0.4996253 -2.10137e-7 0.4996244 -0.8662422 -1.7541e-7 0.7071071 -0.7071065 -1.58051e-7 7.17955e-7 -1 -1.49012e-7 0.4996249 -0.8662419 -1.53897e-7 -0.4996265 -0.866241 -1.25777e-7 0 -1 -1.73847e-7 -0.7071065 -0.7071072 0 -0.7071066 -0.7071068 0 -0.4996255 -0.8662415 0 -0.8662415 -0.4996256 0 -1 0 0 -0.8662415 -0.4996256 0 -0.8662425 0.4996237 1.42293e-7 -1 0 0 -0.7071067 0.707107 1.4049e-7 -0.8662422 0.4996243 0 -0.499626 0.8662413 1.78713e-7 -0.7071068 0.7071068 1.75612e-7 0 1 1.98682e-7 -0.4996271 0.8662407 2.2174e-7 0.4996253 0.8662416 0 1.43591e-6 1 1.49011e-7 0.7071064 0.7071073 0 0.4996247 0.866242 0 0.7071073 -0.7071062 -1.79474e-7 0.8662412 -0.4996261 -1.60503e-7 0.8662409 -0.4996267 -1.8532e-7 0.7071076 -0.7071061 -2.10734e-7 0.4996259 -0.8662412 -1.78713e-7 0 -1 -1.49012e-7 0.4996259 -0.8662412 -1.78713e-7 -0.499624 -0.8662423 0 0 -1 -1.49012e-7 -0.7071068 -0.7071068 0 -0.4996247 -0.8662419 0 -0.866242 -0.4996247 0 -0.7071068 -0.7071068 0 -1 0 0 -0.8662424 -0.4996241 0 -0.8662418 0.4996251 1.42293e-7 -1 0 0 -0.707107 0.7071067 1.5522e-7 -0.7071069 0.7071067 1.75612e-7 -0.8662418 0.4996251 1.42293e-7 -0.4996259 0.8662412 1.7541e-7 -7.17953e-7 1 1.73847e-7 -0.4996259 0.8662413 1.7541e-7 0.499626 0.8662413 1.25777e-7 -7.17951e-7 1 1.73847e-7 0.7071067 0.7071068 0 0.4996259 0.8662413 1.25777e-7 0.866239 0.4996298 0 0.7071068 0.7071068 0 1 0 0 0.8662394 0.4996292 0 1 0 0 -0.499626 0.8662413 1.78713e-7 -0.7071071 0.7071064 1.74623e-7 0 1 1.49012e-7 -0.4996259 0.8662413 1.79508e-7 0.4996253 0.8662416 0 0 1 1.49012e-7 0.7071066 0.707107 0 0.4996253 0.8662416 0 0.8662413 0.4996259 0 0.7071064 0.7071072 0 1 0 0 0.8662417 0.4996252 0 0.8662413 -0.4996258 -1.54702e-7 1 0 0 0.7071067 -0.7071069 -1.94026e-7 0.7071066 -0.707107 -1.75612e-7 0.8662415 -0.4996256 -1.42293e-7 0.4996253 -0.8662416 -2.00227e-7 7.17954e-7 -1 -1.73847e-7 0.4996253 -0.8662416 -2.00227e-7 -0.4996248 -0.8662419 0 7.17954e-7 -1 -1.73847e-7 -0.7071068 -0.7071067 0 -0.4996253 -0.8662416 -1.22473e-7 -0.8662406 -0.499627 0 -0.7071068 -0.7071068 0 -1 1.43591e-6 0 -0.8662406 -0.499627 0 -0.8662424 0.4996241 1.60503e-7 -1 1.43591e-6 0 -0.7071071 0.7071064 1.75612e-7 -0.8662424 0.499624 1.60503e-7 -4.00644e-6 -1.13323e-5 1 1.97033e-6 -3.59907e-6 1 1.50949e-6 -4.05991e-6 1 2.8676e-6 -4.14471e-6 1 1.43592e-6 -5.86799e-6 1 2.65699e-6 -3.97071e-6 1 -1.42799e-6 -8.37312e-6 1 4.14371e-7 -6.49542e-6 1 1.82294e-6 -4.77029e-6 1 1.28546e-6 -5.34224e-6 1 3.00001e-6 -3.53538e-6 1 1.8331e-6 -4.76013e-6 1 2.53007e-6 -3.97634e-6 1 1.69167e-6 -4.84371e-6 1 4.49291e-6 -1.92454e-6 1 0 -6.54648e-6 1 7.99966e-6 1.6447e-6 1 -1.92718e-6 -8.34463e-6 1 -3.06593e-6 -9.73551e-6 1 4.40139e-5 3.7659e-5 1 -3.07168e-5 -3.72053e-5 1 8.76247e-7 -6.45197e-6 1 2.84559e-6 -3.96956e-6 1 1.41426e-7 -7.34304e-6 1 1.75538e-6 -5.55849e-6 1 1.40203e-6 -6.53981e-6 1 2.69133e-6 -4.67226e-6 1 2.41295e-6 -5.33857e-6 1 2.17024e-6 -5.69697e-6 1 2.41537e-6 -5.33638e-6 1 2.45539e-6 -5.38256e-6 1 3.09333e-6 -4.47859e-6 1 2.09953e-6 -5.6664e-6 1 2.75695e-6 -4.08564e-6 1 -1.40863e-6 -8.99226e-6 1 6.08953e-7 -6.71642e-6 1 5.7009e-7 -4.12747e-6 1 3.04428e-5 -2.32122e-5 1 1.91995e-6 -4.90268e-6 1 -1.1938e-6 -2.9457e-6 1 1.86002e-6 -5.17728e-6 1 2.81615e-7 -3.86868e-6 1 4.86292e-7 -4.06848e-6 1 1.19653e-6 -4.90622e-6 1 -1.44382e-6 -6.55612e-6 1 9.27802e-7 -5.11337e-6 1 9.41947e-7 -5.12466e-6 1 2.32067e-6 -6.77814e-6 1 3.02092e-5 -4.69397e-5 1 1.79258e-6 -4.73953e-6 1 4.7266e-5 1.16518e-4 1 2.26512e-6 -4.50416e-6 1 2.00077e-6 -3.03753e-6 1 1.2411e-6 -4.88642e-6 1 1.87289e-6 -3.56116e-6 1 1.43087e-6 -4.31205e-6 1 1.4252e-6 -4.08791e-6 1 1.99813e-6 -3.63306e-6 1 1.36645e-6 -4.16157e-6 1 1.39883e-6 -4.23181e-6 1 1.59124e-6 -3.93732e-6 1 -4.88993e-6 -1.11679e-5 1 2.62941e-6 -4.84879e-6 1 2.64802e-6 -4.82417e-6 1 3.96169e-6 -3.44176e-6 1 3.04825e-6 -3.81891e-6 1 1.59633e-6 -5.581e-6 1 5.07862e-6 -1.61113e-6 1 9.2639e-6 2.67982e-6 1 2.224e-6 -4.7167e-6 1 1.0416e-5 4.88423e-6 1 2.01848e-6 -5.41269e-6 1 3.45272e-6 -3.58976e-6 1 4.71286e-6 -2.27466e-6 1 2.31511e-6 -5.21112e-6 1 2.60335e-6 -4.83016e-6 1 1.549e-6 -3.2152e-6 1 1.72163e-6 -5.8046e-6 1 1.54769e-6 -3.44003e-6 1 1.45599e-6 -4.39664e-6 1 1.69097e-6 -3.2265e-6 1 1.06352e-6 -5.25481e-6 1 2.19921e-6 -2.49518e-6 1 1.16534e-6 -4.57087e-6 1 7.90531e-7 -5.23862e-6 1 3.96056e-6 0 1 7.315e-5 1.07581e-4 1 -2.33813e-5 -4.44413e-5 1 8.06562e-7 -5.15397e-6 1 5.74645e-6 2.5783e-6 1 1.96273e-6 -3.42828e-6 1 1.20068e-6 -4.47112e-6 1 2.47368e-6 -2.93566e-6 1 7.63184e-7 -4.69334e-6 1 8.30873e-7 -4.61859e-6 1 2.15255e-6 -3.46163e-6 1 3.09332e-6 -4.4786e-6 1 -5.28422e-6 -1.13995e-5 1 2.49236e-6 -5.19688e-6 1 2.75696e-6 -4.08563e-6 1 -1.40862e-6 -8.99224e-6 1 6.08954e-7 -6.71642e-6 1 2.97713e-6 -4.85884e-6 1 2.82814e-6 -4.76365e-6 1 2.36617e-6 -4.4671e-6 1 3.01866e-6 -4.88666e-6 1 1.38465e-6 -3.69261e-6 1 1.24424e-6 -3.5762e-6 1 1.30161e-6 -3.6322e-6 1 1.89613e-6 -4.33344e-6 1 -1.55686e-6 -6.69419e-6 1 -2.80114e-6 2.47194e-6 1 1.6424e-6 -3.96524e-6 1 2.22153e-6 -4.42715e-6 1 1.79819e-6 -4.15145e-6 1 1.7355e-6 -4.84618e-6 1 -4.63149e-6 -2.30514e-5 1 2.22942e-6 -4.60017e-6 1 1.67367e-6 -6.39807e-6 1 2.06177e-6 -5.4535e-6 1 2.29757e-6 -4.95888e-6 1 1.56728e-6 -6.19947e-6 1 2.7831e-6 -4.5926e-6 1 2.86391e-6 -4.29089e-6 1 2.17023e-6 -5.20548e-6 1 2.78511e-6 -4.10067e-6 1 1.43591e-6 -5.72466e-6 1 2.08455e-6 -4.58763e-6 1 5.09594e-7 -6.28496e-6 1 5.73069e-7 -6.22028e-6 1 2.52052e-6 -4.07271e-6 1 1.2894e-6 -5.38278e-6 1 2.19613e-6 -4.3791e-6 1 1.83311e-6 -4.76012e-6 1 3.61239e-6 -2.85664e-6 1 5.38243e-7 -6.03699e-6 1 4.49289e-6 -1.92456e-6 1 1.86518e-6 -4.60384e-6 1 2.58784e-6 -3.76712e-6 1 -7.33914e-6 -1.37566e-5 1 -8.32233e-6 -1.49575e-5 1 -1.17236e-4 -1.23591e-4 1 -6.52804e-5 -7.15425e-5 1 6.82151e-7 -6.8147e-6 1 2.9265e-6 -3.98564e-6 1 0 -7.54472e-6 1 1.37499e-5 7.56999e-6 1 1.20402e-6 -4.50542e-6 1 1.59464e-6 -3.93959e-6 1 1.90626e-6 -3.67097e-6 1 1.32444e-6 -4.1127e-6 1 1.17241e-6 -4.33633e-6 1 2.58354e-6 -5.03553e-6 1 2.85084e-6 -4.67539e-6 1 2.57773e-6 -4.94849e-6 1 2.58956e-6 -3.99627e-6 1 2.59385e-6 -3.95153e-6 1 2.56857e-6 -4.07739e-6 1 2.48391e-6 -4.35107e-6 1 2.65356e-6 -3.93883e-6 1 3.35303e-6 -2.53449e-6 1 3.74237e-6 -1.84086e-6 1 4.68777e-6 -2.65202e-7 1 -3.90459e-6 -1.37685e-5 1 5.23128e-6 6.19134e-7 1 1.46141e-6 -5.60158e-6 1 2.72717e-5 3.47985e-5 1 1.80044e-6 -5.09556e-6 1 1.32483e-6 -5.74639e-6 1 2.21179e-6 -4.67657e-6 1 1.9167e-6 -5.22203e-6 1 4.96333e-6 -1.85782e-6 1 2.30129e-6 -5.19423e-6 1 3.70152e-6 -3.63974e-6 1 3.21856e-6 -4.58103e-6 1 3.58842e-6 -4.11732e-6 1 1.82087e-6 -3.58588e-6 1 -1.8078e-6 -9.13961e-6 1 1.16572e-6 -4.30846e-6 1 1.54669e-6 -3.97792e-6 1 1.52605e-6 -4.00522e-6 1 1.06233e-6 -4.48945e-6 1 2.23672e-6 -3.27465e-6 1 1.74298e-6 -3.87386e-6 1 2.49532e-6 -2.99344e-6 1 -1.61789e-6 -7.2105e-6 1 2.83322e-6 -4.11894e-6 1 1.10918e-5 5.56003e-6 1 1.49944e-6 -6.07239e-6 1 3.45272e-6 -3.58976e-6 1 4.71286e-6 -2.27467e-6 1 2.69412e-6 -4.88251e-6 1 1.95563e-6 -4.18078e-6 1 1.89468e-6 -4.55699e-6 1 2.03736e-6 -3.80879e-6 1 1.98846e-6 -3.98048e-6 1 -1.27493e-6 -1.34985e-5 1 -1.8905e-6 -7.99259e-6 1 3.12634e-7 -9.33895e-6 1 2.29762e-6 -3.36236e-6 1 2.48546e-6 -3.51321e-6 1 5.85423e-6 -1.44443e-7 1 5.62464e-7 -4.7959e-6 1 2.12602e-6 -3.97829e-6 1 2.15467e-6 -3.94742e-6 1 1.43612e-6 -4.77559e-6 1 2.25269e-6 -3.85163e-6 1 2.15585e-6 -4.08744e-6 1 2.3454e-6 -3.86631e-6 1 2.00078e-6 -4.21093e-6 1 1.81122e-6 -4.43207e-6 1 -2.86378e-6 -9.64101e-6 1 1.43612e-6 -4.77559e-6 1 3.40531e-6 -3.21245e-6 1 1.352e-6 -5.42523e-6 1 4.09695e-6 -2.43664e-6 1 5.35363e-7 -6.0824e-6 1 1.46526e-6 -3.82999e-6 1 1.80606e-6 -4.72753e-6 1 2.23632e-6 -4.15369e-6 1 1.63768e-6 -3.98893e-6 1 1.88866e-6 -4.60626e-6 1 1.90987e-6 -4.40431e-6 1 1.79354e-6 -4.64733e-6 1 2.35128e-6 -4.37998e-6 1 -6.34273e-6 -1.32698e-5 1 0 -6.71844e-6 1 9.4262e-7 -5.67136e-6 1 2.64015e-6 -3.9287e-6 1 1.10887e-6 -5.52674e-6 1 1.4774e-5 8.19444e-6 1 2.6391e-6 -3.85106e-6 1 1.32619e-6 -5.2327e-6 1 5.53334e-6 -9.02164e-7 1 -9.00006e-7 -7.37046e-6 1 5.44383e-6 -9.61958e-7 1 9.43373e-6 3.02773e-6 1 2.03063e-6 -4.45782e-6 1 2.61449e-6 -3.85596e-6 1 7.25281e-7 -8.57599e-6 1 2.15386e-6 -3.61882e-6 1 2.12036e-6 -3.67623e-6 1 2.22349e-6 -6.28957e-6 1 -1.90534e-5 -2.59036e-5 1 1.6471e-6 -3.94159e-6 1 2.83426e-6 -1.7466e-6 1 1.76707e-6 -4.9598e-6 1 1.4359e-6 -5.55057e-6 1 2.32369e-6 -4.02875e-6 1 1.73099e-6 -3.81356e-6 1 1.84293e-6 -4.47953e-6 1 1.10315e-5 4.76007e-6 1 2.12625e-6 -4.29474e-6 1 -8.96289e-6 -1.60466e-5 1 7.96668e-6 1.72241e-6 1 1.18736e-6 -5.08051e-6 1 2.03029e-6 -4.29361e-6 1 1.85111e-6 -4.4806e-6 1 -3.98769e-6 -1.03434e-5 1 2.90652e-6 -3.31165e-6 1 1.03146e-6 -5.28487e-6 1 3.1338e-6 -3.08008e-6 1 -9.00001e-7 -7.37046e-6 1 5.44379e-6 -9.61996e-7 1 -2.20535e-5 -2.84591e-5 1 9.37022e-6 3.10811e-6 1 2.61448e-6 -3.85597e-6 1 1.65616e-6 -4.55555e-6 1 2.15585e-6 -4.08744e-6 1 1.4666e-6 -4.77669e-6 1 2.29278e-6 -3.8596e-6 1 1.84168e-6 -4.37003e-6 1 2.15468e-6 -3.94741e-6 1 1.50714e-6 -4.64524e-6 1 4.3324e-6 -1.70448e-6 1 1.57324e-6 -4.52885e-6 1 6.09627e-7 -5.97124e-6 1 1.65919e-6 -4.37769e-6 1 4.99141e-7 -5.92485e-6 1 1.14519e-6 -6.46494e-6 1 1.88866e-6 -4.60626e-6 1 1.61777e-6 -7.18615e-6 1 1.89468e-6 -4.557e-6 1 1.95563e-6 -4.18077e-6 1 1.93501e-6 -4.27464e-6 1 2.16737e-6 -3.45868e-6 1 2.04861e-6 -3.80506e-6 1 -1.19653e-6 -7.81429e-6 1 3.98189e-6 -2.51349e-6 1 9.374e-7 -5.55798e-6 1 -7.14638e-7 -7.01012e-6 1 1.36393e-6 -5.36523e-6 1 2.79836e-6 -3.8194e-6 1 1.84167e-6 -4.37003e-6 1 -2.09279e-6 -8.82195e-6 1 2.3454e-6 -3.86631e-6 1 -4.80628e-7 -7.60318e-6 1 1.44662e-6 -4.16298e-6 1 1.849e-6 -3.58977e-6 1 1.31764e-6 -4.23294e-6 1 -2.34223e-5 -3.23785e-5 1 1.04124e-6 -3.61066e-6 1 3.56414e-6 -4.97517e-6 1 1.69478e-6 -4.0389e-6 1 1.36828e-6 -3.68472e-6 1 5.67309e-7 -6.03458e-6 1 2.829e-6 -3.65771e-6 1 -2.21977e-6 -8.66821e-6 1 1.40395e-6 -5.164e-6 1 1.46464e-6 -4.91895e-6 1 -2.96952e-6 -9.57089e-6 1 1.82804e-6 -4.45722e-6 1 -3.38376e-6 -1.00988e-5 1 9.42908e-6 3.06354e-6 1 6.5e-5 5.92345e-5 1 4.29334e-6 -2.10181e-6 1 2.42386e-6 -3.91872e-6 1 3.0099e-6 -3.27946e-6 1 1.72925e-6 -3.74751e-6 1 -1.10669e-5 -1.76285e-5 1 4.40007e-7 -5.89162e-6 1 -1.83663e-7 -4.41253e-6 1 5.90337e-7 -4.4938e-6 1 9.34718e-7 -4.54922e-6 1 -1.81473e-6 -3.52881e-6 1 -2.96979e-7 -4.34969e-6 1 -9.69544e-7 -4.08263e-6 1 3.62991e-6 -9.07203e-6 1 9.26727e-6 7.84846e-6 1 1.0476e-5 4.94427e-6 1 2.04821e-6 -4.64372e-6 1 2.62402e-6 -4.00992e-6 1 2.91895e-6 -3.58978e-6 1 -1.82489e-6 -8.55335e-6 1 1.82804e-6 -4.45722e-6 1 3.00991e-6 -3.27945e-6 1 3.82648e-6 -4.65089e-6 1 1.15062e-5 4.70407e-6 1 2.73128e-5 2.08266e-5 1 -1.69777e-6 -4.22748e-6 1 3.62045e-6 -4.7859e-6 1 9.34717e-7 -4.54922e-6 1 -1.36231e-6 -8.06247e-6 1 -1.0873e-5 -1.72378e-5 1 3.14215e-6 -3.32861e-6 1 9.98265e-6 3.74258e-6 1 1.45753e-6 -4.88323e-6 1 2.31473e-6 -3.98393e-6 1 2.78204e-6 -3.42454e-6 1 7.46744e-6 1.38869e-6 1 -6.04551e-4 -6.17239e-4 0.9999997 5.67986e-6 -6.78153e-7 1 1.01878e-6 -5.44752e-6 1 -7.06013e-4 -7.1374e-4 0.9999995 2.66642e-5 2.03185e-5 1 4.08781e-6 -2.2126e-6 1 1.43591e-6 -5.29625e-6 1 -5.97744e-6 -1.27745e-5 1 1.06757e-5 5.14391e-6 1 1.48537e-6 -4.01808e-6 1 -2.1468e-5 -2.8193e-5 1 1.58687e-6 -3.86982e-6 1 1.53623e-6 -4.10625e-6 1 1.58051e-6 -3.95127e-6 1 1.42234e-6 -4.14898e-6 1 1.98133e-6 -3.58978e-6 1 -4.39899e-6 -1.07772e-5 1 1.43591e-6 -4.02071e-6 1 3.04956e-6 -3.58977e-6 1 7.82015e-7 -5.85802e-6 1 3.45302e-6 -3.0013e-6 1 1.57533e-6 -4.89451e-6 1 5.0514e-4 4.99697e-4 0.9999997 9.97824e-7 -5.48385e-6 1 -1.64965e-5 -2.29237e-5 1 1.34322e-6 -5.11979e-6 1 1.43591e-6 -5.38975e-6 1 -4.57352e-6 -1.13186e-5 1 1.13953e-5 5.86349e-6 1 2.01448e-6 -4.93544e-6 1 4.33251e-6 -2.49404e-6 1 1.67469e-6 -3.78203e-6 1 1.58656e-6 -4.19351e-6 1 8.78061e-7 -6.67325e-6 1 2.43173e-6 -4.73117e-6 1 3.57269e-6 -3.58977e-6 1 2.20929e-6 -4.60287e-6 1 1.07693e-5 5.30915e-6 1 3.14305e-6 -3.58977e-6 1 6.54506e-7 -6.07909e-6 1 3.08519e-6 -3.21346e-6 1 -3.84101e-7 -6.71137e-6 1 -4.05329e-6 -1.06149e-5 1 2.13659e-6 -4.47463e-6 1 1.78551e-6 -4.60449e-6 1 2.75825e-6 -2.68572e-6 1 1.43373e-6 -3.37451e-6 1 1.84411e-6 -4.54027e-6 1 3.83519e-6 -1.09557e-5 1 1.94138e-6 -3.81428e-6 1 2.0232e-6 -4.17272e-6 1 2.01669e-6 -4.16937e-6 1 1.33142e-6 -3.57017e-6 1 1.82154e-6 -3.62436e-6 1 1.78256e-6 -4.14875e-6 1 1.51409e-6 -4.01866e-6 1 1.75087e-6 -3.68626e-6 1 1.59051e-6 -3.9521e-6 1 1.43807e-6 -4.05949e-6 1 2.38007e-6 -4.07359e-6 1 4.58668e-6 -1.25785e-6 1 4.79533e-6 -1.4335e-6 1 2.2675e-6 -4.38231e-6 1 2.39916e-6 -4.48497e-6 1 1.55284e-6 -3.56183e-6 1 1.79444e-6 -4.03019e-6 1 1.67226e-6 -7.69492e-6 1 2.07111e-6 -4.86358e-6 1 2.17386e-6 -4.57032e-6 1 2.19839e-6 -4.46101e-6 1 -8.55953e-6 -1.90786e-5 1 2.78331e-6 -3.63325e-6 1 1.70207e-6 -5.43445e-6 1 2.07666e-6 -5.01347e-6 1 3.10086e-6 -4.7422e-6 1 3.63433e-6 -3.708e-6 1 3.21875e-6 -4.60685e-6 1 3.2901e-6 -4.55121e-6 1 2.13684e-6 -1.02106e-5 1 2.10353e-6 -6.30946e-6 1 2.15335e-6 -5.19863e-6 1 2.23309e-6 -4.73891e-6 1 2.25631e-6 -4.68703e-6 1 1.88138e-6 -4.18777e-6 1 -1.59259e-6 -8.20965e-6 1 -6.88496e-6 -1.3502e-5 1 1.83825e-6 -4.27099e-6 1 2.00921e-6 -4.05994e-6 1 1.79744e-6 -4.33939e-6 1 1.91705e-6 -4.19219e-6 1 1.74753e-6 -4.52755e-6 1 2.37036e-6 -3.76648e-6 1 1.34079e-6 -5.12173e-6 1 2.25377e-6 -4.02132e-6 1 9.68784e-7 -5.86492e-6 1 3.12179e-6 -3.34073e-6 1 -7.00431e-6 -1.5223e-5 1 7.72443e-6 8.90736e-7 1 2.38543e-6 -4.53014e-6 1 3.73975e-5 3.17779e-5 1 1.61616e-6 -3.88824e-6 1 2.02587e-6 -4.69103e-6 1 1.65358e-6 -3.97671e-6 1 1.63432e-6 -3.91303e-6 1 2.05376e-6 -6.62949e-6 1 2.38387e-6 -4.05613e-6 1 2.02209e-6 -4.42644e-6 1 2.14184e-6 -4.28531e-6 1 1.6678e-6 -4.7722e-6 1 2.46754e-6 -4.05189e-6 1 2.84892e-6 -3.5041e-6 1 3.47595e-6 -2.81697e-6 1 3.10828e-6 -3.20015e-6 1 -2.90469e-5 -3.64226e-5 1 1.55417e-6 -4.08297e-6 1 1.09757e-6 -5.31227e-6 1 1.82656e-6 -3.7869e-6 1 1.64542e-6 -4.71819e-6 1 2.30275e-6 -4.04304e-6 1 2.01235e-6 -4.35243e-6 1 2.06198e-6 -4.30163e-6 1 -4.61986e-7 -6.22801e-6 1 1.16811e-6 -5.7162e-6 1 -1.33171e-7 -6.61937e-6 1 2.90527e-6 -3.49949e-6 1 3.49723e-6 -2.85243e-6 1 1.37168e-6 -4.31489e-6 1 -2.00705e-6 -9.9162e-6 1 2.52432e-6 -4.50944e-6 1 1.78256e-6 -6.57018e-6 1 2.02054e-6 -3.36916e-6 1 1.09563e-6 -4.55533e-6 1 2.11375e-6 -7.50593e-6 1 8.42921e-7 -5.55514e-6 1 2.08772e-6 -6.19725e-6 1 1.30475e-6 -5.9574e-6 1 2.10353e-6 -6.30946e-6 1 2.15335e-6 -5.19864e-6 1 2.18388e-6 -5.02264e-6 1 2.39307e-6 -4.55514e-6 1 2.15534e-6 -4.46171e-6 1 2.15532e-6 -4.46173e-6 1 -6.88514e-6 -1.35022e-5 1 2.06399e-6 -4.56518e-6 1 2.11567e-6 -4.50138e-6 1 1.77257e-6 -5.02515e-6 1 2.50313e-6 -4.12604e-6 1 1.99551e-6 -4.22453e-6 1 -6.0694e-7 -7.40466e-6 1 1.34079e-6 -5.12172e-6 1 2.52189e-6 -3.69815e-6 1 1.04201e-6 -5.68815e-6 1 2.59443e-6 -3.86808e-6 1 1.98894e-5 1.41996e-5 1 8.82551e-6 2.09535e-6 1 2.44517e-6 -4.58115e-6 1 4.51921e-5 3.97481e-5 1 1.61616e-6 -3.88823e-6 1 2.05817e-6 -4.75432e-6 1 1.65358e-6 -3.97671e-6 1 2.46346e-6 -6.65467e-6 1 2.04831e-6 -3.96597e-6 1 6.82403e-7 -4.55121e-6 1 2.12516e-6 -4.41657e-6 1 2.4681e-6 -4.68396e-6 1 1.4541e-6 -3.64613e-6 1 1.7311e-6 -4.18314e-6 1 2.03711e-6 -5.1049e-6 1 1.45635e-6 -4.07e-6 1 1.71844e-6 -3.56191e-6 1 1.22579e-6 -4.12751e-6 1 -6.35394e-7 -6.99744e-6 1 0 -6.20745e-6 1 1.83981e-6 -3.68773e-6 1 1.62671e-6 -3.92722e-6 1 -4.17422e-7 -6.87465e-6 1 -9.59844e-7 -7.65376e-6 1 3.33068e-6 -2.95198e-6 1 1.28505e-6 -5.08389e-6 1 2.65072e-5 2.09755e-5 1 2.18198e-6 -4.50005e-6 1 2.19149e-6 -4.47445e-6 1 2.0904e-6 -4.59959e-6 1 1.96379e-5 1.38718e-5 1 1.67224e-6 -7.69508e-6 1 2.30354e-6 -3.76256e-6 1 2.14242e-6 -4.48047e-6 1 1.8376e-6 -4.58639e-6 1 2.19819e-6 -4.46081e-6 1 2.8453e-6 -2.59867e-6 1 1.71384e-6 -4.17022e-6 1 1.84411e-6 -4.54027e-6 1 1.44124e-6 -3.30965e-6 1 1.61131e-6 -3.95097e-6 1 1.97548e-6 -4.25843e-6 1 1.92711e-6 -4.29787e-6 1 2.20457e-6 -3.82223e-6 1 1.84284e-6 -4.3915e-6 1 2.64442e-6 -3.58978e-6 1 -3.90003e-6 -1.0594e-5 1 2.15386e-6 -4.08008e-6 1 -1.1548e-6 -7.77326e-6 1 1.21669e-6 -5.7826e-6 1 2.37053e-6 -3.86371e-6 1 1.95484e-6 -4.3256e-6 1 2.64442e-6 -3.58978e-6 1 2.22639e-6 -3.86008e-6 1 1.0758e-5 4.467e-6 1 1.43591e-6 -5.56343e-6 1 -1.1548e-6 -7.77326e-6 1 -1.78064e-6 4.32255e-6 -1 0.7461823 -0.6609659 -0.07959979 -1.39014e-6 4.66847e-6 -1 -1.39015e-6 4.66846e-6 -1 0.6612941 -0.7465491 -0.07317453 0.6215309 -0.7793711 -0.07924658 -2.15925e-6 3.99035e-6 -1 0.8204137 -0.5661317 -0.08010119 -1.75218e-6 4.35101e-6 -1 0.7795524 -0.6216752 -0.07627511 -2.54075e-6 3.6572e-6 -1 0.8826943 -0.4632695 -0.07894426 -2.11669e-6 4.03291e-6 -1 -2.13632e-6 4.11088e-6 -1 0.9319539 -0.3535436 -0.08042949 -1.70457e-6 4.49339e-6 -1 0.8983317 -0.43262 -0.07642102 -2.50146e-6 3.79325e-6 -1 0.9679505 -0.2386811 -0.07812207 -2.08511e-6 4.16208e-6 -1 -1.95624e-6 4.3786e-6 -1 0.9894832 -0.1201161 -0.08059376 -1.60463e-6 4.69008e-6 -1 0.9720565 -0.2218639 -0.07669866 -2.2426e-6 4.11347e-6 -1 0.9970216 9.05484e-5 -0.07712149 -2.05648e-6 4.27836e-6 -1 -2.84696e-6 3.79944e-6 -1 0.9894756 0.1201769 -0.08059608 -3.00871e-7 6.0552e-6 -1 0.997021 4.14663e-6 -0.07712936 -5.0583e-6 1.93184e-6 -1 0.9681527 0.2385532 -0.07597893 -2.04436e-6 4.60203e-6 -1 -3.10817e-6 4.31953e-6 -1 0.932028 0.353348 -0.08042979 7.26465e-7 7.7166e-6 -1 0.9719797 0.2218548 -0.07769185 1.52836e-5 2.07881e-5 -1 0.8829781 0.4634405 -0.07464963 -1.56563e-6 5.86207e-6 -1 -2.68581e-6 3.14397e-6 -1 0.8202827 0.5663222 -0.0800963 1.66777e-7 5.67123e-6 -1 0.8981973 0.4325445 -0.07840085 -2.91489e-6 2.91489e-6 -1 0.7464781 0.6613751 -0.07316696 0.6610475 0.7461093 -0.07960599 0.7793716 0.6215296 -0.079252 0.5663197 0.8202846 -0.08009618 0.6216713 0.7795553 -0.07627767 0.4632861 0.8826858 -0.07894194 0.353359 0.9320238 -0.08042973 0.4326155 0.8983343 -0.07641589 0.2384997 0.967996 -0.07811355 0.1201764 0.9894756 -0.08059597 0.2218666 0.9720553 -0.07670527 8.18696e-5 0.9970209 -0.07713192 -0.1201165 0.9894831 -0.08059376 -2.3695e-7 0.9970215 -0.07712447 -0.2387213 0.9681124 -0.07596427 -0.3535384 0.9319559 -0.08042931 -0.2218478 0.9719808 -0.07769632 -0.4634364 0.8829799 -0.07465404 -0.5661206 0.8204213 -0.08010149 -0.4325534 0.8981929 -0.07840263 -0.6612975 0.7465463 -0.07317388 -1.78065e-6 4.32254e-6 -1 -0.7461775 0.6609712 -0.07960045 -0.6215267 0.7793744 -0.07924705 -2.15927e-6 3.99033e-6 -1 -0.8204213 0.5661209 -0.08010149 -1.7522e-6 4.35099e-6 -1 -0.7795554 0.6216715 -0.07627499 -2.54069e-6 3.65726e-6 -1 -0.8826872 0.463283 -0.07894486 -2.11664e-6 4.03296e-6 -1 -1.26691e-6 4.88112e-6 -1 -0.9319558 0.3535387 -0.08042931 -1.7046e-6 4.49336e-6 -1 -0.8983315 0.4326204 -0.07642054 -3.35083e-6 2.94388e-6 -1 -0.9679519 0.2386757 -0.0781219 -2.06547e-6 4.08256e-6 -1 -2.06086e-6 4.39128e-6 -1 -0.9894821 0.1201238 -0.080594 -6.81493e-7 5.61322e-6 -1 -0.972056 0.2218654 -0.07669907 -2.37503e-6 4.11345e-6 -1 -0.9970217 -8.99139e-5 -0.07712149 -2.05646e-6 4.39569e-6 -1 6.6415e-6 1.22059e-5 -1 -0.9894767 -0.1201676 -0.08059585 -1.46215e-6 5.02634e-6 -1 -0.997021 -3.3173e-6 -0.07712936 -1.64695e-6 3.8318e-6 -1 -0.9681529 -0.2385526 -0.07597833 -2.39807e-6 3.16635e-6 -1 -2.08778e-6 3.60679e-6 -1 -0.9320219 -0.3533643 -0.08043009 -1.96308e-7 5.28245e-6 -1 -0.9719809 -0.2218496 -0.07769173 -1.81444e-6 3.69e-6 -1 -0.8829818 -0.4634329 -0.07465112 -3.48013e-6 2.21444e-6 -1 -2.68596e-6 3.14384e-6 -1 -0.8202857 -0.5663179 -0.08009666 1.66734e-7 5.67118e-6 -1 -0.8981969 -0.4325454 -0.07840132 -2.91504e-6 2.91476e-6 -1 -0.7464784 -0.6613747 -0.07316702 -0.6610521 -0.7461052 -0.07960599 -0.779372 -0.621529 -0.07925212 -0.5663162 -0.8202868 -0.08009642 -0.6216742 -0.7795531 -0.07627755 -0.4632704 -0.882694 -0.078942 -0.3533791 -0.9320162 -0.08042949 -0.4326113 -0.8983362 -0.07641679 -0.2384983 -0.9679964 -0.07811301 -0.1201777 -0.9894755 -0.08059608 -0.2218716 -0.9720541 -0.07670521 -8.21862e-5 -0.997021 -0.07713204 0.1201316 -0.9894812 -0.08059328 7.40467e-6 -0.9970216 -0.07712388 0.2387095 -0.9681152 -0.07596474 0.3535455 -0.9319531 -0.08042967 0.2218407 -0.9719825 -0.07769632 0.4634231 -0.8829867 -0.07465553 0.5661284 -0.8204159 -0.08010131 0.4325535 -0.898193 -0.07840251 0 0 1 -0.6421888 0.7411614 0.1956357 -0.7418832 0.6428076 0.1908081 -0.7668327 0.6115308 0.1949305 -2.48958e-5 2.1572e-5 1 -0.5299891 0.8248153 0.1969545 0 0 1 -0.6117722 0.7671402 0.1929528 2.06745e-5 -2.29288e-5 1 -0.4075798 0.8926841 0.1923377 1.26635e-5 -1.59873e-5 1 7.19896e-7 -2.45221e-6 1 -0.2762024 0.94084 0.1962969 -3.19127e-6 9.36869e-7 1 -0.4256246 0.8838092 0.1942294 4.80193e-7 -3.34064e-6 1 -0.1394997 0.9704812 0.196739 8.93183e-6 -1.06642e-5 1 -0.2183484 0.9566327 0.1928152 0 -2.47865e-6 1 0 0.9810679 0.1936641 -2.86042e-6 0 1 -4.19764e-7 -2.92035e-6 1 0.1394947 0.9704819 0.1967383 6.03449e-6 -8.51313e-6 1 3.73051e-6 0.981068 0.1936638 -7.0106e-7 -2.38797e-6 1 0.2762108 0.9408375 0.1962972 -2.5821e-6 -7.58019e-7 1 0.2183428 0.9566342 0.1928147 6.39449e-6 -8.3468e-6 1 0.4073994 0.8922404 0.194764 -2.12073e-6 -9.68297e-7 1 6.09519e-6 -7.68579e-6 1 0.5299734 0.8248254 0.1969553 -9.75818e-7 -9.76504e-7 1 2.62556e-6 -4.54797e-6 1 0.4257095 0.8839858 0.1932368 0 0 1 0.642821 0.7418721 0.190806 0 0 1 0 0 1 -1.33903e-6 -1.16025e-6 1 0.7411532 0.6421981 0.1956358 6.74545e-6 -6.74545e-6 1 0.6115285 0.7668344 0.1949304 -1.18752e-6 -7.63027e-7 1 0.8248222 0.5299783 0.1969552 -9.14779e-6 5.2811e-6 1 -2.48848e-6 0 1 0.7671394 0.6117734 0.1929525 4.88571e-6 -7.97474e-6 1 0.8926785 0.4075914 0.1923392 1.3401e-5 -1.53533e-5 1 -9.76725e-7 -9.75582e-7 1 -2.58206e-6 -7.58049e-7 1 0.9408369 0.2762134 0.1962962 -7.01036e-7 -2.38799e-6 1 0.8838125 0.4256178 0.1942291 6.03442e-6 -8.51306e-6 1 0.9704827 0.1394916 0.1967373 -4.1976e-7 -2.92035e-6 1 0.9566344 0.2183434 0.1928135 -2.86041e-6 0 1 0.9810681 9.10935e-6 0.1936629 0 -2.47865e-6 1 8.93192e-6 -1.06642e-5 1 0.9704808 -0.1395028 0.196738 4.80234e-7 -3.34067e-6 1 0.9810681 8.97664e-6 0.1936628 -3.19123e-6 9.36841e-7 1 0.9408407 -0.2762 0.1962965 7.19829e-7 -2.45215e-6 1 0.9566341 -0.2183431 0.1928145 -6.11666e-6 2.79278e-6 1 0.8922461 -0.4073868 0.1947636 1.89422e-6 -4.14861e-6 1 3.08709e-5 -3.08709e-5 1 0.8248171 -0.5299868 0.1969539 5.97484e-6 -9.29872e-6 1 0.8839851 -0.4257118 0.1932353 0 0 1 0.741884 -0.6428071 0.1908069 0.6421852 -0.7411649 0.1956343 0.7668333 -0.6115303 0.1949291 0.529983 -0.8248195 0.1969538 0.6117734 -0.7671393 0.1929519 0.4075896 -0.8926795 0.1923378 0.2761858 -0.940845 0.196296 0.425626 -0.8838086 0.1942287 0.13951 -0.9704797 0.1967382 0.2183457 -0.9566335 0.192815 0 -0.981068 0.1936632 -0.1394934 -0.9704823 0.1967377 -2.21499e-6 -0.9810681 0.193663 -0.2762 -0.9408407 0.1962966 -0.2183371 -0.9566356 0.1928143 -0.4073945 -0.8922426 0.1947635 0 0 1 -0.529993 -0.8248128 0.196955 -2.22638e-5 2.01347e-5 1 -0.4257082 -0.8839865 0.1932361 -1.20403e-6 -1.38962e-6 1 -0.6428059 -0.7418848 0.1908077 6.7685e-6 -6.70553e-6 1 0 0 1 -1.33906e-6 -1.16023e-6 1 -0.7411656 -0.642184 0.1956351 -1.64431e-6 -9.4934e-7 1 -0.6115296 -0.7668338 0.1949298 5.49581e-6 -7.5023e-6 1 -0.8248077 -0.5300011 0.1969552 4.01707e-5 -3.38305e-5 1 -2.48851e-6 0 1 -0.7671378 -0.611775 0.1929531 -0.8926814 -0.4075855 0.1923385 -0.9408407 -0.2762 0.1962965 -0.8838111 -0.4256206 0.1942293 -0.9704817 -0.1394965 0.1967383 -0.9566337 -0.2183449 0.1928146 -0.9810679 -9.10927e-6 0.1936638 -0.9704826 0.1394903 0.1967388 -0.9810679 -8.16053e-6 0.1936638 -0.9408392 0.2762049 0.1962971 -0.956634 0.2183433 0.1928148 -0.8922483 0.4073816 0.1947644 -0.8248152 0.5299894 0.1969551 -0.8839877 0.425706 0.1932362 -0.8660414 0.4999724 2.0146e-7 -0.4999695 0.8660431 -5.33668e-7 -0.5000442 0.8659999 2.63797e-7 -1 9.20734e-6 0 -0.8659965 0.5000501 -6.27152e-7 -0.8660265 -0.4999982 1.68098e-6 -1 1.19749e-4 -1.10758e-6 -0.4999942 -0.8660288 1.1434e-6 -0.8660471 -0.4999625 1.29924e-6 9.20734e-6 -1 -1.53274e-6 -0.4999584 -0.8660494 1.52489e-6 0.4999793 -0.8660374 -1.09245e-6 1.28962e-4 -1 -4.25934e-7 0.8660408 -0.4999734 -2.44033e-7 0.50005 -0.8659964 -3.37536e-7 1 0 -1.70299e-7 0.8659999 -0.5000442 -9.9905e-7 0.8660287 0.4999942 1.71518e-6 1 -1.2896e-4 -1.36314e-6 0.4999912 0.8660304 1.53187e-6 0.8660472 0.4999625 1.37601e-6 -9.20734e-6 1 -9.36695e-7 0.4999555 0.8660511 1.91336e-6 -1.2896e-4 1 1.70123e-7 -0.7818309 0.6234905 0 -0.7818332 0.6234877 2.19429e-7 -0.6234882 0.7818328 2.37026e-7 -0.9009686 0.4338843 1.91682e-7 -0.9009664 0.433889 0 -0.9749282 0.2225196 1.78e-7 -0.974928 0.2225205 1.54022e-7 -1 -7.60503e-6 2.16741e-7 -1 -3.80253e-6 0 -0.9749282 -0.2225196 0 -0.9749276 -0.2225224 0 -0.9009694 -0.4338827 0 -0.9009701 -0.4338812 0 -0.7818309 -0.6234905 0 -0.781831 -0.6234905 0 -0.6234905 -0.7818309 0 -0.6234905 -0.781831 0 -0.4338859 -0.9009679 -3.43538e-7 -0.4338797 -0.9009708 -1.48536e-7 -0.2225133 -0.9749298 0 -0.2225269 -0.9749265 -3.98346e-7 -3.8025e-6 -1 -3.25116e-7 7.60503e-6 -1 0 0.2225205 -0.974928 -1.2977e-7 0.2225133 -0.9749296 -3.41381e-7 0.4338889 -0.9009664 -1.48258e-7 0.433889 -0.9009663 -1.44316e-7 0.6234905 -0.7818309 -1.52298e-7 0.6234918 -0.7818298 0 0.7818299 -0.6234919 -1.52298e-7 0.7818309 -0.6234905 0 -0.6234877 0.7818332 2.20273e-7 0.9009664 -0.4338889 -1.44661e-7 0.9009662 -0.433889 -1.48535e-7 0.9749286 -0.222518 0 0.9749282 -0.2225196 -1.29969e-7 1 1.14076e-5 0 1 3.80253e-6 0 0.9749282 0.2225197 0 0.9749265 0.2225269 0 0.9009701 0.4338812 0 0.9009708 0.4338797 0 0.7818309 0.6234905 0 0.7818309 0.6234905 0 0.6234881 0.7818328 0 0.6234882 0.7818328 0 0.4338874 0.9009671 0 0.4338843 0.9009686 0 0.2225169 0.9749289 1.38966e-7 0.2225224 0.9749276 0 3.8025e-6 1 0 0 1 2.16744e-7 -0.2225241 0.9749272 2.35425e-7 -0.2225205 0.974928 1.29969e-7 -0.4338874 0.9009671 1.91682e-7 -0.433889 0.9009664 2.42214e-7 2.85006e-6 -4.93587e-6 1 4.275e-6 -2.46846e-6 1 4.27497e-6 -2.46849e-6 1 0 0 1 -1.06355e-5 -1.84215e-5 1 0 0 1 2.85009e-6 -4.93585e-6 1 0 0 1 -1.06357e-5 -1.84217e-5 1 0 0 1 -1.10337e-6 3.40312e-6 -1 0.6609663 0.7461819 -0.07959967 -1.65433e-6 4.02509e-6 -1 -1.65428e-6 4.02504e-6 -1 0.7465495 0.6612937 -0.07317423 0.7793727 0.621529 -0.07924646 -1.29607e-6 3.55695e-6 -1 0.5661261 0.8204177 -0.08010113 -1.59815e-6 3.8979e-6 -1 0.6216735 0.7795539 -0.07627481 -2.27211e-6 4.5259e-6 -1 0.4632728 0.8826926 -0.0789442 -2.32713e-6 4.58801e-6 -1 -1.7382e-6 4.11809e-6 -1 0.3535408 0.9319549 -0.08042955 -7.58759e-7 3.01256e-6 -1 0.4326214 0.8983309 -0.07642084 -7.88168e-6 1.09757e-5 -1 0.2386806 0.9679507 -0.07812213 -2.33771e-6 4.71759e-6 -1 -5.93031e-7 3.64314e-6 -1 0.1201163 0.9894831 -0.08059376 -9.33761e-7 4.02777e-6 -1 0.2218632 0.9720567 -0.07669866 -2.05728e-6 5.36773e-6 -1 -8.2187e-5 0.9970217 -0.07712173 0 3.08525e-6 -1 -1.64967e-6 5.05015e-6 -1 -0.1201766 0.9894755 -0.08059602 -9.50166e-7 4.26062e-6 -1 0 0.9970211 -0.07712918 -2.64116e-6 6.41961e-6 -1 -0.2385472 0.9681541 -0.07597905 2.94872e-7 3.10561e-6 -1 -6.47956e-7 4.60939e-6 -1 -0.353352 0.9320266 -0.08042961 7.72744e-7 3.0057e-6 -1 -0.2218536 0.97198 -0.07769149 -5.26981e-6 1.00403e-5 -1 -0.4634431 0.8829768 -0.07464945 1.00946e-6 2.95198e-6 -1 -8.39001e-7 3.02517e-6 -1 -0.566318 0.8202856 -0.08009624 -2.09148e-5 2.56853e-5 -1 -0.4325457 0.8981968 -0.07840085 -4.93497e-6 7.12114e-6 -1 -0.661379 0.7464748 -0.07316631 -0.7461048 0.6610525 -0.07960599 -0.6215291 0.7793719 -0.079252 -0.820284 0.5663205 -0.08009612 -0.7795531 0.6216741 -0.07627749 -0.8826889 0.4632802 -0.07894182 -0.932022 0.3533639 -0.08042955 -0.8983356 0.4326128 -0.07641601 -0.9679955 0.2385021 -0.07811325 -0.9894756 0.1201769 -0.08059561 -0.972055 0.221868 -0.07670485 -0.9970209 8.22662e-5 -0.07713145 -0.9894821 -0.1201241 -0.08059352 -0.9970216 2.96186e-7 -0.07712399 -0.9681105 -0.2387286 -0.07596397 -0.9319587 -0.353531 -0.08042925 -0.9719801 -0.221851 -0.07769644 -0.8829801 -0.4634361 -0.07465362 -0.8204176 -0.566126 -0.0801016 -0.8981948 -0.4325498 -0.07840269 -0.7465428 -0.6613014 -0.07317399 -1.10333e-6 3.40308e-6 -1 -0.6609758 -0.7461733 -0.07960051 -0.7793712 -0.6215308 -0.07924711 -5.51294e-6 8.31642e-6 -1 -0.5661213 -0.8204209 -0.08010154 -1.59817e-6 3.89793e-6 -1 -0.6216738 -0.7795536 -0.07627487 -2.07816e-6 4.8954e-6 -1 -0.4632831 -0.8826871 -0.07894486 -1.97128e-6 4.77477e-6 -1 -1.60183e-6 4.47753e-6 -1 -0.3535386 -0.9319557 -0.08042955 -1.14783e-6 3.96508e-6 -1 -0.4326219 -0.8983307 -0.07642072 -1.95725e-6 4.94457e-6 -1 -0.2386777 -0.9679514 -0.07812207 -1.09065e-6 3.96635e-6 -1 -6.05695e-7 3.53849e-6 -1 -0.1201226 -0.9894823 -0.08059406 -1.02887e-6 4.01619e-6 -1 -0.2218651 -0.9720561 -0.07669907 -2.05727e-6 5.23529e-6 -1 8.18697e-5 -0.9970217 -0.07712179 -1.52468e-7 3.08526e-6 -1 -1.6283e-6 4.87421e-6 -1 0.1201764 -0.9894755 -0.08059602 -1.10087e-6 4.2789e-6 -1 0 -0.9970211 -0.07712924 -2.14697e-6 4.41404e-6 -1 0.2385393 -0.968156 -0.07597941 -9.75057e-6 1.29965e-5 -1 4.10292e-7 1.81802e-6 -1 0.3533719 -0.932019 -0.08042937 0 2.15771e-6 -1 0.2218542 -0.9719798 -0.07769095 -2.43195e-6 4.63373e-6 -1 0.4634234 -0.8829869 -0.07465136 -2.63781e-6 4.86612e-6 -1 -8.39098e-7 3.02527e-6 -1 0.5663238 -0.8202817 -0.08009594 -9.60402e-7 3.16219e-6 -1 0.4325444 -0.8981975 -0.07840049 -4.93497e-6 7.12114e-6 -1 0.6613792 -0.7464747 -0.07316637 0.7461051 -0.6610523 -0.07960605 0.6215295 -0.7793717 -0.07925206 0.820283 -0.5663218 -0.08009606 0.7795533 -0.6216739 -0.07627755 0.8826944 -0.4632697 -0.0789417 0.9320191 -0.3533716 -0.08042979 0.8983357 -0.4326123 -0.07641673 0.9679947 -0.238505 -0.07811361 0.9894775 -0.1201601 -0.08059573 0.972056 -0.2218638 -0.07670462 0.997021 -8.17903e-5 -0.07713198 0.9894822 0.1201238 -0.08059352 0.9970216 4.08738e-6 -0.07712417 0.9681137 0.2387157 -0.07596445 0.931953 0.3535459 -0.08042949 0.9719817 0.2218446 -0.07769626 0.8829882 0.4634205 -0.07465547 0.8204147 0.5661304 -0.08010089 0.8981927 0.4325539 -0.07840204 -4.26879e-5 -4.92674e-5 1 -0.7411565 -0.6421948 0.1956348 -0.6428077 -0.7418834 0.190807 -0.6115296 -0.7668338 0.1949295 9.29846e-6 5.97457e-6 1 -0.8248232 -0.5299769 0.1969545 -1.18262e-5 -1.84052e-5 1 -0.7671351 -0.6117787 0.192952 8.29713e-6 3.78835e-6 1 -0.8926813 -0.4075855 0.1923383 1.59876e-5 1.26637e-5 1 -3.88875e-6 -1.0818e-5 1 -0.9408411 -0.2761983 0.1962963 1.18238e-5 7.31502e-6 1 -0.8838112 -0.4256207 0.1942291 6.68141e-6 9.60539e-7 1 -0.9704786 -0.1395189 0.196738 -1.16316e-6 -8.09243e-6 1 -0.9566326 -0.2183492 0.1928149 -3.08842e-6 -9.28505e-6 1 -0.9810681 -1.79817e-6 0.193663 0 -5.7209e-6 1 4.86724e-6 -6.99605e-7 1 -0.9704822 0.1394947 0.1967372 7.78745e-7 -5.41788e-6 1 -0.9810683 3.03104e-6 0.1936626 3.18396e-6 -9.34737e-7 1 -0.9408383 0.2762084 0.1962959 -6.21699e-6 -1.17839e-5 1 -0.9566341 0.2183442 0.1928135 -2.98546e-6 -8.84239e-6 1 -0.8922436 0.4073927 0.1947629 8.29754e-6 4.17885e-6 1 4.12401e-6 -2.64989e-6 1 -0.8248169 0.5299866 0.196955 2.92985e-6 -2.9271e-6 1 1.36442e-5 7.877e-6 1 -0.8839899 0.4257017 0.193236 2.7792e-6 -2.40811e-6 1 -0.741876 0.6428164 0.1908066 3.16609e-6 -1.82786e-6 1 -4.14479e-6 -9.20742e-6 1 -3.12742e-6 -1.05638e-5 1 -0.6421943 0.7411566 0.1956356 1.89862e-6 -3.28869e-6 1 -0.7668331 0.6115302 0.1949302 2.2891e-6 -3.56254e-6 1 -0.5299847 0.8248181 0.1969551 -1.58426e-5 -2.74424e-5 1 0 -7.46543e-6 1 -0.611774 0.7671389 0.1929526 8.62034e-6 3.47197e-6 1 -0.4075947 0.8926769 0.1923393 4.02099e-6 -1.83594e-6 1 2.92607e-6 -2.93087e-6 1 1.0107e-6 -3.44279e-6 1 -0.2762024 0.94084 0.1962962 -3.50019e-6 -8.64856e-6 1 -0.4256193 0.8838119 0.1942289 6.23001e-7 -4.3343e-6 1 -0.1394947 0.9704821 0.1967378 3.89383e-6 -5.59653e-7 1 -0.2183434 0.9566342 0.1928141 0 -4.29067e-6 1 0 0.9810681 0.1936632 -4.32775e-6 -9.28505e-6 1 -8.72373e-7 -6.06932e-6 1 0.1394921 0.9704821 0.1967393 5.01096e-6 7.20297e-7 1 -1.11916e-5 0.9810678 0.1936641 -2.81052e-6 -9.57369e-6 1 0.2761999 0.9408406 0.1962974 7.35646e-6 2.15952e-6 1 0.218344 0.9566338 0.1928155 1.59877e-5 1.26638e-5 1 0.4073842 0.8922471 0.1947647 -6.33458e-6 -1.30977e-5 1 -1.18268e-5 -1.84057e-5 1 0.529994 0.8248123 0.1969546 9.29898e-6 5.97511e-6 1 0.4257147 0.8839835 0.1932359 4.92628e-5 4.2684e-5 1 0.6428076 0.7418833 0.1908078 0.7411648 0.642185 0.1956357 0.6115279 0.7668349 0.1949304 0.8248152 0.5299894 0.1969549 0.7671397 0.6117727 0.1929532 0.8926801 0.407588 0.1923387 0.9408441 0.2761881 0.1962965 0.8838103 0.4256223 0.1942293 0.9704809 0.139501 0.1967387 0.956634 0.2183433 0.1928153 0.9810679 -1.79818e-6 0.1936637 0.9704834 -0.1394858 0.1967381 0.981068 -4.42998e-6 0.1936635 0.9408442 -0.2761885 0.1962959 0.9566352 -0.2183386 0.1928143 0.8922448 -0.4073903 0.194763 4.12394e-6 -2.64996e-6 1 0.8248062 -0.5300037 0.1969542 1.36444e-5 7.87721e-6 1 0.8839865 -0.4257088 0.1932352 -2.41066e-6 -1.01916e-5 1 0.7418876 -0.6428028 0.1908074 3.16608e-6 -1.82789e-6 1 -4.14478e-6 -9.20742e-6 1 3.48065e-6 -4.01719e-6 1 0.6421789 -0.7411703 0.195634 2.84797e-6 -4.93298e-6 1 0.7668334 -0.6115303 0.194929 2.28917e-6 -3.56244e-6 1 0.530006 -0.8248047 0.196954 -1.58429e-5 -2.74428e-5 1 0 -7.46545e-6 1 0.6117734 -0.7671394 0.1929523 0.4075872 -0.8926808 0.1923372 0.2761899 -0.9408439 0.1962956 0.4256247 -0.8838095 0.1942282 0.1394934 -0.9704822 0.1967379 0.2183441 -0.956634 0.1928141 0 -0.981068 0.1936632 -0.1394921 -0.9704822 0.1967388 7.46107e-6 -0.9810679 0.1936638 -0.2762007 -0.9408404 0.1962966 -0.2183462 -0.9566334 0.1928148 -0.4073892 -0.8922451 0.1947637 -0.529983 -0.8248195 0.1969541 -0.4257111 -0.8839853 0.1932357 -0.4999713 -0.8660419 -1.78657e-7 -0.866039 -0.4999763 -8.51455e-7 -0.8659959 -0.5000512 0 0 -1 -1.70299e-7 -0.5000362 -0.8660045 -8.71432e-7 0.4999883 -0.8660321 1.58742e-6 -1.28961e-4 -1 -1.36311e-6 0.866031 -0.4999902 1.2369e-6 0.4999526 -0.8660528 1.20572e-6 1 0 -1.27724e-6 0.8660517 -0.4999545 1.61838e-6 0.8660357 0.4999822 -7.54914e-7 1 1.28961e-4 0 0.4999695 0.8660431 1.78657e-7 0.8659918 0.500058 0 0 1 1.70299e-7 0.5000442 0.8659999 -6.18934e-7 -0.4999803 0.8660367 1.89374e-6 1.38174e-4 1 -1.10773e-6 -0.8660351 0.4999833 1.48094e-6 -0.4999476 0.8660558 1.54326e-6 -1 0 -1.10694e-6 -0.8660573 0.4999446 1.89352e-6 -1 -1.19748e-4 0 -0.6234905 -0.7818309 0 -0.62349 -0.7818313 0 -0.781828 -0.6234942 0 -0.4338889 -0.9009664 -1.48258e-7 -0.4338905 -0.9009656 -1.98329e-7 -0.2225224 -0.9749276 -2.44619e-7 -0.2225205 -0.974928 -1.86937e-7 7.60505e-6 -1 0 0 -1 -3.25116e-7 0.2225189 -0.9749284 -3.8931e-7 0.2225269 -0.9749265 -1.54021e-7 0.4338889 -0.9009664 -1.44661e-7 0.4338797 -0.9009708 -4.33793e-7 0.6234905 -0.7818309 -1.52298e-7 0.6234905 -0.7818309 -1.52755e-7 0.7818309 -0.6234905 -1.52298e-7 0.781831 -0.6234906 -1.52755e-7 0.9009678 -0.4338858 -2.89322e-7 0.9009701 -0.4338812 -1.44317e-7 0.9749296 -0.2225133 0 0.9749282 -0.2225196 -2.59516e-7 1 -3.8025e-6 -2.16745e-7 1 3.80251e-6 0 0.9749282 0.2225196 0 0.9749289 0.2225169 -1.63306e-7 0.9009678 0.4338858 -1.51856e-7 0.9009664 0.433889 0 0.7818309 0.6234905 0 0.7818318 0.6234895 0 0.62349 0.7818313 0 0.6234881 0.7818328 0 -0.7818298 -0.6234919 -1.35034e-7 0.433892 0.900965 0 0.4338905 0.9009656 0 0.2225189 0.9749284 0 0.2225189 0.9749284 0 -1.14076e-5 1 4.33488e-7 0 1 0 -0.2225196 0.9749282 2.35425e-7 -0.2225261 0.9749267 4.22397e-7 -0.4338812 0.9009701 2.42301e-7 -0.4338812 0.9009701 2.42216e-7 -0.6234905 0.7818309 2.37026e-7 -0.6234905 0.7818309 2.37151e-7 -0.7818309 0.6234905 2.19867e-7 -0.7818309 0.6234905 2.20272e-7 -0.9009701 0.4338812 1.91681e-7 -0.9009701 0.4338812 1.91579e-7 -0.974928 0.2225205 2.35425e-7 -0.9749274 0.2225233 1.536e-7 -1 3.8025e-6 0 -1 0 2.16744e-7 -0.9749271 -0.2225241 0 -0.9749271 -0.2225241 0 -0.9009693 -0.4338828 0 -0.9009678 -0.4338859 0 1.34925e-5 -1.34925e-5 1 -2.46847e-6 -4.27501e-6 1 -2.46844e-6 -4.27505e-6 1 0 0 1 0 0 1 0 0 1 -4.93583e-6 -2.85014e-6 1 -1.34821e-5 0 1 0 -7.78494e-6 1 1.84134e-5 -3.1897e-5 1 -2.10898e-6 4.61338e-6 -1 -0.7461775 0.6609712 -0.07960045 -2.44796e-6 4.31309e-6 -1 -2.44796e-6 4.31309e-6 -1 -0.6612975 0.7465462 -0.07317394 -0.6215273 0.779374 -0.07924705 -2.48032e-6 4.21189e-6 -1 -0.8204174 0.5661264 -0.08010113 -2.74474e-6 3.97762e-6 -1 -0.7795554 0.6216716 -0.07627499 -1.32472e-6 5.34277e-6 -1 -0.8826889 0.4632797 -0.07894438 -1.5415e-6 5.15072e-6 -1 -3.36526e-6 3.47691e-6 -1 -0.9319548 0.3535413 -0.08042955 -1.83367e-6 4.83382e-6 -1 -0.8983293 0.432625 -0.07642072 -2.16564e-6 4.76922e-6 -1 -0.9679542 0.2386662 -0.07812178 -1.35344e-6 5.48874e-6 -1 -2.47926e-6 4.44214e-6 -1 -0.9894811 0.1201329 -0.08059418 -2.59717e-6 4.33769e-6 -1 -0.9720564 0.2218636 -0.07669961 3.92841e-6 1.02845e-5 -1 -0.9970216 -8.12352e-5 -0.07712179 -1.02788e-6 5.89351e-6 -1 -2.67107e-6 3.82076e-6 -1 -0.9894737 -0.1201924 -0.08059638 -1.48048e-6 4.87558e-6 -1 -0.9970211 2.36951e-7 -0.07712918 -3.40168e-6 3.39952e-6 -1 -0.968156 -0.238539 -0.0759803 -6.89057e-7 5.80277e-6 -1 -4.08185e-6 2.85068e-6 -1 -0.9320213 -0.353366 -0.08042925 -2.93093e-6 3.87027e-6 -1 -0.9719783 -0.2218611 -0.07769113 -6.44844e-6 1.25779e-6 -1 -0.882977 -0.4634428 -0.07464969 3.29892e-7 7.26242e-6 -1 -1.44539e-5 -4.9805e-6 -1 -0.8202895 -0.5663123 -0.08009701 1.04061e-6 8.74682e-6 -1 -0.898199 -0.4325409 -0.07840168 3.74573e-5 4.69307e-5 -1 -0.7464792 -0.6613739 -0.07316708 -0.6610485 -0.7461084 -0.07960599 -0.779372 -0.6215291 -0.079252 -0.5663201 -0.8202841 -0.08009642 -0.6216744 -0.7795529 -0.07627779 -0.4632802 -0.8826888 -0.07894212 -0.3533595 -0.9320237 -0.08042979 -0.4326112 -0.8983362 -0.07641613 -0.2385078 -0.9679939 -0.07811379 -0.1201686 -0.9894766 -0.08059585 -0.221867 -0.9720551 -0.0767048 -9.03104e-5 -0.9970209 -0.07713228 0.1201243 -0.9894821 -0.08059364 -2.96187e-7 -0.9970216 -0.07712405 0.2387213 -0.9681124 -0.07596445 0.3535312 -0.9319585 -0.08042943 0.221848 -0.9719808 -0.0776965 0.4634364 -0.8829798 -0.07465386 0.5661262 -0.8204174 -0.08010154 0.4325519 -0.8981937 -0.07840269 0.6612976 -0.7465461 -0.07317429 -2.10898e-6 4.61338e-6 -1 0.7461777 -0.660971 -0.07960051 0.6215292 -0.7793724 -0.07924711 -2.48032e-6 4.21189e-6 -1 0.8204175 -0.5661261 -0.08010154 -2.74476e-6 3.9776e-6 -1 0.7795538 -0.6216736 -0.07627522 3.61659e-6 9.72065e-6 -1 0.8826876 -0.4632821 -0.07894486 -1.54141e-6 5.1508e-6 -1 -2.93397e-6 3.31324e-6 -1 0.9319586 -0.353531 -0.08042949 -1.67877e-6 4.42528e-6 -1 0.8983325 -0.4326184 -0.07642048 -1.65207e-6 4.64264e-6 -1 0.967952 -0.2386752 -0.07812207 -1.23573e-6 5.01147e-6 -1 -2.87945e-6 3.45539e-6 -1 0.9894823 -0.1201232 -0.08059358 -2.52786e-6 3.76685e-6 -1 0.9720571 -0.221861 -0.07669889 -3.53598e-6 3.08493e-6 -1 0.9970217 9.04691e-5 -0.07712101 -1.02794e-6 5.3069e-6 -1 -1.66737e-6 4.97902e-6 -1 0.9894766 0.1201689 -0.08059585 -1.44387e-6 5.17703e-6 -1 0.9970211 3.55424e-7 -0.07712924 -3.65247e-6 3.33767e-6 -1 0.9681522 0.2385551 -0.07597821 -6.38521e-7 6.00787e-6 -1 -4.48052e-6 2.69959e-6 -1 0.9320226 0.3533622 -0.08043026 -2.81558e-6 4.17456e-6 -1 0.9719806 0.2218502 -0.07769185 1.52835e-5 2.07879e-5 -1 0.8829814 0.463434 -0.07465112 6.03206e-7 7.78333e-6 -1 -3.32211e-7 4.76885e-6 -1 0.8202891 0.5663128 -0.08009666 -3.86914e-6 1.63531e-6 -1 0.8981966 0.432546 -0.07840132 3.47821e-6 8.57927e-6 -1 0.7464705 0.6613839 -0.07316595 0.6610563 0.7461015 -0.07960635 0.7793715 0.6215296 -0.07925236 0.5663196 0.8202846 -0.08009618 0.6216738 0.7795533 -0.07627749 0.4632666 0.8826961 -0.07894164 0.3533715 0.9320192 -0.08042979 0.4326108 0.8983364 -0.07641673 0.2385075 0.967994 -0.07811367 0.1201683 0.9894766 -0.08059579 0.2218675 0.9720552 -0.07670474 9.01518e-5 0.9970208 -0.07713222 -0.1201307 0.9894813 -0.08059322 -3.9689e-6 0.9970216 -0.07712364 -0.2387173 0.9681134 -0.07596433 -0.3535456 0.9319531 -0.08042961 -0.2218442 0.9719817 -0.07769632 -0.4634166 0.8829901 -0.07465583 -0.5661302 0.8204149 -0.08010101 -0.4325517 0.8981937 -0.07840222 4.26828e-5 -4.92616e-5 1 0.6421837 -0.7411661 0.1956346 0.7418822 -0.642809 0.1908071 0.7668328 -0.6115308 0.1949297 0 0 1 0.5299875 -0.8248165 0.1969541 -4.92758e-5 4.26969e-5 1 0.6117739 -0.7671388 0.1929523 0 0 1 0.407589 -0.89268 0.1923379 0 0 1 -1.22576e-5 8.79296e-6 1 0.2761924 -0.9408431 0.1962958 1.36973e-5 -1.36973e-5 1 0.425623 -0.8838101 0.1942285 4.80193e-7 -3.34064e-6 1 0.1394997 -0.9704812 0.1967388 -4.04617e-6 5.81538e-7 1 0.218352 -0.956632 0.1928148 9.28514e-6 -1.17638e-5 1 1.7982e-6 -0.9810679 0.1936638 6.4247e-6 -9.28514e-6 1 -2.7984e-7 -1.9469e-6 1 -0.1394934 -0.9704823 0.1967376 -2.16715e-6 -3.11499e-7 1 -6.76155e-6 -0.9810681 0.1936632 7.24665e-6 -8.27632e-6 1 -0.2762007 -0.9408407 0.1962962 -1.72141e-6 -5.05333e-7 1 -0.2183406 -0.9566348 0.1928139 -6.11992e-7 -1.34032e-6 1 -0.4073978 -0.8922412 0.194763 6.29958e-6 -7.32925e-6 1 -8.83283e-7 -1.37468e-6 1 -0.5299783 -0.8248223 0.196955 -9.75815e-7 -9.765e-7 1 2.6256e-6 -4.548e-6 1 -0.4257044 -0.8839883 0.1932362 -2.4081e-6 -2.7792e-6 1 -0.6428157 -0.7418766 0.1908064 -1.8279e-6 -3.16606e-6 1 9.2076e-6 -1.40989e-5 1 1.30931e-5 -1.3216e-5 1 -0.7411503 -0.6422016 0.1956356 -3.28862e-6 -1.89868e-6 1 -0.6115297 -0.7668337 0.19493 -1.18752e-6 -7.63025e-7 1 -0.8248223 -0.5299783 0.1969548 -9.14815e-6 5.28141e-6 1 9.12167e-6 -9.20734e-6 1 -0.7671384 -0.6117745 0.192952 -1.41382e-6 -6.45535e-7 1 -0.8926797 -0.4075889 0.1923388 -6.11992e-7 -1.34032e-6 1 -9.76389e-7 -9.75932e-7 1 6.61953e-6 -7.7329e-6 1 -0.9408346 -0.276221 0.1962961 -4.67345e-7 -1.59201e-6 1 -0.8838127 -0.4256176 0.1942289 -1.08358e-6 -1.5574e-7 1 -0.9704836 -0.1394845 0.1967377 -1.3992e-7 -9.73451e-7 1 -0.9566333 -0.2183477 0.1928132 7.85491e-6 -9.28514e-6 1 -0.9810681 -1.79819e-6 0.1936631 9.28514e-6 -1.05245e-5 1 -2.02313e-6 2.90813e-7 1 -0.9704809 0.139501 0.1967393 2.40099e-7 -1.67032e-6 1 -0.9810679 -1.27072e-5 0.193664 -3.19119e-6 9.36797e-7 1 -0.940843 0.2761916 0.1962975 7.19829e-7 -2.45214e-6 1 -0.9566342 0.2183417 0.1928158 1.87808e-5 -1.87808e-5 1 -0.8922451 0.4073885 0.1947646 1.89425e-6 -4.14864e-6 1 0 0 1 -0.8248163 0.5299875 0.1969553 0 0 1 -0.8839854 0.4257104 0.1932366 -9.19371e-5 9.19371e-5 1 -0.7418871 0.642803 0.1908085 -0.6421811 0.741168 0.1956355 -0.7668337 0.6115295 0.1949304 -0.5299852 0.8248178 0.1969553 -0.6117738 0.7671387 0.1929534 -0.407593 0.8926778 0.1923394 -0.2761857 0.9408449 0.1962967 -0.4256216 0.8838107 0.1942294 -0.139501 0.9704808 0.1967391 -0.2183449 0.9566335 0.1928156 1.7982e-6 0.981068 0.1936641 0.1394934 0.9704821 0.1967384 5.24604e-6 0.981068 0.1936638 0.2761916 0.9408431 0.1962968 0.2183378 0.9566352 0.192815 0.4073978 0.8922411 0.1947636 -8.83299e-7 -1.37467e-6 1 0.5299888 0.8248153 0.1969556 2.62577e-6 -4.54816e-6 1 0.4257056 0.8839876 0.1932367 5.37561e-6 -7.96923e-6 1 0.6428117 0.7418797 0.1908075 -1.82792e-6 -3.16606e-6 1 9.20738e-6 -1.40987e-5 1 -1.33905e-6 -1.16023e-6 1 0.7411612 0.6421892 0.1956357 -1.64431e-6 -9.4934e-7 1 0.6115308 0.7668327 0.1949304 5.49578e-6 -7.50229e-6 1 0.8248164 0.5299873 0.1969555 -1.82951e-5 1.05619e-5 1 6.63331e-6 -9.20746e-6 1 0.7671392 0.6117733 0.1929531 0.8926769 0.4075947 0.1923395 0.9408432 0.2761917 0.1962962 0.8838118 0.4256193 0.1942291 0.9704822 0.1394934 0.1967383 0.9566343 0.2183427 0.1928146 0.981068 -1.79819e-6 0.1936634 0.9704836 -0.1394832 0.1967385 0.981068 2.91448e-6 0.1936638 0.9408419 -0.2761958 0.1962963 0.9566348 -0.2183405 0.1928144 0.8922427 -0.4073943 0.1947633 0.824819 -0.5299838 0.1969544 0.8839864 -0.4257087 0.1932358 0.8660414 -0.4999724 -2.44033e-7 0.4999735 -0.8660407 -1.13502e-6 0.5000482 -0.8659976 -3.37536e-7 1 -1.84147e-5 -2.5548e-7 0.8659964 -0.50005 -1.07271e-6 0.8660265 0.4999981 1.83152e-6 1 -1.28961e-4 -1.278e-6 0.4999981 0.8660265 1.57445e-6 0.8660471 0.4999624 1.44975e-6 -9.20726e-6 1 -9.36696e-7 0.4999583 0.8660494 1.99852e-6 -0.4999833 0.8660351 -4.91115e-7 -1.28962e-4 1 1.70134e-7 -0.8660368 0.4999804 2.01462e-7 -0.5000541 0.8659942 2.63796e-7 -1 9.20726e-6 0 -0.865996 0.5000512 -5.53528e-7 -0.8660265 -0.4999981 1.60724e-6 -1 1.38171e-4 -1.19282e-6 -0.4999941 -0.8660287 1.10083e-6 -0.8660472 -0.4999625 1.22549e-6 1.84147e-5 -1 -1.44765e-6 -0.4999514 -0.8660534 1.55601e-6 1.2896e-4 -1 -4.25945e-7 0.7818309 -0.6234905 -1.69457e-7 0.7818313 -0.62349 -1.51912e-7 0.6234905 -0.7818309 -1.52298e-7 0.9009678 -0.4338858 -1.44661e-7 0.9009671 -0.4338874 -1.94954e-7 0.9749292 -0.2225152 0 0.9749289 -0.2225169 -1.29548e-7 1 3.80253e-6 0 1 0 0 0.9749284 0.2225189 0 0.9749276 0.2225224 0 0.9009694 0.4338827 0 0.9009701 0.4338812 0 0.7818309 0.6234905 0 0.7818309 0.6234905 0 0.6234905 0.7818309 0 0.6234905 0.7818309 0 0.4338828 0.9009693 0 0.4338797 0.9009708 0 0.2225133 0.9749298 2.68737e-7 0.2225233 0.9749274 0 3.8025e-6 1 0 -3.80251e-6 1 3.25117e-7 -0.2225205 0.974928 2.35425e-7 -0.2225169 0.9749289 1.29548e-7 -0.4338843 0.9009686 1.44661e-7 -0.4338874 0.9009671 2.42215e-7 -0.6234905 0.7818309 2.37026e-7 -0.6234882 0.7818328 1.51912e-7 -0.7818332 0.6234877 2.19866e-7 -0.7818309 0.6234905 0 0.62349 -0.7818313 -1.69635e-7 -0.9009664 0.4338889 1.91682e-7 -0.9009642 0.4338936 0 -0.9749286 0.222518 1.77999e-7 -0.9749284 0.2225188 1.54021e-7 -1 -1.14076e-5 4.33485e-7 -1 0 0 -0.9749276 -0.2225224 0 -0.974925 -0.2225341 3.5024e-7 -0.9009708 -0.4338796 0 -0.9009723 -0.4338767 0 -0.7818309 -0.6234905 0 -0.7818309 -0.6234905 0 -0.6234905 -0.7818309 0 -0.6234905 -0.7818309 0 -0.4338828 -0.9009693 -2.45899e-7 -0.4338797 -0.9009708 -1.48536e-7 -0.2225161 -0.974929 0 -0.2225224 -0.9749276 -2.92851e-7 -7.605e-6 -1 -3.25115e-7 0 -1 0 0.2225277 -0.9749264 -1.29771e-7 0.2225205 -0.974928 -3.41381e-7 0.4338858 -0.9009678 -1.95279e-7 0.4338874 -0.9009671 -1.4516e-7 2.85008e-6 -4.93585e-6 1 4.27499e-6 -2.4685e-6 1 -9.21722e-6 -1.59607e-5 1 0 -1.34821e-5 1 7.78484e-6 0 1 -1.84139e-5 -3.1898e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.58195e-6 4.41242e-6 -1 -0.6609668 -0.7461815 -0.07960009 -1.42149e-6 4.23128e-6 -1 -1.42147e-6 4.23126e-6 -1 -0.7465499 -0.6612933 -0.07317388 -0.7793765 -0.6215243 -0.07924669 -1.77728e-6 4.67121e-6 -1 -0.5661283 -0.8204161 -0.08010077 -1.28413e-6 4.1146e-6 -1 -0.6216698 -0.7795569 -0.07627487 -1.25159e-6 4.25666e-6 -1 -0.4632668 -0.8826957 -0.07894378 -3.8805e-7 3.28198e-6 -1 -1.57457e-6 4.54943e-6 -1 -0.3535414 -0.9319548 -0.08042943 -1.80924e-6 4.81431e-6 -1 -0.4326204 -0.8983315 -0.07642078 -1.08672e-6 4.18073e-6 -1 -0.2386815 -0.9679505 -0.07812207 -1.617e-7 3.13656e-6 -1 -2.51565e-6 4.86189e-6 -1 -0.1201166 -0.989483 -0.08059376 -8.31945e-6 1.14135e-5 -1 -0.2218644 -0.9720563 -0.07669866 -1.02869e-6 3.2798e-6 -1 8.1949e-5 -0.9970217 -0.07712179 -1.76756e-6 4.1138e-6 -1 -8.7056e-6 1.19515e-5 -1 0.1201679 -0.9894767 -0.08059585 -9.76388e-7 3.2275e-6 -1 0 -0.9970211 -0.07712924 7.69352e-6 -5.42646e-6 -1 0.2385476 -0.968154 -0.07597857 0 3.15611e-6 -1 -3.28292e-6 5.75883e-6 -1 0.3533591 -0.9320239 -0.08042979 -1.66159e-6 3.92867e-6 -1 0.2218497 -0.9719809 -0.07769143 0 2.19126e-6 -1 0.4634303 -0.8829835 -0.0746507 -2.11695e-6 4.59285e-6 -1 -6.50018e-6 9.41507e-6 -1 0.5663237 -0.8202818 -0.080096 -9.60352e-7 3.16213e-6 -1 0.4325457 -0.8981968 -0.07840049 1.4573e-6 1.45759e-6 -1 0.6613797 -0.7464742 -0.07316631 0.7461056 -0.6610518 -0.07960599 0.6215295 -0.7793716 -0.07925212 0.8202819 -0.5663235 -0.08009594 0.7795533 -0.6216739 -0.07627755 0.8826875 -0.4632828 -0.0789417 0.9320239 -0.353359 -0.08042919 0.8983365 -0.4326109 -0.07641553 0.967996 -0.2384997 -0.07811307 0.9894756 -0.1201763 -0.08059602 0.9720543 -0.221871 -0.07670509 0.9970209 -7.35082e-5 -0.07713168 0.9894829 0.1201173 -0.08059388 0.9970214 4.14661e-6 -0.07712465 0.9681123 0.2387215 -0.07596445 0.9319556 0.3535388 -0.08042955 0.9719808 0.2218481 -0.0776965 0.8829797 0.4634366 -0.07465428 0.8204211 0.566121 -0.08010149 0.8981921 0.4325554 -0.07840275 0.7465419 0.6613023 -0.07317352 -1.58192e-6 4.41239e-6 -1 0.6609708 0.7461779 -0.07960045 0.7793722 0.6215294 -0.07924705 -2.03581e-6 4.29669e-6 -1 0.5661298 0.820415 -0.08010154 -6.46228e-6 9.29275e-6 -1 0.6216753 0.7795524 -0.07627534 -1.47781e-6 3.82551e-6 -1 0.4632826 0.8826873 -0.07894486 -8.03198e-7 3.06408e-6 -1 -1.76549e-6 4.04621e-6 -1 0.353531 0.9319587 -0.08042925 -2.28579e-6 4.63349e-6 -1 0.4326168 0.8983333 -0.0764203 -1.23448e-6 3.58166e-6 -1 0.2386754 0.967952 -0.0781219 -7.18553e-7 2.99928e-6 -1 -1.59237e-6 3.93861e-6 -1 0.1201314 0.9894813 -0.0805937 -1.5997e-6 3.94688e-6 -1 0.2218649 0.9720562 -0.07669907 -1.02868e-6 3.27979e-6 -1 -8.2107e-5 0.9970217 -0.07712125 -1.76758e-6 4.11381e-6 -1 -2.67968e-6 4.99819e-6 -1 -0.1201777 0.9894755 -0.08059555 -2.15598e-6 4.40709e-6 -1 -1.77712e-7 0.9970212 -0.0771287 -7.41251e-7 3.00832e-6 -1 -0.2385529 0.9681528 -0.07597845 -1.14084e-6 3.45935e-6 -1 -3.28302e-6 5.75893e-6 -1 -0.3533647 0.9320216 -0.08043003 -1.6616e-6 3.92867e-6 -1 -0.2218509 0.9719805 -0.07769173 0 2.19126e-6 -1 -0.4634234 0.882987 -0.07465165 -2.11685e-6 4.59277e-6 -1 -6.49979e-6 9.41464e-6 -1 -0.5663181 0.8202856 -0.08009654 -9.60303e-7 3.16208e-6 -1 -0.4325427 0.8981984 -0.07840102 1.45724e-6 1.45766e-6 -1 -0.6613793 0.7464743 -0.07316654 -0.7461094 0.6610474 -0.07960623 -0.6215292 0.7793718 -0.07925236 -0.8202766 0.5663311 -0.08009624 -0.7795529 0.6216742 -0.0762782 -0.882694 0.4632704 -0.0789417 -0.9320237 0.3533594 -0.08042991 -0.898337 0.4326097 -0.07641643 -0.9679954 0.238502 -0.07811373 -0.9894745 0.1201849 -0.0805962 -0.9720544 0.2218708 -0.07670557 -0.997021 8.23456e-5 -0.07713198 -0.9894813 -0.1201312 -0.08059275 -0.9970215 -1.10182e-5 -0.07712346 -0.968114 -0.2387152 -0.07596397 -0.9319505 -0.3535524 -0.08042979 -0.9719827 -0.2218395 -0.07769626 -0.8829917 -0.4634134 -0.07465648 -0.8204154 -0.5661294 -0.08010053 -0.898191 -0.4325577 -0.07840174 0 0 1 0.7411654 0.6421844 0.195635 0.642797 0.741892 0.1908088 0.6115291 0.7668341 0.1949299 -1.22731e-5 -1.89208e-5 1 0.8248174 0.5299859 0.1969544 3.08735e-5 3.08739e-5 1 0.7671388 0.6117739 0.1929526 -6.33483e-6 -1.3098e-5 1 0.8926841 0.4075798 0.1923377 -5.58567e-6 -1.22334e-5 1 7.35663e-6 2.15969e-6 1 0.94084 0.2762024 0.1962969 -2.81047e-6 -9.57364e-6 1 0.8838088 0.4256253 0.1942296 -4.27364e-6 -9.99455e-6 1 0.9704815 0.1394979 0.1967387 -8.72297e-7 -6.06924e-6 1 0.9566334 0.2183461 0.192815 6.19667e-6 0 1 0.981068 9.10935e-6 0.1936641 9.28514e-6 3.56427e-6 1 -2.69655e-5 -3.36458e-5 1 0.9704813 -0.1395007 0.1967371 -2.38259e-5 -3.00226e-5 1 0.9810682 -8.16052e-6 0.1936627 4.77594e-6 -1.40211e-6 1 0.9408382 -0.2762084 0.1962968 1.51597e-6 -5.16426e-6 1 0.9566355 -0.2183378 0.192814 4.02101e-6 -1.83592e-6 1 0.892248 -0.4073827 0.1947639 1.93662e-6 -4.24143e-6 1 2.74931e-6 -1.76661e-6 1 0.8248115 -0.5299955 0.196954 2.92848e-6 -2.92848e-6 1 -1.10381e-5 -1.7012e-5 1 0.8839848 -0.4257125 0.1932352 2.77921e-6 -2.40808e-6 1 0.7418805 -0.6428113 0.1908062 3.16606e-6 -1.8279e-6 1 4.977e-6 0 1 1.16023e-6 -1.33904e-6 1 0.6421886 -0.741162 0.1956341 -4.84688e-6 -1.00342e-5 1 0.766833 -0.611531 0.194929 2.28912e-6 -3.5625e-6 1 0.5299931 -0.824813 0.1969538 2.85505e-5 3.10242e-5 1 9.20742e-6 6.63328e-6 1 0.611774 -0.767139 0.1929516 -5.06978e-6 -1.12478e-5 1 0.407588 -0.8926804 0.1923375 -2.98555e-6 -8.8425e-6 1 2.92811e-6 -2.92879e-6 1 1.51602e-6 -5.16421e-6 1 0.2761966 -0.940842 0.1962955 4.77599e-6 -1.40206e-6 1 0.4256231 -0.8838102 0.1942282 7.78746e-7 -5.41788e-6 1 0.1394934 -0.9704822 0.1967381 -2.36082e-6 -9.04106e-6 1 0.2183477 -0.9566332 0.192814 9.28514e-6 3.56428e-6 1 1.79819e-6 -0.981068 0.1936634 6.19666e-6 0 1 -8.7243e-7 -6.06938e-6 1 -0.1394997 -0.9704812 0.1967387 -4.27386e-6 -9.99477e-6 1 4.43001e-6 -0.981068 0.1936637 -2.81043e-6 -9.5736e-6 1 -0.2761941 -0.9408425 0.1962963 7.35662e-6 2.15968e-6 1 -0.2183468 -0.9566332 0.1928149 1.31949e-5 6.5472e-6 1 -0.4073851 -0.8922469 0.1947636 1.24455e-5 5.68229e-6 1 -1.1827e-5 -1.8406e-5 1 -0.5299916 -0.8248137 0.196955 -1.2273e-5 -1.89207e-5 1 -0.4257045 -0.8839884 0.1932358 -4.26827e-5 -4.92622e-5 1 -0.6428016 -0.7418883 0.1908087 -0.7411596 -0.6421909 0.1956357 -0.6115296 -0.7668337 0.1949302 -0.8248153 -0.5299891 0.196955 -0.7671368 -0.6117762 0.1929531 -0.8926848 -0.4075779 0.1923382 -0.9408398 -0.2762024 0.1962973 -0.8838102 -0.4256221 0.19423 -0.9704806 -0.1395041 0.1967378 -0.9566353 -0.2183377 0.1928149 -0.9810681 -9.10935e-6 0.1936633 -0.9704812 0.1395005 0.196738 -0.9810681 -4.54658e-6 0.193663 -0.9408414 0.2761976 0.1962964 -0.956634 0.2183434 0.1928145 -0.8922488 0.407381 0.1947637 4.12392e-6 -2.64996e-6 1 -0.8248044 0.5300058 0.1969556 1.36438e-5 7.87669e-6 1 -0.8839907 0.4256998 0.193236 7.96914e-6 5.37547e-6 1 -0.7418829 0.6428077 0.1908084 -1.95644e-6 -9.51039e-6 1 7.4655e-6 0 1 1.16022e-6 -1.33905e-6 1 -0.6421832 0.7411661 0.1956359 9.49316e-7 -1.64434e-6 1 -0.766833 0.6115301 0.1949309 -4.4501e-6 -1.02458e-5 1 -0.530001 0.8248075 0.1969559 -1.05628e-5 -1.82963e-5 1 9.20742e-6 6.63329e-6 1 -0.6117743 0.7671381 0.192954 -0.407593 0.8926777 0.1923395 -0.2761857 0.940845 0.196296 -0.4256156 0.8838136 0.1942289 -0.1394988 0.9704813 0.1967387 -0.2183457 0.9566335 0.192815 1.7982e-6 0.9810679 0.1936638 0.1394819 0.9704836 0.1967391 -2.91446e-6 0.9810679 0.1936643 0.2761965 0.9408417 0.1962968 0.2183421 0.9566343 0.192815 0.4073908 0.8922442 0.1947638 0.5299974 0.8248102 0.1969548 0.4257111 0.8839853 0.1932359 0.4999793 0.8660373 1.78655e-7 0.8660413 0.4999724 -7.54901e-7 0.8659976 0.5000482 0 0 1 1.70299e-7 0.5000541 0.8659942 -6.1872e-7 -0.4999833 0.8660351 1.92493e-6 1.28961e-4 1 -1.02252e-6 -0.8660368 0.4999804 1.5121e-6 -0.4999446 0.8660573 1.51209e-6 -1 -9.20742e-6 -1.107e-6 -0.866062 0.4999367 1.9786e-6 -0.8660413 -0.4999724 -8.51448e-7 -1 -1.28962e-4 0 -0.4999793 -0.8660374 -1.78655e-7 -0.8659982 -0.5000471 0 0 -1 -1.70299e-7 -0.5000442 -0.8659999 -8.71314e-7 0.4999912 -0.8660304 1.47112e-6 -1.38171e-4 -1 -1.44829e-6 0.8660287 -0.4999942 1.12059e-6 0.4999555 -0.866051 1.0894e-6 1 9.20742e-6 -1.27729e-6 0.8660557 -0.4999475 1.61833e-6 1 1.38172e-4 0 0.6234882 0.7818328 1.52298e-7 0.6234919 0.7818299 0 0.7818309 0.6234905 0 0.4338889 0.9009664 0 0.4338859 0.9009678 1.44316e-7 0.2225169 0.9749289 1.87195e-7 0.2225205 0.974928 0 -3.8025e-6 1 3.25116e-7 0 1 2.16744e-7 -0.2225205 0.974928 2.35425e-7 -0.2225233 0.9749274 3.16905e-7 -0.4338783 0.9009716 2.42301e-7 -0.4338783 0.9009716 2.42215e-7 -0.6234905 0.7818309 2.37026e-7 -0.6234905 0.7818309 2.37151e-7 -0.7818309 0.6234905 2.19867e-7 -0.7818309 0.6234905 2.20272e-7 -0.9009715 0.4338781 1.91681e-7 -0.9009716 0.4338781 1.91579e-7 -0.9749282 0.2225196 3.4108e-7 -0.9749268 0.2225261 1.54021e-7 -1 -3.80251e-6 0 -1 -1.14076e-5 3.25115e-7 -0.9749298 -0.2225124 0 -0.9749298 -0.2225124 0 -0.9009686 -0.4338843 -2.89322e-7 -0.9009642 -0.4338936 0 -0.7818295 -0.6234924 0 -0.781835 -0.6234854 -3.0467e-7 -0.6234859 -0.7818346 0 -0.6234905 -0.7818309 -2.71346e-7 0.7818313 0.62349 0 -0.4338828 -0.9009693 -1.48259e-7 -0.433889 -0.9009664 -3.43488e-7 -0.2225224 -0.9749276 -2.68734e-7 -0.2225197 -0.9749282 -1.86936e-7 3.80253e-6 -1 -2.16745e-7 0 -1 -3.25116e-7 0.2225233 -0.9749274 -2.5954e-7 0.2225224 -0.9749276 -2.83567e-7 0.4338858 -0.9009678 -1.44661e-7 0.4338812 -0.9009701 -2.89478e-7 0.6234905 -0.7818309 -1.52298e-7 0.6234906 -0.781831 -1.52755e-7 0.7818309 -0.6234905 -1.52298e-7 0.7818309 -0.6234905 -1.52755e-7 0.9009664 -0.4338889 -4.33983e-7 0.9009708 -0.4338798 -1.44316e-7 0.9749298 -0.2225124 0 0.9749265 -0.2225269 -3.89484e-7 1 -7.60502e-6 -2.16747e-7 1 3.80251e-6 0 0.9749276 0.2225224 0 0.974928 0.2225205 -1.38831e-7 0.9009664 0.4338889 0 0.9009656 0.4338905 0 -4.93587e-6 -2.85009e-6 1 -2.46848e-6 -4.27502e-6 1 -2.46852e-6 -4.27498e-6 1 1.84207e-5 -1.84204e-5 1 0 -7.78487e-6 1 0 0 1 -4.93588e-6 -2.85009e-6 1 1.8421e-5 -1.84208e-5 1 0 -7.78494e-6 1 0 0 1 7.28502e-7 -1 5.96046e-7 -1 -7.28502e-7 2.98024e-7 -7.61615e-7 1 0 1 7.28502e-7 -2.98024e-7 -7.9473e-7 2.25173e-6 -1 1.19209e-6 -2.64909e-6 1 -0.7071048 -0.7071087 0 -0.7071089 0.7071048 0 0.7071047 0.7071089 0 0.707109 -0.7071047 0 0 -9.83427e-7 -1 0 8.3123e-7 1 -0.7071086 0.707105 -2.32831e-7 0.7071052 0.7071083 -2.06961e-7 0.7071084 -0.7071052 0 -0.7071051 -0.7071086 0 0 6.38056e-7 -1 0 -6.67325e-7 1 -6.92324e-6 4.84757e-6 -1 -0.8191598 0.5735655 0 0 0 -1 -0.5735642 0.8191578 -0.002123534 1.3487e-5 1.34871e-5 -1 -0.6835747 0.7298806 0 -0.3579841 0.9336221 -0.01404374 -0.4994332 0.866322 -0.007267713 -0.636125 0.7715852 -0.001140594 7.36892e-6 1.1561e-5 -1 -0.9659224 0.2588318 1.23421e-7 8.43113e-6 1.23047e-5 -1 -3.46223e-5 -1.99892e-5 -1 -1.01747e-5 0 -1 -0.8934365 0.4491897 2.1419e-7 -0.8594083 0.5112889 -0.001120865 -0.8178874 0.575368 -0.003472447 -0.8786236 0.4775149 -4.13112e-4 -0.756578 0.6538356 -0.009417533 -7.03801e-6 -6.15954e-7 -1 -0.9961922 -0.08718496 0 4.02095e-7 4.59413e-6 -1 -0.9659219 0.2588334 0 -3.46582e-5 -1.61608e-5 -1 -0.906314 -0.4226049 -3.02271e-7 5.61092e-6 1.20329e-5 -1 -0.9961922 -0.08718383 0 -0.7071068 -0.7071068 -5.05762e-7 -0.906314 -0.4226049 -3.02271e-7 -0.4226103 -0.9063116 -6.48245e-7 -0.7071068 -0.7071068 -5.05762e-7 -0.08719027 -0.9961917 -4.75021e-7 -0.4226049 -0.906314 -4.32164e-7 -2.05354e-6 7.66325e-6 -1 0.2588396 -0.9659203 -2.30293e-7 6.32144e-6 1.09488e-5 -1 -0.08718383 -0.9961922 -2.37511e-7 9.38941e-6 9.38929e-6 -1 0.5735598 -0.8191609 -0.002124369 -4.23458e-6 7.33442e-6 -1 0 1.01748e-5 -1 0.2588273 -0.9659236 -6.90882e-7 0.4610282 -0.8873855 -6.34708e-7 0 0 -1 0.8191628 -0.5735611 -3.47444e-7 0 0 -1 0.35803 -0.9336045 -0.01404201 0.4994186 -0.8663304 -0.007268667 0.636145 -0.7715687 -0.001140058 0.6835557 -0.7298984 -4.42463e-7 -3.30615e-6 8.85904e-7 -1 0.965924 -0.2588257 -1.23418e-7 -5.5681e-5 -3.5785e-5 -1 8.8537e-5 7.23911e-5 -1 0 0 -1 0.893437 -0.4491886 -2.1419e-7 0.7565876 -0.6538246 -0.009417057 0.8594099 -0.511286 -0.001121819 0.8178727 -0.5753889 -0.003474295 0.8786677 -0.4774337 -4.12391e-4 1.43878e-5 1.43878e-5 -1 0.996194 0.08716434 0 4.02029e-7 4.59406e-6 -1 0.9659236 -0.2588273 -1.85128e-7 0 0 -1 0.9063116 0.4226103 3.02274e-7 0 0 -1 0.996194 0.08716434 0 0.70711 0.7071035 3.37173e-7 0.9063127 0.4226077 2.01515e-7 0.4226077 0.9063127 6.48245e-7 0.7071068 0.7071068 5.05762e-7 0.08717733 0.9961929 7.12533e-7 0.4226077 0.9063127 6.48245e-7 0 0 -1 -0.2588334 0.9659219 9.21175e-7 0 0 -1 0.08717083 0.9961934 9.50044e-7 0 0 -1 0 0 -1 -0.2588273 0.9659236 6.90882e-7 -0.4610111 0.8873944 6.34714e-7 0.500001 -0.8660249 -4.12953e-7 0.8660249 -0.500001 -3.57629e-7 0.8660271 -0.499997 -2.38417e-7 -9.21175e-6 -1 -4.76837e-7 0.500001 -0.8660249 -4.12689e-7 -0.500001 -0.8660249 -4.12953e-7 -9.21175e-6 -1 -4.76837e-7 -0.8660231 -0.5000039 -3.57631e-7 -0.5000079 -0.8660209 -6.19426e-7 -1 0 0 -0.8660209 -0.5000079 -2.38422e-7 -0.8660249 0.500001 3.57629e-7 -1 0 0 -0.5000039 0.8660231 6.19428e-7 -0.8660249 0.500001 3.57629e-7 0 1 4.76837e-7 -0.499997 0.8660271 4.12954e-7 0.5000079 0.8660209 4.12951e-7 0 1 4.76837e-7 0.8660249 0.500001 3.57629e-7 0.500001 0.8660249 6.19429e-7 1 -9.21166e-6 0 0.8660249 0.500001 3.57629e-7 1 -9.21166e-6 0 0 0 1 -0.5735611 0.8191629 4.96221e-7 0 0 1 -0.8191585 0.5735646 0.00173372 0 0 1 -0.9912666 0.1287362 0.02859032 -0.9638044 0.2657365 0.02156555 -0.8287558 0.5595894 0.004853665 -0.7850084 0.6194825 0.001773118 -0.7504665 0.6609084 4.90631e-4 -0.7221351 0.6917521 4.18943e-7 8.85908e-7 -3.30614e-6 1 4.80903e-5 6.41125e-5 1 0 0 1 0 0 1 -0.646843 0.7625751 0.008569061 -0.5510343 0.8344799 0.002118468 0 0 1 -9.79378e-6 -1.39858e-5 1 0 0 1 0 0 1 0 0 1 -1.07899e-5 -2.75036e-5 1 0 0 1 0.8191616 -0.5735602 0.001733124 0 0 1 0 0 1 -6.01459e-6 -1.42091e-5 1 0.5735655 -0.8191598 -4.96219e-7 0 0 1 0.7221361 -0.691751 -4.19039e-7 0.9912627 -0.1287663 0.02858817 0.9638659 -0.2655125 0.02157682 0.8287208 -0.5596413 0.004849493 0.7850393 -0.6194434 0.001773536 0.7504675 -0.6609073 4.89832e-4 8.85906e-7 -3.30613e-6 1 -3.57862e-5 -5.56823e-5 1 -1.99891e-5 -3.4622e-5 1 0 -1.01748e-5 1 0.6468433 -0.7625748 0.00856769 0.5510364 -0.8344786 0.002117037 -6.15945e-7 -7.038e-6 1 4.5941e-6 4.02062e-7 1 -1.61608e-5 -3.46582e-5 1 1.20328e-5 5.61079e-6 1 -4.80503e-6 -1.22481e-5 1 0 0 1 -2.95162e-6 -1.95695e-5 1 1.01747e-5 0 1 -0.738708 -0.6240372 -0.2547312 -0.6197171 -0.619706 -0.4815758 -0.7945308 -0.603302 -0.06890201 -0.7035121 -0.637716 -0.3136703 -0.7786447 -0.6102164 -0.1461112 -0.7053387 -0.7051427 0.07260292 -0.8124563 -0.5829727 0.00759077 -0.8015665 -0.5958395 -0.04966425 -0.7051531 -0.7053278 0.07260745 -0.7050535 -0.705429 0.07259052 -0.7051891 -0.7052922 0.07260435 -0.8216089 -0.5065033 0.2615593 -0.7053448 -0.7051312 0.07265371 -0.8271853 -0.5482088 0.1234157 -0.8265104 -0.5502373 0.1188252 -0.0745927 0.2527979 0.9646393 -0.8215293 -0.5076935 0.2594934 -0.7312511 -0.2983755 0.6133872 0.6197022 0.6197019 0.4816002 0.3396981 0.5250918 0.78031 0.6197158 0.6197072 0.4815758 0.6196496 0.6197695 0.4815809 0.6197116 0.6197073 0.481581 0.6197155 0.619707 0.4815766 -0.6197878 -0.619634 0.4815774 -0.6197072 -0.6197158 0.4815759 -0.6197078 -0.6197142 0.4815773 -0.619705 -0.6197143 0.4815807 -0.619739 -0.6196813 0.4815794 -0.7052736 -0.7052078 -0.07260221 -0.7052769 -0.7052045 -0.07260215 0.6198251 0.6195905 -0.4815852 -0.7053743 -0.7051072 -0.07260149 0.6197549 0.6196599 -0.4815866 0.6197124 0.6197138 -0.4815719 0.6197101 0.6197044 -0.4815866 -0.6197165 -0.6197055 -0.481577 -0.618363 -0.6210495 -0.4815856 -0.6197151 -0.6196995 -0.4815866 0.7387028 0.6240431 -0.2547318 0.6197105 0.6197121 -0.4815764 0.7945298 0.6033042 -0.06889516 0.6738113 0.6461861 -0.3583602 0.7525722 0.6226561 -0.2143231 0.7829867 0.6088764 -0.1272857 0.7052088 0.7052721 0.07260656 0.8122762 0.5832229 0.007642924 0.7964813 0.6013023 -0.06366384 0.810137 0.5861645 -0.009446024 0.7053181 0.7051642 0.07259297 0.7052124 0.7052685 0.07260668 0.7051891 0.7052922 0.07260435 0.8196504 0.5094557 0.2619701 0.7051821 0.7053036 0.07256019 0.8253715 0.551128 0.1225559 0.8275169 0.5325474 0.1777892 0.08321601 -0.2591046 0.9622578 0.8192492 0.4917608 0.2949612 0.7711031 0.3648007 0.5218434 -0.6196934 -0.6197105 0.4816005 -0.4722703 -0.5791103 0.6645238 0.3222834 -0.05481076 0.9450551 0.6196812 0.6197388 0.4815797 0.7052077 0.7052735 -0.07260423 0.7053948 0.7050869 -0.07259845 -0.6195995 -0.6198341 -0.4815623 0.7051073 0.7053743 -0.07260036 -0.8210549 -0.5663974 -0.07115203 -0.6197158 -0.6197124 0.4815691 -0.6197144 -0.6197128 0.4815705 -0.6197053 -0.6197164 0.4815773 -0.6197116 -0.6197128 0.4815742 -0.6197127 -0.6197118 0.4815739 -0.6197161 -0.6197085 0.4815741 -0.7520734 -0.615341 0.2360953 -0.7538152 -0.6142745 0.2333011 -0.8210846 -0.5663215 -0.07141387 -0.8210865 -0.566318 -0.07142001 -0.8210809 -0.5663287 -0.07140076 -0.8210375 -0.5663984 -0.07134723 -0.8210807 -0.5663313 -0.07138043 -0.8210945 -0.5662974 -0.07149147 -0.8210778 -0.5663368 -0.07137101 -0.8210658 -0.5663643 -0.07129156 -0.8210893 -0.5663111 -0.07144296 -0.8210879 -0.5663141 -0.07143509 -0.8210814 -0.5663278 -0.07140278 -0.4846315 -0.5660027 0.6669132 -0.4761618 -0.5104311 0.7160518 -0.5218924 -0.5790433 0.6263684 -0.5156992 -0.4775177 0.7113587 -0.5643309 -0.5637128 0.603124 -0.5868153 -0.5196073 0.6210121 -0.589837 -0.3970716 0.7031546 -0.5950808 -0.5346095 0.6000597 -0.6196982 -0.6197171 0.4815858 -0.6323506 -0.5070335 0.5857046 -0.6197109 -0.6197096 0.4815791 -0.6626612 -0.350898 0.6616273 -0.6326603 -0.5122621 0.5807999 -0.619708 -0.6197115 0.4815802 -0.6717313 -0.4397385 0.5961603 -0.6197168 -0.6197046 0.4815778 -0.6958497 -0.359629 0.6216591 -0.6684071 -0.4630228 0.5821012 -0.619709 -0.6197115 0.4815792 -0.6984435 -0.3761284 0.6088548 -0.6197158 -0.6197052 0.4815787 -0.6968011 -0.386893 0.6039719 -0.6197112 -0.61971 0.4815782 -0.6950853 -0.3737092 0.6141645 -0.6197099 -0.619711 0.4815787 -0.7007535 -0.3635195 0.6138387 -0.619709 -0.6197117 0.4815788 -0.6739022 0.04118531 0.7376717 -0.6196978 -0.6197211 0.4815814 -0.6626796 -0.4217367 0.6188651 -0.698006 -0.277812 0.6600062 -0.6197158 -0.6197052 0.4815784 -0.5469326 0.08841985 0.8324943 -0.6197109 -0.6197098 0.4815789 -0.6209967 -0.4639835 0.6317296 -0.603104 -0.08674067 0.7929323 -0.6197057 -0.6197148 0.481579 -0.5414437 -0.2817198 0.7921317 -0.6197112 -0.61971 0.4815781 -0.5821392 -0.4935851 0.6461329 -0.6197067 -0.6197139 0.4815791 -0.5784618 -0.3803164 0.7216241 -0.6197058 -0.6197148 0.4815788 -0.5640193 -0.4953256 0.6607079 -0.5331878 -0.4137747 0.7379034 -0.619712 -0.619709 0.4815784 -0.5495437 -0.4921574 0.6751168 -0.6197085 -0.619712 0.481579 -0.5509755 -0.5067539 0.6630436 -0.6197112 -0.6197097 0.4815784 -0.541461 -0.481765 0.6890011 -0.6197099 -0.6197108 0.4815788 -0.5335029 -0.4932487 0.687081 -0.6197049 -0.6197154 0.4815793 -0.5403518 -0.5146362 0.6657099 -0.5414385 -0.5025845 0.6739831 -0.6197103 -0.6197106 0.4815786 -0.5389551 -0.5246344 0.6590038 -0.6197069 -0.6197135 0.4815793 -0.528396 -0.5027623 0.6841256 -0.6197096 -0.6197112 0.4815786 -0.5350829 -0.5318784 0.6563473 -0.5204576 -0.5090546 0.6855563 -0.6197091 -0.6197116 0.4815789 -0.5305784 -0.5387335 0.6544103 -0.6197102 -0.6197107 0.4815786 -0.5147436 -0.5165678 0.6842491 -0.6197078 -0.6197128 0.4815789 -0.5232732 -0.5432879 0.6565237 -0.5115509 -0.5251153 0.6801247 -0.6197113 -0.6197098 0.4815784 -0.5208837 -0.5514073 0.6516366 -0.6197068 -0.6197139 0.4815788 -0.5085203 -0.5404115 0.6703451 -0.5152755 -0.5377792 0.6672966 -0.6197074 -0.619714 0.4815782 -0.5145677 -0.5555834 0.6531057 -0.6197078 -0.6197135 0.4815781 -0.498748 -0.5402066 0.6778106 -0.619707 -0.6197136 0.4815789 -0.5104382 -0.5596889 0.6528409 -0.6197114 -0.6197096 0.4815785 -0.4971431 -0.5496141 0.6713964 -0.5062107 -0.5509276 0.663498 -0.6197113 -0.6197098 0.4815783 -0.4969215 -0.5563691 0.6659748 -0.619709 -0.6197116 0.4815788 -0.6197071 -0.6197136 0.481579 -0.497235 -0.5532034 0.6683737 -0.6197062 -0.6197143 0.4815791 -0.4954934 -0.5566151 0.6668327 -0.6197093 -0.619712 0.4815781 -0.6197087 -0.6197124 0.4815782 -0.4954829 -0.556455 0.6669741 -0.5101478 -0.5632171 0.6500275 -0.6197078 -0.6197121 0.4815797 -0.4937604 -0.5553011 0.6692095 -0.619711 -0.6197096 0.4815792 -0.4927491 -0.554599 0.6705358 -0.4919075 -0.5545587 0.6711868 -0.4869188 -0.5521143 0.6768158 -0.6197127 -0.6197085 0.4815782 -0.506501 -0.5666235 0.6499189 -0.6197068 -0.6197136 0.4815795 -0.6197067 -0.6197136 0.4815795 -0.4889761 -0.5540765 0.6737223 -0.4954944 -0.5561672 0.6672055 -0.6197073 -0.6197138 0.4815783 -0.507475 -0.5755321 0.6412737 -0.6197082 -0.6197131 0.4815781 -0.6197113 -0.61971 0.4815778 -0.4815498 -0.5589888 0.6750121 -0.5014706 -0.5643535 0.6557685 -0.6197087 -0.6197119 0.4815791 -0.5015959 -0.5830713 0.6390847 -0.6197105 -0.6197105 0.4815786 -0.4769526 -0.5708596 0.6683079 -0.486542 -0.5677608 0.6640213 -0.6197065 -0.6197131 0.4815804 -0.4898997 -0.5894817 0.6422691 -0.6197197 -0.6197054 0.4815732 -0.6197111 -0.6197108 0.4815772 -0.6197119 -0.6197103 0.4815769 -0.6196872 -0.6197284 0.4815854 -0.619709 -0.6197113 0.4815791 -0.4588087 -0.5722393 0.6797329 -0.001972258 -0.9533589 0.3018326 -0.3812472 -0.8335869 0.3997294 -0.4760569 -0.5862447 0.6555051 -0.07683867 -0.9568587 0.2802094 -0.2512935 -0.9326155 0.2589976 -0.07415086 -0.9629792 0.2591768 -0.4020019 -0.8841681 0.2379944 -0.29291 -0.9305229 0.2198429 -0.5304631 -0.8245521 0.1967806 -0.6156973 -0.7582194 0.214523 -0.5140597 -0.8298822 0.2168826 -0.6207826 -0.7682819 0.1561152 -0.6370041 -0.7403365 0.2147733 -0.6210444 -0.7579367 0.1995895 -0.6396345 -0.7406138 0.2058127 -0.6409715 -0.737369 0.2131721 -0.6393427 -0.7401304 0.2084419 -0.6405571 -0.737656 0.2134253 -0.6408315 -0.7377998 0.2120996 -0.6422717 -0.7357887 0.2147137 -0.6408245 -0.737785 0.2121729 -0.644224 -0.7353781 0.2102248 -0.6478348 -0.7308312 0.214932 -0.644964 -0.7362497 0.204836 -0.6527462 -0.7278569 0.2101112 -0.6583483 -0.7213685 0.2149537 -0.6549869 -0.7292764 0.1978592 -0.6672111 -0.715154 0.2082885 -0.6760227 -0.7030998 0.2205539 -0.671292 -0.7165832 0.1894088 -0.6901447 -0.6956367 0.1994745 -0.6999926 -0.678362 0.2232382 -0.6924014 -0.6959475 0.1903606 -0.7142429 -0.6645303 0.2196735 -0.7170006 -0.6727876 0.1823925 -0.73197 -0.6494055 0.2061364 -0.7418764 -0.6311426 0.2264472 -0.7371896 -0.6477243 0.1923661 -0.7597276 -0.6219991 0.189555 0.6197071 0.6197227 -0.4815672 0.6711862 0.6326945 -0.3862727 0.6816843 0.6375112 -0.359007 0.6197059 0.6197133 -0.4815809 -0.8210823 -0.5663265 -0.07140076 0.619714 0.6197298 -0.481549 0.6197022 0.6197031 -0.4815986 -0.8210845 -0.5663208 -0.07142144 -0.8210852 -0.566315 -0.07145899 -0.821079 -0.5663392 -0.07133799 -0.8210842 -0.5663218 -0.07141745 -0.8210861 -0.5663157 -0.07144391 -0.8210804 -0.566332 -0.07137894 0.6197101 0.6197108 -0.4815787 -0.08545655 0.301122 -0.9497488 0.6197128 0.619706 -0.4815812 0.6197127 0.6197065 -0.4815809 0.619718 0.619698 -0.4815849 0.6196991 0.6197264 -0.4815727 0.6197102 0.6197106 -0.4815785 0.6196982 0.619726 -0.4815742 0.6197153 0.6197068 -0.481577 0.6197084 0.6197134 -0.4815775 0.6197161 0.6197077 -0.481575 -0.8210847 -0.5663211 -0.07141691 -0.609582 -0.04769009 -0.7912873 0.6197104 0.6197106 -0.4815785 -0.06764507 0.2077493 -0.9758403 0.6197141 0.6197057 -0.4815802 0.6197057 0.6197163 -0.4815772 0.6197145 0.6197056 -0.4815796 0.6197021 0.6197198 -0.4815772 0.619719 0.6197013 -0.4815793 0.6197088 0.619712 -0.4815787 -0.5209667 -0.09035658 -0.8487811 0.6197075 0.6197131 -0.4815789 -0.05900591 0.1007075 -0.9931648 0.619708 0.6197125 -0.4815791 0.6197044 0.6197168 -0.4815784 0.6197101 0.6197105 -0.481579 0.6197041 0.6197167 -0.4815788 -0.4509546 -0.1620764 -0.8777079 0.6197088 0.6197118 -0.4815791 -0.03104031 0.006982088 -0.9994938 0.6197053 0.6197157 -0.4815783 0.6197113 0.6197094 -0.4815787 -0.4276859 -0.28775 -0.8569041 0.6197088 0.6197121 -0.4815785 0.007496654 -0.06487911 -0.997865 0.619709 0.619712 -0.4815785 0.6197121 0.6197088 -0.4815787 -0.3792613 -0.3906142 -0.8387976 0.6197085 0.6197122 -0.4815788 -0.01886332 -0.1834192 -0.9828538 0.6197074 0.6197135 -0.4815787 -0.2513461 -0.3983821 -0.8821093 0.6197074 0.6197133 -0.4815791 -0.0629267 -0.2966383 -0.9529145 0.6197071 0.6197134 -0.481579 0.6197118 0.6197094 -0.4815784 0.02391821 -0.2461641 -0.9689329 0.6197114 0.6197097 -0.4815784 -0.1081057 -0.3503181 -0.9303711 0.6197082 0.6197125 -0.4815787 -0.1007305 -0.4136 -0.9048693 0.6197085 0.6197122 -0.4815788 0.6197086 0.6197116 -0.4815794 0.0181753 -0.2986834 -0.9541792 0.6197074 0.6197136 -0.4815787 -0.001895129 -0.2965244 -0.9550234 0.6197089 0.6197113 -0.4815795 0.01761662 -0.3028346 -0.9528803 0.00782901 -0.3124229 -0.9499109 0.6197077 0.6197127 -0.4815793 0.01685047 -0.301278 -0.9533875 0.6197085 0.6197118 -0.4815796 0.6197096 0.6197108 -0.4815793 -0.07659018 -0.4222733 -0.9032272 0.6197074 0.6197135 -0.4815785 0.06644558 -0.3136833 -0.9472 0.6197103 0.6197102 -0.481579 0.01326638 -0.3146716 -0.9491078 0.61971 0.6197098 -0.4815803 -0.3201125 -0.7577875 -0.5685825 0.6197055 0.619715 -0.481579 0.6197124 0.6197078 -0.4815794 0.3195073 -0.4670056 -0.8245126 0.6197125 0.6197078 -0.4815794 0.08201301 -0.3402947 -0.9367355 0.6196836 0.6197419 -0.4815725 0.6306304 -0.4204817 -0.652304 0.3090647 -0.5796808 -0.7539557 0.6196879 0.6197372 -0.4815732 0.7904868 -0.3415179 -0.5084251 0.6570813 -0.5406989 -0.5252513 0.6196895 0.6197355 -0.4815735 0.8649529 -0.3383301 -0.3706606 0.8002392 0.3568854 -0.4819232 0.8651979 -0.2871932 -0.4110385 0.911363 -0.1847121 -0.3678301 0.836717 -0.4811098 -0.2616068 0.9085465 -0.1894358 -0.3723671 0.6865129 0.6250432 -0.3715119 0.6912997 0.6243537 -0.3637132 0.6813724 0.6304025 -0.3719197 0.6935011 0.6281796 -0.3527697 0.6763649 0.6350894 -0.3730844 0.6858282 0.6316955 -0.3613871 0.6844135 0.6350742 -0.3581326 0.677954 0.6400458 -0.3615522 0.6817403 0.6376779 -0.3586043 0.6774584 0.6415789 -0.3597592 0.6717735 0.6375437 -0.3771716 0.6778165 0.640899 -0.3602964 0.6774373 0.6415767 -0.3598029 0.6778085 0.6414543 -0.3593214 0.678135 0.6419005 -0.3579059 0.6776589 0.6414634 -0.3595874 0.6730651 0.6417529 -0.3676091 0.6760879 0.6407246 -0.3638365 0.6773282 0.6414134 -0.3602988 0.6770744 0.6421931 -0.3593863 0.6702298 0.644412 -0.3681373 0.6747065 0.6426834 -0.3629451 0.6759393 0.6449047 -0.3566567 0.666656 0.6476354 -0.3689693 0.6718582 0.6455501 -0.3631415 0.672553 0.6487613 -0.3560634 0.6655501 0.6529564 -0.361512 0.6698463 0.6509314 -0.3572036 0.6602303 0.6556146 -0.3664222 0.6642482 0.6516097 -0.3663049 0.6652598 0.6574391 -0.3538406 0.6568864 0.6596605 -0.3651688 0.6623752 0.6613311 -0.3519949 0.6535705 0.6634784 -0.3642006 0.6586644 0.6651766 -0.3517121 0.6504159 0.6671236 -0.3631879 0.6546526 0.6694323 -0.3511274 0.6480286 0.6716763 -0.3590402 0.6500143 0.6735209 -0.3519247 0.6450635 0.6747416 -0.3586319 0.6405817 0.6761243 -0.3640207 0.6453918 0.6792759 -0.3493618 0.635732 0.6926803 -0.3406446 0.6250311 0.6883679 -0.368084 0.6357743 0.6917481 -0.3424552 0.6036183 0.7437867 -0.2870997 0.6020206 0.7074551 -0.3702414 0.6122237 0.7187529 -0.3295092 0.5655655 0.7646926 -0.3088384 0.5728065 0.7278877 -0.3769246 0.5446848 0.7953791 -0.265877 0.5363097 0.7683357 -0.3493309 0.5440636 0.7487639 -0.3786125 0.5204873 0.7876255 -0.329756 0.5377938 0.7560641 -0.3730215 0.5437606 0.7540305 -0.3684595 0.537409 0.7565485 -0.3725937 0.5579645 0.7461156 -0.3633002 0.5717524 0.7161785 -0.4002342 0.5819571 0.7242968 -0.3697568 0.612001 0.6672595 -0.4245226 0.618592 0.7023863 -0.3521327 0.5954672 0.708274 -0.3791659 0.6311486 0.6574361 -0.4116179 0.6547966 0.668061 -0.3534625 0.6302052 0.6837661 -0.3678388 0.6756091 0.6542733 -0.3398216 0.6506439 0.6510805 -0.390841 0.8185548 0.5725011 0.04701882 0.8210809 0.5663267 0.07141661 0.8210837 0.5663232 0.07141184 0.817718 0.5739873 0.0433126 0.8227866 0.5614143 0.08852189 0.8246271 0.5563967 0.1020444 0.7996053 0.5962127 0.07184606 0.7932835 0.6051406 0.06712651 0.7919235 0.6084765 0.05112266 0.7898465 0.6046459 0.1026929 0.7969728 0.6024302 0.04372978 0.8297246 0.5533444 0.07326108 0.8329321 0.5432679 0.1052806 0.8307256 0.5521128 0.07117891 0.5819673 -0.8131251 -0.01189839 0.544246 -0.8388152 0.01361739 0.8112127 0.5798528 0.07552874 0.8103927 0.582047 0.06696909 0.8145045 0.575941 0.0698167 0.8310335 0.5532011 0.05789542 0.823583 0.5545934 0.1189006 0.7985898 0.5979061 0.06901186 0.8010163 0.5894441 0.1045396 0.7987431 0.5977272 0.06878852 0.8100385 0.5779572 0.09901052 0.7931634 0.6046988 0.07232666 0.7948005 0.5988213 0.09851491 0.7999811 0.5890237 0.114373 0.787863 0.6115692 0.07249158 0.7898655 0.6028805 0.1124623 0.7893615 0.6097257 0.07171499 0.783095 0.617656 0.07254838 0.7844696 0.6119457 0.1006472 0.7850197 0.6153039 0.0717296 0.7903378 0.6033928 0.1062219 0.7790636 0.6227369 0.07251614 0.7802726 0.6173973 0.09997737 0.7811669 0.6201776 0.07181876 0.7830626 0.6120996 0.1102141 0.7759352 0.6266421 0.07241666 0.7771455 0.6206849 0.1038994 0.777929 0.6242188 0.07195413 0.7777349 0.6193539 0.1073737 0.7741211 0.6288985 0.07227182 0.775277 0.622924 0.104457 0.7754498 0.6272779 0.07211118 0.7734055 0.6297804 0.07225412 0.7744919 0.6241911 0.102703 0.7738683 0.6292254 0.07213455 0.775186 0.6229344 0.105068 0.7734953 0.6296769 0.07219481 0.7745839 0.624106 0.1025252 0.7733409 0.6298627 0.07222729 0.7743067 0.6286829 0.07215964 0.7753627 0.6235592 0.09993231 0.7736481 0.629481 0.07226675 0.7749519 0.6241953 0.09914571 0.7750253 0.6277937 0.07218635 0.7760273 0.6231612 0.09721952 0.7744753 0.628465 0.07224822 0.7752752 0.6274836 0.0721988 0.776436 0.6217927 0.1025723 0.7750779 0.6277253 0.07221609 0.7756109 0.6228467 0.1024203 0.7751131 0.6276816 0.07221794 0.7762992 0.6217454 0.1038855 0.7752826 0.627474 0.07220292 0.7762511 0.6218366 0.1036999 0.7745595 0.6283625 0.07223629 0.7757371 0.6223418 0.104512 0.7750641 0.6277455 0.07219088 0.7734522 0.629717 0.07230693 0.7745158 0.6243126 0.1017799 0.7735028 0.6296591 0.07226943 0.7744615 0.6284894 0.0721839 0.7756471 0.622342 0.1051762 0.7716754 0.6318897 0.07233709 0.7726812 0.6264846 0.1023759 0.7719404 0.6315878 0.07214593 0.7733722 0.625014 0.1060796 0.769401 0.6346528 0.07237362 0.7703317 0.6292198 0.1033023 0.7696998 0.634314 0.07216656 0.7666656 0.6379477 0.07243275 0.767443 0.6331412 0.1008141 0.7670423 0.6375226 0.07218605 0.7697829 0.629221 0.107308 0.7635239 0.6416973 0.07249671 0.764259 0.6353203 0.1107985 0.7640162 0.6411448 0.07219815 0.7600007 0.6458578 0.07257181 0.7605261 0.6412214 0.1021533 0.7606807 0.6450989 0.07219672 0.7649011 0.635566 0.1047948 0.75613 0.6503757 0.07265537 0.7564955 0.6460611 0.1015866 0.7570785 0.6493232 0.07219171 0.7586846 0.6418933 0.1112239 0.7518573 0.6558485 0.06762623 0.7521314 0.6505052 0.1055524 0.7493197 0.6583333 0.07153666 0.7474962 0.6604048 0.07151842 0.747536 0.6565567 0.1006146 0.7509974 0.6507437 0.1119624 0.7380312 0.6706776 0.07417201 0.7380096 0.6702018 0.07855731 0.7419231 0.6614077 0.1099548 0.722738 0.6872239 0.07330226 0.7223249 0.6860644 0.08696353 0.7229411 0.6870375 0.07304656 0.7365103 0.6725735 0.07209283 0.7311687 0.6725452 0.1143482 0.7071077 0.7032286 0.07394641 0.7054144 0.7013667 0.1023485 0.709202 0.7013183 0.07200956 0.719527 0.6865893 0.1042886 0.6918208 0.7182565 0.07410538 0.6897834 0.7172238 0.09893792 0.6956052 0.7148542 0.07153201 0.7064709 0.7011611 0.0962916 0.6902194 0.7152482 0.1096231 0.677182 0.732087 0.07398045 0.6734739 0.7312469 0.1082175 0.6823762 0.7275069 0.07138907 0.6634262 0.7446051 0.07368093 0.6601685 0.7445263 0.09928882 0.6696543 0.7392293 0.07143622 0.6733002 0.7313051 0.108902 0.6506882 0.7557965 0.07332563 0.6474381 0.7561118 0.09549313 0.6576458 0.7499194 0.07157433 0.6526748 0.7478458 0.1214173 0.638058 0.7665048 0.07315999 0.6287652 0.7673999 0.1255058 0.6463779 0.7596418 0.07169306 0.6167267 0.7838586 0.07220721 0.6125442 0.7849592 0.0928902 0.6139811 0.7858767 0.07365518 0.6343547 0.769722 0.07156902 0.6327856 0.7659794 0.1133929 0.5752013 0.8145758 0.07489842 0.5756468 0.814413 0.07322603 0.5838053 0.8087341 0.07155907 0.5767825 0.7998522 0.166007 0.513529 0.8547856 0.07503134 0.47297 0.8635182 0.1750303 0.5441908 0.8361303 0.06886589 0.438933 0.8956706 0.07149821 0.4406166 0.8951042 0.06815713 0.4428706 0.8938179 0.07039487 0.4965925 0.86524 0.06896114 0.4764514 0.8627602 0.1692305 0.3541224 0.9325505 0.0703333 0.1852338 0.9345946 0.3036798 0.3852819 0.9204842 0.06532067 0.2649592 0.9619313 0.06696921 0.2674992 0.961443 0.06380981 0.3150095 0.9470711 0.0618503 0.282754 0.9382866 0.1991688 0.1943268 0.9789119 0.06299662 0.0669201 0.9782042 0.1965664 0.237928 0.9694821 0.05911684 0.153975 0.9862586 0.05988049 0.1358569 0.98764 0.07816642 0.1772442 0.9824936 0.05736398 0.1144312 0.9809997 0.1566686 0.1427884 0.9880463 0.0581035 0.1053992 0.9898813 0.09500449 0.1456275 0.9876587 0.05764514 0.1572736 0.9858216 0.05848753 0.1191482 0.9881333 0.09693461 0.1524361 0.9865205 0.05950289 0.127716 0.9887749 0.07754248 0.2003177 0.9778946 0.05995863 0.2011076 0.977785 0.05909538 0.1955798 0.9787875 0.0610212 0.2742591 0.9597111 0.06112748 0.226911 0.9665435 0.1196032 0.2614181 0.9631142 0.0638104 0.2662572 0.9638936 0.004034757 0.3743649 0.9251948 0.06217348 0.3841648 0.9221031 0.04629504 0.3412616 0.9375058 0.06799572 0.4778967 0.8760449 0.06449878 0.444729 0.8851877 0.1365973 0.4247778 0.9024785 0.07139056 0.4558673 0.8893002 -0.0364688 0.5718517 0.8174033 0.06955194 0.5780395 0.8147032 0.04614162 0.5750288 0.8152808 0.06825673 0.5020774 0.8617915 0.07234448 0.6574711 0.7505149 0.06677782 0.6428656 0.7490888 0.1599679 0.6395254 0.7652208 0.07378721 0.5949345 0.8037284 0.008577704 0.7307483 0.6794596 0.06589055 0.7279552 0.6706352 0.1425822 0.6989448 0.7110781 0.07644689 0.7056422 0.7084805 0.01115876 0.7522913 0.6544525 0.07582694 0.7499831 0.6612617 0.01607263 0.7903778 0.6012498 0.1174806 0.6936942 0.7069497 0.1378782 0.6468877 0.7622874 0.02131229 0.7016335 0.7048954 0.1040825 0.5409803 0.8213765 0.180779 0.5215649 0.8529584 0.02078461 0.5603095 0.816084 0.1416341 0.406244 0.9076306 0.1057004 -0.04407787 0.8458635 0.5315753 0.2902363 0.9565466 0.02795314 0.4008578 0.9138497 0.06474435 0.07860195 0.9797772 0.1840066 0.1874247 0.9819886 0.02388048 0.2086464 0.9754987 0.06977796 0.1711117 0.9847294 0.03207772 0.1671233 0.9851998 0.03809303 0.2016515 0.9789466 0.03162378 0.3698397 0.9233947 -0.1027662 0.330251 0.9430176 0.04064553 0.2329013 0.9720851 0.02841657 0.4677044 0.8800293 -0.08246821 0.4509558 0.8909109 0.05400604 0.4359555 0.8989421 -0.04296344 0.5157654 0.856505 0.01962924 0.5876955 0.8037442 -0.09278601 0.5898719 0.8061486 0.04664266 0.528925 0.8479697 0.03443711 0.6320225 0.7741203 -0.03584951 0.6385577 0.7682728 0.04473245 0.6070134 0.7935906 0.04181593 0.6498045 0.7586647 0.04671329 0.6463516 0.7626054 0.02574169 0.6612376 0.7490699 0.04073309 0.6716096 0.7390782 0.05199867 0.6641377 0.7469655 0.03104388 0.6839689 0.7276955 0.05143684 0.6806612 0.7319782 0.03014194 0.6969321 0.7154914 0.04855561 0.6954107 0.7177318 0.03556489 0.7100387 0.7024343 0.04930841 0.7089643 0.7041098 0.03998816 0.7232714 0.6883832 0.05483669 0.7212871 0.6914862 0.03989869 0.7365096 0.6736461 0.06127458 0.7321516 0.6801661 0.03644359 0.7490933 0.6597512 0.05989742 0.7416259 0.6698759 0.03546023 0.7560217 0.6531122 0.04331016 0.7502311 0.6595676 0.04608595 0.7596071 0.6487657 0.04582709 0.7568326 0.6525092 0.03789842 0.762558 0.6456023 0.0412693 0.7657347 0.6415225 0.04581648 0.7626485 0.6455551 0.04032063 0.7682254 0.6386157 0.04471832 0.7670691 0.6403021 0.04022896 0.7703255 0.6361396 0.04387485 0.7718893 0.6341742 0.04483366 0.7704824 0.6360692 0.04210501 0.7726578 0.6333898 0.04263013 0.7732894 0.6325686 0.04336208 0.7726663 0.6333878 0.04250544 0.7734478 0.6324222 0.04267042 0.7732897 0.6325796 0.04319709 0.7734205 0.6324166 0.0432434 0.7729223 0.6328167 0.04619872 0.7728725 0.632889 0.04604107 0.7721658 0.6336948 0.04680716 0.771769 0.6342859 0.04532235 0.7722065 0.6336718 0.04644441 0.7722249 0.6337878 0.04451709 0.7737223 0.6319839 0.04416018 0.7723287 0.633779 0.04280966 0.7762049 0.6288495 0.04532545 0.7743545 0.6315079 0.03965997 0.7789682 0.6257324 0.04083526 0.7831577 0.6200822 0.04650098 0.7790632 0.6257065 0.03939485 0.7861623 0.6170889 0.03391492 0.7970287 0.6018639 0.05005156 0.7859588 0.6169466 0.04056525 0.8143555 0.5763265 0.0683577 0.7973185 0.5993531 0.07112562 0.8035002 0.5944562 0.03176802 0.829059 0.5561714 0.05774611 0.814905 0.578635 0.03333574 0.5819673 -0.8131251 -0.01189833 0.6886509 -0.7193964 -0.0907132 0.5959964 -0.8020408 -0.03896963 0.8283709 0.5587465 0.04005044 0.4195283 -0.9073948 -0.02511197 0.3031651 -0.9516791 0.04896932 0.3031651 -0.9516789 0.04896932 0.4656267 -0.882673 0.06387615 0.3577852 -0.9272376 0.1105446 0.7046155 0.7068412 -0.06238853 0.4657433 -0.8830005 0.05825191 0.419531 -0.9073936 -0.0251109 0.5368295 -0.8370536 -0.1056185 -0.3498604 -0.9344664 -0.06610822 -0.4001197 -0.9163783 0.01246094 -0.3498601 -0.9344665 -0.06610816 -0.5543193 -0.8292516 -0.071217 -0.5939115 -0.8000013 0.08524739 -0.5900989 -0.8072743 0.00955826 0.04658424 -0.997714 -0.04895681 -0.04944175 -0.9984165 0.02683162 0.04658138 -0.9977141 -0.0489577 -0.4001165 -0.9163796 0.01246351 -0.04944217 -0.9984166 0.02683109 0.1608214 -0.9771641 -0.1388769 0.5368292 -0.8370537 -0.1056203 -0.280479 -0.9453237 -0.1664177 0.1608204 -0.977164 -0.1388794 -0.5559103 -0.8278974 -0.07449567 -0.5214673 -0.8345452 -0.1777811 -0.2804739 -0.9453262 -0.1664113 -0.8537997 -0.5173106 -0.05844467 -0.8522626 -0.5208345 -0.0487861 -0.8605287 -0.5045324 -0.07026726 -0.8263021 -0.5598396 -0.06168049 -0.8192329 -0.5733158 -0.01290816 -0.8432371 -0.5321217 -0.07614254 -0.8274031 -0.5602145 0.03954172 -0.8287448 -0.5584602 0.03611099 -0.8317959 -0.5543774 0.02794921 -0.8385666 -0.5447489 0.007410049 -0.8450156 -0.5345071 -0.01583999 -0.7982545 -0.5990204 -0.06296348 -0.7928897 -0.6092091 -0.01379209 -0.8160454 -0.5704293 -0.09316909 -0.7990736 -0.5998271 0.04109477 -0.7710258 -0.6323087 -0.07553082 -0.7658269 -0.6430435 -0.002074539 -0.7751735 -0.6258826 -0.08588975 -0.7690515 -0.6379345 0.03999155 -0.7433823 -0.665198 -0.06996005 -0.7394183 -0.6728478 0.02316099 -0.7167756 -0.6941764 -0.0659691 -0.7171969 -0.6968633 -0.00319612 -0.7355348 -0.6720151 -0.08593207 -0.738292 -0.6739033 0.02791875 -0.6909033 -0.719494 -0.07057672 -0.6943726 -0.7196074 0.00345236 -0.6979054 -0.7112703 -0.08380144 -0.7039414 -0.7091082 0.04039788 -0.6676029 -0.7403943 -0.07824784 -0.6752792 -0.7374058 0.01519036 -0.6664185 -0.7418076 -0.07488584 -0.6503176 -0.7564508 -0.06977921 -0.6585644 -0.7525197 0.002622961 -0.6725004 -0.7394188 0.03167086 -0.6358005 -0.7686426 -0.07033014 -0.6477468 -0.7616028 0.01962733 -0.6419917 -0.7627826 -0.07752144 -0.6243497 -0.7777752 -0.07248038 -0.6366392 -0.7711395 0.005857765 -0.6254839 -0.7766597 -0.07462978 -0.6473393 -0.7618395 0.02350354 -0.616362 -0.7841759 -0.07187455 -0.6308705 -0.7757493 0.01468878 -0.6109676 -0.7884289 -0.07140272 -0.6252513 -0.7803779 0.008436501 -0.6146138 -0.7853931 -0.0735374 -0.6305618 -0.7759292 0.01804858 -0.6076369 -0.7909609 -0.07182025 -0.6226547 -0.7824366 0.009715318 -0.6085046 -0.7902035 -0.072806 -0.6062882 -0.7919809 -0.07197874 -0.6220995 -0.7828246 0.01333779 -0.6063345 -0.7919382 -0.07205814 -0.6066653 -0.7916849 -0.07205706 -0.6218317 -0.783093 0.009520649 -0.6221445 -0.7828415 0.009774208 -0.6064242 -0.7919141 -0.07156747 -0.6216164 -0.7832577 0.01002967 -0.6069389 -0.7914932 -0.07185846 -0.599485 -0.7972847 -0.07039082 -0.6149706 -0.7885153 0.007405757 -0.6027789 -0.7945224 -0.0734291 -0.6210823 -0.783544 0.01776683 -0.5831573 -0.8093602 -0.06974118 -0.6020258 -0.7983543 0.01397985 -0.5867822 -0.8062971 -0.07464432 -0.5595262 -0.8106958 -0.1723449 -0.5082191 -0.8226173 -0.2549791 -0.5744213 -0.7975651 -0.1842015 -0.5802232 -0.7943694 -0.1797728 -0.5737655 -0.796357 -0.1913344 -0.5796757 -0.794862 -0.1793611 -0.5832583 -0.7929085 -0.1763684 -0.5793137 -0.7942429 -0.1832317 -0.5874794 -0.7871386 -0.1878318 -0.6052169 -0.7777696 -0.1696676 -0.5869232 -0.786553 -0.1919775 -0.6258748 -0.7623223 -0.164759 -0.6046632 -0.7676068 -0.212514 -0.6436749 -0.7345871 -0.2146267 -0.6883504 -0.7035382 -0.1766572 -0.6466175 -0.7403018 -0.1839538 -0.7328592 -0.6631388 -0.1521988 -0.687333 -0.6948031 -0.2117119 -0.7760753 -0.6147252 -0.140784 -0.7348832 -0.6419514 -0.2187354 -0.8191416 -0.5540624 -0.1483975 -0.7808373 -0.5893787 -0.2071856 -0.8510735 -0.4934503 -0.1793901 -0.8217523 -0.5425636 -0.174207 -0.8696569 -0.466985 -0.1600682 -0.8577709 -0.4555534 -0.2381179 -0.821036 -0.5664005 -0.0713464 -0.8210383 -0.5663969 -0.0713486 -0.8211205 -0.5662634 -0.07146179 -0.8210507 -0.5663846 -0.0713045 -0.8211075 -0.5662753 -0.07151836 -0.7923889 -0.5909519 0.1513133 -0.8137052 -0.5740571 0.09133708 -0.8235983 -0.5643168 0.05685472 0.8210964 0.5662905 -0.0715267 0.6197041 0.61971 0.4815875 0.6197181 0.6197043 0.4815768 0.6197025 0.6197143 0.4815838 0.6197159 0.6197013 0.4815835 0.61971 0.6197091 0.4815809 0.7461633 0.6020651 0.2841795 0.7340941 0.6065897 0.3052126 0.8210831 0.5663239 -0.07141304 0.821085 0.5663208 -0.07141524 0.8210824 0.5663257 -0.0714066 0.8210728 0.5663408 -0.07139718 0.8211492 0.5662168 -0.07150328 0.821906 0.5649837 -0.07255321 0.8210808 0.56633 -0.07139003 0.8210852 0.5663192 -0.07142651 0.82108 0.5663319 -0.07138556 0.8211075 0.566269 -0.07156836 0.8210837 0.5663226 -0.071415 0.8210801 0.5663306 -0.07139474 0.8210881 0.5663144 -0.07143145 0.3614518 0.5016279 0.7859529 0.3572145 0.4073907 0.8404943 0.4251226 0.5284525 0.734853 0.4237698 0.352394 0.8344086 0.5065429 0.500824 0.7018474 0.545661 0.4109982 0.7302976 0.6197145 0.6197059 0.4815792 0.5453703 0.2214291 0.8084185 0.5680779 0.4470201 0.6909852 0.6197102 0.6197097 0.48158 0.6349976 0.3759498 0.6748629 0.6197102 0.6197095 0.4815803 0.6613518 0.1631578 0.7321157 0.6197107 0.6197091 0.48158 0.6397088 0.4053907 0.6530169 0.6197175 0.619704 0.4815779 0.6951691 0.2531471 0.6727975 0.6197016 0.6197173 0.4815812 0.7135658 0.177779 0.6776566 0.6956084 0.308811 0.6486638 0.6197127 0.6197071 0.48158 0.7207961 0.1825842 0.6686674 0.6197161 0.6197038 0.48158 0.7201834 0.166113 0.673604 0.619707 0.6197119 0.4815812 0.7094086 0.2014791 0.6753855 0.6197127 0.6197074 0.4815797 0.7201349 0.1626209 0.6745073 0.6197205 0.6197004 0.4815787 0.5919185 -0.2710598 0.7590515 0.6197068 0.6197128 0.4815802 0.6467797 0.2874906 0.7064172 0.6805552 0.05459678 0.73066 0.6197037 0.6197158 0.4815803 0.597786 0.3074731 0.7403461 0.4537938 -0.2185891 0.8638807 0.6197137 0.6197063 0.4815798 0.5312718 0.284984 0.7978311 0.6197096 0.6197096 0.4815806 0.6197134 0.6197065 0.4815798 0.5265352 0.3910142 0.7548964 0.4856145 0.1985946 0.8513159 0.6197099 0.6197099 0.4815799 0.4962968 0.3963105 0.7724165 0.451735 0.2966272 0.8413964 0.6197103 0.6197093 0.4815803 0.4773173 0.3968963 0.7839906 0.6197118 0.619708 0.4815801 0.4602409 0.3659619 0.8088573 0.6197145 0.6197053 0.48158 0.4650268 0.4033979 0.7880483 0.4565058 0.3899149 0.7997305 0.6197157 0.6197045 0.4815793 0.456188 0.4170048 0.7861295 0.6197124 0.6197075 0.48158 0.4490947 0.4069163 0.7954452 0.6197078 0.6197122 0.4815798 0.4513781 0.4358374 0.778655 0.4358948 0.4155703 0.7983088 0.6197136 0.6197069 0.4815792 0.4468535 0.4543377 0.7706485 0.6197078 0.6197122 0.4815798 0.4190933 0.4199026 0.8050109 0.6197114 0.6197082 0.4815801 0.4367945 0.4668794 0.7689175 0.6197174 0.619703 0.4815793 0.405626 0.4269744 0.8081833 0.6197159 0.6197044 0.4815794 0.4106447 0.4662799 0.7835522 0.6197106 0.6197091 0.4815801 0.4066694 0.4457269 0.7974632 0.6197077 0.6197131 0.4815787 0.4179742 0.4909239 0.7643896 0.6197062 0.6197145 0.4815789 0.3840623 0.4574549 0.8020169 0.429906 0.4795281 0.7650057 0.6197147 0.6197061 0.4815788 0.4098936 0.5017256 0.7617471 0.6197088 0.6197111 0.48158 0.6197155 0.6197047 0.4815796 0.3808521 0.4784434 0.7912293 0.3929522 0.4762017 0.7866515 0.6197092 0.61971 0.4815806 0.3783068 0.4963078 0.781385 0.6197142 0.6197059 0.4815796 0.6197195 0.6197011 0.481579 0.3743527 0.4834518 0.7912865 0.6197126 0.6197076 0.4815796 0.3703287 0.5028689 0.7810119 0.6197078 0.6197112 0.481581 0.619708 0.6197111 0.4815809 0.6197107 0.6197086 0.4815808 0.3665757 0.4933004 0.7888453 0.4156713 0.5162434 0.7488058 0.6197108 0.6197091 0.4815797 0.3737185 0.511397 0.7738267 0.6197113 0.6197088 0.4815797 0.6197025 0.6197157 0.4815822 0.6197171 0.6197031 0.4815795 0.6197146 0.6197055 0.4815797 0.3615056 0.5032853 0.7848679 0.3652657 0.502243 0.7837939 0.4048766 0.5203285 0.7518864 0.6197113 0.6197085 0.4815801 0.3583995 0.5041181 0.7857575 0.6197102 0.6197092 0.4815806 0.6197077 0.6197109 0.4815816 0.6197164 0.6197039 0.4815795 0.6197124 0.6197075 0.4815798 0.3608815 0.5059738 0.7834253 0.3658195 0.5076678 0.7800316 0.6197099 0.6197072 0.4815834 0.3298797 0.4810174 0.8122819 0.6197322 0.6197011 0.4815626 0.6197229 0.6197042 0.4815704 0.6196879 0.6197178 0.481598 0.6197348 0.6196974 0.481564 0.6197121 0.6197082 0.4815794 0.6197023 0.6197146 0.481584 0.6197133 0.6197058 0.4815809 0.6197171 0.6197022 0.4815806 0.3647718 0.5047257 0.7824279 0.3620049 0.5053889 0.7832844 0.3490661 0.499441 0.7929133 0.001919746 0.9533647 0.3018146 0.276202 0.8837946 0.37765 0.3830297 0.5059584 0.7728483 0.3185802 0.4749004 0.8203513 0.07681196 0.9568684 0.280184 0.2512991 0.9326161 0.2589904 0.07412642 0.9629843 0.2591652 0.4019551 0.8841902 0.2379912 0.2929092 0.9305224 0.2198461 0.5304918 0.82454 0.1967545 0.6207535 0.7181202 0.3145926 0.424494 0.8480023 0.3173279 0.6241213 0.7321963 0.2726926 0.619225 0.7718883 0.1440442 0.6336249 0.7063854 0.3154982 0.625742 0.7228794 0.2930735 0.6362922 0.7065896 0.3096181 0.6387862 0.711364 0.2931098 0.6407937 0.7186881 0.269946 0.6399649 0.7013735 0.3138789 0.6379538 0.7056357 0.3083719 0.6401151 0.7014065 0.3134989 0.640125 0.7014229 0.3134421 0.640402 0.7021509 0.3112384 0.6405394 0.7008842 0.3138002 0.6402037 0.7014898 0.3131316 0.6410724 0.7011459 0.3121231 0.6421318 0.7031872 0.3052778 0.6425148 0.6987965 0.314417 0.6416561 0.7018089 0.3094217 0.6440212 0.6990876 0.310666 0.6471341 0.7048582 0.2905037 0.647333 0.6941944 0.3147289 0.6447033 0.6983312 0.3109525 0.6524133 0.6998524 0.290798 0.6530295 0.6880354 0.3164804 0.6502988 0.6956986 0.3051474 0.6629168 0.696327 0.2750817 0.6624692 0.6796502 0.3149766 0.6566929 0.6874563 0.3100942 0.6663064 0.6708115 0.3256498 0.669938 0.6853675 0.2854025 0.6759921 0.6652916 0.3168942 0.6820148 0.6735801 0.284861 0.6897851 0.6570124 0.3041899 0.6925687 0.6431177 0.3267235 0.6913618 0.6573802 0.2997832 0.6990989 0.6315885 0.3351966 0.7145835 0.6427692 0.2760766 0.7131091 0.6200304 0.3271662 0.7412504 0.6211211 0.2544729 -0.6197185 -0.6196982 -0.4815842 -0.6161004 -0.2501196 -0.7469005 -0.6197063 -0.6197132 -0.4815803 -0.6197122 -0.6197082 -0.4815793 0.4572941 0.8350569 -0.3058795 -0.5257238 -0.3387933 -0.7802779 -0.6196731 -0.6197519 -0.4815733 -0.6306467 0.4204897 -0.6522829 -0.2415971 0.8592491 -0.4509121 -0.3090748 0.5796925 -0.7539426 -0.6197066 -0.6197137 -0.4815791 -0.7905076 0.3414779 -0.5084197 -0.6570897 0.5406876 -0.5252525 -0.619796 -0.6196151 -0.4815911 -0.864959 0.3382966 -0.3706768 -0.860706 -0.210394 -0.4635943 -0.865204 0.2872028 -0.4110191 -0.9111333 0.1853408 -0.3680828 -0.8658888 0.4049057 -0.2937479 -0.704116 -0.6399022 -0.3078082 -0.6987844 -0.6406374 -0.3182519 -0.6197123 -0.6197081 -0.4815793 -0.7045636 -0.6393309 -0.3079709 -0.6197144 -0.6197056 -0.4815796 -0.7048439 -0.6387112 -0.3086149 -0.6197121 -0.6197082 -0.4815793 -0.7043476 -0.6392151 -0.3087047 -0.6197094 -0.6197103 -0.4815799 -0.7039031 -0.637757 -0.3127082 -0.6197116 -0.6197081 -0.4815801 -0.7035966 -0.6379924 -0.3129178 -0.6197116 -0.6197086 -0.4815794 -0.7037549 -0.6367837 -0.3150167 -0.6197181 -0.6197009 -0.481581 -0.6197055 -0.6197138 -0.4815806 -0.7030496 -0.6371871 -0.3157749 -0.6197158 -0.6197043 -0.4815797 -0.7042385 -0.6367067 -0.3140903 -0.6197142 -0.6197061 -0.4815794 -0.7038559 -0.6368691 -0.3146183 -0.619712 -0.6197069 -0.4815812 -0.7037976 -0.6372248 -0.3140279 -0.619705 -0.6197145 -0.4815805 -0.7044957 -0.6369023 -0.3131155 -0.6197099 -0.6197099 -0.48158 -0.7031405 -0.6374412 -0.3150588 -0.6197195 -0.6197001 -0.4815804 -0.7037254 -0.6371691 -0.3143026 -0.6197084 -0.6197117 -0.4815798 -0.7024258 -0.6384052 -0.3147011 -0.6197125 -0.6197069 -0.4815804 -0.6197066 -0.6197129 -0.4815804 -0.7036574 -0.6378784 -0.3130134 -0.6197097 -0.6197099 -0.4815804 -0.7012745 -0.6394798 -0.3150868 -0.6197057 -0.6197143 -0.4815797 -0.7028904 -0.6388997 -0.3126537 -0.6197152 -0.6197044 -0.4815801 -0.7002409 -0.6406516 -0.3150049 -0.6197155 -0.6197041 -0.4815803 -0.7017182 -0.6402443 -0.3125364 -0.6197079 -0.6197118 -0.4815801 -0.6992222 -0.6421931 -0.3141278 -0.7003762 -0.6419731 -0.3119997 -0.6197102 -0.6197095 -0.4815801 -0.6982678 -0.6439063 -0.3127408 -0.6197087 -0.6197111 -0.48158 -0.6197121 -0.6197082 -0.4815793 -0.6925272 -0.6476283 -0.3177792 -0.619715 -0.6197046 -0.4815803 -0.6197128 -0.6197069 -0.48158 -0.6983345 -0.643961 -0.312479 -0.6197114 -0.6197092 -0.4815791 -0.6833088 -0.653912 -0.3247895 -0.6197126 -0.6197079 -0.4815793 -0.6823108 -0.6426775 -0.3484505 -0.690136 -0.647954 -0.3222857 -0.6918197 -0.6523696 -0.3095148 -0.6197142 -0.6197061 -0.4815793 -0.677613 -0.6615434 -0.3212491 -0.6197109 -0.6197097 -0.4815791 -0.6820535 -0.6528338 -0.329562 -0.685074 -0.6594105 -0.3095986 -0.6197109 -0.6197093 -0.4815796 -0.6705881 -0.6680089 -0.3226075 -0.6197123 -0.6197077 -0.4815796 -0.6768215 -0.6605189 -0.3250038 -0.6774911 -0.6680133 -0.3078377 -0.619713 -0.6197069 -0.4815798 -0.666374 -0.6763709 -0.3137964 -0.6197109 -0.6197092 -0.4815796 -0.6718214 -0.6714762 -0.3126912 -0.6197124 -0.6197073 -0.4815801 -0.6597438 -0.6808467 -0.3180975 -0.6197112 -0.6197087 -0.4815798 -0.665781 -0.6745551 -0.3189221 -0.6627377 -0.6822257 -0.3087832 -0.6197127 -0.6197068 -0.4815802 -0.6550154 -0.6863701 -0.3159919 -0.6573698 -0.6876693 -0.3081821 -0.6197071 -0.6197127 -0.4815801 -0.6512095 -0.6931098 -0.3090711 -0.6197153 -0.6197042 -0.4815805 -0.6445446 -0.6964095 -0.3155568 -0.6197125 -0.6197076 -0.4815798 -0.6512312 -0.692042 -0.3114093 -0.6197078 -0.6197126 -0.4815794 -0.6325657 -0.7031999 -0.3246083 -0.6425101 -0.7064548 -0.2968204 -0.6197089 -0.6197114 -0.4815794 -0.6085221 -0.7489247 -0.2623218 -0.619717 -0.6197021 -0.481581 -0.5935022 -0.7383636 -0.3202723 -0.6197118 -0.6197085 -0.4815793 -0.6184278 -0.7230515 -0.3078045 -0.6197112 -0.619709 -0.4815796 -0.4705607 -0.8752887 -0.1115455 -0.6197038 -0.6197172 -0.4815785 -0.5341775 -0.7809631 -0.3236529 -0.5777827 -0.7525625 -0.3159381 -0.6197138 -0.6197068 -0.4815791 -0.5174304 -0.7853557 -0.3398268 -0.4912557 -0.8268582 -0.2738125 -0.6197216 -0.6196949 -0.4815843 -0.4980318 -0.8045257 -0.323578 -0.6197101 -0.6197102 -0.4815793 -0.4987176 -0.803635 -0.3247331 -0.6197032 -0.6197174 -0.4815791 -0.5287339 -0.7770663 -0.3414797 -0.6197174 -0.6197021 -0.4815806 -0.5402636 -0.78359 -0.3067602 -0.5287353 -0.7770646 -0.3414814 -0.6197121 -0.6197077 -0.48158 -0.6011561 -0.7008986 -0.3838652 -0.6197131 -0.6197059 -0.4815809 -0.6197014 -0.6197241 -0.4815728 -0.6169721 -0.7223957 -0.3122339 -0.5717715 -0.7542126 -0.3228634 -0.6197236 -0.6196987 -0.4815767 -0.6498923 -0.702799 -0.2893333 -0.6280323 -0.6936998 -0.3526415 -0.6197143 -0.619717 -0.4815654 -0.6778889 -0.6690249 -0.3047497 -0.6197103 -0.6197087 -0.4815811 -0.6633029 -0.6665524 -0.3402016 -0.619713 -0.6197127 -0.4815726 -0.6976225 -0.6396938 -0.3226683 -0.7003076 -0.6413393 -0.3134539 0.8211006 0.5662782 -0.07157349 0.8210836 0.5663213 -0.07142841 0.821082 0.5663265 -0.07140344 0.8210778 0.5663411 -0.07133674 0.8210947 0.5662918 -0.0715332 0.8210661 0.5663707 -0.07123678 -0.02052074 -0.4449197 -0.8953354 0.8210142 0.5664765 -0.07099264 -0.3725597 -0.5538362 -0.744624 -0.213706 -0.5334769 -0.8183715 -0.4373194 -0.5494914 -0.7119065 -0.0786156 -0.39736 -0.9142892 -0.4651641 -0.5324884 -0.7071623 -0.1204037 -0.3365218 -0.9339465 -0.47526 -0.505782 -0.7199393 -0.1977121 -0.3088495 -0.9303343 -0.4759128 -0.4724205 -0.7418395 -0.2687703 -0.2931506 -0.9175104 -0.4659029 -0.429507 -0.7736009 -0.3475087 -0.3071017 -0.8859606 -0.4380936 -0.3654367 -0.8212977 -0.485359 -0.4056704 -0.7745051 -0.4246389 -0.3468351 -0.8362937 -0.3959798 -0.2587257 -0.8810568 -0.4881743 -0.3785341 -0.7863827 -0.4740557 -0.3771662 -0.7956234 -0.4369261 -0.2872566 -0.8523961 -0.4952815 -0.3719462 -0.785081 -0.4835286 -0.365033 -0.7955821 -0.4818095 -0.3439887 -0.8059351 -0.4976541 -0.3672279 -0.7858014 -0.4861083 -0.3519085 -0.799912 -0.4976273 -0.3651012 -0.7868088 -0.4953077 -0.3601461 -0.7905474 -0.4952778 -0.3600882 -0.7905924 -0.4990766 -0.3642189 -0.7862998 -0.4979333 -0.3650541 -0.7866371 -0.4814955 -0.3255595 -0.8137402 -0.3483285 -0.09495651 -0.9325505 -0.5167621 -0.3571633 -0.7780689 -0.4934935 -0.3433733 -0.7990989 -0.4643747 -0.2249901 -0.8565837 -0.8205228 -0.569723 0.04645264 -0.8210855 -0.5663201 0.07141649 -0.8210863 -0.5663189 0.071415 -0.8158601 -0.5774787 0.0298444 -0.8227983 -0.5613852 0.08859854 -0.7933484 -0.6045006 0.07195436 -0.7936612 -0.6035578 0.07628893 -0.7893251 -0.6022211 0.1195648 -0.79123 -0.6069835 0.07433831 -0.7873983 -0.6156949 0.03039062 -0.7885126 -0.6107756 0.07211893 -0.7908267 -0.6000387 0.1206101 -0.7886151 -0.610654 0.07202643 -0.5819652 0.8131265 -0.01189887 -0.5255805 0.8503504 0.0258696 -0.7907836 -0.6078556 0.07192319 -0.7932477 -0.5968279 0.120642 -0.7916597 -0.5997272 0.1166276 -0.7927151 -0.6053417 0.07186198 -0.7951941 -0.5948545 0.1175353 -0.7910881 -0.6074362 0.07211738 -0.794322 -0.6032366 0.07182139 -0.7969887 -0.591907 0.1202301 -0.7931247 -0.6047775 0.07209259 -0.7951447 -0.5948508 0.1178879 -0.7956169 -0.6015288 0.07181149 -0.7982147 -0.5910222 0.116388 -0.7947965 -0.6025835 0.07205349 -0.7967149 -0.6000769 0.07178705 -0.7995024 -0.5886275 0.1196395 -0.7960965 -0.6008701 0.07201105 -0.7979016 -0.5908645 0.1192982 -0.7975535 -0.5989566 0.07182967 -0.8003914 -0.5873786 0.1198329 -0.7970444 -0.5996187 0.07195395 -0.7997177 -0.5885896 0.1183807 -0.797994 -0.598366 0.07185852 -0.8008401 -0.5868441 0.1194528 -0.7976739 -0.5987876 0.07190084 -0.8007098 -0.5871254 0.1189438 -0.7980708 -0.5982611 0.0718792 -0.8009189 -0.5867389 0.1194416 -0.7980331 -0.5983108 0.07188481 -0.7977876 -0.5986367 0.07189643 -0.8006097 -0.5872071 0.1192139 -0.7980343 -0.5983127 0.07185578 -0.8008648 -0.5867475 0.1197625 -0.7971922 -0.5994252 0.07193189 -0.8000307 -0.5877136 0.1205976 -0.7976956 -0.598766 0.07184058 -0.7963047 -0.6005982 0.07197654 -0.799036 -0.5893502 0.1191966 -0.797024 -0.5996603 0.07183521 -0.8001258 -0.5877565 0.1197537 -0.7951253 -0.6021549 0.07200974 -0.7977803 -0.5910859 0.1190126 -0.796023 -0.6009898 0.07182317 -0.7985566 -0.5895682 0.1213129 -0.7936929 -0.6040363 0.07205396 -0.7963095 -0.5927945 0.1203563 -0.7947646 -0.602653 0.07182365 -0.7920098 -0.6062322 0.07213187 -0.7944654 -0.5956118 0.1186218 -0.7930682 -0.6048927 0.07174676 -0.7960714 -0.5928242 0.1217783 -0.7900951 -0.6087229 0.0721538 -0.7925532 -0.5973832 0.1224449 -0.7908993 -0.6077249 0.07175374 -0.787958 -0.6114909 0.07211762 -0.7901844 -0.6012701 0.1186712 -0.7884396 -0.6109049 0.07182133 -0.7926605 -0.5973922 0.1217045 -0.7852185 -0.6149821 0.07231009 -0.7872846 -0.6049817 0.11908 -0.7857187 -0.6143851 0.07195192 -0.7883748 -0.6026728 0.1234943 -0.7817707 -0.6193414 0.07246357 -0.7836531 -0.6093974 0.1205099 -0.7827827 -0.6181287 0.07188993 -0.7780149 -0.6240496 0.0724917 -0.7796194 -0.6151101 0.1176145 -0.7792313 -0.622614 0.07176554 -0.7830763 -0.6094932 0.1237317 -0.7739655 -0.6290618 0.07251584 -0.7753539 -0.620119 0.1194939 -0.7750524 -0.6277987 0.07185155 -0.7768232 -0.6171143 0.1253621 -0.7696659 -0.6343122 0.07254344 -0.7707942 -0.6256024 0.1204069 -0.7706527 -0.6331812 0.07194495 -0.7651361 -0.6397649 0.07258063 -0.7659754 -0.6320185 0.1176186 -0.7660837 -0.6386928 0.07202225 -0.769522 -0.6260666 0.126002 -0.7603841 -0.6454555 0.07213205 -0.7608785 -0.6365633 0.1259018 -0.760577 -0.6452452 0.07197958 -0.7554753 -0.6511449 0.07257628 -0.7557196 -0.6441702 0.1180365 -0.7611821 -0.6365098 0.1243269 -0.7503945 -0.6569647 0.0728389 -0.7499742 -0.648172 0.1319537 -0.7541081 -0.6528119 0.07181543 -0.7399028 -0.6684377 0.07573044 -0.7391972 -0.663279 0.1168267 -0.7408474 -0.6675125 0.07464593 -0.7475008 -0.660367 0.07181793 -0.7518145 -0.6479547 0.1221871 -0.7232386 -0.6864233 0.07582312 -0.7222813 -0.6839745 0.1024142 -0.7274719 -0.6822581 0.07286065 -0.7341452 -0.6751322 0.07230031 -0.7419311 -0.6635447 0.09615957 -0.7292687 -0.6717813 0.1299118 -0.7060694 -0.7041105 0.07546162 -0.7035521 -0.7014791 0.113761 -0.7147607 -0.695995 0.06861507 -0.7166537 -0.6860916 0.1252431 -0.6887936 -0.7210713 0.07496404 -0.6857366 -0.7196769 0.1087681 -0.6958791 -0.714774 0.06964635 -0.7035681 -0.7014745 0.1136909 -0.6872826 -0.7154256 0.1257334 -0.6718392 -0.7369373 0.07453542 -0.6677926 -0.7363147 0.1090577 -0.6782758 -0.7314304 0.07036751 -0.670171 -0.7306587 0.1304173 -0.6557175 -0.7513576 0.07413828 -0.6501961 -0.7514048 0.1124091 -0.6621868 -0.7459873 0.07079237 -0.6521181 -0.7466157 0.1315555 -0.6402485 -0.764602 0.07392972 -0.6330414 -0.765358 0.1161279 -0.6477517 -0.7585278 0.07108765 -0.6336677 -0.7626802 0.1295539 -0.6157929 -0.7843183 0.07512611 -0.6050047 -0.786284 0.1254069 -0.6334538 -0.7705359 0.07078659 -0.5666007 -0.8205933 0.0747677 -0.5587119 -0.8230745 0.1019281 -0.6065763 -0.791961 0.06973701 -0.5999112 -0.7882933 0.1367488 -0.4923051 -0.8673723 0.07280838 -0.4887101 -0.8686317 0.08149594 -0.4948974 -0.8659853 0.07173568 -0.5593231 -0.8259937 0.06994313 -0.499784 -0.845054 0.1899989 -0.3917672 -0.9170858 0.07397383 -0.2929643 -0.928084 0.2298522 -0.4219173 -0.9042285 0.06600433 -0.2782102 -0.9579834 0.0697624 -0.2624487 -0.9607576 0.08980834 -0.3312605 -0.941631 0.05997961 -0.3577196 -0.9206181 0.1565218 -0.1962385 -0.9785857 0.06213283 0.02388995 -0.9574013 0.2877706 -0.2261332 -0.9724965 0.05580842 -0.1569674 -0.9859821 0.05657392 -0.1136353 -0.9884654 0.1001155 -0.1547592 -0.9862913 0.05726349 -0.1782793 -0.9764111 0.1218104 -0.1426243 -0.9880675 0.05814558 -0.07827883 -0.9895245 0.1213002 -0.1555241 -0.9860015 0.06011188 -0.1068445 -0.9882781 0.1090445 -0.1531866 -0.9863303 0.0607165 -0.1035472 -0.9893507 0.1022903 -0.2007447 -0.9778558 0.05915814 -0.2015236 -0.9777467 0.05830699 -0.2751274 -0.9595624 0.05953997 -0.215854 -0.9674065 0.1324072 -0.2174591 -0.9737873 0.06670838 -0.2028077 -0.9775414 0.05728894 -0.3737742 -0.9254254 0.06229555 -0.389979 -0.9201217 0.03594845 -0.323295 -0.9436032 0.07136863 -0.4769724 -0.876493 0.0652486 -0.4379605 -0.8865453 0.1490913 -0.4412317 -0.8943392 0.07397276 -0.406284 -0.9135491 0.019014 -0.5718231 -0.8176093 0.06732976 -0.5767974 -0.8154407 0.04859328 -0.5462416 -0.8341674 0.07605904 -0.6565734 -0.7511011 0.06898254 -0.6429949 -0.7499196 0.155493 -0.640174 -0.7643625 0.07698881 -0.5728462 -0.8177518 0.05594033 -0.730052 -0.6797497 0.07045859 -0.7267095 -0.6703214 0.1502082 -0.7217597 -0.6879112 0.07642769 -0.700494 -0.7121571 0.04626399 -0.7221567 -0.6915745 0.01464915 -0.785547 -0.6166994 0.05096751 -0.6504223 -0.7595726 -5.29763e-4 -0.6976632 -0.7101961 0.09427422 -0.5203455 -0.8403336 0.1519208 -0.469437 -0.8828296 0.01551741 -0.5736001 -0.8174056 0.05320763 -0.1714667 -0.94739 0.2702805 -0.2579972 -0.965936 0.02012538 -0.4004229 -0.9158712 0.02900439 -0.206609 -0.9784054 0.00596553 -0.1900937 -0.9791784 0.07123273 -0.1832753 -0.9826559 0.0282396 -0.1904177 -0.981585 0.01523226 -0.2767048 -0.9609509 -0.002760469 -0.3373107 -0.9399955 0.05128127 -0.3054437 -0.9518334 -0.02678507 -0.4789941 -0.8765274 -0.04758554 -0.504706 -0.8620024 0.04715538 -0.4563869 -0.8895553 -0.02006065 -0.5863581 -0.8093497 -0.03372085 -0.6140408 -0.7886103 0.03236711 -0.5568341 -0.830241 0.02521204 -0.6386408 -0.7685924 0.03746849 -0.6255723 -0.7801118 0.00922054 -0.652602 -0.7569404 0.03393924 -0.6500468 -0.7595965 0.02127236 -0.6662936 -0.7450015 0.03202563 -0.6655141 -0.7459197 0.02636265 -0.6811339 -0.731328 0.03487175 -0.6803867 -0.7322636 0.0293914 -0.6973462 -0.7154486 0.04291331 -0.6946423 -0.7188386 0.02726125 -0.7152894 -0.6970956 0.04918384 -0.7078185 -0.7060191 0.02302497 -0.7275944 -0.6852475 0.03228223 -0.7198619 -0.6935554 0.02792382 -0.7338439 -0.678576 0.03174483 -0.7308959 -0.6820793 0.02364522 -0.7400664 -0.6718841 0.02955234 -0.7464859 -0.6645484 0.03367942 -0.7410297 -0.6709989 0.02520614 -0.7526565 -0.6576218 0.03227579 -0.7501505 -0.6607972 0.02492725 -0.7585253 -0.6510153 0.0286076 -0.7639231 -0.6445208 0.03185123 -0.7585723 -0.6509758 0.02826249 -0.7682373 -0.6393741 0.03181713 -0.7656742 -0.6427174 0.02563917 -0.7721382 -0.6348067 0.02869099 -0.7763804 -0.6294466 0.03209835 -0.7722555 -0.6347045 0.02777457 -0.7796462 -0.6254455 0.0311411 -0.7776856 -0.6280872 0.02667999 -0.7822532 -0.6222636 0.02945941 -0.7850393 -0.6186441 0.03150779 -0.7824714 -0.6220644 0.02782714 -0.7872666 -0.6158583 0.03049027 -0.7863196 -0.6171895 0.02790707 -0.7892789 -0.6132963 0.03010648 -0.7909655 -0.6110801 0.03089767 -0.7894413 -0.6131525 0.02874624 -0.7918953 -0.6099882 0.02856922 -0.7930453 -0.6084054 0.03036409 -0.7918106 -0.6100336 0.02991712 -0.793689 -0.6075623 0.03043043 -0.7932037 -0.6082438 0.02945208 -0.793959 -0.6072306 0.03000378 -0.7939761 -0.6071996 0.03017771 -0.7939479 -0.6072372 0.03015905 -0.7936214 -0.6076688 0.03006345 -0.7938968 -0.6072807 0.03062719 -0.7930872 -0.6083368 0.03064519 -0.7920892 -0.6096785 0.02978092 -0.7930558 -0.6083619 0.03095817 -0.7909021 -0.6111974 0.0301944 -0.7914868 -0.610362 0.03173202 -0.7893455 -0.6131931 0.03046101 -0.7872945 -0.6158813 0.02928596 -0.7891059 -0.613412 0.03221285 -0.7849968 -0.6187926 0.02959442 -0.7860465 -0.617311 0.03252786 -0.5819643 0.8131273 -0.01189488 -0.6886646 0.719382 -0.09072297 -0.6185176 0.7841094 -0.05107313 -0.4195529 0.9073836 -0.02510625 -0.303162 0.9516788 0.04899382 -0.3031559 0.9516817 0.04897248 -0.4656597 0.882655 0.06388306 -0.3555247 0.9279998 0.1114384 -0.4391152 0.8955724 0.07160925 -0.4195389 0.9073899 -0.02511203 -0.5368491 0.83704 -0.1056274 0.3498474 0.9344716 -0.06610298 0.3759124 0.926289 -0.02605086 0.3498586 0.9344671 -0.06610608 0.5462102 0.8346273 -0.07107454 0.5949296 0.7949776 0.1186138 0.576838 0.8163128 -0.02985543 -0.04655843 0.997715 -0.04896062 0.04947459 0.9984149 0.02683025 -0.04657804 0.9977144 -0.0489543 0.3498634 0.9353421 0.05225735 0.4001272 0.9163749 0.01246172 0.04945755 0.9984152 0.0268532 -0.1608384 0.9771597 -0.1388881 -0.5368492 0.83704 -0.105627 0.2804708 0.9453252 -0.1664224 -0.1608415 0.9771603 -0.1388806 0.5481958 0.83317 -0.07286304 0.5332392 0.837628 -0.1184706 0.2320818 0.966828 -0.1066845 0.881777 0.4661952 -0.0716325 0.8756585 0.4814792 -0.03741341 0.8804841 0.4689595 -0.0694614 0.8602535 0.5052767 -0.06825882 0.8569688 0.5131628 -0.04762583 0.865871 0.5002354 -0.005657136 0.8483872 0.5277588 0.04134923 0.8356795 0.5451521 -0.06670171 0.825449 0.5644739 -0.001810133 0.8579955 0.5081766 -0.07483583 0.8078361 0.585844 -0.06471168 0.8076995 0.5861827 -0.06333506 0.8307915 0.5509751 -0.07881695 0.8209007 0.570885 0.01457345 0.7777978 0.6253219 -0.06327104 0.7784872 0.6231105 -0.0754382 0.798778 0.5958815 -0.08293968 0.7836636 0.6204349 0.03052783 0.7477944 0.6607948 -0.06444942 0.7476336 0.6616714 -0.05687701 0.7631956 0.6405665 -0.08489376 0.7519103 0.6589348 0.02087926 0.7204048 0.6901586 -0.06854206 0.7204437 0.6935133 3.85531e-4 0.7284508 0.6801645 -0.08207178 0.6970162 0.7133573 -0.07272934 0.6987219 0.7142425 -0.04056388 0.6990941 0.7108822 -0.07690286 0.7220898 0.6916354 -0.01506316 0.6779385 0.7315409 -0.07243865 0.6803069 0.7315749 -0.04450577 0.6934658 0.7204365 0.008747279 0.6626079 0.745615 -0.07077503 0.6686454 0.7435297 -0.008771181 0.6758818 0.733165 -0.07518577 0.6500734 0.7565789 -0.07066011 0.6541535 0.7553631 -0.03885567 0.6578072 0.7494145 -0.07528358 0.6685645 0.7436257 -0.006516933 0.6398606 0.7651916 -0.07113528 0.6483057 0.7613298 -0.008764863 0.6439368 0.7614386 -0.07454293 0.6316258 0.771945 -0.07176238 0.6374704 0.7696909 -0.03475004 0.633345 0.7703645 -0.07357037 0.6483094 0.7612927 -0.01133954 0.6250768 0.7772061 -0.07231622 0.6333339 0.7735592 -0.02223384 0.6253654 0.7769405 -0.07267487 0.6200848 0.781221 -0.07203137 0.6330569 0.7740716 0.007217049 0.6162881 0.7842389 -0.0718224 0.6237158 0.7810296 -0.03117048 0.6193557 0.7817513 -0.07254928 0.6312134 0.7751254 -0.02739161 0.6134517 0.7864578 -0.07184052 0.6225987 0.7822234 -0.02230513 0.6150466 0.7851539 -0.07246392 0.6113995 0.7880473 -0.07191795 0.6228536 0.7822785 -0.009682655 0.6121239 0.7874502 -0.07229506 0.6099863 0.7891354 -0.07198721 0.6179641 0.7856062 -0.03071361 0.6102226 0.7889387 -0.07213932 0.6216717 0.7828175 -0.02685022 0.6091012 0.7898152 -0.07202702 0.6174129 0.7860949 -0.02926158 0.6091083 0.7898091 -0.07203257 0.6086302 0.7901815 -0.07199043 0.6173448 0.7862231 -0.02717572 0.6085536 0.7902389 -0.07200747 0.6173684 0.7862218 -0.02667933 0.6085805 0.7902176 -0.07201319 0.6083156 0.7904295 -0.07192522 0.6164079 0.7868297 -0.03066551 0.6085482 0.7902429 -0.07200944 0.6170808 0.7863251 -0.03007018 0.606302 0.7919861 -0.07180505 0.6151633 0.7879319 -0.02715361 0.6070981 0.7913384 -0.07221889 0.6021589 0.7951324 -0.07189631 0.6146156 0.7887688 -0.009564578 0.6026725 0.7947116 -0.07224518 0.5959214 0.7997721 -0.07240366 0.6158806 0.7873346 0.02820378 0.5952772 0.8003004 -0.07186263 0.5880559 0.8056706 -0.07131129 0.5969839 0.8015832 -0.03277951 0.6121843 0.7904474 -0.02057206 0.5777881 0.8131144 -0.07075309 0.5912543 0.8063348 -0.01557391 0.5844029 0.8081983 -0.07272279 0.5643662 0.8225179 -0.07039189 0.5908767 0.8060002 0.03504717 0.5694556 0.8187682 -0.07306838 0.5114721 0.8230606 -0.2469162 0.5727146 0.8113868 -0.1168307 0.5260612 0.8280102 -0.1940588 0.5828724 0.8033751 -0.1218534 0.5812685 0.798096 -0.1586494 0.5731672 0.79341 -0.20489 0.5978816 0.7926334 -0.1194568 0.5893441 0.7983311 -0.1238591 0.5978883 0.79261 -0.1195788 0.5974438 0.7922962 -0.1238048 0.5998657 0.7912259 -0.1188397 0.5978425 0.7923966 -0.1212102 0.600661 0.7897801 -0.1243127 0.5980418 0.7875786 -0.1485456 0.6099041 0.7835837 -0.1183798 0.6023411 0.7888417 -0.1221226 0.6084023 0.7785119 -0.1541619 0.6259738 0.7714406 -0.1141766 0.6119309 0.7801661 -0.1299289 0.6366493 0.7619872 -0.1185467 0.6246708 0.765241 -0.1555406 0.6510328 0.7491476 -0.122206 0.6739543 0.7328378 -0.09345763 0.6482546 0.7435389 -0.1640605 0.6984195 0.7103886 -0.08693826 0.6773754 0.7132897 -0.1799457 0.7283459 0.679747 -0.08634972 0.7154645 0.6769128 -0.1729151 0.7633013 0.639776 -0.08976656 0.7567842 0.6324608 -0.16514 0.8016989 0.5755076 -0.1614615 0.8342598 0.53902 -0.1160523 0.7987819 0.5889903 -0.122629 0.8584282 0.5069734 -0.07796758 0.8427213 0.5011888 -0.1965469 0.8860428 0.4506359 -0.1088824 0.8835502 0.4073404 -0.231112 0.8210183 0.5664231 -0.07137113 0.8211025 0.566289 -0.07146567 0.8835571 0.4234794 -0.1999802 0.8211882 0.5661408 -0.07165521 0.8209559 0.5665601 -0.07100129 0.854312 0.3025455 -0.4226316 0.8748748 0.3722106 -0.3099248 0.6664777 0.04855233 -0.7439423 0.7935431 0.5806694 0.181968 0.8118192 0.5667116 0.1406689 0.7956506 0.5794074 0.1767126 0.8308436 0.549116 0.09039133 0.8401001 0.5390881 0.06013083 0.8472927 0.5294921 0.04162937 0.8365238 0.5431329 0.07235062 0.8569951 0.5152708 0.007455408 0.6117937 0.7774215 0.1460281 0.4785047 0.8655089 0.1480794 0.6341786 0.7590793 0.1470244 0.6116149 0.7780256 0.1435391 0.63883 0.75543 0.1456773 0.6341582 0.759652 0.1441257 0.6413087 0.7531655 0.1465092 0.6388328 0.7555068 0.1452655 0.6474134 0.7476441 0.1479331 0.641348 0.7536495 0.1438235 0.6570244 0.7388055 0.1499511 0.6476145 0.748664 0.1417668 0.6699809 0.7265591 0.1524383 0.6576889 0.7403624 0.1389564 0.6860113 0.7107822 0.1554896 0.6716336 0.7283841 0.135517 0.7047632 0.6913915 0.1590175 0.6894662 0.7122987 0.1314034 0.7257443 0.6683714 0.1630179 0.7110977 0.6915709 0.1267669 0.7483438 0.6418373 0.1674113 0.736239 0.6656697 0.1218029 0.7718829 0.6120538 0.1720089 0.7643223 0.6341781 0.1167461 0.7944148 0.5969653 0.1119714 0.595081 0.8021287 0.04968047 0.6236819 0.780067 0.05016463 0.5948834 0.8023765 0.04801851 0.6293995 0.7755148 0.04932647 0.6235805 0.7802615 0.04836839 0.6327724 0.7727326 0.04983466 0.6293847 0.7755485 0.048985 0.6409115 0.7659308 0.05081713 0.6327078 0.7728991 0.04803913 0.6536918 0.7549616 0.05215281 0.6408343 0.7662639 0.04659688 0.6709151 0.7395733 0.05389076 0.6537588 0.7553822 0.04468864 0.6922587 0.7194703 0.05603897 0.6714388 0.739851 0.04231441 0.717231 0.6943636 0.05864119 0.6937323 0.7191462 0.03955131 0.7451366 0.6640572 0.0616405 0.7203321 0.6926715 0.03643828 0.775064 0.628531 0.06499642 0.750655 0.6598628 0.03313553 0.8059223 0.5880336 0.06859785 0.7837724 0.6203302 0.02985566 0.8183532 0.5740848 0.02692317 -0.1329202 0.9617511 0.239514 -0.2742523 0.946141 0.1720554 -0.61777 -0.3163175 0.719933 -0.684932 -0.380068 0.6216241 -0.7541978 -0.4847236 0.4429772 -0.7816496 -0.5531736 0.2881371 -0.7874633 -0.5586234 0.260464 -0.7915179 -0.5804869 0.1911394 -0.784685 -0.5623543 0.2608205 -0.7846058 -0.5622785 0.2612218 -0.6804548 -0.3862414 0.6227351 -0.6798338 -0.3856216 0.6237964 -0.7912833 -0.5527126 0.2614948 -0.7943896 -0.5483891 0.2611793 -0.79149 -0.5529228 0.2604227 -0.7965156 -0.5454242 0.2609128 -0.7945346 -0.5485427 0.2604146 -0.7976256 -0.5438541 0.2607994 -0.7965841 -0.545499 0.2605471 -0.7977783 -0.5437111 0.2606303 -0.7976621 -0.5438945 0.2606034 -0.7969468 -0.5449619 0.2605617 -0.7977574 -0.543688 0.2607425 -0.7951062 -0.5476428 0.260564 -0.7968759 -0.544884 0.2609414 -0.792276 -0.5517564 0.2605064 -0.7950121 -0.5475416 0.2610632 -0.7884005 -0.5572577 0.2605544 -0.7921285 -0.5516035 0.2612774 -0.783467 -0.5641292 0.2606486 -0.7882114 -0.5570712 0.2615234 -0.7774051 -0.5723586 0.2608583 -0.7832213 -0.5639018 0.2618768 -0.7702335 -0.5819582 0.2608925 -0.7771605 -0.5721492 0.2620435 -0.7618447 -0.5927994 0.261116 -0.769914 -0.5817096 0.2623858 -0.7522106 -0.6048992 0.2612975 -0.7614951 -0.5925562 0.2626829 -0.7412955 -0.6181651 0.261444 -0.7518289 -0.6046658 0.2629308 -0.7290211 -0.6325278 0.261604 -0.7408664 -0.6179394 0.2631882 -0.7153574 -0.6478813 0.2617514 -0.7285478 -0.6323184 0.263423 -0.7002515 -0.6641414 0.2618473 -0.714846 -0.6476956 0.2636016 -0.6836867 -0.681172 0.2618724 -0.6997051 -0.6639838 0.2637012 -0.6656172 -0.6988495 0.261846 -0.6830969 -0.6810418 0.2637435 -0.6460644 -0.7170104 0.2617194 -0.6649991 -0.6987504 0.263674 -0.6249474 -0.7355595 0.2615202 -0.6454046 -0.7169393 0.2635356 -0.6026771 -0.7540107 0.2612435 -0.624262 -0.7355161 0.2632735 -0.5649703 -0.7832317 0.2595317 -0.6019654 -0.7539911 0.2629352 -0.4725216 -0.8437324 0.254635 -0.5632492 -0.7832555 0.2631751 -0.3017078 -0.9216331 0.2440587 -0.4686176 -0.8439306 0.2611103 -0.07961755 -0.9702444 0.2286635 -0.2944116 -0.9216783 0.2526478 0.02320158 -0.9743492 0.2238426 -0.07240164 -0.969318 0.2349051 -0.03652459 -0.9722291 0.2311635 0.02394026 -0.9741986 0.224419 -0.2562895 -0.9341993 0.2481682 -0.04048073 -0.9728459 0.2278863 -0.5044364 -0.8232634 0.2603486 -0.2608071 -0.9342541 0.2432057 -0.6743479 -0.6898916 0.2632576 -0.5061065 -0.8231826 0.2573453 -0.6748048 -0.6899781 0.2618564 -0.6872039 -0.3715894 0.6242372 -0.6911972 -0.3660783 0.6230835 -0.6891747 -0.373568 0.6208746 -0.693912 -0.3623529 0.6222431 -0.6925265 -0.3674243 0.6208112 -0.6955002 -0.3606073 0.6214836 -0.6947706 -0.3632271 0.6207735 -0.6958508 -0.3606845 0.6210461 -0.6957887 -0.360902 0.6209895 -0.6950552 -0.3627057 0.62076 -0.6956984 -0.3605287 0.6213073 -0.6930074 -0.3665746 0.6207769 -0.6944018 -0.362039 0.6218793 -0.6896691 -0.372288 0.6210944 -0.6918768 -0.3654264 0.6227119 -0.6850911 -0.3799354 0.6215297 -0.688187 -0.3707934 0.6236272 -0.6791476 -0.3894321 0.6221746 -0.6832183 -0.3780652 0.6247235 -0.6718593 -0.4008013 0.6228671 -0.6769927 -0.3873076 0.6258383 -0.662917 -0.4138421 0.6239196 -0.6692404 -0.3982595 0.6273011 -0.6525185 -0.4287184 0.624836 -0.6601318 -0.4111894 0.6286091 -0.6403648 -0.4452034 0.625881 -0.6494066 -0.4258195 0.6300387 -0.6264318 -0.463242 0.6268892 -0.6370195 -0.4421653 0.631424 -0.6105507 -0.4826878 0.6278856 -0.6228245 -0.4600589 0.6327996 -0.5927953 -0.5035061 0.6285503 -0.6068688 -0.4795414 0.6338379 -0.5729444 -0.5254194 0.6290224 -0.588936 -0.5003221 0.6346907 -0.5508995 -0.5481613 0.6293082 -0.5688906 -0.5221993 0.6353514 -0.5267304 -0.5716429 0.6291102 -0.5468208 -0.5450487 0.6355385 -0.5003686 -0.5954923 0.6285063 -0.5225687 -0.5685968 0.6353107 -0.4717881 -0.6195583 0.6273463 -0.4962019 -0.5925689 0.6345438 -0.4415687 -0.6431146 0.6256361 -0.4677098 -0.6168153 0.633077 -0.3917417 -0.6813834 0.6182679 -0.4374581 -0.6404579 0.6312242 -0.2707066 -0.7552729 0.5968924 -0.3823869 -0.6756771 0.6302705 -0.05637001 -0.832206 0.5515938 -0.2524167 -0.7450401 0.617415 0.196362 -0.8482952 0.4917695 -0.02934342 -0.8168444 0.5761113 0.3069152 -0.826344 0.4721849 0.2168676 -0.8341223 0.5071572 0.2498435 -0.8321245 0.4951232 0.3084057 -0.8251828 0.4732434 0.008562386 -0.8280706 0.5605586 0.2389313 -0.8400123 0.4871255 -0.3066208 -0.7239151 0.6180055 -0.007445752 -0.83737 0.5465857 -0.5366215 -0.5569038 0.6339524 -0.3148728 -0.7286292 0.608239 -0.5398405 -0.5593204 0.6290732 0.5009234 0.8257471 -0.2592631 0.2255152 0.9441612 -0.2402133 0.5488594 0.7949253 -0.258548 0.5022868 0.8261484 -0.2553173 0.5470714 0.7947245 -0.2629176 0.5576589 0.788119 -0.2605475 0.557374 0.7880833 -0.2612643 0.5640602 0.7842416 -0.2584595 0.5623533 0.7840138 -0.2628332 0.5785807 0.774538 -0.2556071 0.5748113 0.7739464 -0.2657044 0.6009501 0.7585885 -0.2517986 0.5947058 0.7573181 -0.2698046 0.6305789 0.7357476 -0.2470741 0.6218941 0.73325 -0.2749403 0.666644 0.7052521 -0.2412576 0.6559 0.7005485 -0.281118 0.7078597 0.6663767 -0.2342578 0.6958908 0.6578887 -0.2879557 0.7524276 0.6185599 -0.2263544 0.7403973 0.6040077 -0.294935 0.7981893 0.5617071 -0.2176671 0.7871201 0.5380505 -0.3015689 0.8426958 0.4963381 -0.2085958 0.8330765 0.4602438 -0.3068537 0.6383178 0.1727612 -0.7501361 0.8049039 0.3836334 -0.4527196 0.6007933 0.2890486 -0.7453175 0.7472268 0.4573602 -0.4821551 0.558441 0.3917142 -0.7312344 0.6839971 0.5206184 -0.5109838 0.5154066 0.4771323 -0.7118293 0.6192991 0.572594 -0.5372196 0.475353 0.544891 -0.6907484 0.5571574 0.6132159 -0.5599481 0.440884 0.5965847 -0.6706026 0.5010928 0.6432954 -0.5788584 0.4134635 0.6344367 -0.6530987 0.4538586 0.6641859 -0.5940281 0.3938246 0.6605876 -0.6391607 0.4172827 0.6773 -0.6059208 0.3823277 0.6767742 -0.6291282 0.3925009 0.683895 -0.6150045 0.3784594 0.6836721 -0.6239879 0.3802236 0.6849015 -0.6215626 0.3604588 0.688813 -0.6289723 0.3715043 0.6964142 -0.6139966 0.3121497 0.7361165 -0.6005789 0.3029589 0.7289677 -0.6138585 -0.6949259 0.7118584 -0.1016654 -0.7595865 0.6326966 -0.1507428 -0.8228226 0.5266704 -0.2134975 -0.06525027 -0.9958309 0.06374174 -0.7745751 -0.6304643 -0.05048018 -0.1218064 -0.9910382 0.0548321 -0.7539697 -0.6397591 -0.1491242 -0.7751066 -0.6299327 -0.0489332 -0.7555297 -0.6387992 -0.1452946 -0.7535574 -0.6411208 -0.1453111 -0.7535345 -0.6410948 -0.1455452 -0.773167 -0.6323035 -0.04904097 -0.7731677 -0.6322916 -0.04918557 -0.7574824 -0.6364841 -0.1452875 -0.7572165 -0.6366508 -0.1459423 -0.7591521 -0.6344569 -0.1454381 -0.7589834 -0.6345643 -0.1458503 -0.7602749 -0.633087 -0.1455434 -0.7601658 -0.6331571 -0.1458082 -0.7608526 -0.632377 -0.1456115 -0.7608035 -0.6324087 -0.1457306 -0.7608574 -0.6323449 -0.1457255 -0.7608981 -0.6323187 -0.1456271 -0.7603317 -0.6329658 -0.1457743 -0.7604122 -0.632914 -0.1455783 -0.7592404 -0.6342674 -0.1458044 -0.7593768 -0.6341807 -0.1454709 -0.7575752 -0.6362425 -0.1458602 -0.7577781 -0.6361155 -0.1453596 -0.7553693 -0.6388676 -0.1458268 -0.7555869 -0.6387342 -0.1452832 -0.7525537 -0.6421743 -0.1458597 -0.7528412 -0.6420028 -0.1451295 -0.7491748 -0.646117 -0.1458423 -0.7494782 -0.6459421 -0.1450561 -0.7451831 -0.6507154 -0.1458478 -0.7455239 -0.6505272 -0.1449432 -0.74061 -0.6559275 -0.1457939 -0.7409489 -0.6557499 -0.1448684 -0.7354041 -0.661768 -0.1457528 -0.7357605 -0.6615929 -0.1447454 -0.729582 -0.6681879 -0.1457226 -0.7299451 -0.6680234 -0.1446546 -0.7231266 -0.6751804 -0.1456683 -0.7234777 -0.675037 -0.1445862 -0.7160289 -0.6827095 -0.1456379 -0.7163745 -0.6825861 -0.1445125 -0.7082875 -0.6907442 -0.1456064 -0.7086126 -0.6906479 -0.1444775 -0.6999008 -0.6992457 -0.1455829 -0.700201 -0.6991783 -0.1444584 -0.6908679 -0.7081677 -0.1456023 -0.6911457 -0.7081297 -0.1444646 -0.6812037 -0.7174667 -0.1456127 -0.6814411 -0.7174602 -0.1445302 -0.670915 -0.7270866 -0.1456646 -0.6711192 -0.7271097 -0.1446038 -0.6600027 -0.7369902 -0.1457464 -0.6601687 -0.7370411 -0.1447333 -0.6416752 -0.752811 -0.146726 -0.6419422 -0.7530316 -0.1444088 -0.5971302 -0.7883139 -0.1483132 -0.5971023 -0.7890931 -0.1442245 -0.5157656 -0.8432263 -0.1515098 -0.5143925 -0.8450834 -0.1457206 -0.4058722 -0.9004613 -0.1563242 -0.4032235 -0.9024723 -0.1515079 -0.3539779 -0.9217951 -0.158093 -0.3537013 -0.9219697 -0.1576933 -0.3865932 -0.9092417 -0.1543536 -0.3881219 -0.9081524 -0.15691 -0.496882 -0.8551723 -0.1476088 -0.4978864 -0.8539741 -0.151121 -0.6143262 -0.7756667 -0.1447227 -0.6142492 -0.7753682 -0.1466358 -0.6960061 -0.703357 -0.1444454 -0.6957888 -0.7033959 -0.1453005 -0.7013577 -0.711128 -0.04893225 -0.7014843 -0.7110432 -0.04834467 -0.5976753 -0.8001759 -0.05002921 -0.5976948 -0.8002402 -0.0487492 -0.4474018 -0.8927141 -0.05378806 -0.4467161 -0.8931921 -0.05150282 -0.3057893 -0.9502819 -0.05879688 -0.304782 -0.950708 -0.0571165 -0.2627316 -0.9630197 -0.05970937 -0.2629103 -0.9629547 -0.05996906 -0.3283681 -0.9429494 -0.05496197 -0.3301482 -0.9421347 -0.0581761 -0.4712694 -0.8805671 -0.05006492 -0.4722441 -0.8798175 -0.05391412 -0.5767853 -0.8154565 -0.04847085 -0.5768712 -0.8152244 -0.05127328 -0.6336255 -0.7721202 -0.04846727 -0.6334971 -0.7721298 -0.04997128 -0.6566017 -0.7526701 -0.04859805 -0.656508 -0.7527054 -0.04931402 -0.6704595 -0.7403609 -0.04847609 -0.6703441 -0.7404171 -0.04920738 -0.6834861 -0.7283563 -0.04841411 -0.6833527 -0.7284324 -0.04914581 -0.6956999 -0.7167021 -0.04837179 -0.6955437 -0.7168019 -0.04913353 -0.7070652 -0.7054926 -0.04836285 -0.7068925 -0.7056128 -0.04912769 -0.7175924 -0.6947811 -0.04837691 -0.7174046 -0.6949211 -0.0491445 -0.7272761 -0.6846359 -0.04840683 -0.7270762 -0.6847938 -0.04917114 -0.7361193 -0.6751152 -0.04845327 -0.7359125 -0.6752867 -0.04920095 -0.7441315 -0.6662667 -0.04854899 -0.7439322 -0.6664389 -0.0492354 -0.7513501 -0.6581133 -0.04857861 -0.7511298 -0.6583105 -0.0493077 -0.7577432 -0.6507335 -0.04869288 -0.7575529 -0.6509094 -0.04930233 -0.7633801 -0.6441061 -0.04876667 -0.7631853 -0.6442907 -0.04937249 -0.7682452 -0.6382896 -0.04884362 -0.7680655 -0.638464 -0.04938983 -0.7723612 -0.6332966 -0.04892534 -0.7722017 -0.6334542 -0.04940062 -0.7757419 -0.6291449 -0.04900163 -0.7756038 -0.6292834 -0.04940706 -0.7784036 -0.6258403 -0.04910874 -0.7783026 -0.6259429 -0.04940146 -0.7803739 -0.6233777 -0.04916131 -0.7802854 -0.6234685 -0.04941588 -0.7816403 -0.6217843 -0.04922139 -0.7815889 -0.6218372 -0.04936802 -0.7822117 -0.6210589 -0.04930341 -0.7822054 -0.6210653 -0.04932111 -0.7821152 -0.6211782 -0.0493316 -0.7821303 -0.6211625 -0.04928863 -0.7813315 -0.6221603 -0.04937231 -0.7813934 -0.6220966 -0.04919564 -0.7798604 -0.6239975 -0.04944586 -0.7799772 -0.623878 -0.04911023 -0.7777174 -0.6266651 -0.04946154 -0.7778598 -0.6265209 -0.04904925 -0.01864045 -0.9542083 0.2985616 0.189565 -0.9583777 0.2134883 0.2771891 -0.9455612 0.170529 0.3300014 -0.1339611 0.9344267 0.3457132 -0.1224226 0.9303199 0.7565354 0.3061535 0.5778619 0.780648 0.3376406 0.5259159 0.8125405 0.3988259 0.425107 0.837195 0.4705063 0.2787979 0.8345621 0.4641888 0.2967067 0.7045181 0.7068878 -0.06295943 0.8388962 0.5142852 0.1782242 0.8394533 0.5185132 0.1626722 0.790645 0.5856031 0.1787443 0.7906324 0.5855845 0.178861 0.7820079 0.5481647 0.2966127 0.7819221 0.5480446 0.2970606 0.7248702 0.4426075 0.5278843 0.7244821 0.4421558 0.5287947 0.2944309 -0.0120573 0.9555967 0.2926555 -0.01349592 0.9561228 0.825738 0.5355953 0.1769022 0.8127151 0.5549741 0.1774766 0.8256111 0.535184 0.1787299 0.8010054 0.5715918 0.1779696 0.8125833 0.5546585 0.1790595 0.791019 0.5852241 0.1783303 0.8008843 0.571368 0.1792291 0.7830207 0.5957821 0.1786684 0.7909078 0.5850587 0.1793638 0.7773367 0.6031004 0.1789347 0.7829337 0.5956732 0.1794112 0.7746211 0.6065173 0.1791617 0.7772815 0.6030392 0.1793793 0.7745217 0.6066167 0.1792554 0.7746083 0.6065039 0.179262 0.7751474 0.605811 0.1792749 0.7745251 0.6066202 0.1792285 0.775811 0.6049721 0.1792376 0.775158 0.6058222 0.1791912 0.7751189 0.6058782 0.1791708 0.7758134 0.6049748 0.1792177 0.7726264 0.6090558 0.1791634 0.7750998 0.605858 0.179322 0.7687067 0.6139894 0.1791847 0.772593 0.6090222 0.1794214 0.763424 0.6205346 0.1792219 0.7686609 0.6139471 0.1795255 0.7566397 0.6287699 0.1792899 0.7633621 0.6204836 0.1796619 0.7483082 0.6386381 0.1793774 0.7565613 0.6287144 0.1798142 0.7383963 0.650049 0.1794632 0.7482146 0.6385833 0.1799623 0.7268518 0.6629203 0.1795085 0.7382916 0.6500006 0.1800687 0.7135991 0.6771531 0.179555 0.7267256 0.6628767 0.1801784 0.6985791 0.6926341 0.1795696 0.7134544 0.677119 0.1802571 0.6817402 0.7092213 0.1795423 0.6984142 0.6926116 0.1802967 0.6630259 0.7267706 0.1794466 0.6815582 0.7092119 0.1802692 0.6423877 0.7451111 0.179297 0.6628187 0.7267747 0.1801941 0.6192184 0.7645383 0.1790246 0.6421635 0.7451285 0.1800271 0.5733865 0.7997674 0.1777635 0.6189388 0.7645725 0.1798439 0.4741531 0.8629721 0.1745218 0.5726663 0.7998918 0.1795175 0.3049427 0.9375637 0.167285 0.4725688 0.8632693 0.177327 0.1133545 0.9809442 0.1577948 0.3021056 0.9378662 0.1707024 0.04812818 0.9866938 0.1553027 0.1109862 0.9808709 0.1599193 0.1253628 0.9790095 0.1607005 0.04819262 0.9866992 0.1552492 0.3360614 0.9261022 0.171457 0.1270381 0.9790428 0.1591747 0.5486801 0.8167963 0.1783089 0.3376285 0.9259004 0.1694561 0.6937293 0.6973755 0.1800193 0.5491361 0.8167103 0.1772958 0.6938479 0.6973881 0.1795127 0.8205168 0.4913455 0.2921158 0.8063296 0.5135658 0.2933987 0.8196399 0.4895633 0.29752 0.7934759 0.5326023 0.2945008 0.8055258 0.5121473 0.298049 0.7824287 0.5481904 0.2954534 0.7927696 0.531506 0.2983587 0.7735452 0.5602566 0.2962101 0.7818534 0.5473915 0.298442 0.7671983 0.5685637 0.2968873 0.7731053 0.5596978 0.2984064 0.764147 0.5723534 0.2974743 0.7669361 0.568251 0.2981608 0.7640113 0.5723788 0.2977737 0.7640811 0.5722771 0.2977904 0.7647098 0.5714372 0.2977892 0.7640397 0.5724116 0.2976381 0.7654452 0.5704763 0.2977421 0.7647505 0.5714849 0.2975927 0.7646885 0.5716052 0.2975214 0.7654584 0.5704916 0.2976794 0.7619248 0.5753463 0.2974006 0.7646051 0.5715079 0.2979225 0.7575545 0.5810809 0.2974159 0.7617582 0.5751574 0.2981921 0.7516468 0.5886693 0.2974821 0.7573269 0.580834 0.2984759 0.7440478 0.5982152 0.2975423 0.7513664 0.5883826 0.2987548 0.7346865 0.6096224 0.2976515 0.7437013 0.5978872 0.2990642 0.7235118 0.6227747 0.2977956 0.7342739 0.6092669 0.299392 0.7104443 0.637591 0.2979038 0.7230453 0.6224156 0.299674 0.6953971 0.6539312 0.2979879 0.7099155 0.637234 0.2999216 0.6782819 0.67166 0.2980048 0.6948104 0.6535905 0.3000969 0.6590289 0.6905853 0.2979478 0.6776328 0.6713423 0.3001888 0.6375656 0.7105292 0.2977557 0.6583281 0.6903021 0.300145 0.6138275 0.7312582 0.2974513 0.6368 0.7102792 0.2999821 0.5871152 0.7530937 0.2968935 0.6130145 0.7310482 0.2996366 0.5344216 0.7924616 0.2939356 0.5860984 0.752891 0.2994058 0.4204279 0.8607405 0.2869951 0.5319097 0.7921568 0.2992657 0.2287034 0.9345887 0.2724679 0.4154155 0.8604442 0.2950692 0.01659286 0.966552 0.2559333 0.2200152 0.933736 0.2823658 -0.05540192 0.9659413 0.2527613 0.01013833 0.9651307 0.261572 0.02682095 0.9644322 0.2629663 -0.05513691 0.9660131 0.2525447 0.2609266 0.9228963 0.2831605 0.03153634 0.9654201 0.2587847 0.5051697 0.8104538 0.2965943 0.2653812 0.9232584 0.2777891 0.6726114 0.6766616 0.2995378 0.5068828 0.8106134 0.2932163 0.6730684 0.6768735 0.2980288 0.76936 0.3756709 0.5166786 0.7534415 0.4024574 0.5199557 0.7645683 0.3693045 0.5282515 0.7387431 0.4253424 0.5228217 0.7492259 0.3971296 0.5300459 0.7259072 0.4439929 0.5252895 0.7351807 0.4210461 0.5312528 0.7154769 0.4583866 0.5272329 0.7231055 0.44075 0.531844 0.7078766 0.4681079 0.5289478 0.7133802 0.4560387 0.5320879 0.7040583 0.4722563 0.5303545 0.7066541 0.466771 0.5317564 0.7037277 0.4720008 0.5310205 0.70376 0.4719337 0.531037 0.7045078 0.4707907 0.53106 0.7038498 0.4721329 0.5307409 0.7053998 0.4696994 0.5308423 0.7047357 0.4710381 0.5305383 0.7046558 0.4713184 0.5303955 0.7054461 0.4697497 0.5307362 0.7015308 0.47609 0.5302764 0.7042295 0.4708561 0.5313712 0.6965051 0.4832677 0.5304082 0.7007622 0.475265 0.5320296 0.6896823 0.492736 0.5306125 0.6954987 0.4822055 0.5326908 0.6808195 0.5045742 0.5309329 0.688409 0.4914225 0.5334762 0.6697875 0.5186445 0.5314064 0.6792647 0.5030165 0.5343912 0.6565762 0.5348603 0.5318196 0.6680486 0.516964 0.5352191 0.6409875 0.5530533 0.5322287 0.6546164 0.5330451 0.5360412 0.6229372 0.5730497 0.5325068 0.638854 0.5511728 0.5367255 0.6022427 0.5946311 0.5326514 0.6206119 0.5711115 0.5372824 0.5788939 0.6175836 0.5324212 0.5998255 0.5927373 0.5374682 0.5526882 0.641564 0.531913 0.576314 0.6156933 0.5373862 0.5236306 0.6662766 0.5309298 0.5500271 0.6397476 0.5368363 0.4908457 0.6920688 0.5292555 0.520884 0.6645335 0.5357938 0.4270259 0.7386811 0.5215354 0.4875107 0.6901035 0.5348743 0.289946 0.8143427 0.5027695 0.4194207 0.7347205 0.5331718 0.06757563 0.8826269 0.4651916 0.2761556 0.8081547 0.5202155 -0.1631669 0.8907645 0.4241639 0.04776221 0.8734556 0.4845556 -0.2395223 0.8774825 0.415516 -0.1758702 0.8833976 0.4343712 -0.1570114 0.8850913 0.4381332 -0.2390025 0.877813 0.4151172 0.09848803 0.8668399 0.4887625 -0.1476244 0.8904346 0.4305036 0.389252 0.7557497 0.5266169 0.1093446 0.8717223 0.4776442 0.5945455 0.5991678 0.536203 0.3941159 0.758153 0.5194967 0.5963726 0.6005761 0.5325863 0.3517152 -0.0731939 0.9332413 0.3324342 -0.04751849 0.9419286 0.3289176 -0.09067893 0.9399949 0.3144721 -0.02551692 0.9489237 0.3128104 -0.06287801 0.947732 0.2988908 -0.007407486 0.9542586 0.2985566 -0.03819751 0.9536272 0.2859317 0.006327807 0.9582292 0.2863923 -0.01751476 0.9579524 0.2760349 0.01514798 0.9610283 0.2767798 -0.00115931 0.9609326 0.2703028 0.01810008 0.9626051 0.2707983 0.01082921 0.9625753 0.2693021 0.01727133 0.9629008 0.2693023 0.01727181 0.9629009 0.2699731 0.01581907 0.9627379 0.2697845 0.01767051 0.9627587 0.2710276 0.01477122 0.9624582 0.2708224 0.01652151 0.9624876 0.2710099 0.01720803 0.9624227 0.2713073 0.01500236 0.9623758 0.2680099 0.02265191 0.9631498 0.269104 0.01563107 0.9629843 0.262836 0.03056681 0.9643563 0.2647485 0.01994329 0.9641113 0.2554417 0.04074764 0.9659654 0.258331 0.02680361 0.9656845 0.2457925 0.0535171 0.9678439 0.2499293 0.0361073 0.9675907 0.2339065 0.06888639 0.9698157 0.2395249 0.04818916 0.9696937 0.2192888 0.08636671 0.9718298 0.2266197 0.06261837 0.9719683 0.2020679 0.1061175 0.9736055 0.2113837 0.07947218 0.9741668 0.1821708 0.1279643 0.9749046 0.1937126 0.09871399 0.9760794 0.1596119 0.1518393 0.9754327 0.1736229 0.1202533 0.9774427 0.1338726 0.1770043 0.9750629 0.150537 0.143488 0.9781359 0.1055685 0.2037616 0.9733121 0.1250627 0.1687171 0.9776983 0.07436966 0.2313343 0.9700276 0.09676533 0.1952806 0.9759621 0.03943991 0.2601519 0.9647619 0.06550645 0.2225715 0.9727131 -0.02323812 0.3179874 0.9478101 0.02993869 0.2504836 0.9676579 -0.1543623 0.4097011 0.8990646 -0.04328763 0.2964153 0.9540777 -0.3467845 0.4912893 0.7989839 -0.1826759 0.3756086 0.9085965 -0.5220223 0.498112 0.6923706 -0.3760408 0.4491901 0.8104452 -0.5758172 0.4773228 0.6637752 -0.5356372 0.4741102 0.6987934 -0.5214818 0.4754509 0.7085219 -0.5752195 0.4784595 0.663475 -0.3306906 0.4472069 0.8310534 -0.5109292 0.4937688 0.7036645 -0.06845015 0.3240646 0.9435553 -0.3136703 0.4707568 0.8246206 0.1473231 0.1519182 0.9773519 -0.05588334 0.3379147 0.9395162 0.1535961 0.1577255 0.9754645 0.6819418 -0.725597 -0.09200143 0.6091307 0.7905884 -0.0626865 0.765985 -0.6234885 -0.1566174 0.8210487 -0.5302149 -0.2115445 0.6091644 0.7904627 -0.06393325 0.8201592 0.5720894 -0.00724554 0.8075668 0.5863286 -0.06367653 0.8192508 0.5733438 -0.01025211 0.1747137 0.9831334 0.05407327 0.7897894 0.5998015 -0.1283383 0.80711 0.5868152 -0.06497281 0.7587197 0.613898 -0.2178845 0.789565 0.5999783 -0.128892 0.7595652 0.6134808 -0.2161063 0.7355391 0.6429343 -0.2135829 0.7355021 0.6429198 -0.2137537 0.7587259 0.6389953 -0.1265704 0.7587001 0.6389854 -0.126775 0.7716354 0.6329286 -0.06308948 0.7716262 0.6329252 -0.06323671 0.7800506 0.6256539 -0.008855342 0.7800492 0.6256543 -0.008947014 0.7057219 0.7084372 -0.008565962 0.7057611 0.7084016 -0.008282244 0.5987861 0.8008534 -0.009434461 0.5987511 0.8008869 -0.008782148 0.4435446 0.8961623 -0.01270914 0.4431368 0.8963795 -0.01156121 0.2850546 0.9583443 -0.01789569 0.2843837 0.9585619 -0.01688534 0.2239172 0.9744046 -0.01991868 0.2238691 0.974417 -0.01985692 0.2730002 0.9618638 -0.01699984 0.2739561 0.9615664 -0.01838737 0.4181591 0.9082974 -0.01178497 0.419022 0.9078698 -0.01389199 0.5434926 0.839363 -0.009240031 0.5437645 0.8391669 -0.01090806 0.6164334 0.7873603 -0.008582413 0.6164567 0.7873305 -0.009586215 0.6502758 0.7596501 -0.008552014 0.6502569 0.7596608 -0.009029984 0.667408 0.7446445 -0.008433938 0.6673777 0.7446667 -0.008866071 0.6827123 0.7306391 -0.008396625 0.6826741 0.73067 -0.008788526 0.6966774 0.7173363 -0.008321821 0.6966209 0.7173856 -0.008786797 0.7093087 0.7048488 -0.008321166 0.7092497 0.7049033 -0.008735179 0.7206399 0.6932592 -0.008354485 0.7205767 0.6933202 -0.008746504 0.7306925 0.6826551 -0.008400857 0.7306253 0.6827223 -0.00877887 0.7395051 0.673098 -0.008445322 0.7394345 0.6731708 -0.008813321 0.7471011 0.664656 -0.008504271 0.7470337 0.6647275 -0.008835315 0.7535182 0.657371 -0.00858277 0.7534587 0.6574355 -0.00886166 0.7587751 0.6512955 -0.008641481 0.7587184 0.651358 -0.008897066 0.7628653 0.6464987 -0.008710384 0.7628217 0.6465476 -0.008902192 0.7658986 0.6429017 -0.008760333 0.7658628 0.6429422 -0.008914649 0.7678853 0.6405268 -0.008807659 0.7678633 0.6405519 -0.008901059 0.7685251 0.6397584 -0.008863687 0.768527 0.6397561 -0.008855521 0.767836 0.6405851 -0.00886166 0.7678479 0.6405717 -0.008811116 0.767201 0.6413459 -0.00883919 0.7672075 0.6413387 -0.008811354 0.7675527 0.6409254 -0.008804678 0.7675381 0.6409422 -0.008866906 0.7696569 0.6383981 -0.00872302 0.769596 0.638468 -0.00897932 0.7740549 0.633059 -0.008683443 0.7739516 0.6331793 -0.009107291 0.7803676 0.6252608 -0.008679807 0.7802198 0.6254367 -0.009264945 0.7883017 0.6152274 -0.008709669 0.7881059 0.615467 -0.009453356 0.7976904 0.6030032 -0.008782505 0.7974421 0.6033178 -0.009683966 0.8082445 0.5887798 -0.008899629 0.8079404 0.5891801 -0.009952962 0.7521858 0.6226999 -0.2155489 0.753355 0.6221848 -0.2129371 0.7456262 0.6306865 -0.2151188 0.746582 0.6303142 -0.2128834 0.7398683 0.6375615 -0.214733 0.7406226 0.6373032 -0.2128913 0.7350549 0.6432125 -0.2144109 0.7356281 0.64304 -0.2129572 0.731287 0.6475924 -0.2141109 0.7316827 0.6474868 -0.2130761 0.7287349 0.6505512 -0.2138424 0.7289615 0.6504962 -0.2132369 0.7276024 0.6518883 -0.2136266 0.7276647 0.651874 -0.2134585 0.7274697 0.6520709 -0.2135217 0.7274503 0.6520752 -0.2135742 0.7279128 0.6515894 -0.2134814 0.7278509 0.6516038 -0.2136483 0.7282763 0.6511507 -0.2135798 0.7282704 0.6511521 -0.2135959 0.7277827 0.6516711 -0.2136753 0.7278648 0.6516522 -0.2134536 0.7264834 0.6531006 -0.2137327 0.7266283 0.6530686 -0.213337 0.7245528 0.6552311 -0.2137652 0.7247391 0.6551936 -0.2132479 0.7219774 0.6580631 -0.2137792 0.7221999 0.6580241 -0.2131474 0.7186986 0.661641 -0.2137841 0.7189547 0.6616047 -0.2130341 0.7147356 0.6659321 -0.2137463 0.7150027 0.6659057 -0.2129337 0.7100663 0.6709091 -0.2137447 0.7103586 0.670896 -0.2128126 0.7046989 0.6765469 -0.2137374 0.704992 0.6765536 -0.2127479 0.6986204 0.6828364 -0.2136914 0.698895 0.682866 -0.2126966 0.6918105 0.6897294 -0.2137095 0.6920838 0.6897885 -0.2126303 0.6842764 0.6972062 -0.2137038 0.6845171 0.6972925 -0.2126489 0.6760028 0.7052152 -0.2137564 0.6762204 0.7053355 -0.2126684 0.6670002 0.7137153 -0.2138251 0.6671791 0.7138639 -0.2127689 0.6569239 0.7229102 -0.2141305 0.6570925 0.7231268 -0.2128781 0.6369565 0.7402493 -0.2152146 0.6371285 0.7408666 -0.2125657 0.5950874 0.7737743 -0.2171273 0.59473 0.775209 -0.2129487 0.5247796 0.8219958 -0.2211995 0.5228676 0.8246787 -0.2156719 0.4438877 0.8669545 -0.2266135 0.4416108 0.8690253 -0.223103 0.4159417 0.8803969 -0.227802 0.4161259 0.8802462 -0.2280479 0.4500188 0.8646907 -0.2231438 0.4516084 0.8631939 -0.2257123 0.5394526 0.8138573 -0.2159331 0.5403444 0.8124331 -0.2190444 0.6278433 0.7486429 -0.212947 0.6277913 0.7482172 -0.2145906 0.6903289 0.6915423 -0.2126389 0.6901462 0.6914963 -0.2133805 0.7803361 0.6120273 -0.1284455 0.7812976 0.6113223 -0.1259332 0.7719783 0.6226139 -0.1280687 0.7727663 0.6220756 -0.125913 0.7646136 0.6317107 -0.1277012 0.7652273 0.6313195 -0.1259482 0.7584273 0.6391837 -0.1274057 0.7588979 0.6389021 -0.1260088 0.7535508 0.6449776 -0.1271419 0.7538805 0.6447907 -0.1261309 0.7502192 0.6489015 -0.1268783 0.7504028 0.6488016 -0.1263022 0.7486986 0.6506982 -0.1266576 0.7487474 0.6506722 -0.1265031 0.7484852 0.6509605 -0.1265718 0.7484754 0.6509656 -0.126603 0.7490331 0.650342 -0.1265097 0.7489768 0.6503721 -0.1266883 0.7495238 0.6497549 -0.1266197 0.7495233 0.6497552 -0.1266218 0.7489347 0.6504116 -0.1267341 0.7490066 0.6503733 -0.1265065 0.747314 0.6522641 -0.1267797 0.7474268 0.6522052 -0.1264183 0.7448794 0.655041 -0.1267911 0.7450226 0.6549685 -0.1263234 0.7416105 0.6587355 -0.1268122 0.7417908 0.6586484 -0.1262094 0.7374406 0.6634009 -0.126809 0.7376432 0.663309 -0.1261096 0.7323687 0.6689959 -0.126809 0.7325919 0.6689032 -0.1260069 0.7263961 0.6754766 -0.1268072 0.7266288 0.675391 -0.1259272 0.7195039 0.6828159 -0.1267932 0.7197349 0.6827445 -0.1258635 0.7116646 0.6909832 -0.1267897 0.7118908 0.6909301 -0.1258065 0.7028806 0.6999213 -0.1267635 0.7030859 0.6998924 -0.1257811 0.6931157 0.7095919 -0.126767 0.6933034 0.7095888 -0.1257538 0.6823714 0.7199201 -0.1268241 0.6825378 0.719946 -0.1257775 0.6706401 0.7308519 -0.1268744 0.6707699 0.7309058 -0.1258754 0.657515 0.7426375 -0.1271362 0.6576286 0.7427369 -0.1259621 0.6315382 0.7646854 -0.1281231 0.6316131 0.7650387 -0.1256206 0.5764177 0.806774 -0.1298394 0.575952 0.8077409 -0.125833 0.4827297 0.8655653 -0.1332997 0.4807818 0.8674392 -0.128055 0.3736924 0.9172765 -0.1376875 0.371481 0.9186668 -0.1343621 0.3359341 0.9316161 -0.1387072 0.335976 0.9315928 -0.1387622 0.3817345 0.9144239 -0.1345653 0.383359 0.9133653 -0.1371126 0.5015735 0.8555207 -0.1284855 0.5024774 0.8545534 -0.1313584 0.6188949 0.7752956 -0.1260389 0.6188989 0.7750433 -0.1275622 0.7006163 0.7023653 -0.1257768 0.7004643 0.702382 -0.1265273 0.7967379 0.6008615 -0.06460797 0.7974022 0.6001899 -0.06262463 0.7871772 0.6133665 -0.06429439 0.7877287 0.6128364 -0.06257057 0.7787098 0.6241108 -0.06400543 0.7791436 0.6237128 -0.06258904 0.7715803 0.6329283 -0.06376338 0.7719095 0.6326383 -0.06264495 0.7659366 0.6397691 -0.06353545 0.7661638 0.6395757 -0.0627374 0.7620473 0.6444204 -0.06329464 0.7621692 0.6443192 -0.06285625 0.7602291 0.6465809 -0.06312692 0.7602672 0.6465495 -0.06298786 0.7599515 0.6469132 -0.06306266 0.7599467 0.6469173 -0.06308013 0.7605504 0.6462119 -0.0630325 0.7605172 0.6462392 -0.0631532 0.7611475 0.6455014 -0.06310677 0.7611427 0.6455054 -0.06312423 0.7605182 0.6462359 -0.06317538 0.7605612 0.6462006 -0.06301933 0.758686 0.6483834 -0.06320136 0.7587612 0.6483225 -0.06292492 0.7559087 0.6516166 -0.06322801 0.7560124 0.6515339 -0.06283897 0.7521775 0.6559186 -0.06324476 0.7523021 0.6558218 -0.06276553 0.747402 0.6613548 -0.06324654 0.747543 0.6612488 -0.0626859 0.7415859 0.6678717 -0.06322807 0.7417352 0.6677643 -0.06260842 0.7347186 0.6754212 -0.06320321 0.7348732 0.6753162 -0.06252658 0.7267733 0.6839662 -0.06317228 0.7269266 0.6838693 -0.0624538 0.7177171 0.6934623 -0.06318426 0.7178726 0.693373 -0.0623908 0.7075395 0.7038434 -0.06318449 0.7076802 0.7037732 -0.06238746 0.6962107 0.7150509 -0.06318867 0.696334 0.7150012 -0.06238901 0.6837218 0.7269995 -0.06321561 0.6838254 0.7269715 -0.06241309 0.6700468 0.7396171 -0.06327629 0.6701275 0.7396119 -0.06247735 0.654751 0.7531738 -0.06348437 0.6548142 0.7531954 -0.06257289 0.6245316 0.7783479 -0.06430304 0.6245407 0.7785002 -0.06234008 0.5598956 0.8259465 -0.06579792 0.5594621 0.8264843 -0.06265628 0.449359 0.8906894 -0.06891226 0.4477589 0.8918036 -0.06479376 0.3204473 0.9444463 -0.07303988 0.3186486 0.9452568 -0.07037377 0.2756511 0.958406 -0.07398957 0.2757645 0.958362 -0.07413727 0.329654 0.9414615 -0.0705589 0.3308745 0.9408904 -0.07243973 0.4709478 0.8797554 -0.06510317 0.4716981 0.8791839 -0.06735372 -6.92328e-6 4.84752e-6 -1 -0.819164 0.5735594 3.47443e-7 0 0 -1 -0.5735554 0.819164 -0.002123951 1.34871e-5 1.34871e-5 -1 -0.6835718 0.7298833 4.42139e-7 -0.3581099 0.933574 -0.01403713 -0.4994233 0.8663277 -0.007267355 -0.6361277 0.7715831 -0.001139879 7.36884e-6 1.15609e-5 -1 -0.9659208 0.2588379 0 8.43165e-6 1.23051e-5 -1 -3.46223e-5 -1.99892e-5 -1 -1.01747e-5 0 -1 -0.8934327 0.4491969 0 -0.8594312 0.5112501 -0.001120328 -0.8178688 0.5753944 -0.003474354 -0.8786427 0.4774796 -4.12632e-4 -0.756586 0.6538265 -0.009416818 -7.03803e-6 -6.15998e-7 -1 -0.9961916 -0.08719086 0 4.02004e-7 4.59406e-6 -1 -0.9659208 0.2588379 0 -3.46594e-5 -1.61619e-5 -1 -0.9063079 -0.4226182 0 5.61117e-6 1.20332e-5 -1 -0.9961916 -0.08719086 0 -0.7071068 -0.7071068 -1.68587e-7 -0.9063079 -0.4226182 0 -0.4226182 -0.9063079 -2.16081e-7 -0.7071068 -0.7071068 -1.68587e-7 -0.08717197 -0.9961933 -2.37511e-7 -0.4226182 -0.9063079 -2.16081e-7 -2.0535e-6 7.66337e-6 -1 0.2588318 -0.9659224 -2.30294e-7 6.32167e-6 1.0949e-5 -1 -0.08717197 -0.9961933 -2.37511e-7 -5.04939e-6 7.21156e-6 -1 0.5735598 -0.8191609 -0.002124726 -4.23455e-6 7.33446e-6 -1 0 1.01748e-5 -1 0.2588318 -0.9659224 -2.30294e-7 0.4609841 -0.8874084 -2.11575e-7 -6.92331e-6 4.84752e-6 -1 0.8191649 -0.573558 -3.47442e-7 -7.77318e-6 4.48778e-6 -1 0.3580998 -0.9335778 -0.01403886 0.4994196 -0.8663297 -0.007268607 0.6361451 -0.7715687 -0.001140058 0.6835556 -0.7298985 -4.42462e-7 -6.61222e-6 1.77188e-6 -1 0.9659208 -0.2588379 0 -1.11372e-4 -7.15771e-5 -1 5.39111e-5 5.2399e-5 -1 -1.01747e-5 0 -1 0.8934869 -0.4490892 0 0.7565879 -0.6538242 -0.009417355 0.8593813 -0.511334 -0.001123845 0.817873 -0.5753884 -0.003474593 0.8786333 -0.4774969 -4.14664e-4 7.35012e-6 1.37722e-5 -1 0.9961938 0.08716547 0 8.04062e-7 9.18817e-6 -1 0.9659208 -0.2588379 0 -3.46594e-5 -1.61619e-5 -1 0.9063079 0.4226182 0 5.61111e-6 1.20332e-5 -1 0.9961938 0.08716547 0 0.7071068 0.7071068 1.68587e-7 0.9063079 0.4226182 0 0.4226157 0.9063091 2.16081e-7 0.7071068 0.7071068 1.68587e-7 0.08717733 0.9961929 2.16726e-7 0.4226182 0.9063079 0 0 0 -1 -0.2588318 0.9659224 2.30294e-7 0 0 -1 0.08717674 0.9961928 2.37511e-7 0 0 -1 0 0 -1 -0.2588318 0.9659224 2.30294e-7 -0.4610026 0.8873988 2.11572e-7 0.5000079 -0.8660209 -2.06475e-7 0.8660249 -0.500001 -1.1921e-7 0.8660249 -0.500001 -1.1921e-7 0 -1 -2.38419e-7 0.5000079 -0.8660209 -2.06906e-7 -0.5000079 -0.8660209 -2.06475e-7 0 -1 -2.38419e-7 -0.8660271 -0.499997 -2.38417e-7 -0.5000149 -0.8660168 -4.12949e-7 -1 1.84235e-5 0 -0.8660249 -0.500001 -1.1921e-7 -0.8660288 0.4999941 0 -1 1.84235e-5 0 -0.5 0.8660254 2.06477e-7 -0.8660288 0.4999941 0 -9.21175e-6 1 2.38419e-7 -0.5 0.8660254 2.06477e-7 0.5000149 0.8660168 2.06474e-7 -9.21175e-6 1 2.38419e-7 0.8660249 0.500001 2.38419e-7 0.5000079 0.8660209 4.12951e-7 1 -9.21166e-6 0 0.8660271 0.499997 0 1 -9.21166e-6 0 0 0 1 -0.5735611 0.8191629 0 0 0 1 -0.8191606 0.5735615 0.001733601 0 0 1 -0.9912893 0.1285598 0.0285989 -0.963779 0.2658293 0.02156054 -0.8287041 0.559666 0.004848062 -0.7850394 0.6194433 0.001773416 -0.7504929 0.6608784 4.9069e-4 -0.7221356 0.6917516 0 1.77184e-6 -6.61226e-6 1 9.61779e-5 1.28222e-4 1 0 0 1 0 0 1 -0.6468423 0.7625758 0.008568525 -0.5510461 0.8344721 0.002118587 -6.15888e-7 -7.03792e-6 1 -5.19991e-6 -1.3584e-5 1 -1.61619e-5 -3.46594e-5 1 1.20332e-5 5.61117e-6 1 7.66334e-6 -2.05355e-6 1 1.59319e-7 -2.11819e-5 1 7.21159e-6 -5.04937e-6 1 0.8191637 -0.5735571 0.001734673 7.33449e-6 -4.23451e-6 1 1.01747e-5 0 1 4.84754e-6 -6.92328e-6 1 0.5735611 -0.8191629 0 4.48781e-6 -7.77312e-6 1 0.7221092 -0.6917791 0 0.9912177 -0.1291168 0.02857118 0.9638716 -0.2654917 0.02157819 0.8287052 -0.5596643 0.004848659 0.7850664 -0.619409 0.001775741 0.7504467 -0.6609309 4.90337e-4 8.85922e-7 -3.30613e-6 1 -3.5786e-5 -5.56825e-5 1 -1.99914e-5 -3.46253e-5 1 0 -1.01748e-5 1 0.6468424 -0.7625756 0.008568525 0.5510461 -0.8344721 0.002118587 -6.1585e-7 -7.03788e-6 1 4.59413e-6 4.02098e-7 1 -1.61619e-5 -3.46594e-5 1 1.20332e-5 5.61117e-6 1 -4.80488e-6 -1.2248e-5 1 0 0 1 -2.95165e-6 -1.95697e-5 1 1.01747e-5 0 1 -0.7386967 -0.6240442 -0.2547472 -0.6197225 -0.6197133 -0.4815594 -0.7945325 -0.603301 -0.06889098 -0.7035367 -0.6377099 -0.3136274 -0.7786397 -0.6102183 -0.1461296 -0.7051275 -0.7053536 0.07260614 -0.8124389 -0.5829983 0.007493257 -0.8015667 -0.5958398 -0.04965674 -0.7051309 -0.7053506 0.07260209 -0.7051337 -0.7053472 0.07260638 -0.7051099 -0.7053714 0.07260394 -0.8216068 -0.5064935 0.2615847 -0.7049481 -0.7055376 0.07255804 -0.8271937 -0.5481839 0.1234704 -0.8265109 -0.5502365 0.1188257 -0.07465744 0.2527484 0.9646474 -0.8215265 -0.5076963 0.2594973 -0.7312478 -0.2983819 0.6133881 0.6197072 0.6197078 0.4815863 0.3397352 0.5251131 0.7802796 0.619713 0.61971 0.4815758 0.6198762 0.619543 0.4815809 0.6197108 0.6197082 0.481581 0.6197105 0.6197083 0.4815815 -0.6196995 -0.6197196 0.4815809 -0.6196994 -0.6197128 0.4815898 -0.6197068 -0.6197123 0.4815809 -0.6196992 -0.6197127 0.4815902 -0.6197096 -0.6197096 0.4815806 -0.7052407 -0.7052407 -0.07260286 -0.7052615 -0.7052199 -0.07260221 0.6197105 0.6197105 -0.4815784 -0.705241 -0.7052403 -0.07260233 0.6191626 0.6202498 -0.481589 0.6197109 0.6197151 -0.481572 0.6197084 0.6197043 -0.4815892 -0.6197129 -0.6197049 -0.4815824 -0.6199856 -0.6194325 -0.4815818 -0.619713 -0.6197052 -0.4815821 0.7387008 0.624045 -0.2547334 0.619709 0.6197134 -0.4815765 0.7945297 0.6033032 -0.06890326 0.6738106 0.6461873 -0.3583592 0.7526041 0.6226419 -0.2142525 0.7829806 0.6088771 -0.1273191 0.705155 0.7053253 0.07261347 0.8122731 0.5832273 0.007633566 0.7964749 0.6013079 -0.06368911 0.8101311 0.5861721 -0.009475231 0.7052134 0.7052688 0.07259488 0.7052396 0.7052403 0.07261717 0.7051099 0.7053714 0.07260394 0.8196486 0.5094581 0.2619706 0.7049775 0.7055104 0.07253801 0.8253738 0.5511129 0.1226081 0.8275159 0.5325533 0.1777766 0.08328592 -0.2590508 0.9622662 0.8192465 0.4917456 0.2949942 0.7711017 0.3647981 0.5218473 -0.6197171 -0.6197196 0.4815584 -0.4722877 -0.5791211 0.6645021 0.3223254 -0.05477339 0.945043 0.619707 0.6197067 0.4815878 0.7052406 0.7052406 -0.07260465 0.7053804 0.7051011 -0.07260036 -0.619707 -0.619707 -0.4815876 0.7052407 0.7052407 -0.07260125 -0.8210953 -0.5662938 -0.07151132 -0.6197104 -0.6197108 0.4815782 -0.6197112 -0.6197106 0.4815775 -0.6197035 -0.6197137 0.4815833 -0.6197165 -0.6197059 0.4815767 -0.6197114 -0.61971 0.4815779 -0.6197099 -0.6197116 0.4815778 -0.7520714 -0.6153443 0.2360928 -0.7538454 -0.6142581 0.233247 -0.8210851 -0.5663207 -0.07141458 -0.8210861 -0.5663189 -0.07141661 -0.8210757 -0.5663388 -0.07138055 -0.821078 -0.5663324 -0.07140445 -0.8210843 -0.566322 -0.0714153 -0.8210828 -0.5663257 -0.07140296 -0.8210889 -0.5663112 -0.07144713 -0.8210688 -0.566357 -0.07131445 -0.8210816 -0.5663281 -0.07139694 -0.8210919 -0.5663056 -0.07145559 -0.8210833 -0.5663234 -0.07141333 -0.4846507 -0.5660125 0.666891 -0.4762072 -0.5104672 0.7159958 -0.5219241 -0.5790563 0.6263297 -0.5157814 -0.4776235 0.7112281 -0.5643632 -0.5637397 0.6030685 -0.5868492 -0.519679 0.6209203 -0.5898525 -0.3971299 0.7031087 -0.5950863 -0.5346307 0.6000353 -0.6197072 -0.6197129 0.4815796 -0.632357 -0.5070808 0.5856566 -0.6197074 -0.6197128 0.4815796 -0.6626607 -0.3508012 0.6616791 -0.6326613 -0.5122173 0.5808383 -0.6197107 -0.6197105 0.4815781 -0.6717415 -0.4397028 0.5961751 -0.6197008 -0.6197183 0.4815809 -0.6958231 -0.3597269 0.6216325 -0.6684225 -0.4629582 0.582135 -0.619713 -0.6197077 0.4815788 -0.6984191 -0.3762544 0.6088047 -0.6197077 -0.6197128 0.4815793 -0.6967833 -0.3869712 0.6039424 -0.6197178 -0.6197051 0.4815759 -0.6950904 -0.3737025 0.6141626 -0.6197088 -0.6197115 0.4815793 -0.700748 -0.3635309 0.6138384 -0.6197074 -0.6197132 0.481579 -0.6738863 0.04129505 0.7376801 -0.6197162 -0.6197059 0.481577 -0.6626833 -0.4218412 0.6187898 -0.6979975 -0.2780691 0.6599069 -0.6196976 -0.6197221 0.4815801 -0.5467664 0.08880972 0.8325619 -0.6197109 -0.6197098 0.4815787 -0.621005 -0.4640678 0.6316597 -0.6032164 -0.08723205 0.7927929 -0.6197083 -0.6197123 0.4815788 -0.5415244 -0.281929 0.792002 -0.6197161 -0.6197057 0.4815775 -0.582145 -0.493587 0.6461261 -0.6197094 -0.6197112 0.4815788 -0.5784666 -0.3803446 0.7216054 -0.6197047 -0.6197159 0.481579 -0.5640356 -0.4953542 0.6606725 -0.533206 -0.4137962 0.7378781 -0.6197078 -0.6197128 0.4815788 -0.5495516 -0.4921861 0.6750897 -0.6197101 -0.6197108 0.4815785 -0.5509867 -0.5067624 0.6630275 -0.6197087 -0.619712 0.4815788 -0.5414937 -0.4818257 0.688933 -0.61971 -0.6197109 0.4815785 -0.5335029 -0.4932487 0.687081 -0.6197101 -0.6197108 0.4815785 -0.5403257 -0.5145897 0.6657669 -0.5414095 -0.5025504 0.6740317 -0.6196992 -0.6197205 0.4815801 -0.538901 -0.5245974 0.6590777 -0.6197072 -0.6197138 0.4815785 -0.5283014 -0.5026471 0.6842831 -0.6197135 -0.6197074 0.4815785 -0.5351572 -0.531946 0.6562319 -0.5205388 -0.5091314 0.6854376 -0.6197054 -0.6197147 0.4815796 -0.5306015 -0.5387622 0.6543679 -0.6197111 -0.61971 0.4815785 -0.5147657 -0.5165962 0.684211 -0.6197082 -0.619712 0.4815794 -0.523324 -0.5433268 0.656451 -0.5116154 -0.5251738 0.6800311 -0.6197109 -0.6197097 0.4815789 -0.5209579 -0.5514642 0.651529 -0.6197072 -0.6197132 0.4815794 -0.5084841 -0.5403707 0.6704054 -0.5152223 -0.5377464 0.667364 -0.6197069 -0.6197136 0.4815791 -0.5145418 -0.5555639 0.6531428 -0.6197096 -0.6197112 0.4815788 -0.4987836 -0.5402459 0.6777531 -0.6197112 -0.6197093 0.481579 -0.510401 -0.5596596 0.652895 -0.6197086 -0.6197118 0.4815793 -0.4971373 -0.5496088 0.671405 -0.5062124 -0.5509233 0.6635003 -0.6197078 -0.619713 0.4815788 -0.4967919 -0.5563027 0.6661269 -0.6197158 -0.6197063 0.4815769 -0.6197024 -0.6197192 0.4815777 -0.4971057 -0.5531277 0.6685326 -0.6197091 -0.6197119 0.4815783 -0.4955024 -0.5566142 0.6668268 -0.6197065 -0.619714 0.4815792 -0.6197086 -0.6197122 0.4815789 -0.4954929 -0.5564675 0.6669564 -0.5102569 -0.5632743 0.6498923 -0.6197096 -0.6197113 0.4815787 -0.4937489 -0.5552926 0.6692252 -0.6197111 -0.61971 0.4815783 -0.4927472 -0.554597 0.6705389 -0.491931 -0.5545579 0.6711702 -0.4867379 -0.5520132 0.6770285 -0.619707 -0.6197144 0.4815781 -0.5065219 -0.5666444 0.6498843 -0.6197084 -0.6197131 0.4815777 -0.6197056 -0.619716 0.4815777 -0.4889087 -0.5540345 0.6738057 -0.4953997 -0.556117 0.6673178 -0.6197091 -0.6197115 0.481579 -0.5075363 -0.5755574 0.6412026 -0.6197072 -0.6197128 0.4815796 -0.6197125 -0.619708 0.4815793 -0.4816059 -0.5590116 0.6749531 -0.501448 -0.564355 0.6557843 -0.6197085 -0.6197118 0.4815794 -0.5015898 -0.583069 0.6390918 -0.6197098 -0.6197108 0.481579 -0.4769409 -0.5708543 0.6683208 -0.4865252 -0.5677577 0.6640363 -0.6197089 -0.6197127 0.4815776 -0.4898954 -0.5894784 0.6422755 -0.6196995 -0.6197182 0.4815828 -0.6197025 -0.6197164 0.4815813 -0.6197388 -0.6196915 0.4815666 -0.6196971 -0.6197221 0.4815809 -0.619705 -0.6197158 0.4815786 -0.4588102 -0.5722392 0.6797321 -0.001957237 -0.9533618 0.3018237 -0.3812561 -0.833584 0.3997268 -0.4760775 -0.5862473 0.6554878 -0.07680422 -0.9568624 0.280206 -0.2512836 -0.932619 0.2589949 -0.07411676 -0.9629831 0.2591722 -0.4020303 -0.884157 0.2379878 -0.2929087 -0.930526 0.2198316 -0.5304691 -0.8245478 0.1967827 -0.6156969 -0.7582141 0.2145429 -0.5140506 -0.8298825 0.2169035 -0.6207837 -0.7682783 0.1561286 -0.6370037 -0.7403354 0.2147784 -0.621045 -0.7579346 0.1995952 -0.6396358 -0.7406129 0.2058123 -0.6409736 -0.7373625 0.213189 -0.6393426 -0.7401275 0.2084522 -0.6405558 -0.7376517 0.2134442 -0.640832 -0.7377963 0.212111 -0.642269 -0.7357894 0.2147201 -0.6408247 -0.7377814 0.2121849 -0.644224 -0.7353781 0.2102248 -0.6478408 -0.7308236 0.21494 -0.6449652 -0.7362511 0.2048274 -0.6527414 -0.7278558 0.2101299 -0.6583471 -0.7213747 0.2149365 -0.6549872 -0.7292783 0.1978507 -0.6672136 -0.7151576 0.2082685 -0.6760236 -0.7031024 0.2205427 -0.6712924 -0.7165858 0.1893967 -0.6901487 -0.6956374 0.1994581 -0.6999891 -0.6783599 0.2232558 -0.6923978 -0.6959471 0.1903756 -0.7142382 -0.6645306 0.2196878 -0.716996 -0.6727865 0.1824148 -0.731967 -0.6494048 0.2061496 -0.7418771 -0.6311432 0.2264434 -0.7371913 -0.6477221 0.1923672 -0.7597249 -0.6220014 0.1895582 0.6197075 0.6197096 -0.4815835 0.6711548 0.6326775 -0.3863554 0.6816863 0.6375098 -0.3590055 0.6197062 0.6197125 -0.4815814 -0.8210661 -0.56637 -0.07124412 0.6197378 0.6197758 -0.4814594 0.6197066 0.619706 -0.4815893 -0.8210847 -0.5663188 -0.07143419 -0.8210844 -0.5663216 -0.07141655 -0.821085 -0.5663189 -0.07142996 -0.8210853 -0.5663183 -0.07143247 -0.8210836 -0.5663236 -0.07140928 -0.821087 -0.5663138 -0.0714482 0.6197094 0.6197117 -0.4815784 -0.08546191 0.3011192 -0.9497492 0.6196972 0.6197324 -0.4815674 0.6197454 0.6196531 -0.4816073 0.6197088 0.6197111 -0.4815798 0.6196972 0.6197285 -0.4815723 0.6197153 0.6197032 -0.4815818 0.619705 0.6197162 -0.4815781 0.61971 0.6197105 -0.4815789 0.6197082 0.6197123 -0.4815791 0.6197128 0.6197089 -0.4815776 -0.8210985 -0.5662918 -0.07148998 -0.6096006 -0.04770648 -0.7912719 0.6197094 0.6197116 -0.4815785 -0.06761032 0.2077755 -0.9758372 0.619708 0.6197134 -0.4815778 0.6197152 0.6197041 -0.4815805 0.6197043 0.6197175 -0.4815776 0.6197124 0.6197081 -0.4815791 0.6197146 0.6197056 -0.4815794 0.6196994 0.6197216 -0.4815784 -0.5209406 -0.09032839 -0.8488001 0.6197069 0.6197142 -0.4815783 -0.05898076 0.1007329 -0.9931637 0.6197097 0.6197105 -0.4815793 0.6197044 0.6197169 -0.4815781 0.6197077 0.6197132 -0.4815785 0.6197091 0.6197117 -0.4815785 -0.4509075 -0.1620323 -0.8777402 0.6197105 0.6197106 -0.4815783 -0.0310558 0.006970882 -0.9994933 0.6197091 0.6197121 -0.4815781 0.61971 0.6197113 -0.4815782 -0.4276758 -0.2877389 -0.8569129 0.619708 0.6197124 -0.4815793 0.007503151 -0.06488096 -0.9978648 0.6197086 0.6197116 -0.4815794 0.619703 0.6197174 -0.4815793 -0.3793093 -0.3906624 -0.8387536 0.6197102 0.6197103 -0.4815791 -0.0189079 -0.1834717 -0.9828431 0.61971 0.6197106 -0.4815791 -0.2513349 -0.3983791 -0.8821138 0.6197061 0.6197146 -0.481579 -0.06296104 -0.2966656 -0.9529037 0.6197095 0.6197109 -0.4815793 0.6197125 0.6197084 -0.4815786 0.02395337 -0.2461247 -0.9689422 0.61971 0.6197112 -0.4815782 -0.1081151 -0.3503158 -0.9303709 0.6197075 0.6197136 -0.4815783 -0.1007262 -0.413602 -0.9048688 0.6197097 0.619711 -0.481579 0.6197097 0.6197112 -0.4815785 0.01817446 -0.2986828 -0.9541794 0.6197094 0.6197117 -0.4815783 -0.001889526 -0.296525 -0.9550231 0.6197076 0.6197137 -0.4815781 0.01765811 -0.3027816 -0.9528964 0.00785917 -0.3123815 -0.9499242 0.6197074 0.6197142 -0.4815777 0.01689338 -0.3012276 -0.9534026 0.6197082 0.6197131 -0.4815781 0.6197103 0.6197112 -0.4815778 -0.07656157 -0.4222443 -0.9032431 0.6197081 0.6197134 -0.4815778 0.06641554 -0.3137254 -0.9471881 0.6197096 0.6197118 -0.4815781 0.0132358 -0.3147139 -0.9490942 0.6197075 0.6197133 -0.4815787 -0.3200788 -0.7577596 -0.5686386 0.619706 0.6197152 -0.4815783 0.6197501 0.6196635 -0.481588 0.3195129 -0.467051 -0.8244847 0.6197144 0.619708 -0.4815767 0.08197706 -0.3403344 -0.9367243 0.6196469 0.6197859 -0.4815634 0.630611 -0.4204871 -0.6523193 0.3090723 -0.5796778 -0.753955 0.6196924 0.6197342 -0.4815714 0.7904784 -0.3415307 -0.5084294 0.6570632 -0.5407169 -0.5252555 0.6196992 0.6197264 -0.4815724 0.8649585 -0.3383514 -0.3706283 0.800188 0.3569917 -0.4819295 0.8652044 -0.2871713 -0.41104 0.9113638 -0.1846992 -0.3678344 0.8367434 -0.4810491 -0.2616341 0.9085456 -0.1894524 -0.3723608 0.6865086 0.6250432 -0.3715198 0.6912663 0.6243579 -0.3637692 0.6813404 0.6303994 -0.3719837 0.6934846 0.6281746 -0.3528112 0.6763619 0.6350896 -0.3730896 0.6858004 0.6316938 -0.3614425 0.6843852 0.6350747 -0.3581857 0.6779394 0.6400427 -0.3615846 0.6817279 0.6376735 -0.3586356 0.6774539 0.6415753 -0.3597742 0.6717575 0.6375402 -0.3772061 0.6777924 0.6408907 -0.360356 0.6774119 0.6415709 -0.3598609 0.6778103 0.6414541 -0.3593186 0.6781094 0.641887 -0.357979 0.6776483 0.6414637 -0.3596066 0.673081 0.6417593 -0.3675688 0.6761173 0.6407361 -0.3637619 0.6773481 0.6414194 -0.3602507 0.6770939 0.6421993 -0.3593381 0.6702371 0.6444123 -0.3681235 0.6747026 0.6426784 -0.3629613 0.6759383 0.6449044 -0.3566589 0.6666668 0.6476374 -0.3689461 0.671873 0.6455556 -0.3631045 0.6725664 0.6487637 -0.3560338 0.6655688 0.6529693 -0.3614541 0.6698666 0.6509431 -0.3571443 0.6602354 0.6556335 -0.3663796 0.6642711 0.6516268 -0.3662328 0.665283 0.6574636 -0.3537513 0.6568778 0.6596458 -0.3652109 0.6623681 0.6613174 -0.3520337 0.6535773 0.6634914 -0.3641647 0.658664 0.6651869 -0.3516932 0.6504066 0.667103 -0.363242 0.6546542 0.6694181 -0.3511515 0.6480286 0.6716763 -0.3590402 0.6500048 0.6735122 -0.3519591 0.6450608 0.6747443 -0.3586314 0.6405936 0.6761398 -0.3639707 0.6453893 0.6792815 -0.3493553 0.6357295 0.6927376 -0.3405331 0.6250431 0.6883513 -0.3680946 0.6357754 0.6917271 -0.3424956 0.6035939 0.7438517 -0.2869827 0.6020242 0.7074541 -0.3702372 0.6122238 0.7187535 -0.3295075 0.5655665 0.7646927 -0.3088361 0.5727769 0.7279335 -0.3768812 0.5446312 0.7954531 -0.2657651 0.5362578 0.7683994 -0.3492705 0.5440922 0.7487329 -0.3786329 0.5205375 0.7875646 -0.3298222 0.5377627 0.7561022 -0.3729889 0.5437607 0.7540305 -0.3684595 0.5374082 0.7565485 -0.3725946 0.5579671 0.7461133 -0.3633009 0.5717572 0.7161714 -0.4002403 0.5819632 0.724291 -0.3697584 0.6119911 0.6672871 -0.4244937 0.6185884 0.7024255 -0.352061 0.5954478 0.7083173 -0.3791152 0.6311519 0.6574628 -0.41157 0.6547953 0.6680727 -0.3534427 0.630208 0.683775 -0.3678177 0.6755827 0.6542586 -0.3399027 0.6506354 0.6510649 -0.3908812 0.8185557 0.5724982 0.04703694 0.821083 0.5663235 0.07141619 0.8210851 0.5663211 0.07141286 0.8177257 0.5739727 0.04335987 0.8227887 0.5614117 0.08851927 0.8246274 0.5563989 0.1020289 0.7996027 0.5962162 0.07184696 0.7932812 0.6051437 0.06712752 0.791923 0.6084756 0.05114126 0.7898471 0.6046479 0.1026763 0.7969755 0.602423 0.04377853 0.8297258 0.5533431 0.0732553 0.8329337 0.5432661 0.1052766 0.8307234 0.552116 0.07118076 0.5819747 -0.8131198 -0.01189804 0.5442585 -0.8388071 0.01361411 0.8112111 0.5798544 0.07553362 0.8103926 0.582045 0.06698876 0.8145086 0.5759359 0.06981164 0.8310363 0.5531947 0.05791646 0.8235834 0.554587 0.1189272 0.7985887 0.5979072 0.06901544 0.8010134 0.5894535 0.1045098 0.7987411 0.5977291 0.06879323 0.8100391 0.577962 0.09897851 0.7931709 0.6046891 0.07232487 0.7948089 0.5988087 0.09852308 0.7999782 0.5890331 0.1143456 0.7878578 0.6115761 0.07249051 0.7898617 0.6028773 0.1125051 0.7893605 0.6097275 0.07171183 0.7830978 0.6176522 0.07255101 0.7844712 0.6119491 0.1006142 0.7850247 0.6152973 0.07173126 0.7903399 0.6033959 0.1061891 0.77906 0.6227419 0.07251197 0.780269 0.6174027 0.09997022 0.7811572 0.6201902 0.07181668 0.7830601 0.6121034 0.1102105 0.7759402 0.6266358 0.07241791 0.7771505 0.620677 0.1039096 0.7779355 0.6242104 0.07195496 0.7777352 0.6193566 0.1073559 0.7741209 0.6288986 0.07227361 0.7752771 0.6229219 0.1044686 0.7754548 0.6272717 0.07211238 0.773402 0.6297848 0.07225269 0.7744881 0.6241981 0.1026884 0.7738629 0.6292321 0.0721336 0.7751876 0.6229321 0.105071 0.7735017 0.6296694 0.07218974 0.7745899 0.6241042 0.1024916 0.7733349 0.6298703 0.07222479 0.7742995 0.6286923 0.07215631 0.7753557 0.6235643 0.09995591 0.7736538 0.6294745 0.07226127 0.7749505 0.6241916 0.09917992 0.7750273 0.6277912 0.0721867 0.7760289 0.623161 0.09720754 0.7744754 0.6284647 0.07224875 0.7752747 0.6274842 0.07219934 0.7764359 0.6217901 0.1025896 0.7750799 0.6277229 0.07221645 0.77561 0.6228448 0.1024373 0.7751132 0.627682 0.072214 0.7762988 0.6217509 0.1038556 0.7752752 0.6274835 0.07219964 0.7762555 0.6218327 0.1036891 0.7745535 0.6283695 0.07223999 0.7757306 0.6223537 0.1044887 0.775075 0.6277315 0.07219296 0.7734551 0.6297134 0.07230716 0.7745181 0.6243137 0.1017565 0.7734963 0.6296663 0.07227665 0.7744612 0.628489 0.07219064 0.7756432 0.6223539 0.1051341 0.7716767 0.631888 0.07233756 0.772682 0.6264869 0.1023557 0.7719421 0.6315855 0.07214599 0.7733734 0.6250158 0.1060606 0.769404 0.6346493 0.07237237 0.7703346 0.6292198 0.1032811 0.7697004 0.6343133 0.07216697 0.7666783 0.6379334 0.07242453 0.767457 0.6331112 0.1008952 0.7670446 0.6375201 0.07218468 0.7697786 0.629221 0.1073394 0.7635147 0.6417082 0.07249605 0.7642511 0.635304 0.1109457 0.7640208 0.6411404 0.07218927 0.7599977 0.6458616 0.0725699 0.760523 0.6412237 0.1021608 0.7606748 0.645106 0.07219642 0.7649079 0.6355558 0.1048082 0.7561378 0.6503671 0.07265102 0.7565029 0.6460547 0.1015701 0.75708 0.6493215 0.07219034 0.7586892 0.6418931 0.111194 0.7518506 0.6558555 0.06763237 0.7521247 0.6505136 0.1055486 0.7493205 0.6583329 0.07153111 0.7474952 0.6604058 0.07151943 0.7475348 0.6565511 0.1006602 0.750987 0.6507529 0.1119791 0.7380324 0.6706762 0.07417243 0.738011 0.6702012 0.07855051 0.7419288 0.6613956 0.1099892 0.7227346 0.6872276 0.07330083 0.7223202 0.6860653 0.08699357 0.7229414 0.6870378 0.07304042 0.736507 0.6725779 0.07208698 0.7311632 0.6725459 0.1143791 0.7071107 0.7032258 0.07394486 0.7054161 0.701362 0.1023693 0.7092042 0.7013161 0.07200866 0.7195235 0.6865898 0.1043084 0.6918206 0.7182565 0.07410639 0.6897817 0.717223 0.09895581 0.6956089 0.7148508 0.07153058 0.7064718 0.7011567 0.09631776 0.6902179 0.7152454 0.1096511 0.6771799 0.7320894 0.07397741 0.6734688 0.7312485 0.1082374 0.6823695 0.7275132 0.0713883 0.6634207 0.7446094 0.0736863 0.6601637 0.7445307 0.09928786 0.6696624 0.7392219 0.07143664 0.6732994 0.7313054 0.1089051 0.6506937 0.7557913 0.07332956 0.647444 0.7561065 0.0954948 0.6576426 0.7499217 0.07158052 0.6526765 0.7478475 0.1213979 0.6380551 0.7665071 0.07316178 0.6287589 0.7674016 0.125527 0.6463771 0.7596424 0.07169455 0.6167228 0.7838613 0.07221031 0.6125415 0.7849616 0.09288752 0.6139844 0.7858742 0.07365447 0.6343483 0.7697273 0.07156932 0.632786 0.7659789 0.1133934 0.5752043 0.8145736 0.07489955 0.5756525 0.8144099 0.07321721 0.5838033 0.8087353 0.07156217 0.5767876 0.7998523 0.1659891 0.51353 0.8547852 0.07502841 0.4729674 0.8635184 0.1750362 0.5441834 0.8361352 0.06886482 0.4389407 0.8956674 0.07149159 0.4406158 0.8951038 0.06816738 0.4428476 0.8938289 0.0703969 0.4966049 0.8652328 0.06896233 0.4764444 0.8627614 0.1692436 0.3541235 0.9325501 0.07033312 0.1852176 0.9345894 0.3037056 0.3853093 0.9204729 0.0653162 0.2649495 0.961934 0.06696772 0.2674849 0.9614467 0.06381404 0.315003 0.9470734 0.06184852 0.2827461 0.9382855 0.1991856 0.1943238 0.9789125 0.0629971 0.06691676 0.9782054 0.1965611 0.2379248 0.9694828 0.05911737 0.1539692 0.9862593 0.05988538 0.1358384 0.9876413 0.07818406 0.1772506 0.9824923 0.05736738 0.1144157 0.9810005 0.1566748 0.1427794 0.9880474 0.05810493 0.1053643 0.9898825 0.09503126 0.1456125 0.9876607 0.05764758 0.1572887 0.9858192 0.05848813 0.1191528 0.9881315 0.09694564 0.1524392 0.9865199 0.05950605 0.1277306 0.988774 0.07753038 0.2003121 0.9778956 0.05996102 0.2010778 0.9777894 0.05912423 0.1955854 0.9787864 0.06102102 0.2742539 0.9597127 0.06112694 0.2269 0.9665456 0.1196081 0.2614014 0.9631186 0.06381219 0.2662466 0.9638965 0.004047095 0.3743581 0.9251975 0.06217581 0.3841568 0.9221062 0.04629892 0.3412654 0.9375044 0.06799608 0.4779092 0.8760379 0.06450122 0.444757 0.8851783 0.1365668 0.4247795 0.9024772 0.07139456 0.4558931 0.8892856 -0.03650569 0.5718436 0.817409 0.06955146 0.5780317 0.8147089 0.04614025 0.5750045 0.8152976 0.06826281 0.5020959 0.8617804 0.07234871 0.6574763 0.7505105 0.06677556 0.6428743 0.7490864 0.1599444 0.6395246 0.7652213 0.07378715 0.5949397 0.8037249 0.00854665 0.7307469 0.6794614 0.06588786 0.7279528 0.6706318 0.1426097 0.6989451 0.7110782 0.07644367 0.7056385 0.7084839 0.01116859 0.7522947 0.6544487 0.07582646 0.7499873 0.6612566 0.01609086 0.7903811 0.6012431 0.1174928 0.6936917 0.7069476 0.1379021 0.646887 0.7622881 0.02131366 0.701636 0.704892 0.1040868 0.5409383 0.8213918 0.180835 0.5215984 0.8529389 0.0207476 0.5603327 0.8160813 0.1415577 0.4062611 0.9076256 0.1056773 -0.0440371 0.8458841 0.5315456 0.2902236 0.9565506 0.02795022 0.4008563 0.9138502 0.06474685 0.07865589 0.979782 0.1839584 0.18743 0.9819876 0.02388131 0.2086489 0.9754986 0.06977188 0.1711508 0.9847242 0.03202611 0.1671267 0.9851991 0.03809529 0.2017093 0.9789364 0.03157269 0.3698418 0.9233931 -0.1027724 0.3302235 0.9430261 0.04067343 0.232863 0.9720934 0.02844625 0.4677408 0.880007 -0.0824995 0.4509453 0.8909175 0.05398452 0.4359549 0.8989433 -0.04294723 0.5157918 0.85649 0.01958721 0.5876891 0.8037492 -0.09278374 0.5898662 0.8061517 0.04666161 0.5289102 0.8479781 0.03445702 0.6320253 0.7741183 -0.03584623 0.6385554 0.7682763 0.04470545 0.6070262 0.7935823 0.04179024 0.6498076 0.7586636 0.04668515 0.646353 0.7626056 0.02570474 0.6612376 0.7490713 0.04070687 0.6716173 0.739071 0.0520029 0.6641362 0.7469677 0.03102231 0.683966 0.7277019 0.05138456 0.6806675 0.7319719 0.03014886 0.6969358 0.7154878 0.04855632 0.6954079 0.7177374 0.03551036 0.7100403 0.7024309 0.04933303 0.7089636 0.7041103 0.03999167 0.7232711 0.6883808 0.05487012 0.7212862 0.6914854 0.03992563 0.7365062 0.6736485 0.06128996 0.7321517 0.6801642 0.0364775 0.7490943 0.6597502 0.05989569 0.7416265 0.6698754 0.03545707 0.7560232 0.6531104 0.04330968 0.7502321 0.6595664 0.04608553 0.7596005 0.6487743 0.04581403 0.756833 0.6525083 0.03790551 0.7625607 0.6456007 0.0412417 0.7657371 0.6415192 0.0458219 0.7626486 0.645555 0.0403214 0.7682282 0.6386105 0.04474675 0.7670688 0.6403014 0.04024505 0.7703292 0.6361331 0.04390299 0.7718836 0.6341797 0.04485195 0.7704856 0.636063 0.04214018 0.7726572 0.6333903 0.04263389 0.7733007 0.6325544 0.04337072 0.7726663 0.6333881 0.042499 0.7734461 0.6324199 0.04273569 0.7732913 0.6325782 0.04319316 0.7734221 0.6324149 0.04323941 0.7729225 0.6328167 0.04619389 0.7728736 0.6328877 0.04603946 0.7721707 0.6336896 0.0467987 0.7717632 0.6342936 0.04531461 0.7722089 0.633668 0.04645782 0.772219 0.6337956 0.04450935 0.7737254 0.631982 0.04413199 0.7723243 0.6337865 0.04277455 0.7762115 0.6288408 0.04533147 0.7743552 0.6315077 0.03964805 0.7789611 0.6257395 0.04086351 0.7831616 0.6200782 0.04648774 0.7790597 0.6257126 0.03936898 0.7861614 0.6170895 0.0339232 0.7970278 0.6018638 0.05006647 0.7859578 0.6169471 0.04058039 0.8143609 0.576318 0.06836569 0.7973174 0.5993573 0.0711041 0.8034972 0.5944614 0.03174841 0.8290612 0.5561645 0.05778235 0.8149109 0.5786245 0.03337574 0.5819747 -0.8131198 -0.01189804 0.688664 -0.7193832 -0.09071785 0.5959892 -0.8020467 -0.03896278 0.8283717 0.5587457 0.04004532 0.4195248 -0.9073965 -0.02511286 0.3031554 -0.951682 0.04897075 0.3031581 -0.9516807 0.04897999 0.4656057 -0.8826833 0.06388527 0.3577761 -0.9272408 0.1105479 0.7046164 0.7068392 -0.06240206 0.4658745 -0.8829358 0.05818432 0.419524 -0.9073967 -0.02511316 0.5368285 -0.8370537 -0.1056229 -0.3498586 -0.9344669 -0.06610983 -0.400116 -0.9163798 0.01245772 -0.3498566 -0.9344677 -0.06610924 -0.554319 -0.8292517 -0.07121807 -0.5939117 -0.8000008 0.08525109 -0.590099 -0.8072742 0.009556889 0.04659301 -0.9977134 -0.04895877 -0.04944652 -0.9984161 0.0268408 0.04659485 -0.9977134 -0.04895818 -0.4000985 -0.9163873 0.01247185 -0.04945462 -0.998416 0.02682989 0.1608232 -0.9771649 -0.1388691 0.5368292 -0.8370538 -0.1056185 -0.2804777 -0.9453239 -0.1664181 0.1608164 -0.9771636 -0.1388856 -0.5559105 -0.8278972 -0.07449764 -0.5214648 -0.834545 -0.1777896 -0.280476 -0.9453247 -0.1664161 -0.8537991 -0.5173115 -0.05844569 -0.8522582 -0.5208437 -0.04876416 -0.8605256 -0.5045381 -0.07026374 -0.8263028 -0.5598387 -0.06168019 -0.8192347 -0.5733129 -0.01291549 -0.8432375 -0.5321213 -0.07614201 -0.8274183 -0.5601953 0.03949964 -0.8287472 -0.5584571 0.03610497 -0.8317818 -0.5543969 0.02798718 -0.8385731 -0.5447391 0.00738573 -0.8450181 -0.5345029 -0.01584851 -0.7982537 -0.5990211 -0.06296533 -0.7928878 -0.6092118 -0.01378369 -0.816045 -0.5704293 -0.09317159 -0.7990711 -0.5998302 0.04109907 -0.7710247 -0.6323102 -0.07552987 -0.7658272 -0.6430428 -0.002088129 -0.7751734 -0.6258825 -0.08589118 -0.7690533 -0.6379323 0.03999042 -0.7433823 -0.665198 -0.06995946 -0.7394194 -0.6728469 0.02314716 -0.7167742 -0.694178 -0.06596738 -0.7171953 -0.6968647 -0.003212094 -0.7355347 -0.6720151 -0.08593159 -0.7382929 -0.6739027 0.02790576 -0.6909069 -0.7194904 -0.07057869 -0.6943766 -0.7196035 0.003456532 -0.697906 -0.7112702 -0.08379787 -0.7039403 -0.7091103 0.04038131 -0.6675999 -0.7403969 -0.07824897 -0.6752769 -0.7374078 0.01519834 -0.6664161 -0.7418094 -0.07488876 -0.650319 -0.7564494 -0.06978243 -0.6585666 -0.7525178 0.002626895 -0.6724998 -0.7394194 0.03166919 -0.6358008 -0.768642 -0.07033401 -0.6477479 -0.7616017 0.01963275 -0.6419921 -0.7627816 -0.07752549 -0.6243475 -0.7777774 -0.07247507 -0.6366357 -0.7711424 0.005856096 -0.6254862 -0.7766575 -0.07463282 -0.6473404 -0.7618383 0.02350944 -0.6163657 -0.7841734 -0.07186973 -0.6308724 -0.7757478 0.01467847 -0.6109669 -0.7884296 -0.07140237 -0.6252493 -0.7803795 0.008431136 -0.6146128 -0.7853939 -0.07353687 -0.6305629 -0.7759283 0.0180487 -0.6076362 -0.7909613 -0.07182222 -0.6226537 -0.7824373 0.009709358 -0.6085025 -0.790205 -0.07280641 -0.6062889 -0.7919802 -0.07197958 -0.6220991 -0.7828251 0.01332908 -0.6063357 -0.7919371 -0.07205975 -0.6066642 -0.7916858 -0.07205742 -0.62183 -0.7830944 0.009518384 -0.6221439 -0.782842 0.009772837 -0.606425 -0.7919136 -0.07156634 -0.6216163 -0.7832578 0.01002335 -0.6069399 -0.7914925 -0.07185739 -0.5994865 -0.7972834 -0.07039219 -0.6149727 -0.7885137 0.007407486 -0.6027784 -0.7945228 -0.07342869 -0.621082 -0.7835443 0.0177645 -0.5831567 -0.8093603 -0.06974333 -0.6020262 -0.7983539 0.01398229 -0.5867815 -0.8062973 -0.07464629 -0.5595251 -0.8106957 -0.1723491 -0.5082166 -0.8226167 -0.2549856 -0.5744193 -0.7975657 -0.1842044 -0.5802263 -0.794369 -0.1797648 -0.5737637 -0.7963581 -0.1913347 -0.5796794 -0.794861 -0.1793535 -0.5832538 -0.7929096 -0.1763786 -0.579317 -0.7942413 -0.1832284 -0.5874749 -0.7871395 -0.187842 -0.6052198 -0.7777673 -0.1696674 -0.5869188 -0.7865543 -0.1919859 -0.6258796 -0.762321 -0.1647464 -0.6046663 -0.7676062 -0.2125075 -0.6436766 -0.734592 -0.2146042 -0.6883507 -0.7035379 -0.1766571 -0.6466171 -0.7403022 -0.1839541 -0.7328596 -0.6631396 -0.152193 -0.6873336 -0.6948042 -0.2117066 -0.7760751 -0.614725 -0.1407857 -0.7348839 -0.6419509 -0.2187348 -0.8191408 -0.554067 -0.1483851 -0.7808363 -0.5893843 -0.2071735 -0.8510739 -0.493451 -0.1793863 -0.8217524 -0.5425645 -0.1742032 -0.8696556 -0.4669824 -0.1600832 -0.8577716 -0.4555525 -0.2381169 -0.8210581 -0.5663627 -0.07139283 -0.8210864 -0.5663183 -0.0714209 -0.8210786 -0.5663307 -0.07141017 -0.8211145 -0.5662634 -0.07153087 -0.8210719 -0.5663456 -0.07136982 -0.7923921 -0.5909484 0.1513102 -0.8136827 -0.574077 0.09141182 -0.8236133 -0.5643004 0.05680024 0.8210771 0.5663399 -0.07135552 0.6196994 0.6197111 0.4815919 0.6197191 0.619703 0.4815769 0.619717 0.6197045 0.4815778 0.6197089 0.6197125 0.4815781 0.6197117 0.6197086 0.4815793 0.7461597 0.6020652 0.2841885 0.7340887 0.6065903 0.3052244 0.8210844 0.5663219 -0.07141369 0.8210862 0.566319 -0.07141536 0.8210812 0.5663287 -0.07139819 0.821089 0.5663144 -0.07141953 0.8211497 0.5662159 -0.07150375 0.8213305 0.5659218 -0.07175415 0.821092 0.5663016 -0.07148689 0.8210662 0.5663668 -0.07126802 0.8210901 0.5663086 -0.07145452 0.8210672 0.5663608 -0.07130271 0.8210837 0.5663236 -0.07140898 0.8210846 0.5663215 -0.07141441 0.8210784 0.566334 -0.07138609 0.3614816 0.5016541 0.7859226 0.3572684 0.4074292 0.8404528 0.4251659 0.5284816 0.7348068 0.4237924 0.3523955 0.8343964 0.5065768 0.5008478 0.7018061 0.5456429 0.4109776 0.7303227 0.6197145 0.6197066 0.4815782 0.5454037 0.2215252 0.8083696 0.5680943 0.4470553 0.690949 0.6197132 0.6197078 0.4815785 0.6350044 0.376012 0.6748219 0.6197042 0.6197128 0.4815835 0.6613478 0.1631555 0.7321197 0.6197155 0.6197055 0.4815785 0.639705 0.4053912 0.6530203 0.619715 0.6197047 0.4815801 0.6951662 0.2531518 0.6727988 0.6197041 0.6197139 0.4815823 0.7135652 0.1778357 0.6776424 0.6956046 0.3088586 0.6486452 0.6197137 0.6197051 0.4815813 0.7207921 0.1826379 0.6686569 0.6197148 0.6197041 0.4815813 0.7201772 0.1660953 0.673615 0.6197124 0.6197072 0.4815803 0.7094125 0.2015216 0.6753686 0.6197097 0.6197093 0.481581 0.72013 0.1627044 0.6744924 0.6197099 0.6197093 0.4815807 0.5919001 -0.2710988 0.7590519 0.6197113 0.619708 0.4815806 0.6467872 0.2875213 0.7063977 0.680567 0.05469632 0.7306413 0.619715 0.6197044 0.4815806 0.5977876 0.3074271 0.7403638 0.4538369 -0.2185102 0.8638781 0.6197115 0.6197088 0.4815794 0.5312506 0.2849342 0.797863 0.6197081 0.6197116 0.48158 0.6197096 0.6197106 0.4815797 0.5265288 0.39101 0.7549031 0.485601 0.1985645 0.8513306 0.6197127 0.6197075 0.4815796 0.4962818 0.3962887 0.7724375 0.4517263 0.2966195 0.8414037 0.6197113 0.6197084 0.4815802 0.4772951 0.3968567 0.7840244 0.6197142 0.6197057 0.4815797 0.4602345 0.3659507 0.8088662 0.6197136 0.6197062 0.48158 0.4650747 0.4034668 0.7879848 0.4564866 0.3898772 0.7997598 0.6197143 0.619706 0.4815794 0.4561953 0.4170156 0.7861196 0.6197112 0.6197087 0.4815799 0.4491444 0.4069873 0.7953809 0.6197098 0.6197103 0.4815796 0.4513679 0.4358198 0.7786709 0.4359073 0.4155821 0.7982959 0.6197109 0.6197089 0.48158 0.446865 0.4543521 0.7706335 0.6197122 0.6197077 0.4815798 0.4190767 0.4198821 0.8050303 0.6197131 0.6197077 0.4815788 0.4367574 0.4668457 0.7689591 0.6197059 0.6197141 0.4815797 0.4056116 0.4269711 0.8081924 0.6197107 0.6197091 0.48158 0.4106411 0.4662884 0.7835489 0.6197186 0.6197021 0.4815789 0.4066616 0.4457131 0.7974748 0.6197139 0.6197061 0.48158 0.41796 0.4908974 0.7644143 0.6197122 0.6197075 0.4815801 0.3840946 0.4574738 0.8019907 0.4298686 0.4795132 0.7650361 0.6197112 0.6197087 0.4815796 0.4098333 0.5016936 0.7618007 0.6197116 0.6197084 0.4815796 0.6197109 0.6197092 0.4815796 0.3807666 0.4783909 0.791302 0.3928894 0.4761458 0.7867166 0.6197097 0.6197103 0.48158 0.3782738 0.4962879 0.7814136 0.6197135 0.619707 0.481579 0.6197087 0.6197115 0.4815795 0.3743206 0.4834333 0.791313 0.6197102 0.6197095 0.48158 0.370296 0.5028539 0.781037 0.6197078 0.6197114 0.4815807 0.61971 0.6197096 0.4815803 0.6197127 0.619707 0.4815801 0.3665443 0.4932873 0.7888681 0.4157333 0.5162738 0.7487504 0.6197113 0.619708 0.4815806 0.3737214 0.5113965 0.7738255 0.6197135 0.6197065 0.4815798 0.61971 0.6197092 0.4815808 0.6197159 0.6197041 0.4815798 0.6197111 0.6197087 0.4815801 0.3614767 0.5032638 0.7848951 0.3652284 0.502224 0.7838234 0.4048137 0.5202993 0.7519406 0.6197108 0.6197083 0.4815809 0.3584556 0.5041487 0.7857121 0.6197074 0.6197104 0.4815826 0.6197192 0.619702 0.4815782 0.6197026 0.6197153 0.4815821 0.6197158 0.6197033 0.4815809 0.3609035 0.5059788 0.7834119 0.3658133 0.5076632 0.7800377 0.6197133 0.6197066 0.4815797 0.329818 0.4809811 0.8123283 0.6197261 0.6197032 0.4815678 0.6197134 0.6197074 0.4815786 0.6197059 0.6197105 0.4815846 0.6196988 0.6197136 0.4815897 0.6197099 0.6197082 0.4815821 0.619709 0.6197088 0.4815827 0.6197158 0.6197035 0.4815807 0.619712 0.6197069 0.481581 0.3647766 0.5047346 0.7824199 0.3620249 0.5053942 0.7832718 0.3489023 0.4993613 0.7930356 0.001925826 0.9533652 0.301813 0.2760504 0.8838583 0.3776116 0.3829727 0.5059221 0.7729004 0.3184258 0.4748136 0.8204615 0.07681792 0.9568684 0.2801822 0.2513132 0.9326083 0.2590051 0.07413446 0.9629784 0.2591847 0.4020014 0.8841682 0.2379946 0.2929313 0.930515 0.2198479 0.53046 0.8245541 0.1967806 0.6207475 0.7181531 0.3145294 0.4245408 0.8480024 0.3172652 0.6241192 0.7322541 0.2725422 0.6192148 0.7719138 0.1439527 0.6336205 0.7063753 0.3155301 0.62574 0.7228658 0.2931115 0.6362882 0.7065795 0.3096494 0.6387963 0.7113813 0.2930461 0.6407763 0.7186015 0.2702179 0.6399707 0.70138 0.3138529 0.6379562 0.7056493 0.3083361 0.6401203 0.701413 0.3134739 0.6401364 0.7014395 0.3133814 0.6403974 0.702125 0.3113064 0.640533 0.7008675 0.3138505 0.6402002 0.7014681 0.3131873 0.6410698 0.7011311 0.3121615 0.6421337 0.7031811 0.305288 0.6425147 0.6987916 0.3144285 0.6416571 0.7018 0.3094401 0.6440195 0.6990823 0.3106812 0.6471179 0.7048255 0.2906193 0.647332 0.6941804 0.3147616 0.6446966 0.6983261 0.3109775 0.6524001 0.6998244 0.290895 0.6530389 0.6880366 0.3164581 0.6503047 0.6957085 0.3051126 0.6629269 0.6963282 0.2750545 0.6624419 0.6796347 0.3150671 0.6566789 0.6874237 0.3101962 0.6663151 0.6708133 0.3256283 0.6699482 0.6853803 0.2853479 0.6759913 0.6652924 0.3168939 0.6820135 0.6735799 0.2848643 0.6897876 0.6570113 0.3041861 0.6925689 0.6431199 0.3267188 0.6913627 0.6573789 0.2997841 0.6991019 0.6315904 0.3351868 0.7145888 0.642771 0.2760585 0.7131099 0.6200274 0.32717 0.7412666 0.621118 0.2544336 -0.6197344 -0.6196797 -0.4815875 -0.6161275 -0.2501936 -0.7468535 -0.6197116 -0.619708 -0.4815803 -0.6197065 -0.6197123 -0.4815813 0.4573169 0.8350627 -0.3058294 -0.5257523 -0.3388649 -0.7802276 -0.6196573 -0.619771 -0.4815691 -0.6306612 0.4204299 -0.6523075 -0.2415795 0.8592817 -0.4508597 -0.3090746 0.5796568 -0.7539701 -0.6197621 -0.6196519 -0.4815876 -0.7904887 0.3414834 -0.5084453 -0.6571193 0.5406251 -0.5252797 -0.6197385 -0.619678 -0.4815844 -0.8649645 0.3382929 -0.3706673 -0.8606976 -0.2104189 -0.4635984 -0.8652082 0.2871733 -0.4110306 -0.9111362 0.1853066 -0.3680927 -0.8658527 0.4050153 -0.2937039 -0.704133 -0.6398976 -0.3077789 -0.6987922 -0.6406342 -0.318241 -0.6197085 -0.61971 -0.4815817 -0.7045738 -0.639335 -0.3079392 -0.6197092 -0.6197103 -0.4815803 -0.7048445 -0.6387162 -0.3086032 -0.6197136 -0.6197054 -0.4815809 -0.704352 -0.6392161 -0.3086923 -0.6197097 -0.6197104 -0.4815795 -0.7039097 -0.6377572 -0.3126929 -0.6197127 -0.6197074 -0.4815797 -0.7035971 -0.6379972 -0.3129068 -0.6197136 -0.6197071 -0.481579 -0.7037689 -0.6367819 -0.3149895 -0.6197183 -0.6197013 -0.4815801 -0.6197076 -0.6197123 -0.4815799 -0.7030579 -0.6371884 -0.3157539 -0.6197108 -0.6197099 -0.4815789 -0.7042297 -0.6367136 -0.3140962 -0.6197112 -0.6197095 -0.481579 -0.7038692 -0.6368665 -0.3145937 -0.6197133 -0.6197063 -0.4815803 -0.7037671 -0.6372216 -0.3141027 -0.6197044 -0.6197159 -0.4815793 -0.7044704 -0.6368969 -0.3131835 -0.6197174 -0.6197022 -0.4815805 -0.7031462 -0.6374335 -0.3150619 -0.6197135 -0.6197061 -0.4815803 -0.7037049 -0.6371735 -0.3143395 -0.6197066 -0.6197132 -0.48158 -0.7024276 -0.638407 -0.3146934 -0.6197142 -0.6197046 -0.4815813 -0.6197113 -0.6197075 -0.4815813 -0.7036692 -0.6378759 -0.3129918 -0.6197136 -0.6197056 -0.4815807 -0.7012654 -0.6394736 -0.3151199 -0.619709 -0.6197109 -0.48158 -0.7028837 -0.6388926 -0.3126831 -0.6197077 -0.6197125 -0.4815796 -0.7002206 -0.6406574 -0.3150386 -0.6197148 -0.6197045 -0.4815807 -0.7017135 -0.6402457 -0.3125439 -0.6197148 -0.6197054 -0.4815796 -0.6992165 -0.6421852 -0.3141564 -0.7003546 -0.6419684 -0.3120579 -0.6197081 -0.6197117 -0.48158 -0.6982582 -0.6439055 -0.3127639 -0.6197099 -0.6197097 -0.4815801 -0.6197127 -0.6197067 -0.4815805 -0.6925208 -0.6476259 -0.3177982 -0.6197122 -0.6197073 -0.4815804 -0.6197091 -0.6197107 -0.48158 -0.6983253 -0.6439606 -0.3125005 -0.6197087 -0.6197109 -0.4815803 -0.6833053 -0.6539126 -0.3247958 -0.6197112 -0.6197081 -0.4815806 -0.6822988 -0.6426718 -0.3484843 -0.690154 -0.6479688 -0.3222174 -0.6918305 -0.6523672 -0.3094958 -0.6197119 -0.6197081 -0.4815798 -0.6776053 -0.661542 -0.3212681 -0.6197121 -0.619708 -0.4815798 -0.6820476 -0.652832 -0.3295778 -0.6850687 -0.6594088 -0.3096141 -0.6197122 -0.6197078 -0.4815797 -0.6705865 -0.6680044 -0.3226205 -0.6197122 -0.6197078 -0.4815797 -0.6768267 -0.660534 -0.3249623 -0.6774942 -0.6680087 -0.3078407 -0.619715 -0.6197052 -0.4815798 -0.666381 -0.6763772 -0.3137677 -0.6197135 -0.6197066 -0.4815796 -0.6718246 -0.6714859 -0.3126635 -0.6197111 -0.6197093 -0.4815793 -0.6597467 -0.6808509 -0.3180825 -0.6197128 -0.6197071 -0.4815798 -0.6657857 -0.6745541 -0.3189142 -0.6627402 -0.6822297 -0.3087684 -0.6197107 -0.6197097 -0.4815793 -0.6550046 -0.6863579 -0.3160408 -0.6573752 -0.6876663 -0.3081766 -0.6197112 -0.6197092 -0.4815793 -0.6512069 -0.6930844 -0.3091337 -0.6197172 -0.6197018 -0.4815812 -0.6445484 -0.6964139 -0.3155396 -0.61971 -0.6197102 -0.4815793 -0.651228 -0.6920509 -0.3113967 -0.6197035 -0.619717 -0.4815792 -0.6325609 -0.7032104 -0.3245948 -0.6425119 -0.7064673 -0.296787 -0.6197138 -0.6197062 -0.4815796 -0.6085317 -0.7489088 -0.262345 -0.619714 -0.6197052 -0.4815809 -0.5934914 -0.7383856 -0.3202416 -0.6197108 -0.6197092 -0.4815797 -0.6184249 -0.7230686 -0.3077702 -0.6197131 -0.6197063 -0.4815806 -0.4705046 -0.8753315 -0.1114463 -0.6197071 -0.619713 -0.4815797 -0.5341767 -0.7809658 -0.3236475 -0.5777831 -0.7525639 -0.315934 -0.6197121 -0.6197077 -0.4815799 -0.5174313 -0.785354 -0.3398292 -0.491252 -0.8268634 -0.2738035 -0.6197106 -0.6197094 -0.4815797 -0.4980568 -0.8044944 -0.3236174 -0.6197112 -0.6197086 -0.48158 -0.4987223 -0.80363 -0.3247383 -0.6197142 -0.6197051 -0.4815807 -0.5287836 -0.7770088 -0.341534 -0.6197117 -0.6197077 -0.4815805 -0.5402451 -0.783611 -0.3067395 -0.5287176 -0.7770858 -0.3414605 -0.6197092 -0.6197112 -0.4815792 -0.6011529 -0.7009032 -0.3838618 -0.6197106 -0.6197087 -0.4815806 -0.6197084 -0.6197125 -0.4815786 -0.6169775 -0.7224054 -0.3122006 -0.5717535 -0.75424 -0.322831 -0.6197177 -0.6197019 -0.4815803 -0.649886 -0.7028127 -0.2893136 -0.6280365 -0.6937174 -0.3525994 -0.6197178 -0.6197233 -0.4815524 -0.6778759 -0.669018 -0.3047934 -0.6197101 -0.6197076 -0.4815827 -0.6633045 -0.6665475 -0.3402081 -0.6197126 -0.6197073 -0.4815797 -0.6976094 -0.6396858 -0.3227124 -0.7003201 -0.6413469 -0.3134102 0.8210743 0.5663472 -0.07132917 0.821085 0.5663189 -0.07143115 0.8210706 0.5663698 -0.07119286 0.8210885 0.5663086 -0.07147252 0.8210801 0.5663332 -0.07137417 0.8210965 0.5662878 -0.07154506 -0.02074229 -0.4450318 -0.8952745 0.8211297 0.5662196 -0.07170212 -0.3725106 -0.5538157 -0.7446638 -0.2136362 -0.5334487 -0.8184083 -0.4373177 -0.5494914 -0.7119077 -0.07856369 -0.3973284 -0.9143074 -0.4651797 -0.5325037 -0.7071406 -0.1204512 -0.3365608 -0.9339264 -0.4751738 -0.5057072 -0.7200487 -0.1974861 -0.3086562 -0.9304464 -0.4758733 -0.4723711 -0.7418963 -0.2685381 -0.2929264 -0.9176499 -0.4659389 -0.4295545 -0.7735528 -0.3475483 -0.3071535 -0.8859272 -0.4381245 -0.365471 -0.821266 -0.4853717 -0.4056906 -0.7744867 -0.4246759 -0.3468773 -0.8362575 -0.3960014 -0.2587591 -0.8810372 -0.4881707 -0.3785441 -0.7863801 -0.4740624 -0.3771784 -0.7956138 -0.4368322 -0.2871115 -0.8524932 -0.4952899 -0.3719566 -0.7850708 -0.4835276 -0.3650377 -0.7955806 -0.4818171 -0.3439962 -0.8059273 -0.4976908 -0.3672872 -0.7857506 -0.4861396 -0.3519604 -0.79987 -0.4976639 -0.3651544 -0.786761 -0.49542 -0.3603598 -0.7903796 -0.4952224 -0.3599788 -0.7906769 -0.4990754 -0.3642369 -0.7862921 -0.4979421 -0.3650643 -0.7866269 -0.4814301 -0.3254389 -0.8138272 -0.3482739 -0.09487092 -0.9325797 -0.5167741 -0.3571849 -0.778051 -0.4935021 -0.343392 -0.7990854 -0.4643927 -0.2250206 -0.8565659 -0.8205327 -0.5697066 0.04648131 -0.8210858 -0.5663197 0.07141613 -0.8210877 -0.5663173 0.07141274 -0.8158614 -0.577477 0.0298413 -0.8227947 -0.5613968 0.088557 -0.79335 -0.6044988 0.07195174 -0.7936615 -0.6035597 0.07626885 -0.789324 -0.6022228 0.1195641 -0.791229 -0.6069847 0.07433861 -0.7873972 -0.6156966 0.03038853 -0.7885143 -0.6107735 0.0721178 -0.7908297 -0.600028 0.1206434 -0.7886174 -0.6106513 0.07202482 -0.5819706 0.8131226 -0.01189988 -0.5256438 0.8503126 0.02583134 -0.7907795 -0.6078609 0.07192254 -0.7932445 -0.5968282 0.1206625 -0.7916624 -0.5997169 0.1166629 -0.7927129 -0.6053448 0.07185924 -0.7951925 -0.594853 0.1175529 -0.7910819 -0.6074446 0.0721153 -0.7943232 -0.6032347 0.07182413 -0.7969899 -0.5919079 0.1202177 -0.7931307 -0.6047695 0.07209438 -0.7951471 -0.5948495 0.1178774 -0.7956171 -0.6015279 0.07181549 -0.7982144 -0.5910241 0.1163797 -0.7947989 -0.6025799 0.07205688 -0.7967154 -0.6000761 0.07178544 -0.7995023 -0.5886299 0.1196283 -0.7960897 -0.600879 0.07201206 -0.7979016 -0.5908667 0.1192871 -0.7975568 -0.5989523 0.07182717 -0.8003972 -0.5873636 0.1198677 -0.7970448 -0.5996186 0.07195216 -0.7997135 -0.5885926 0.118394 -0.7979921 -0.5983685 0.07185983 -0.8008381 -0.5868452 0.1194621 -0.7976816 -0.5987774 0.0719009 -0.8007147 -0.5871111 0.1189808 -0.7980591 -0.5982772 0.07187581 -0.8009079 -0.5867519 0.1194522 -0.7980237 -0.5983237 0.07188105 -0.7977986 -0.5986212 0.07190316 -0.8006191 -0.5872001 0.1191855 -0.7980397 -0.5983045 0.07186341 -0.8008639 -0.5867589 0.1197119 -0.7971945 -0.5994225 0.07192838 -0.8000327 -0.587713 0.120587 -0.7976917 -0.5987714 0.0718382 -0.7962983 -0.6006076 0.07196855 -0.7990312 -0.5893506 0.1192269 -0.7970184 -0.5996689 0.07182711 -0.8001232 -0.5877537 0.1197851 -0.7951316 -0.6021462 0.07201147 -0.797787 -0.5910732 0.1190319 -0.796033 -0.6009764 0.07182413 -0.7985577 -0.5895658 0.1213163 -0.7936919 -0.6040378 0.07205241 -0.7963099 -0.5927891 0.1203813 -0.7947644 -0.6026535 0.07182198 -0.792007 -0.6062358 0.07213294 -0.7944628 -0.5956149 0.1186248 -0.7930694 -0.6048913 0.07174628 -0.7960736 -0.5928184 0.1217912 -0.790093 -0.608725 0.07215797 -0.7925513 -0.5973855 0.1224465 -0.7909008 -0.6077228 0.07175624 -0.7879598 -0.6114884 0.07212084 -0.7901849 -0.6012757 0.1186395 -0.7884391 -0.6109049 0.0718258 -0.792663 -0.5973948 0.1216753 -0.7852182 -0.6149816 0.07231885 -0.7872838 -0.6049814 0.1190866 -0.7857255 -0.6143759 0.0719555 -0.7883688 -0.6026833 0.1234801 -0.7817729 -0.6193384 0.07246482 -0.7836554 -0.6093932 0.1205158 -0.7827742 -0.6181386 0.07189726 -0.7780134 -0.6240509 0.07249581 -0.7796168 -0.6151205 0.1175772 -0.7792344 -0.6226101 0.07176697 -0.7830834 -0.6094883 0.1237115 -0.7739629 -0.6290653 0.07251507 -0.7753521 -0.6201242 0.1194791 -0.775044 -0.6278088 0.07185423 -0.7768179 -0.617127 0.1253327 -0.7696716 -0.6343051 0.07254493 -0.7707994 -0.6255992 0.120391 -0.7706595 -0.6331729 0.07194572 -0.7651324 -0.6397688 0.07258272 -0.7659716 -0.6320192 0.117641 -0.7660829 -0.6386938 0.07202273 -0.7695183 -0.6260665 0.1260256 -0.7603847 -0.6454542 0.07213747 -0.7608782 -0.6365603 0.1259179 -0.7605806 -0.6452408 0.07198268 -0.7554759 -0.6511437 0.0725817 -0.7557201 -0.64417 0.1180354 -0.7611848 -0.6365064 0.124328 -0.750393 -0.6569668 0.07283622 -0.7499726 -0.648173 0.1319574 -0.7540984 -0.6528234 0.07181501 -0.7399033 -0.6684374 0.0757274 -0.7391975 -0.6632767 0.1168373 -0.7408443 -0.6675159 0.07464706 -0.7475033 -0.6603645 0.07181668 -0.7518119 -0.647956 0.1221966 -0.7232376 -0.6864246 0.07582032 -0.7222794 -0.6839738 0.1024325 -0.7274645 -0.6822656 0.07286226 -0.7341519 -0.675125 0.07230085 -0.7419304 -0.6635426 0.09617894 -0.729267 -0.671779 0.1299327 -0.7060704 -0.7041095 0.07546079 -0.7035529 -0.7014781 0.1137617 -0.7147619 -0.6959939 0.06861418 -0.7166556 -0.6860891 0.1252453 -0.6887905 -0.7210741 0.07496494 -0.685735 -0.7196806 0.1087543 -0.6958791 -0.7147741 0.0696448 -0.703565 -0.7014747 0.1137087 -0.6872835 -0.715422 0.1257481 -0.6718375 -0.7369387 0.07453703 -0.6677907 -0.7363161 0.1090597 -0.6782741 -0.7314318 0.07036906 -0.6701677 -0.7306636 0.1304062 -0.6557188 -0.7513563 0.0741406 -0.6502014 -0.7514039 0.1123847 -0.6621875 -0.7459865 0.07079493 -0.652125 -0.7466116 0.1315449 -0.6402533 -0.7645979 0.07393258 -0.6330434 -0.7653536 0.1161456 -0.6477551 -0.7585245 0.07109087 -0.6336681 -0.7626831 0.1295344 -0.6157918 -0.7843196 0.07512152 -0.6049979 -0.7862858 0.1254273 -0.6334459 -0.7705427 0.07078367 -0.5665988 -0.8205943 0.07477122 -0.5587069 -0.8230763 0.1019416 -0.6065858 -0.7919535 0.06973862 -0.5999069 -0.788294 0.1367637 -0.4923024 -0.8673734 0.07281392 -0.4887169 -0.8686294 0.08147841 -0.494893 -0.8659873 0.07174187 -0.5593244 -0.8259922 0.06994891 -0.4997922 -0.8450505 0.1899933 -0.3917639 -0.9170869 0.0739783 -0.2929726 -0.9280852 0.2298365 -0.4219115 -0.9042308 0.06600958 -0.2782092 -0.9579836 0.06976586 -0.2624497 -0.9607572 0.089809 -0.3312569 -0.9416321 0.05998373 -0.357716 -0.9206199 0.1565195 -0.1962466 -0.9785841 0.0621311 0.02386981 -0.9574058 0.2877576 -0.2261257 -0.9724979 0.05581003 -0.1569764 -0.9859808 0.05657291 -0.1136683 -0.988464 0.1000915 -0.1547697 -0.9862898 0.05726206 -0.1783113 -0.9764083 0.1217864 -0.1426147 -0.9880688 0.05814665 -0.07826787 -0.989525 0.1213028 -0.1555362 -0.9859998 0.06010693 -0.1068336 -0.9882772 0.1090627 -0.1531761 -0.9863318 0.0607174 -0.1035306 -0.9893516 0.102297 -0.2007405 -0.9778569 0.05915355 -0.2014841 -0.9777528 0.05834102 -0.2751262 -0.9595625 0.05954283 -0.2158428 -0.9674072 0.1324203 -0.2174682 -0.9737851 0.06670987 -0.2027961 -0.9775431 0.05730074 -0.3737726 -0.9254258 0.06229811 -0.3899697 -0.9201251 0.03596383 -0.3232931 -0.9436036 0.07137131 -0.476964 -0.8764973 0.06525319 -0.4379635 -0.8865462 0.1490764 -0.4412313 -0.8943393 0.0739755 -0.4062867 -0.9135477 0.01901715 -0.5718284 -0.8176054 0.06733262 -0.5768088 -0.8154339 0.04857373 -0.5462391 -0.8341685 0.07606452 -0.6565735 -0.7511011 0.06898039 -0.6429964 -0.7499209 0.155481 -0.6401673 -0.7643679 0.07698982 -0.5728511 -0.8177489 0.05593258 -0.7300516 -0.67975 0.07045894 -0.7267104 -0.6703257 0.1501851 -0.7217618 -0.6879091 0.07642626 -0.700496 -0.712156 0.04625046 -0.7221586 -0.6915726 0.01464158 -0.7855466 -0.6167009 0.05095767 -0.6504173 -0.7595769 -5.361e-4 -0.697662 -0.7101967 0.09427797 -0.5203469 -0.8403342 0.1519126 -0.4694398 -0.8828282 0.01551187 -0.5736006 -0.8174058 0.05319982 -0.1714619 -0.9473891 0.2702863 -0.2579968 -0.9659358 0.02013766 -0.4004124 -0.9158754 0.02901536 -0.2065923 -0.9784088 0.005972921 -0.1900711 -0.9791807 0.07126152 -0.1832742 -0.9826558 0.02824968 -0.1904255 -0.9815837 0.01522582 -0.276684 -0.9609571 -0.002743124 -0.3373032 -0.9399977 0.05129134 -0.3054333 -0.951837 -0.02677637 -0.4789851 -0.8765331 -0.04757142 -0.5047065 -0.8620026 0.04714882 -0.456391 -0.889553 -0.02006328 -0.5863659 -0.8093434 -0.0337364 -0.6140493 -0.7886034 0.03237372 -0.5568323 -0.8302421 0.02521556 -0.6386316 -0.7685996 0.03747367 -0.6255721 -0.7801116 0.009244859 -0.6526053 -0.7569375 0.03393852 -0.650048 -0.7595955 0.02126276 -0.6662934 -0.7450009 0.03204303 -0.6655119 -0.7459216 0.02636486 -0.6811317 -0.7313295 0.03488028 -0.6803858 -0.7322638 0.02940869 -0.6973462 -0.7154486 0.04291313 -0.6946436 -0.7188371 0.02726823 -0.7152905 -0.6970946 0.04917848 -0.7078201 -0.7060174 0.02302163 -0.7275869 -0.6852562 0.03226822 -0.7198637 -0.6935539 0.02791517 -0.733851 -0.6785672 0.03176707 -0.7308891 -0.6820871 0.0236293 -0.7400639 -0.6718859 0.02957755 -0.7464883 -0.6645455 0.03367978 -0.7410326 -0.6709958 0.02520716 -0.7526447 -0.6576374 0.03223752 -0.7501522 -0.6607951 0.02492946 -0.7585263 -0.6510162 0.02856111 -0.7639222 -0.6445217 0.03185236 -0.758567 -0.6509818 0.02826118 -0.7682434 -0.6393672 0.03180801 -0.7656778 -0.6427137 0.02562439 -0.7721294 -0.6348171 0.02869367 -0.7763831 -0.6294435 0.03209674 -0.7722486 -0.6347135 0.027763 -0.7796365 -0.6254581 0.0311309 -0.7776852 -0.6280871 0.02669084 -0.7822582 -0.6222584 0.02943992 -0.7850406 -0.6186414 0.03153109 -0.7824709 -0.6220642 0.02784776 -0.7872673 -0.6158579 0.03048467 -0.7863257 -0.6171811 0.02791649 -0.7892796 -0.6132958 0.03010082 -0.7909639 -0.611083 0.03088319 -0.7894425 -0.6131514 0.02873611 -0.7919017 -0.6099815 0.02853405 -0.793045 -0.6084038 0.03040623 -0.7918122 -0.6100295 0.02996003 -0.7936873 -0.6075633 0.0304504 -0.793206 -0.6082395 0.02947968 -0.7939649 -0.6072225 0.03001189 -0.793968 -0.60721 0.03018206 -0.7939535 -0.6072295 0.0301724 -0.7936301 -0.6076568 0.03007638 -0.793892 -0.6072878 0.0306124 -0.7930897 -0.6083326 0.03066492 -0.792083 -0.6096861 0.02978718 -0.7930585 -0.6083575 0.03097522 -0.7909016 -0.611199 0.03017503 -0.7914876 -0.6103617 0.03171598 -0.7893495 -0.6131891 0.03044068 -0.7872865 -0.6158923 0.02926963 -0.7891073 -0.6134104 0.03221148 -0.7849985 -0.6187905 0.02958881 -0.7860417 -0.6173184 0.03250348 -0.5819703 0.813123 -0.01189839 -0.6886476 0.7194001 -0.09070837 -0.6184794 0.7841412 -0.05104786 -0.4195438 0.9073877 -0.02511143 -0.3031822 0.9516736 0.04896879 -0.303183 0.9516732 0.04897183 -0.4656708 0.8826496 0.06387919 -0.355501 0.9280076 0.111449 -0.4389375 0.8956526 0.07169651 -0.4195433 0.9073879 -0.02511155 -0.5368341 0.8370516 -0.1056121 0.3498582 0.9344674 -0.06610506 0.3759163 0.9262869 -0.02606326 0.3498556 0.9344685 -0.06610435 0.5462071 0.8346297 -0.07107204 0.5949308 0.7949728 0.1186408 0.576834 0.816315 -0.02987402 -0.04658162 0.997714 -0.04895913 0.0494486 0.9984161 0.0268315 -0.04660117 0.9977134 -0.04895281 0.3498712 0.9353404 0.0522347 0.4001035 0.9163852 0.01246541 0.0494517 0.9984161 0.02682733 -0.1608268 0.9771654 -0.1388617 -0.5368349 0.8370516 -0.1056068 0.2804666 0.9453262 -0.1664233 -0.1608182 0.9771638 -0.1388822 0.5481948 0.8331708 -0.07286256 0.5332303 0.8376304 -0.118494 0.2321009 0.9668203 -0.1067129 0.8817747 0.4662001 -0.07163101 0.8756552 0.4814858 -0.03740811 0.880482 0.4689633 -0.06946063 0.8602541 0.505276 -0.06825768 0.8569685 0.513164 -0.04761958 0.8658542 0.500265 -0.00561279 0.8483878 0.5277583 0.0413441 0.8356791 0.5451532 -0.06669759 0.8254485 0.5644744 -0.00180459 0.8579968 0.5081748 -0.07483255 0.8078349 0.5858456 -0.06471264 0.8076979 0.5861854 -0.0633316 0.8307892 0.5509783 -0.07881724 0.8208997 0.5708864 0.01458144 0.7777962 0.625324 -0.06326854 0.7784861 0.6231113 -0.07544332 0.7987778 0.5958818 -0.08293867 0.7836634 0.6204354 0.03052538 0.7477975 0.660791 -0.06445336 0.7476366 0.661668 -0.05687654 0.763194 0.6405687 -0.08489155 0.7519132 0.6589322 0.02085834 0.7204056 0.6901575 -0.06854569 0.7204445 0.6935125 3.91067e-4 0.7284524 0.6801621 -0.08207702 0.697013 0.7133608 -0.07272678 0.6987196 0.714246 -0.04054111 0.699094 0.7108818 -0.07690668 0.7220888 0.691637 -0.01503783 0.677941 0.7315388 -0.07243627 0.6803078 0.7315732 -0.04451799 0.693467 0.7204354 0.008737981 0.6626073 0.7456154 -0.07077562 0.6686447 0.7435302 -0.00877881 0.6758819 0.7331649 -0.07518649 0.6500739 0.7565789 -0.07065629 0.654156 0.7553621 -0.03883481 0.6578099 0.7494124 -0.07528114 0.6685631 0.743627 -0.006505131 0.6398595 0.7651925 -0.07113552 0.6483073 0.7613285 -0.008744001 0.6439336 0.7614414 -0.07454138 0.631628 0.771943 -0.07176506 0.6374751 0.7696877 -0.03473526 0.6333447 0.7703648 -0.07357043 0.648311 0.7612913 -0.0113309 0.6250734 0.7772086 -0.07231926 0.6333351 0.773559 -0.02220898 0.6253623 0.7769427 -0.07267838 0.6200832 0.7812219 -0.07203453 0.6330578 0.7740709 0.007229506 0.616287 0.7842395 -0.07182461 0.6237161 0.7810296 -0.03116393 0.6193553 0.7817515 -0.07255166 0.6312142 0.775125 -0.02738499 0.6134576 0.7864535 -0.07183855 0.6226016 0.7822206 -0.02231931 0.6150532 0.7851489 -0.07246226 0.6113924 0.788053 -0.07191509 0.6228582 0.7822757 -0.009605288 0.6121228 0.787451 -0.07229542 0.6099937 0.7891297 -0.0719853 0.6179662 0.7856033 -0.0307424 0.6102256 0.7889369 -0.07213449 0.6216689 0.7828186 -0.02688419 0.6090943 0.7898203 -0.07202768 0.6174055 0.7861004 -0.02926534 0.6090992 0.7898162 -0.07203149 0.6086367 0.7901763 -0.07199215 0.6173396 0.786225 -0.02724224 0.6085438 0.7902464 -0.0720058 0.6173693 0.7862231 -0.0266155 0.6085869 0.7902126 -0.07201498 0.6083238 0.7904233 -0.07192486 0.6164107 0.7868262 -0.03069788 0.6085457 0.7902452 -0.07200521 0.6170728 0.7863298 -0.03011214 0.6063052 0.791984 -0.07180064 0.6151615 0.7879327 -0.02717238 0.6071082 0.7913306 -0.07221806 0.6021637 0.7951281 -0.07190239 0.6146147 0.788769 -0.00960654 0.6026639 0.7947185 -0.07224214 0.5959138 0.7997779 -0.07240259 0.6158829 0.7873305 0.02826631 0.5952779 0.8002994 -0.07186865 0.5880578 0.8056691 -0.07131153 0.5969851 0.8015823 -0.03278166 0.6121824 0.7904488 -0.02057677 0.5777858 0.8131163 -0.07074993 0.5912527 0.8063361 -0.01556879 0.584408 0.8081949 -0.07272189 0.56437 0.8225154 -0.07039058 0.5908756 0.806002 0.03502601 0.5694549 0.818769 -0.07306474 0.511464 0.8230611 -0.2469311 0.5727255 0.8113823 -0.1168094 0.5260557 0.8280122 -0.1940653 0.5828806 0.8033726 -0.1218303 0.5812805 0.7981032 -0.1585698 0.5731475 0.7933984 -0.2049899 0.597888 0.7926348 -0.1194156 0.5893543 0.7983302 -0.123816 0.5978966 0.7926047 -0.1195722 0.5974644 0.7922997 -0.1236829 0.5998687 0.7912243 -0.1188353 0.597845 0.7923954 -0.1212065 0.600663 0.7897806 -0.1243008 0.5980383 0.7875744 -0.1485826 0.6099089 0.7835831 -0.1183583 0.6023473 0.7888404 -0.122101 0.6084082 0.778514 -0.1541281 0.6259757 0.7714406 -0.1141664 0.6119331 0.7801662 -0.1299182 0.6366446 0.7619901 -0.1185529 0.6246727 0.7652422 -0.1555263 0.6510338 0.7491454 -0.1222128 0.6739516 0.7328369 -0.0934841 0.6482547 0.7435356 -0.1640755 0.6984192 0.710388 -0.08694612 0.6773715 0.7132886 -0.1799648 0.7283483 0.6797474 -0.08632719 0.7154635 0.6769131 -0.1729176 0.7632995 0.639779 -0.08975893 0.7567853 0.6324666 -0.1651125 0.8016989 0.5755102 -0.1614522 0.8342587 0.539018 -0.1160686 0.7987836 0.5889852 -0.1226432 0.8584301 0.5069699 -0.07796877 0.842719 0.5011849 -0.1965661 0.8860431 0.4506314 -0.1088992 0.8835507 0.4073451 -0.2311021 0.8210453 0.5663803 -0.07139891 0.8210709 0.5663429 -0.07140332 0.8835571 0.4234866 -0.1999651 0.8206245 0.5671471 -0.07013988 0.821124 0.5662484 -0.07154214 0.8543095 0.3025394 -0.4226406 0.8748752 0.3722139 -0.3099195 0.6664132 0.04848575 -0.7440044 0.7935496 0.5806649 0.1819539 0.8117809 0.5667433 0.1407618 0.795647 0.579409 0.1767235 0.8308655 0.5490935 0.09032756 0.8400172 0.539185 0.0604211 0.8472929 0.5294923 0.0416243 0.8365319 0.5431239 0.07232451 0.8569997 0.5152633 0.007432579 0.611799 0.7774062 0.1460877 0.4785113 0.8654944 0.1481426 0.6341771 0.7590857 0.1469977 0.6116139 0.7780314 0.1435121 0.6388303 0.7554281 0.1456859 0.6341569 0.7596516 0.1441338 0.6413096 0.7531681 0.1464914 0.6388332 0.75551 0.1452475 0.6474079 0.7476519 0.1479181 0.6413488 0.7536509 0.1438127 0.6570261 0.7388175 0.1498851 0.6476106 0.7486808 0.1416956 0.6699824 0.7265633 0.1524111 0.6576879 0.740369 0.1389254 0.6860128 0.710783 0.15548 0.6716334 0.7283867 0.1355044 0.7047626 0.6913909 0.1590229 0.6894654 0.7122983 0.1314097 0.7257436 0.6683705 0.1630247 0.7110969 0.6915702 0.1267744 0.7483453 0.6418378 0.1674023 0.7362415 0.6656681 0.1217969 0.7718894 0.6120514 0.1719878 0.7643269 0.6341761 0.1167264 0.794411 0.5969694 0.1119769 0.5950804 0.8021303 0.04966276 0.6236815 0.7800666 0.05017358 0.5948862 0.802374 0.04802858 0.6294014 0.7755131 0.0493294 0.6235798 0.7802618 0.04837077 0.6327763 0.7727277 0.04985827 0.6293874 0.7755448 0.04900825 0.6409116 0.7659306 0.05081963 0.6327113 0.7728963 0.04804217 0.6536918 0.7549613 0.05215936 0.6408345 0.7662631 0.04660356 0.6709143 0.7395747 0.05388343 0.653759 0.7553826 0.04468178 0.692258 0.7194705 0.05604642 0.6714372 0.739852 0.04232221 0.7172325 0.6943635 0.05862593 0.6937337 0.7191458 0.03953486 0.7451376 0.6640558 0.06164377 0.7203313 0.6926723 0.03643828 0.775062 0.6285324 0.0650072 0.7506546 0.6598628 0.03314661 0.8059162 0.5880402 0.06861329 0.7837688 0.6203338 0.0298739 0.8183597 0.5740768 0.02689498 -0.1329229 0.96175 0.2395172 -0.2740563 0.9461789 0.1721594 -0.6177702 -0.3163163 0.7199334 -0.68491 -0.3800445 0.6216626 -0.7542409 -0.4847879 0.4428334 -0.7816419 -0.5531639 0.2881764 -0.7874693 -0.5586262 0.2604397 -0.7915233 -0.5805185 0.1910209 -0.7846843 -0.5623522 0.2608269 -0.7846043 -0.5622756 0.2612326 -0.680457 -0.3862379 0.6227348 -0.6798291 -0.3856113 0.6238078 -0.791289 -0.552716 0.2614706 -0.7943861 -0.5483697 0.2612308 -0.7914813 -0.5529116 0.2604727 -0.7965088 -0.5454216 0.2609389 -0.7945356 -0.5485282 0.2604419 -0.7976312 -0.5438616 0.2607664 -0.7965884 -0.5455085 0.2605138 -0.797781 -0.5437142 0.2606152 -0.7976644 -0.5438984 0.2605882 -0.7969439 -0.54497 0.2605533 -0.7977588 -0.5436896 0.2607349 -0.7951069 -0.5476429 0.2605612 -0.7968722 -0.5448911 0.2609376 -0.7922764 -0.5517521 0.2605142 -0.7950109 -0.5475397 0.2610705 -0.7884008 -0.5572374 0.2605966 -0.7921226 -0.5515926 0.2613183 -0.7834611 -0.5641344 0.2606551 -0.7882183 -0.5570573 0.2615323 -0.7774185 -0.57237 0.2607935 -0.7832297 -0.5639201 0.2618117 -0.7702234 -0.5819487 0.2609436 -0.7771502 -0.5721405 0.2620934 -0.7618438 -0.5928135 0.2610864 -0.7699207 -0.5817131 0.2623586 -0.7522184 -0.6049078 0.2612547 -0.7614974 -0.5925725 0.2626396 -0.7412913 -0.6181643 0.2614579 -0.7518232 -0.6046662 0.2629461 -0.7290228 -0.6325297 0.261595 -0.7408677 -0.6179414 0.2631795 -0.7153601 -0.6478883 0.2617264 -0.7285533 -0.6323218 0.2633993 -0.7002535 -0.6641377 0.2618517 -0.7148407 -0.6476997 0.2636057 -0.6836826 -0.6811712 0.2618854 -0.6997044 -0.6639791 0.2637149 -0.6656195 -0.6988481 0.2618435 -0.6830978 -0.6810421 0.2637404 -0.6460546 -0.7170112 0.2617413 -0.6649929 -0.6987477 0.263697 -0.624956 -0.7355571 0.2615067 -0.6454082 -0.7169414 0.2635211 -0.6026766 -0.7540137 0.2612361 -0.6242682 -0.7355135 0.263266 -0.5649787 -0.7832356 0.2595016 -0.601974 -0.7539944 0.2629066 -0.47255 -0.8437315 0.2545853 -0.5632674 -0.7832594 0.2631245 -0.3016856 -0.9216338 0.2440839 -0.4686009 -0.8439321 0.2611356 -0.07961314 -0.9702411 0.2286788 -0.2944055 -0.9216786 0.2526537 0.02326107 -0.9743368 0.2238902 -0.07235318 -0.9693087 0.2349586 -0.03654873 -0.9722338 0.2311392 0.02390623 -0.9742053 0.2243937 -0.2563243 -0.9341999 0.24813 -0.04051637 -0.9728524 0.2278523 -0.5044393 -0.8232627 0.2603451 -0.2608003 -0.9342541 0.2432129 -0.6743534 -0.6898961 0.2632316 -0.5061178 -0.8231816 0.2573262 -0.6747977 -0.68998 0.2618693 -0.6871814 -0.3715677 0.6242749 -0.6912218 -0.3661049 0.6230406 -0.6891999 -0.3735942 0.6208309 -0.6939327 -0.3623765 0.6222065 -0.6925472 -0.3674468 0.6207747 -0.6954904 -0.360588 0.6215059 -0.6947582 -0.3632171 0.6207933 -0.695871 -0.3607095 0.6210091 -0.6958119 -0.3609164 0.6209551 -0.6950572 -0.3627247 0.6207466 -0.6957033 -0.3605381 0.6212964 -0.6930277 -0.3665986 0.6207398 -0.6944193 -0.3620737 0.6218397 -0.6897073 -0.3723431 0.621019 -0.6919183 -0.3654716 0.6226393 -0.6851356 -0.3799723 0.6214582 -0.688225 -0.3708483 0.6235527 -0.6791431 -0.3894224 0.6221855 -0.6832143 -0.3780537 0.6247349 -0.6718095 -0.4007481 0.6229552 -0.6769436 -0.387254 0.6259247 -0.6629344 -0.4138492 0.6238965 -0.6692558 -0.3982697 0.6272782 -0.6524658 -0.4286665 0.6249267 -0.6600812 -0.4111321 0.6286996 -0.6403361 -0.4451813 0.6259261 -0.6493805 -0.4257926 0.6300839 -0.6264491 -0.463265 0.6268549 -0.6370391 -0.4421873 0.6313887 -0.6105598 -0.4826863 0.6278779 -0.6228276 -0.4600694 0.632789 -0.5927886 -0.5035073 0.6285555 -0.6068689 -0.4795322 0.6338447 -0.5729485 -0.525421 0.6290174 -0.5889373 -0.5003296 0.6346835 -0.5508981 -0.5481633 0.6293079 -0.5688906 -0.5221975 0.6353529 -0.5267606 -0.571678 0.6290528 -0.5468554 -0.5450782 0.6354833 -0.50037 -0.5954933 0.6285043 -0.5225648 -0.568607 0.6353048 -0.4718634 -0.6196113 0.6272374 -0.4962795 -0.5926234 0.6344323 -0.4415819 -0.6431248 0.6256166 -0.4677217 -0.6168259 0.633058 -0.3917645 -0.6813996 0.6182355 -0.4374808 -0.6404742 0.6311921 -0.2706778 -0.7552609 0.5969208 -0.3823606 -0.6756633 0.6303012 -0.05641812 -0.8322384 0.5515401 -0.2524644 -0.745071 0.6173581 0.1962817 -0.8483513 0.4917048 -0.02940589 -0.8168879 0.5760464 0.3069275 -0.8263305 0.4722008 0.2168843 -0.8341128 0.5071659 0.2498748 -0.8320986 0.4951508 0.3084393 -0.8251525 0.4732743 0.008583605 -0.8280554 0.5605807 0.2389525 -0.8399941 0.4871463 -0.3066051 -0.7239034 0.6180269 -0.007424354 -0.8373554 0.5466085 -0.5365667 -0.5568611 0.6340361 -0.3148162 -0.7285946 0.6083097 -0.53983 -0.5593109 0.6290906 0.50093 0.8257505 -0.2592393 0.2255353 0.9441587 -0.2402045 0.5488426 0.7949219 -0.2585943 0.5022814 0.8261483 -0.2553284 0.5470668 0.7947223 -0.262934 0.5576589 0.7881176 -0.260552 0.5573573 0.7880796 -0.2613112 0.5640512 0.7842381 -0.2584894 0.562354 0.7840116 -0.262838 0.5785713 0.7745344 -0.25564 0.5748026 0.7739426 -0.2657346 0.6009551 0.7585918 -0.2517769 0.5946934 0.7573178 -0.2698324 0.6305978 0.7357541 -0.2470067 0.6219 0.7332537 -0.2749174 0.666651 0.7052591 -0.2412179 0.6559164 0.7005603 -0.2810496 0.7078554 0.6663725 -0.2342827 0.6959004 0.6578946 -0.2879188 0.7524253 0.6185547 -0.2263767 0.7403928 0.6040005 -0.2949607 0.7981929 0.5617182 -0.217625 0.7871156 0.5380429 -0.3015938 0.8426935 0.4963437 -0.2085918 0.8330821 0.4602726 -0.3067952 0.6382684 0.1727102 -0.7501897 0.8048928 0.3836148 -0.4527552 0.6008144 0.2890668 -0.7452936 0.7472014 0.4573221 -0.4822307 0.5584405 0.3917166 -0.7312334 0.6840034 0.5206271 -0.5109666 0.5153295 0.4770574 -0.7119352 0.619307 0.5725978 -0.5372063 0.475309 0.5448445 -0.6908154 0.5571035 0.6131644 -0.5600581 0.4408237 0.5965332 -0.6706882 0.5010532 0.6432623 -0.5789293 0.4135289 0.6344883 -0.6530072 0.4538045 0.664149 -0.5941109 0.393837 0.6605977 -0.6391425 0.4173451 0.6773451 -0.6058273 0.3823239 0.67677 -0.629135 0.392513 0.6839016 -0.6149895 0.3784666 0.6836798 -0.6239752 0.3802192 0.6849004 -0.6215665 0.3604249 0.6887883 -0.6290187 0.3715127 0.696419 -0.6139862 0.3121155 0.7360906 -0.6006284 0.3029653 0.7289729 -0.6138489 -0.6949276 0.7118564 -0.1016654 -0.759626 0.632642 -0.1507731 -0.8228056 0.526707 -0.2134732 -0.06573355 -0.9958018 0.06370317 -0.7745743 -0.6304659 -0.05047231 -0.1207338 -0.9911558 0.0550782 -0.7539573 -0.6397684 -0.1491469 -0.7750981 -0.6299422 -0.04894781 -0.7555428 -0.6387927 -0.1452544 -0.7535533 -0.6411218 -0.1453282 -0.753533 -0.6410987 -0.1455357 -0.7731686 -0.6323022 -0.04903304 -0.7731692 -0.6322903 -0.04917585 -0.7574836 -0.636484 -0.1452817 -0.7572313 -0.636642 -0.1459027 -0.7591497 -0.6344609 -0.1454339 -0.7589818 -0.6345677 -0.1458435 -0.7602732 -0.6330878 -0.1455489 -0.7601675 -0.6331557 -0.1458054 -0.7608563 -0.6323726 -0.1456114 -0.7608044 -0.6324061 -0.1457371 -0.7608718 -0.6323383 -0.1456793 -0.7608944 -0.6323237 -0.1456244 -0.7603221 -0.6329734 -0.1457915 -0.7604285 -0.6329051 -0.1455327 -0.7592439 -0.6342642 -0.1457994 -0.7593708 -0.6341837 -0.1454893 -0.7575852 -0.6362349 -0.1458417 -0.7577823 -0.6361115 -0.1453549 -0.755371 -0.6388681 -0.1458154 -0.755592 -0.6387326 -0.145263 -0.7525599 -0.6421716 -0.1458401 -0.7528439 -0.6420022 -0.1451183 -0.749178 -0.6461176 -0.1458228 -0.7494817 -0.6459426 -0.1450361 -0.7451936 -0.6507123 -0.1458082 -0.7455268 -0.6505282 -0.1449236 -0.7406015 -0.6559353 -0.1458021 -0.740958 -0.6557485 -0.1448283 -0.7354103 -0.661764 -0.1457393 -0.7357586 -0.6615929 -0.1447551 -0.7295824 -0.6681898 -0.1457117 -0.7299467 -0.6680247 -0.14464 -0.72313 -0.6751811 -0.1456484 -0.723478 -0.6750389 -0.1445755 -0.7160204 -0.6827152 -0.1456533 -0.716377 -0.6825879 -0.1444922 -0.708294 -0.6907417 -0.1455864 -0.7086089 -0.6906483 -0.1444932 -0.6998965 -0.699248 -0.1455928 -0.7002048 -0.6991788 -0.1444379 -0.6908694 -0.708164 -0.1456126 -0.6911471 -0.7081261 -0.1444751 -0.6812044 -0.7174683 -0.1456015 -0.6814373 -0.7174619 -0.1445394 -0.6709195 -0.7270855 -0.1456492 -0.671123 -0.7271087 -0.1445925 -0.6599994 -0.7369887 -0.1457691 -0.6601718 -0.7370415 -0.1447172 -0.6416754 -0.7528112 -0.1467244 -0.6419394 -0.7530293 -0.1444324 -0.5971379 -0.788299 -0.148361 -0.5971098 -0.7890881 -0.1442221 -0.5157725 -0.84322 -0.151522 -0.514408 -0.8450655 -0.1457692 -0.4058713 -0.9004626 -0.1563194 -0.4032328 -0.9024658 -0.1515214 -0.3539793 -0.9217947 -0.1580923 -0.3537017 -0.92197 -0.1576912 -0.3865801 -0.9092497 -0.1543402 -0.388116 -0.908155 -0.1569091 -0.4968836 -0.8551691 -0.147623 -0.4978803 -0.8539798 -0.1511084 -0.6143308 -0.7756582 -0.1447483 -0.6142544 -0.775362 -0.1466467 -0.6960104 -0.7033548 -0.1444352 -0.6957836 -0.7033955 -0.1453272 -0.7013588 -0.7111288 -0.04890465 -0.7014814 -0.7110468 -0.04833585 -0.5976738 -0.8001768 -0.0500307 -0.5976939 -0.8002424 -0.04872554 -0.4474095 -0.8927088 -0.05381053 -0.4467185 -0.8931906 -0.05150711 -0.3057856 -0.9502838 -0.05878764 -0.304798 -0.9507014 -0.05714029 -0.2627298 -0.9630203 -0.0597071 -0.2629044 -0.9629569 -0.05996096 -0.3283755 -0.9429461 -0.05497509 -0.3301485 -0.9421346 -0.05817669 -0.4712589 -0.8805744 -0.05003684 -0.4722439 -0.8798168 -0.05392652 -0.5767879 -0.815454 -0.04848414 -0.5768727 -0.8152251 -0.0512458 -0.6336258 -0.7721217 -0.04844009 -0.6334941 -0.7721314 -0.0499826 -0.6566008 -0.7526713 -0.04859209 -0.6565099 -0.7527055 -0.04928708 -0.6704586 -0.7403603 -0.04849565 -0.6703473 -0.7404145 -0.0492013 -0.6834864 -0.728356 -0.04841476 -0.6833496 -0.7284341 -0.04916447 -0.6957018 -0.7167003 -0.04837173 -0.6955454 -0.7168001 -0.04913389 -0.7070669 -0.705491 -0.04836302 -0.7068942 -0.7056112 -0.04912781 -0.7175948 -0.6947799 -0.04835987 -0.7174029 -0.6949229 -0.04914438 -0.7272688 -0.6846426 -0.04842168 -0.7270774 -0.6847937 -0.04915356 -0.7361226 -0.6751122 -0.04844659 -0.7359097 -0.6752886 -0.04921579 -0.7441355 -0.6662639 -0.04852771 -0.7439319 -0.6664397 -0.0492289 -0.7513454 -0.6581186 -0.04858028 -0.7511321 -0.6583095 -0.04928648 -0.7577508 -0.6507266 -0.04867094 -0.7575527 -0.6509094 -0.04930454 -0.7633731 -0.6441138 -0.04877257 -0.7631877 -0.6442897 -0.04934972 -0.7682426 -0.6382921 -0.04885149 -0.7680634 -0.638466 -0.04939603 -0.7723546 -0.6333027 -0.04894912 -0.7722004 -0.6334552 -0.04940891 -0.7757471 -0.6291387 -0.04900127 -0.7756005 -0.6292856 -0.04943144 -0.7784057 -0.6258378 -0.04911011 -0.7783054 -0.6259396 -0.04940062 -0.7803688 -0.6233832 -0.04917162 -0.7802836 -0.6234706 -0.0494166 -0.7816326 -0.621791 -0.04926115 -0.7815911 -0.6218337 -0.04937976 -0.782218 -0.6210516 -0.04929238 -0.7821942 -0.6210763 -0.04936045 -0.7821071 -0.6211864 -0.04935634 -0.7821348 -0.6211576 -0.04927718 -0.7813271 -0.6221637 -0.04940146 -0.7813901 -0.6220986 -0.04922127 -0.7798636 -0.6239939 -0.04944139 -0.7799689 -0.6238861 -0.04913872 -0.7777161 -0.6266655 -0.04947745 -0.7778653 -0.6265143 -0.04904532 -0.01869815 -0.9542019 0.2985783 0.1896202 -0.9583731 0.2134599 0.2769923 -0.9456012 0.170627 0.3299924 -0.1339666 0.9344291 0.3456382 -0.1224763 0.9303407 0.7565146 0.3061246 0.5779044 0.7806279 0.3376094 0.5259659 0.812546 0.3988384 0.4250847 0.8371906 0.4704868 0.2788444 0.8345586 0.4641734 0.296741 0.7045236 0.7068835 -0.06294602 0.8388938 0.5143003 0.1781919 0.8394516 0.5185391 0.1625977 0.7906457 0.5856063 0.1787304 0.790634 0.5855891 0.1788385 0.7820009 0.5481556 0.2966478 0.7819222 0.5480453 0.2970592 0.7248662 0.4426081 0.5278893 0.7244486 0.442122 0.5288689 0.29447 -0.01202434 0.9555851 0.2927445 -0.0134226 0.9560964 0.8257362 0.5356087 0.1768698 0.8127178 0.5549713 0.1774733 0.8256074 0.535191 0.1787263 0.8010036 0.5715922 0.1779763 0.8125851 0.5546537 0.1790664 0.7910221 0.5852136 0.178351 0.8008812 0.5713659 0.1792496 0.7830178 0.5957741 0.1787078 0.7909087 0.585045 0.1794041 0.7773367 0.6030949 0.1789532 0.7829331 0.5956683 0.1794297 0.7746236 0.6065255 0.1791228 0.7772887 0.6030417 0.1793406 0.7745169 0.6066089 0.179302 0.7746001 0.6065008 0.1793084 0.7751482 0.6058251 0.1792241 0.7745327 0.6066254 0.1791781 0.7758164 0.6049684 0.1792266 0.7751538 0.6058311 0.1791793 0.775116 0.6058787 0.1791819 0.7758161 0.6049681 0.1792291 0.7726284 0.609057 0.1791504 0.7751001 0.6058617 0.1793085 0.7687 0.6139888 0.1792149 0.7725893 0.6090178 0.1794522 0.7634326 0.620532 0.1791943 0.7686621 0.6139539 0.1794974 0.7566455 0.6287698 0.1792661 0.7633701 0.6204806 0.1796381 0.7482964 0.6386469 0.1793951 0.7565607 0.6287097 0.1798331 0.7384092 0.650057 0.1793818 0.7482187 0.6386014 0.1798809 0.7268457 0.6629195 0.1795358 0.7382855 0.6499997 0.1800971 0.7136003 0.6771609 0.1795209 0.7267314 0.66288 0.1801436 0.6985836 0.6926337 0.1795534 0.713452 0.677126 0.1802407 0.6817421 0.7092214 0.1795346 0.6984168 0.6926109 0.1802886 0.6630253 0.7267714 0.1794453 0.6815583 0.709212 0.1802683 0.6423881 0.7451124 0.1792908 0.6628198 0.7267755 0.1801869 0.6192247 0.7645386 0.1790013 0.6421692 0.7451292 0.1800031 0.5733865 0.7997675 0.1777634 0.6189371 0.7645738 0.1798437 0.4741519 0.8629728 0.1745217 0.5726661 0.7998918 0.1795178 0.3049864 0.93756 0.167226 0.4725984 0.8632643 0.1772722 0.1133388 0.9809451 0.1578011 0.3020939 0.9378685 0.1707101 0.0481525 0.9866959 0.1552823 0.1109996 0.9808726 0.1598996 0.1253628 0.9790095 0.1607005 0.04819244 0.9866992 0.1552491 0.3361021 0.9260967 0.1714064 0.1270932 0.9790438 0.1591246 0.5486615 0.8167974 0.1783608 0.3375903 0.9259052 0.1695064 0.693725 0.6973799 0.1800193 0.5491407 0.8167071 0.1772962 0.6938496 0.6973931 0.1794875 0.8205096 0.4913377 0.2921494 0.8063296 0.5135565 0.2934148 0.8196356 0.4895619 0.2975339 0.7934748 0.5326135 0.2944836 0.8055311 0.5121474 0.2980345 0.7824322 0.5481891 0.2954468 0.7927668 0.5315148 0.2983501 0.7735482 0.5602605 0.2961945 0.7818588 0.5473926 0.2984265 0.7672072 0.5685645 0.2968628 0.7731105 0.5597044 0.2983808 0.7641298 0.5723357 0.2975528 0.7669233 0.568226 0.298241 0.7640163 0.5723743 0.2977696 0.7640812 0.5722797 0.2977851 0.7646922 0.5714139 0.2978792 0.7640247 0.5723841 0.2977289 0.7654501 0.5704752 0.2977318 0.7647541 0.571486 0.2975819 0.7646864 0.5715992 0.2975384 0.7654574 0.5704838 0.2976968 0.7619184 0.5753414 0.297427 0.7646008 0.5714994 0.2979494 0.7575592 0.5810898 0.2973864 0.7617634 0.5751656 0.2981628 0.751663 0.5886814 0.2974171 0.7573394 0.5808512 0.2984107 0.7440451 0.5982071 0.2975653 0.7513632 0.5883749 0.2987779 0.7346782 0.6096146 0.2976878 0.7436955 0.597876 0.2991009 0.7235069 0.6227804 0.2977957 0.7342742 0.6092665 0.2993924 0.7104514 0.637592 0.2978847 0.7230452 0.6224249 0.2996544 0.6953905 0.6539323 0.2980012 0.7099139 0.637229 0.2999361 0.6782879 0.6716629 0.297984 0.6948134 0.6535973 0.300075 0.6590396 0.6905921 0.2979082 0.6776444 0.671348 0.30015 0.6375599 0.7105273 0.2977726 0.658321 0.6903018 0.3001613 0.6138278 0.7312562 0.2974557 0.6367989 0.7102788 0.2999854 0.5871038 0.7530903 0.2969245 0.6130036 0.7310432 0.2996705 0.534433 0.792466 0.2939028 0.5861141 0.752893 0.2993699 0.4204599 0.8607407 0.2869477 0.5319229 0.7921615 0.2992291 0.2286373 0.9345822 0.2725456 0.4153715 0.8604397 0.295144 0.01654577 0.9665423 0.255973 0.2199736 0.933731 0.2824149 -0.05540174 0.9659413 0.2527613 0.01013696 0.9651308 0.2615719 0.02682965 0.9644318 0.2629665 -0.05513852 0.9660125 0.2525461 0.2608813 0.9228923 0.2832152 0.03147178 0.9654049 0.2588496 0.5051898 0.810455 0.296557 0.2654025 0.92326 0.2777631 0.6726003 0.6766541 0.2995797 0.506859 0.8106104 0.2932657 0.6730694 0.6768715 0.2980314 0.7693395 0.3756479 0.5167257 0.7534532 0.4024664 0.5199318 0.7645768 0.3693202 0.5282281 0.7387372 0.4253398 0.522832 0.7492234 0.3971207 0.530056 0.7259198 0.4439981 0.5252677 0.7351887 0.42106 0.5312307 0.7154408 0.4583336 0.527328 0.7230681 0.4406968 0.5319389 0.7078442 0.4680665 0.5290278 0.7133495 0.4559919 0.5321691 0.7040815 0.4722898 0.530294 0.706682 0.4667954 0.5316978 0.7037687 0.4720653 0.5309087 0.7038048 0.4719904 0.5309273 0.7045469 0.4708462 0.5309591 0.7038865 0.4721928 0.5306391 0.7053956 0.4696812 0.530864 0.7047231 0.4710372 0.5305557 0.7046368 0.471296 0.5304405 0.7054305 0.4697193 0.5307838 0.7015592 0.4761265 0.530206 0.7042607 0.4708881 0.5313015 0.6964856 0.4832288 0.5304695 0.7007342 0.475241 0.5320879 0.6896531 0.4926994 0.5306844 0.6954737 0.4821609 0.5327638 0.6808184 0.504576 0.5309325 0.6884115 0.4914185 0.5334768 0.669813 0.5186727 0.5313466 0.6792906 0.5030451 0.5343314 0.65654 0.5348327 0.5318921 0.6680136 0.5169336 0.535292 0.6409755 0.5530295 0.5322675 0.6545968 0.5330331 0.536077 0.6229465 0.5730651 0.5324792 0.6388727 0.5511759 0.5367 0.602255 0.5946356 0.5326327 0.6206167 0.5711231 0.5372648 0.5788568 0.6175565 0.5324931 0.5997918 0.5927057 0.5375403 0.5526759 0.6415514 0.5319409 0.5763004 0.6156834 0.5374122 0.5236346 0.6662832 0.5309177 0.5500345 0.6397484 0.5368279 0.4908303 0.6920496 0.5292949 0.5208619 0.6645235 0.5358278 0.4270526 0.7386967 0.5214914 0.4875447 0.6901136 0.5348303 0.2899184 0.8143357 0.502797 0.4194012 0.734712 0.5331987 0.0676707 0.8826765 0.4650838 0.2762525 0.8082044 0.5200867 -0.1630744 0.8908222 0.4240785 0.04785656 0.8735086 0.4844506 -0.2395223 0.8774825 0.415516 -0.1758801 0.883397 0.4343686 -0.1570459 0.8850703 0.4381635 -0.2390393 0.8777897 0.4151453 0.09848403 0.8668357 0.4887706 -0.1476103 0.8904415 0.4304943 0.3892381 0.7557427 0.5266371 0.109343 0.8717193 0.4776502 0.5945597 0.5991767 0.5361772 0.3941271 0.7581585 0.5194802 0.5963303 0.6005415 0.5326727 0.3516408 -0.07324862 0.9332649 0.3324828 -0.04748022 0.9419134 0.3289705 -0.09063583 0.9399806 0.3142957 -0.02566832 0.9489781 0.3126334 -0.06301593 0.9477813 0.2990056 -0.007305979 0.9542235 0.2986712 -0.03811699 0.9535945 0.2859506 0.006329536 0.9582235 0.2864107 -0.0174911 0.9579472 0.2760534 0.01516085 0.9610226 0.2767986 -0.001157879 0.9609272 0.270286 0.01808369 0.9626102 0.2707811 0.01081252 0.9625802 0.2691046 0.01709669 0.9629592 0.269104 0.01710522 0.9629592 0.2699621 0.01582777 0.9627408 0.269776 0.01765245 0.9627612 0.2710552 0.01479345 0.9624501 0.2708482 0.01656067 0.9624796 0.2710026 0.01718473 0.9624253 0.2712982 0.01499426 0.9623786 0.2678571 0.02252489 0.9631953 0.2689533 0.01548928 0.9630286 0.2628723 0.03059673 0.9643454 0.2647843 0.01997321 0.9641009 0.2554131 0.04071259 0.9659745 0.2582989 0.02677631 0.9656939 0.2458119 0.05353409 0.9678381 0.2499503 0.03611379 0.967585 0.2337881 0.0687862 0.9698514 0.2394061 0.04808908 0.9697279 0.219402 0.08649194 0.9717931 0.2267411 0.06272447 0.9719332 0.2021977 0.1062141 0.973568 0.2115022 0.07960224 0.9741306 0.1821668 0.1279624 0.9749056 0.1937118 0.09869474 0.9760816 0.1594794 0.1517158 0.9754736 0.1734898 0.120135 0.9774809 0.1339751 0.1771095 0.9750298 0.1506424 0.1435835 0.9781057 0.1055874 0.2037793 0.9733064 0.1250728 0.1687356 0.9776937 0.07421672 0.2311736 0.9700776 0.09660798 0.1951284 0.9760081 0.03957897 0.2602836 0.9647207 0.06564754 0.2227015 0.9726739 -0.02323997 0.3179929 0.9478082 0.02994102 0.2504767 0.9676595 -0.1544994 0.4095193 0.8991239 -0.04343748 0.2962599 0.9541191 -0.3468708 0.4911671 0.7990216 -0.1827753 0.3754664 0.9086354 -0.5219514 0.4982547 0.6923215 -0.3759445 0.4493321 0.8104112 -0.5758396 0.47728 0.6637866 -0.5356704 0.4740715 0.6987943 -0.5214194 0.4755632 0.7084925 -0.5751547 0.4785821 0.6634427 -0.3306863 0.4472056 0.8310557 -0.5109303 0.493768 0.7036642 -0.06843227 0.3240864 0.9435492 -0.3136427 0.4707877 0.8246134 0.1473047 0.1519182 0.9773547 -0.05588096 0.3379192 0.9395148 0.153693 0.1578321 0.9754319 0.6819044 -0.7256356 -0.09197425 0.6091237 0.7905948 -0.06267488 0.765986 -0.6234874 -0.1566174 0.8210394 -0.5302343 -0.2115328 0.609157 0.7904702 -0.06391012 0.8201591 0.5720897 -0.007254183 0.8075678 0.5863272 -0.06367677 0.8192493 0.5733456 -0.01026493 0.1713511 0.9836769 0.05494242 0.7897944 0.5997976 -0.1283261 0.8071115 0.5868133 -0.06497192 0.7587285 0.6138966 -0.2178581 0.7895574 0.5999843 -0.1289109 0.7595667 0.6134829 -0.2160949 0.7355563 0.6429384 -0.2135117 0.7355049 0.6429184 -0.2137489 0.7587181 0.6389981 -0.1266027 0.7586976 0.6389901 -0.1267668 0.7716315 0.6329306 -0.06311607 0.7716232 0.6329275 -0.06324875 0.7800499 0.6256543 -0.008883535 0.7800488 0.6256546 -0.008950471 0.7057254 0.7084336 -0.008578717 0.7057662 0.7083964 -0.00828284 0.5987838 0.8008552 -0.009423732 0.5987501 0.8008877 -0.008793056 0.4435443 0.8961623 -0.01270866 0.4431338 0.896381 -0.0115531 0.2850616 0.958342 -0.01790797 0.2843822 0.9585623 -0.01688474 0.2239097 0.9744065 -0.01990568 0.2238822 0.9744136 -0.0198704 0.2730048 0.9618622 -0.01701736 0.2739406 0.961571 -0.01837581 0.4181488 0.9083026 -0.01175266 0.4190317 0.9078651 -0.01390844 0.5434978 0.8393593 -0.009280681 0.5437572 0.8391721 -0.01087254 0.6164366 0.7873581 -0.008556723 0.6164614 0.7873263 -0.009626507 0.6502735 0.759652 -0.00856173 0.6502559 0.7596619 -0.009004294 0.667407 0.744645 -0.00847119 0.6673784 0.7446658 -0.00887686 0.6827178 0.7306345 -0.008357524 0.6826721 0.7306715 -0.008826076 0.6966726 0.7173407 -0.008346498 0.6966238 0.7173832 -0.008747994 0.7093077 0.7048497 -0.008340418 0.7092477 0.704905 -0.008760809 0.7206398 0.6932597 -0.008328139 0.7205691 0.6933277 -0.008765459 0.7306912 0.6826564 -0.008408248 0.73063 0.6827176 -0.008752703 0.7395063 0.6730967 -0.008438706 0.7394331 0.6731723 -0.008821249 0.7471042 0.6646528 -0.008485317 0.7470344 0.6647269 -0.00882852 0.7535214 0.6573678 -0.008550286 0.753459 0.6574354 -0.008842706 0.7587737 0.651297 -0.008655071 0.7587273 0.6513481 -0.00886476 0.7628637 0.6465007 -0.008710086 0.7628169 0.6465531 -0.00891596 0.7658966 0.6429039 -0.00878787 0.765867 0.6429373 -0.008914947 0.7678843 0.640528 -0.008816123 0.7678579 0.6405581 -0.008928298 0.7685275 0.6397553 -0.008861303 0.768527 0.639756 -0.008864104 0.7678384 0.6405825 -0.008851647 0.7678485 0.6405709 -0.008808791 0.7672012 0.6413456 -0.00884819 0.7672119 0.6413332 -0.008801698 0.767549 0.6409296 -0.008824467 0.7675369 0.6409434 -0.008875727 0.7696602 0.6383945 -0.008709251 0.7695914 0.6384734 -0.008999288 0.7740519 0.6330625 -0.008695304 0.7739548 0.6331756 -0.009093642 0.7803642 0.625265 -0.00868541 0.780215 0.6254428 -0.00927639 0.7883043 0.6152241 -0.008699536 0.7881044 0.6154689 -0.009458899 0.7976896 0.6030043 -0.008782505 0.7974442 0.6033153 -0.009673178 0.8082426 0.5887821 -0.008912622 0.8079423 0.5891776 -0.009953141 0.7521925 0.6226957 -0.2155375 0.7533608 0.6221809 -0.212928 0.7456244 0.6306869 -0.2151238 0.7465873 0.630312 -0.2128714 0.7398507 0.6375669 -0.2147778 0.7406218 0.6373028 -0.2128955 0.7350626 0.6432091 -0.2143946 0.7356116 0.6430439 -0.2130025 0.7312834 0.6475937 -0.214119 0.7316886 0.6474857 -0.2130591 0.7287332 0.6505503 -0.2138515 0.7289598 0.6504952 -0.2132456 0.7276054 0.6518914 -0.2136073 0.7276579 0.6518792 -0.2134657 0.7274844 0.6520674 -0.2134822 0.7274571 0.6520736 -0.2135563 0.7279105 0.6515916 -0.2134824 0.7278637 0.6516025 -0.2136085 0.7282791 0.6511521 -0.2135663 0.7282677 0.6511548 -0.2135969 0.7277687 0.6516702 -0.2137256 0.7278739 0.6516458 -0.2134417 0.7264699 0.6530997 -0.213781 0.7266141 0.6530679 -0.2133877 0.7245516 0.6552288 -0.2137757 0.7247247 0.655194 -0.2132959 0.7219756 0.658062 -0.2137888 0.7221978 0.658023 -0.2131576 0.718706 0.6616408 -0.2137599 0.7189508 0.6616059 -0.2130427 0.7147292 0.6659294 -0.2137758 0.7150138 0.6659013 -0.2129102 0.7100623 0.6709066 -0.2137659 0.7103521 0.6708937 -0.2128419 0.7047006 0.676548 -0.2137284 0.7049848 0.6765545 -0.2127685 0.6986171 0.6828387 -0.2136948 0.6988952 0.6828687 -0.2126874 0.6918153 0.68973 -0.2136918 0.6920832 0.6897879 -0.2126344 0.6842706 0.6972088 -0.2137142 0.6845178 0.6972974 -0.2126306 0.6760094 0.7052122 -0.2137454 0.6762228 0.70533 -0.2126791 0.666998 0.7137204 -0.213815 0.6671773 0.7138692 -0.2127563 0.6569212 0.7229123 -0.214132 0.6570912 0.7231308 -0.2128686 0.636958 0.7402582 -0.2151794 0.6371275 0.7408667 -0.2125683 0.5950811 0.7737889 -0.2170926 0.5947237 0.7752236 -0.2129132 0.5247782 0.8219946 -0.2212074 0.5228512 0.8246984 -0.215637 0.4438625 0.8669764 -0.226579 0.4416082 0.8690266 -0.2231033 0.4159989 0.8803526 -0.2278689 0.4161074 0.8802638 -0.2280136 0.450036 0.8646762 -0.223165 0.4516538 0.8631526 -0.2257794 0.5394639 0.8138387 -0.2159754 0.5403476 0.8124271 -0.2190585 0.627847 0.7486355 -0.2129631 0.627794 0.7482038 -0.214629 0.6903316 0.6915396 -0.2126393 0.6901445 0.6914924 -0.2133982 0.7803475 0.6120194 -0.1284138 0.7812897 0.6113286 -0.125952 0.7719961 0.6226048 -0.1280057 0.7727732 0.6220738 -0.1258798 0.7646121 0.6317108 -0.1277105 0.7652501 0.6313038 -0.125888 0.7584278 0.6391857 -0.1273928 0.7588912 0.6389083 -0.126017 0.7535482 0.6449774 -0.1271585 0.7538869 0.6447855 -0.1261198 0.750234 0.6488969 -0.1268146 0.7503924 0.6488106 -0.1263168 0.7486971 0.6507034 -0.1266404 0.7487606 0.6506695 -0.1264388 0.7484856 0.6509594 -0.1265746 0.7484815 0.6509616 -0.1265878 0.7490365 0.6503396 -0.1265021 0.748977 0.6503714 -0.1266911 0.7495135 0.6497595 -0.1266581 0.7495273 0.6497519 -0.1266143 0.7489553 0.6504005 -0.1266691 0.7489947 0.6503795 -0.1265444 0.7473223 0.6522637 -0.1267341 0.7474414 0.6522014 -0.126352 0.7448711 0.6550439 -0.126825 0.7450383 0.6549592 -0.1262791 0.7416015 0.6587351 -0.1268675 0.7417879 0.6586449 -0.1262444 0.7374353 0.6634035 -0.1268269 0.7376272 0.6633164 -0.1261641 0.7323725 0.6689912 -0.1268122 0.7325914 0.6689003 -0.1260254 0.7264003 0.6754774 -0.1267794 0.7266251 0.6753947 -0.1259291 0.7195026 0.6828178 -0.1267908 0.7197398 0.6827445 -0.1258361 0.7116672 0.6909876 -0.1267516 0.7118852 0.6909364 -0.1258035 0.7028815 0.6999222 -0.1267541 0.7030925 0.6998924 -0.1257441 0.6931115 0.7095898 -0.1268025 0.6933076 0.7095864 -0.1257444 0.6823755 0.7199188 -0.1268094 0.6825339 0.7199434 -0.1258133 0.6706382 0.7308565 -0.1268585 0.6707677 0.7309102 -0.1258609 0.6575137 0.7426359 -0.1271518 0.6576305 0.742738 -0.1259464 0.6315369 0.7646862 -0.1281259 0.6316114 0.765038 -0.1256336 0.5764156 0.8067772 -0.1298286 0.5759518 0.8077402 -0.1258379 0.4827374 0.8655588 -0.1333143 0.48078 0.8674418 -0.1280441 0.373744 0.9172455 -0.137754 0.3715023 0.9186551 -0.134383 0.3358775 0.9316473 -0.1386346 0.3360249 0.9315654 -0.1388282 0.3817135 0.9144359 -0.1345427 0.3833065 0.9133981 -0.1370404 0.5015771 0.8555163 -0.1284993 0.5024721 0.8545588 -0.1313434 0.6188928 0.7753 -0.1260225 0.6188969 0.7750411 -0.1275854 0.7006179 0.7023657 -0.1257658 0.7004667 0.7023823 -0.1265124 0.7967243 0.6008746 -0.06465417 0.7974047 0.6001868 -0.06262314 0.7871651 0.6133764 -0.0643481 0.7877188 0.6128441 -0.06261742 0.778722 0.6240978 -0.06398516 0.7791332 0.6237207 -0.06264245 0.771579 0.6329317 -0.06374555 0.7719096 0.6326404 -0.06262218 0.7659471 0.6397605 -0.06349599 0.7661678 0.6395725 -0.06272053 0.7620394 0.6444296 -0.06329727 0.7621733 0.6443184 -0.0628156 0.7602283 0.6465813 -0.06313085 0.7602666 0.6465499 -0.06299155 0.7599512 0.6469118 -0.06308078 0.7599502 0.6469126 -0.0630846 0.7605488 0.6462127 -0.06304633 0.7605144 0.646241 -0.0631712 0.7611495 0.6454986 -0.06310987 0.7611417 0.6455051 -0.06313806 0.7605139 0.6462403 -0.06318372 0.7605584 0.6462037 -0.06302165 0.7586808 0.6483858 -0.06323909 0.7587636 0.6483186 -0.06293433 0.7559215 0.6516059 -0.06318664 0.7560042 0.6515399 -0.0628764 0.7521868 0.6559113 -0.06320881 0.7523128 0.6558133 -0.06272405 0.7473959 0.6613615 -0.06324821 0.7475466 0.6612482 -0.06264936 0.7415885 0.6678695 -0.06322103 0.7417355 0.6677637 -0.06261092 0.7347136 0.6754254 -0.06321823 0.7348732 0.6753168 -0.06251949 0.7267724 0.6839649 -0.06319761 0.7269279 0.6838666 -0.06246948 0.7177099 0.6934682 -0.06320178 0.7178641 0.6933797 -0.06241518 0.7075433 0.7038413 -0.06316637 0.7076776 0.7037742 -0.06240522 0.6962147 0.7150487 -0.06317073 0.6963378 0.714999 -0.06237161 0.6837197 0.7270035 -0.06319338 0.6838226 0.7269756 -0.06239515 0.6700445 0.7396202 -0.06326562 0.6701263 0.7396148 -0.06245517 0.6547521 0.7531738 -0.06347382 0.6548151 0.7531952 -0.06256288 0.6245279 0.7783513 -0.06429737 0.6245371 0.7785039 -0.06233102 0.5599024 0.8259398 -0.06582415 0.5594642 0.8264835 -0.06264895 0.4493649 0.890686 -0.06891804 0.447771 0.8917959 -0.06481581 0.3204137 0.9444611 -0.0729953 0.3186514 0.9452553 -0.07038301 0.275662 0.9584011 -0.07401329 0.2757231 0.9583773 -0.07409286 0.3296507 0.9414634 -0.07054895 0.3308932 0.9408819 -0.07246381 0.4709404 0.8797608 -0.06508517 0.4716916 0.8791887 -0.06733834 7.28596e-6 1.08621e-5 -1 -0.8191628 0.5735611 0 -5.04935e-6 7.21151e-6 -1 -0.5735598 0.8191609 -0.002123117 -7.77303e-6 4.48786e-6 -1 -0.6835551 0.729899 0 -0.3579571 0.9336324 -0.01404434 -0.4994447 0.8663153 -0.007266402 -0.6361242 0.7715859 -0.001140058 -3.30615e-6 8.859e-7 -1 -0.9659245 0.2588241 1.85125e-7 6.41087e-5 4.80873e-5 -1 0 0 -1 0 0 -1 -0.8934401 0.4491823 3.2128e-7 -0.8594277 0.5112562 -0.001120448 -0.8178657 0.5753986 -0.003474354 -0.8786461 0.4774733 -4.12501e-4 -0.7565946 0.6538164 -0.009415626 -7.0379e-6 -6.15848e-7 -1 -0.9961933 -0.08717137 0 4.0203e-7 4.59407e-6 -1 -0.9659236 0.2588273 0 2.7027e-5 2.7027e-5 -1 -0.906314 -0.4226049 -2.01514e-7 5.61092e-6 1.20329e-5 -1 -0.9961934 -0.08717083 0 -0.7071068 -0.7071068 -5.05762e-7 -0.9063152 -0.4226024 -3.02269e-7 -0.4226103 -0.9063116 -4.32163e-7 -0.7071035 -0.70711 -3.37176e-7 -0.08717733 -0.9961929 -4.75022e-7 -0.4226103 -0.9063116 -4.32163e-7 0 0 -1 0.2588318 -0.9659224 -2.30294e-7 -2.75037e-5 -1.07898e-5 -1 -0.08717083 -0.9961934 -2.37511e-7 -1.94881e-5 5.03372e-6 -1 0.5735598 -0.8191609 -0.002124249 1.53349e-5 1.02861e-5 -1 0 0 -1 0.2588257 -0.965924 -4.60588e-7 0.4610174 -0.8873912 -4.23141e-7 3.62618e-7 1.57097e-5 -1 0.8191628 -0.5735611 -3.47444e-7 -1.55462e-5 8.97563e-6 -1 0.3580452 -0.9335988 -0.0140413 0.4994924 -0.8662878 -0.007264912 0.6361083 -0.7715991 -0.001141011 0.6835568 -0.7298973 -4.41769e-7 -6.61225e-6 1.77183e-6 -1 0.9659229 -0.2588302 -1.2342e-7 8.43186e-6 1.23052e-5 -1 -3.46226e-5 -1.99894e-5 -1 -1.01748e-5 0 -1 0.8934293 -0.449204 -2.14197e-7 0.7565951 -0.6538159 -0.009415984 0.85942 -0.5112691 -0.001120746 0.8178749 -0.5753856 -0.003473758 0.8786248 -0.4775126 -4.13315e-4 -1.40759e-5 -1.2318e-6 -1 0.9961926 0.08717846 0 8.04126e-7 9.18822e-6 -1 0.9659219 -0.2588334 -2.46843e-7 -7.6313e-6 1.08661e-5 -1 0.9063116 0.4226103 2.01516e-7 1.12219e-5 2.40659e-5 -1 0.9961929 0.08717733 0 0.7071068 0.7071068 3.37175e-7 0.9063116 0.4226103 2.01516e-7 0.4226103 0.9063116 4.32163e-7 0.7071068 0.7071068 3.37175e-7 0.08718383 0.9961922 7.12532e-7 0.4226049 0.906314 6.48246e-7 -2.0535e-6 7.6633e-6 -1 -0.2588334 0.9659219 6.90881e-7 6.32147e-6 1.09489e-5 -1 0.08718383 0.9961922 7.12532e-7 -4.23461e-6 7.3344e-6 -1 0 1.01748e-5 -1 -0.2588273 0.9659236 4.60588e-7 -0.4610435 0.8873775 4.23135e-7 0.5000079 -0.8660209 -4.12951e-7 0.8660209 -0.5000079 -2.38422e-7 0.8660209 -0.5000079 -2.38422e-7 0 -1 -7.15256e-7 0.500001 -0.8660249 -6.19596e-7 -0.5000079 -0.8660209 -6.19426e-7 0 -1 -7.15256e-7 -0.8660249 -0.500001 -2.38419e-7 -0.500001 -0.8660249 -4.12953e-7 -1 0 0 -0.8660249 -0.500001 -2.38419e-7 -0.8660249 0.500001 2.38419e-7 -1 0 0 -0.5000039 0.8660231 6.19428e-7 -0.8660271 0.499997 3.57626e-7 1.84235e-5 1 4.76837e-7 -0.499997 0.8660271 4.12954e-7 0.500005 0.8660225 6.19428e-7 9.21175e-6 1 7.15256e-7 0.8660209 0.5000079 2.38422e-7 0.5000119 0.8660185 4.1295e-7 1 9.21175e-6 0 0.8660209 0.5000079 2.38422e-7 1 9.21175e-6 0 4.84756e-6 -6.92323e-6 1 -0.5735655 0.8191598 9.92437e-7 -2.17782e-6 -1.44387e-5 1 -0.8191617 0.5735602 0.001733958 4.48781e-6 -7.7731e-6 1 -0.9912636 0.1287596 0.02858865 -0.9638732 0.265486 0.0215786 -0.8287232 0.5596379 0.004850685 -0.7850257 0.6194607 0.001773774 -0.7504411 0.6609371 4.89719e-4 -0.7221862 0.6916987 8.37886e-7 1.77181e-6 -6.61226e-6 1 1.23053e-5 8.43202e-6 1 -1.99891e-5 -3.4622e-5 1 0 -1.01748e-5 1 -0.6468331 0.7625834 0.008567869 -0.5510278 0.8344842 0.002117395 -1.23189e-6 -1.4076e-5 1 9.18813e-6 8.04058e-7 1 -1.61608e-5 -3.46582e-5 1 -2.96137e-6 -1.58055e-5 1 7.6633e-6 -2.0535e-6 1 1.09488e-5 6.32132e-6 1 5.03379e-6 -1.94882e-5 1 0.8191615 -0.5735602 0.001732885 7.33446e-6 -4.23452e-6 1 1.01748e-5 0 1 1.08621e-5 7.28596e-6 1 0.5735611 -0.8191629 -4.96221e-7 -4.51136e-6 -2.90334e-5 1 0.7221878 -0.691697 -4.19006e-7 0.9912657 -0.1287446 0.02858918 0.9638319 -0.2656368 0.02157014 0.8287283 -0.5596302 0.004850029 0.7850258 -0.6194605 0.001772642 0.7504425 -0.6609355 4.88517e-4 8.85903e-7 -3.30614e-6 1 -3.57842e-5 -5.56795e-5 1 7.23961e-5 8.85431e-5 1 0 0 1 0.6468285 -0.7625874 0.008566379 0.5510477 -0.8344711 0.002117574 -6.15841e-7 -7.03787e-6 1 4.59405e-6 4.01998e-7 1 0 0 1 -1.4994e-5 -2.1416e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.7387074 -0.6240416 -0.2547226 -0.6197115 -0.6197089 -0.4815793 -0.7945246 -0.6033093 -0.06890881 -0.7035341 -0.6377131 -0.3136272 -0.778633 -0.6102247 -0.1461385 -0.7052521 -0.705229 0.07260531 -0.8124483 -0.5829843 0.007550954 -0.801569 -0.5958375 -0.04964673 -0.7053056 -0.705177 0.07259273 -0.7051595 -0.705322 0.07260131 -0.7051818 -0.7052994 0.07260358 -0.8216068 -0.5064936 0.2615845 -0.7052019 -0.705283 0.07256776 -0.8271797 -0.5482265 0.1233757 -0.8265116 -0.5502337 0.1188335 -0.07465052 0.2527542 0.9646464 -0.8215265 -0.5076963 0.2594973 -0.73123 -0.2983548 0.6134225 0.6196877 0.6197053 0.4816145 0.339798 0.5251448 0.7802309 0.6197094 0.6197136 0.4815759 0.619989 0.6194299 0.481581 0.6197104 0.6197087 0.4815809 0.6197032 0.6197093 0.4815893 -0.6196179 -0.6197966 0.4815868 -0.6197122 -0.6197108 0.4815759 -0.6197023 -0.6197121 0.4815869 -0.6197134 -0.6197116 0.4815733 -0.6196794 -0.619737 0.4815843 -0.7052077 -0.7052734 -0.07260566 -0.7053804 -0.7051011 -0.07260036 0.6195958 0.6198305 -0.4815714 -0.7051072 -0.7053742 -0.07260215 0.6184665 0.6209408 -0.4815929 0.6197166 0.6197055 -0.4815771 0.619714 0.619695 -0.4815937 -0.6197123 -0.6197096 -0.4815772 -0.6197543 -0.6196603 -0.4815866 -0.6197109 -0.6197037 -0.4815867 0.7387023 0.6240407 -0.2547392 0.6197217 0.61971 -0.4815648 0.7945283 0.6033052 -0.06890338 0.6737844 0.6461892 -0.3584051 0.752582 0.6226509 -0.2143039 0.7829821 0.6088777 -0.1273061 0.7053766 0.7051045 0.07260453 0.8122861 0.5832082 0.007726788 0.7964819 0.6013013 -0.06366628 0.8101357 0.5861662 -0.009456396 0.7051823 0.7052993 0.0726009 0.7049877 0.7054951 0.07258766 0.7051477 0.7053336 0.07260394 0.8196477 0.5094644 0.2619613 0.7057363 0.7047312 0.07273453 0.8253659 0.5511476 0.1225051 0.8275144 0.532558 0.1777697 0.08325809 -0.2590639 0.9622651 0.8192451 0.4917417 0.2950041 0.7711008 0.3647998 0.5218474 -0.6196906 -0.6197025 0.4816144 -0.4722305 -0.5790876 0.664572 0.3223226 -0.05476915 0.9450441 0.6197344 0.6196767 0.4815912 0.7052736 0.7052079 -0.07260185 0.7052692 0.7052122 -0.07260197 -0.6199434 -0.6194741 -0.4815829 0.7055078 0.7049736 -0.07260042 -0.8210669 -0.5663665 -0.07126104 -0.619695 -0.6197147 0.481593 -0.6197168 -0.619709 0.4815721 -0.619704 -0.6197143 0.481582 -0.6197122 -0.6197093 0.4815778 -0.6197174 -0.619705 0.4815765 -0.6197103 -0.6197124 0.4815763 -0.7520704 -0.6153441 0.2360972 -0.7538356 -0.6142632 0.2332652 -0.8210843 -0.566322 -0.07141441 -0.8210836 -0.5663232 -0.07141381 -0.8210818 -0.5663263 -0.07140874 -0.8210767 -0.5663343 -0.07140374 -0.821085 -0.56632 -0.0714218 -0.8210828 -0.5663257 -0.07140296 -0.8210959 -0.5662946 -0.07149773 -0.821038 -0.5664271 -0.07111364 -0.8210866 -0.5663169 -0.07142782 -0.8210825 -0.5663259 -0.07140439 -0.8210915 -0.5663074 -0.07144832 -0.4845819 -0.5659903 0.6669598 -0.4762157 -0.5104653 0.7159914 -0.5219398 -0.5790641 0.6263096 -0.5157637 -0.4776006 0.7112562 -0.5643534 -0.5637293 0.6030876 -0.5868332 -0.5196564 0.6209542 -0.5898613 -0.3971396 0.7030958 -0.5950914 -0.5346457 0.6000168 -0.6197026 -0.6197161 0.4815813 -0.6323555 -0.5070496 0.5856853 -0.6197041 -0.6197153 0.4815806 -0.6626598 -0.3508277 0.661666 -0.6326617 -0.5122186 0.5808367 -0.6197137 -0.6197085 0.4815768 -0.6717371 -0.4397253 0.5961634 -0.6197005 -0.619719 0.4815804 -0.6958238 -0.3597305 0.6216295 -0.6684193 -0.4629712 0.5821284 -0.6197165 -0.6197052 0.4815778 -0.6984204 -0.3762621 0.6087988 -0.6197152 -0.6197063 0.4815778 -0.6967871 -0.386961 0.6039445 -0.6197074 -0.6197136 0.4815784 -0.6950967 -0.3736365 0.6141958 -0.6197091 -0.6197124 0.4815778 -0.7007628 -0.3634497 0.6138696 -0.6197071 -0.6197139 0.4815785 -0.6739088 0.04116874 0.7376665 -0.6197119 -0.6197099 0.4815774 -0.6626812 -0.4218119 0.618812 -0.6980016 -0.2779595 0.6599488 -0.61971 -0.6197115 0.4815778 -0.5468207 0.08869236 0.8325388 -0.6197016 -0.6197194 0.4815787 -0.6209869 -0.4639555 0.63176 -0.6030971 -0.08674138 0.7929375 -0.6197125 -0.6197086 0.4815782 -0.5414867 -0.2818041 0.7920724 -0.6197162 -0.6197062 0.4815768 -0.5821555 -0.4936131 0.6460968 -0.6197099 -0.6197114 0.4815781 -0.5784819 -0.3803538 0.7215884 -0.6197023 -0.6197186 0.4815787 -0.5640118 -0.495315 0.6607222 -0.5331764 -0.4137568 0.7379217 -0.6197038 -0.6197171 0.4815786 -0.5495158 -0.4921409 0.6751518 -0.6197086 -0.6197121 0.4815788 -0.5510054 -0.5067992 0.6629838 -0.6197096 -0.6197113 0.4815786 -0.5415037 -0.4818391 0.6889157 -0.6197174 -0.6197044 0.4815775 -0.5335811 -0.4933327 0.6869599 -0.6197052 -0.6197158 0.4815785 -0.5403102 -0.5145834 0.6657844 -0.541395 -0.5025256 0.6740619 -0.6197078 -0.6197134 0.481578 -0.5388962 -0.5245747 0.6590997 -0.6197056 -0.6197153 0.4815785 -0.5283219 -0.5026767 0.6842457 -0.6197091 -0.6197123 0.4815779 -0.535104 -0.5319041 0.6563092 -0.5204527 -0.5090397 0.685571 -0.6197074 -0.6197137 0.4815785 -0.5305956 -0.5387505 0.6543824 -0.61971 -0.6197115 0.4815779 -0.5147708 -0.5165987 0.6842052 -0.6197056 -0.6197153 0.4815785 -0.5232593 -0.5432835 0.6565385 -0.5115334 -0.5251069 0.6801444 -0.6197128 -0.6197081 0.4815785 -0.5209246 -0.5514335 0.6515817 -0.6197091 -0.6197115 0.4815789 -0.5085214 -0.5404024 0.6703516 -0.5152623 -0.5377752 0.66731 -0.6197074 -0.6197132 0.481579 -0.5145546 -0.5555729 0.653125 -0.6197122 -0.619709 0.4815784 -0.4987561 -0.5402166 0.6777967 -0.6197068 -0.6197142 0.4815787 -0.5104256 -0.5596818 0.6528569 -0.6197051 -0.6197156 0.4815788 -0.4971084 -0.5495903 0.6714415 -0.5061752 -0.5509043 0.6635444 -0.6197087 -0.6197121 0.4815787 -0.4969695 -0.5564018 0.6659118 -0.6197091 -0.6197118 0.4815787 -0.6197076 -0.6197131 0.4815787 -0.4972838 -0.5532265 0.6683182 -0.61971 -0.619711 0.4815785 -0.495507 -0.5566173 0.6668207 -0.6197084 -0.6197122 0.481579 -0.6197099 -0.6197109 0.4815788 -0.4954975 -0.5564709 0.6669501 -0.5101739 -0.5632378 0.6499891 -0.6197112 -0.61971 0.4815784 -0.4936718 -0.5552445 0.6693218 -0.6197105 -0.6197105 0.4815785 -0.4927425 -0.5545993 0.6705404 -0.4919241 -0.5545601 0.6711735 -0.4868701 -0.5520837 0.676876 -0.6197074 -0.619714 0.4815777 -0.5064405 -0.566601 0.6499856 -0.6197108 -0.6197114 0.4815771 -0.6197057 -0.6197165 0.4815771 -0.4888356 -0.5539963 0.6738901 -0.4953699 -0.5560929 0.6673601 -0.6197087 -0.6197131 0.4815773 -0.5074843 -0.5755354 0.6412634 -0.6197043 -0.6197165 0.4815788 -0.6197105 -0.6197105 0.4815784 -0.4815469 -0.5589845 0.6750177 -0.5014283 -0.5643392 0.6558132 -0.6197076 -0.6197128 0.4815791 -0.5015468 -0.5830541 0.6391392 -0.619713 -0.6197087 0.4815778 -0.4769335 -0.5708568 0.6683241 -0.4865299 -0.5677562 0.6640343 -0.6197051 -0.6197142 0.4815807 -0.4898965 -0.5894817 0.6422715 -0.6197366 -0.619696 0.4815636 -0.6197052 -0.6197157 0.4815785 -0.6196804 -0.6197327 0.4815886 -0.6197211 -0.6197029 0.4815746 -0.6197062 -0.6197145 0.4815789 -0.4587827 -0.5722261 0.6797615 -0.001966238 -0.9533605 0.3018277 -0.3811986 -0.8336141 0.3997189 -0.476049 -0.5862435 0.655512 -0.076846 -0.9568608 0.2802 -0.2512879 -0.9326134 0.2590111 -0.07416141 -0.9629758 0.2591869 -0.4019589 -0.8841874 0.2379952 -0.2929143 -0.9305198 0.2198502 -0.530487 -0.8245416 0.1967604 -0.6156953 -0.7582212 0.2145229 -0.5140689 -0.8298768 0.2168813 -0.6207828 -0.7682885 0.1560815 -0.6369988 -0.7403379 0.2147845 -0.6210449 -0.7579318 0.199606 -0.6396351 -0.7406157 0.2058041 -0.6409737 -0.7373686 0.2131676 -0.6393432 -0.7401325 0.2084327 -0.6405569 -0.737657 0.2134221 -0.6408294 -0.7377998 0.2121063 -0.6422724 -0.7357853 0.2147232 -0.6408225 -0.7377854 0.2121776 -0.6442247 -0.7353748 0.2102348 -0.6478346 -0.7308325 0.2149283 -0.6449656 -0.7362475 0.2048387 -0.652747 -0.7278575 0.2101066 -0.6583436 -0.7213746 0.2149472 -0.6549853 -0.7292754 0.1978683 -0.667216 -0.7151533 0.208275 -0.6760233 -0.7030987 0.2205556 -0.6712929 -0.7165811 0.1894136 -0.6901447 -0.6956359 0.1994769 -0.6999886 -0.6783624 0.2232495 -0.6923988 -0.6959465 0.1903749 -0.7142397 -0.6645299 0.2196855 -0.7169981 -0.672788 0.182401 -0.7319675 -0.6494047 0.2061482 -0.741875 -0.6311444 0.2264473 -0.7371896 -0.6477229 0.1923712 -0.7597249 -0.6220018 0.1895576 0.6197103 0.6197171 -0.4815703 0.671148 0.6326816 -0.3863602 0.6816642 0.6375072 -0.3590523 0.619708 0.6197118 -0.48158 -0.8210934 -0.5662976 -0.07150405 0.6197145 0.6197246 -0.4815552 0.6197094 0.6197133 -0.4815763 -0.8210839 -0.5663202 -0.07143288 -0.8210833 -0.566325 -0.07140183 -0.8210813 -0.5663325 -0.07136416 -0.8210898 -0.5663041 -0.07149392 -0.8210845 -0.5663208 -0.07142084 -0.8210816 -0.5663291 -0.07138758 0.6197078 0.6197127 -0.4815793 -0.08541107 0.3011571 -0.9497417 0.6196997 0.6197264 -0.4815719 0.6197219 0.61969 -0.4815903 0.6197097 0.6197093 -0.4815811 0.6196926 0.6197348 -0.4815701 0.6197269 0.6196867 -0.4815879 0.6197016 0.6197191 -0.4815789 0.6197139 0.6197053 -0.4815809 0.6196938 0.6197243 -0.4815821 0.6197174 0.6197065 -0.4815747 -0.8210791 -0.5663319 -0.07139468 -0.6095157 -0.04761928 -0.7913426 0.619709 0.619712 -0.4815783 -0.06760483 0.2077803 -0.9758365 0.6197153 0.6197035 -0.4815813 0.6197084 0.6197123 -0.4815788 0.6197146 0.6197049 -0.4815804 0.6197006 0.619721 -0.4815777 0.6197147 0.6197054 -0.4815796 0.619709 0.6197114 -0.4815792 -0.5209395 -0.09032827 -0.8488009 0.6197078 0.619713 -0.4815785 -0.05897635 0.1007362 -0.9931637 0.6197081 0.6197127 -0.4815787 0.6197108 0.6197096 -0.4815793 0.6197064 0.6197144 -0.4815788 0.6197027 0.6197181 -0.4815786 -0.4509125 -0.1620368 -0.8777368 0.6197081 0.6197129 -0.4815785 -0.03105449 0.006972193 -0.9994934 0.6197096 0.6197112 -0.4815787 0.6197073 0.6197136 -0.4815787 -0.427677 -0.2877385 -0.8569125 0.6197098 0.619711 -0.4815787 0.007545828 -0.0648359 -0.9978675 0.6197093 0.6197115 -0.4815787 0.6197071 0.6197138 -0.4815787 -0.3792691 -0.3906204 -0.8387912 0.6197093 0.6197115 -0.4815788 -0.01890879 -0.1834726 -0.9828429 0.6197088 0.619712 -0.4815788 -0.2513073 -0.3983548 -0.8821328 0.6197044 0.6197168 -0.4815781 -0.06296277 -0.2966693 -0.9529024 0.6197105 0.6197103 -0.4815787 0.6197114 0.6197101 -0.4815779 0.02394199 -0.2461309 -0.9689409 0.6197084 0.6197134 -0.4815775 -0.1080997 -0.3502997 -0.9303787 0.6197112 0.6197085 -0.48158 -0.100773 -0.4136551 -0.9048394 0.6197062 0.6197146 -0.4815785 0.6197108 0.6197084 -0.4815807 0.01816844 -0.2986904 -0.9541771 0.6197094 0.6197104 -0.48158 -0.001895308 -0.2965316 -0.9550212 0.6197046 0.6197155 -0.4815797 0.01765578 -0.3027766 -0.952898 0.007878065 -0.3123559 -0.9499325 0.6197081 0.6197138 -0.4815772 0.01689583 -0.3012327 -0.953401 0.6197121 0.6197087 -0.4815788 0.619706 0.619716 -0.4815772 -0.07648974 -0.4221625 -0.9032874 0.6197123 0.6197088 -0.4815782 0.06639397 -0.3137576 -0.947179 0.619706 0.6197161 -0.4815772 0.01321065 -0.3147458 -0.949084 0.6197065 0.6197134 -0.4815798 -0.3200859 -0.757766 -0.5686263 0.619706 0.6197139 -0.4815797 0.6197343 0.619682 -0.4815847 0.3194817 -0.4670717 -0.824485 0.619713 0.6197085 -0.4815779 0.08196878 -0.3403467 -0.9367204 0.6196473 0.619785 -0.4815639 0.6306361 -0.4204817 -0.6522986 0.30904 -0.5796847 -0.7539628 0.6197411 0.6196783 -0.4815804 0.790503 -0.3414778 -0.5084269 0.6570889 -0.540678 -0.5252634 0.6197612 0.6196562 -0.4815831 0.864959 -0.3382966 -0.3706768 0.8002881 0.3567849 -0.4819164 0.865204 -0.2872028 -0.4110191 0.9113604 -0.1847454 -0.3678198 0.8366781 -0.4811991 -0.2615665 0.9085432 -0.1894722 -0.3723565 0.6865089 0.6250435 -0.3715187 0.6913222 0.6243497 -0.363677 0.6813444 0.6303987 -0.3719776 0.6934849 0.6281747 -0.3528103 0.6763498 0.6350926 -0.3731063 0.6858506 0.6317061 -0.3613258 0.6844394 0.6350772 -0.3580777 0.6779214 0.6400325 -0.3616365 0.6817009 0.6376695 -0.3586944 0.6774692 0.641579 -0.3597388 0.6717961 0.6375529 -0.3771157 0.6778272 0.640901 -0.3602722 0.6774492 0.641577 -0.3597798 0.6778425 0.6414678 -0.3592334 0.6781513 0.6419033 -0.3578704 0.6776869 0.6414771 -0.3595103 0.6730422 0.6417485 -0.367659 0.6760866 0.6407231 -0.363842 0.6773468 0.6414229 -0.360247 0.6770957 0.6421934 -0.3593452 0.6702327 0.6444093 -0.368137 0.6746867 0.6426808 -0.3629867 0.6759188 0.6449003 -0.3567036 0.6666511 0.6476317 -0.3689845 0.6718533 0.645542 -0.3631651 0.672549 0.6487581 -0.3560769 0.6655402 0.6529478 -0.361546 0.6698365 0.6509227 -0.3572378 0.660219 0.6556136 -0.3664449 0.6642495 0.6516128 -0.3662968 0.6652609 0.6574426 -0.353832 0.6568885 0.6596545 -0.365176 0.6623604 0.6613201 -0.352043 0.653567 0.6634821 -0.3642001 0.6586705 0.6651837 -0.3516873 0.6504061 0.6671077 -0.3632343 0.6546461 0.6694186 -0.3511654 0.6480339 0.6716712 -0.35904 0.6500051 0.6735026 -0.3519768 0.6450606 0.6747452 -0.3586304 0.640584 0.6761329 -0.3640006 0.645389 0.6792812 -0.3493564 0.6357337 0.6926912 -0.3406197 0.625034 0.6883933 -0.3680317 0.6357755 0.6917714 -0.3424063 0.6036015 0.7438415 -0.2869936 0.6020139 0.7074683 -0.3702269 0.6122226 0.7187726 -0.3294685 0.5655662 0.7646918 -0.3088384 0.5727985 0.7279025 -0.3769083 0.5446667 0.7954046 -0.2658381 0.5362745 0.7683776 -0.349293 0.5440831 0.7487375 -0.3786367 0.5205134 0.7875923 -0.3297942 0.5377987 0.7560549 -0.3730329 0.543753 0.7540386 -0.3684544 0.5374001 0.7565568 -0.3725895 0.5579811 0.7460985 -0.3633102 0.571777 0.7161408 -0.4002668 0.5819599 0.7242921 -0.3697617 0.6119986 0.6672661 -0.4245159 0.6185728 0.7024435 -0.352052 0.5954396 0.7083348 -0.3790956 0.6311498 0.6574307 -0.4116246 0.6547994 0.6680585 -0.3534625 0.6302067 0.6837635 -0.3678413 0.6755756 0.6542619 -0.3399106 0.6506438 0.6510695 -0.3908594 0.8185411 0.5725252 0.04695981 0.8210858 0.5663197 0.07141613 0.8210863 0.5663189 0.071415 0.8177247 0.5739756 0.04334318 0.8228009 0.5613772 0.08862406 0.8246211 0.5564135 0.1020008 0.7996082 0.5962081 0.07184934 0.7932776 0.6051489 0.06712311 0.7919226 0.6084735 0.05117231 0.7898493 0.60465 0.1026479 0.7969791 0.6024196 0.04375952 0.8297248 0.5533438 0.07326322 0.8329309 0.5432728 0.1052652 0.830726 0.5521119 0.0711807 0.5819725 -0.8131214 -0.01189821 0.5443261 -0.838764 0.01356786 0.8112154 0.5798496 0.0755254 0.8103944 0.5820462 0.06695622 0.8145042 0.5759413 0.06981867 0.8310319 0.5532044 0.05788785 0.8235831 0.5545974 0.1188803 0.7985839 0.5979135 0.06901526 0.8010126 0.5894406 0.1045876 0.7987428 0.5977278 0.0687837 0.8100392 0.5779486 0.09905546 0.7931634 0.6046989 0.07232648 0.7948018 0.5988163 0.0985344 0.7999808 0.5890215 0.1143874 0.7878595 0.6115738 0.07249176 0.7898634 0.6028777 0.1124925 0.7893594 0.6097284 0.07171446 0.7830965 0.6176534 0.07255393 0.7844703 0.6119473 0.1006321 0.785027 0.6152942 0.07173269 0.7903391 0.6033939 0.1062076 0.7790644 0.622736 0.0725153 0.7802744 0.6173908 0.1000025 0.7811592 0.6201872 0.07182085 0.7830598 0.6121015 0.1102231 0.7759358 0.626641 0.07241898 0.7771459 0.6206844 0.1039003 0.7779339 0.6242124 0.07195538 0.7777385 0.6193458 0.1073945 0.7741136 0.6289072 0.07227611 0.7752689 0.6229336 0.1044604 0.7754517 0.6272752 0.07211428 0.7734154 0.6297679 0.07225674 0.7745021 0.6241765 0.1027143 0.7738642 0.6292296 0.07214081 0.7751834 0.6229432 0.1050353 0.7734952 0.6296768 0.07219505 0.7745846 0.6241003 0.1025547 0.7733436 0.6298595 0.07222694 0.7743015 0.6286896 0.07215601 0.7753579 0.623564 0.09994024 0.7736406 0.6294904 0.07226347 0.7749537 0.6241899 0.09916633 0.7750279 0.6277902 0.0721879 0.7760292 0.623162 0.09719979 0.7744798 0.6284595 0.07224959 0.7752705 0.6274892 0.07220011 0.7764309 0.6218025 0.1025509 0.7750793 0.6277235 0.07221692 0.7756127 0.6228476 0.1023999 0.7751175 0.6276755 0.07222551 0.7763034 0.6217389 0.103894 0.7752885 0.6274658 0.07221037 0.7762466 0.6218461 0.1036754 0.7745615 0.6283599 0.0722385 0.7757391 0.6223374 0.1045228 0.7750596 0.6277505 0.07219368 0.7734535 0.6297156 0.07230508 0.774518 0.6243059 0.1018049 0.773496 0.629667 0.07227367 0.7744654 0.6284842 0.07218718 0.7756478 0.6223376 0.1051973 0.7716717 0.6318939 0.07233875 0.7726774 0.6264907 0.1023679 0.7719416 0.6315866 0.07214409 0.7733745 0.625007 0.1061046 0.7694026 0.6346508 0.07237464 0.770333 0.6292198 0.1032924 0.7696999 0.6343138 0.07216858 0.7666726 0.6379401 0.07242727 0.7674509 0.6331222 0.1008723 0.7670397 0.6375256 0.0721867 0.7697792 0.629221 0.107335 0.7635139 0.6417087 0.07250154 0.7642495 0.6353123 0.1109105 0.7640233 0.641137 0.07219266 0.7599983 0.6458604 0.07257324 0.7605236 0.6412279 0.102131 0.7606719 0.6451087 0.07220166 0.7649058 0.6355637 0.1047765 0.756136 0.6503689 0.07265502 0.7565013 0.6460531 0.1015935 0.7570798 0.6493215 0.07219356 0.758683 0.6418997 0.1111979 0.7518526 0.6558535 0.06762886 0.7521263 0.6505084 0.1055688 0.7493177 0.6583356 0.07153499 0.7474946 0.6604066 0.0715183 0.7475343 0.6565587 0.1006134 0.7509955 0.6507463 0.1119603 0.7380303 0.6706786 0.07417172 0.7380089 0.6702051 0.07853573 0.7419244 0.6614073 0.1099484 0.7227373 0.6872243 0.07330417 0.7223248 0.6860668 0.08694493 0.7229405 0.6870379 0.07304829 0.736511 0.6725726 0.0720945 0.7311684 0.6725486 0.1143297 0.7071138 0.7032228 0.07394415 0.7054205 0.7013605 0.1023495 0.7092031 0.7013169 0.0720117 0.7195238 0.6865925 0.1042893 0.6918189 0.7182584 0.07410407 0.6897799 0.7172247 0.09895694 0.6956067 0.7148531 0.07152861 0.70647 0.7011563 0.09633284 0.6902165 0.7152444 0.1096663 0.6771824 0.7320872 0.07397472 0.6734715 0.7312463 0.1082359 0.6823703 0.7275128 0.07138663 0.6634209 0.7446098 0.07368123 0.6601611 0.7445312 0.09930074 0.6696603 0.7392244 0.07143241 0.6732981 0.7313045 0.1089191 0.6506934 0.755792 0.07332563 0.6474469 0.7561072 0.09546995 0.6576444 0.7499204 0.07157605 0.6526821 0.7478446 0.121386 0.6380604 0.766503 0.07315737 0.628772 0.7673973 0.1254875 0.6463776 0.7596423 0.07169091 0.6167129 0.7838689 0.07221245 0.6125308 0.7849695 0.09289169 0.6139815 0.7858766 0.0736528 0.6343572 0.7697202 0.07156652 0.6327821 0.7659805 0.1134048 0.5752079 0.8145712 0.07489752 0.5756599 0.8144061 0.07320064 0.5837962 0.80874 0.07156419 0.5767983 0.799853 0.1659484 0.5135245 0.854788 0.07503467 0.4729716 0.8635199 0.1750174 0.5442028 0.8361225 0.06886601 0.4389317 0.895671 0.07150238 0.4406112 0.895106 0.06816935 0.4428769 0.8938145 0.0703969 0.4965861 0.8652435 0.06896376 0.4764415 0.8627644 0.1692369 0.35412 0.9325513 0.07033705 0.1852076 0.9345891 0.3037126 0.3852773 0.9204859 0.06532466 0.2649545 0.9619321 0.06697505 0.267495 0.9614438 0.06381493 0.3150112 0.9470702 0.06185513 0.2827501 0.9382859 0.1991783 0.1943237 0.9789121 0.06300354 0.06692725 0.9782044 0.1965624 0.2379258 0.9694822 0.05912357 0.1539787 0.9862579 0.05988293 0.1358787 0.9876383 0.07815074 0.1772331 0.9824954 0.05736809 0.1144528 0.9809998 0.1566525 0.1427817 0.9880471 0.05810487 0.1053919 0.9898821 0.09500581 0.1456251 0.987659 0.05764579 0.157274 0.9858216 0.05848717 0.1191459 0.9881333 0.09693694 0.1524288 0.9865215 0.05950415 0.1277168 0.9887752 0.07753729 0.2003217 0.9778937 0.05995965 0.2011128 0.977784 0.05909508 0.1955881 0.9787858 0.0610212 0.274264 0.9597099 0.06112402 0.2268745 0.9665467 0.1196472 0.2614051 0.9631175 0.06381058 0.2662339 0.9638999 0.004057943 0.3743638 0.9251955 0.0621711 0.3841345 0.9221135 0.04633903 0.3412681 0.9375038 0.06799209 0.4779012 0.8760426 0.06449776 0.4447348 0.885186 0.1365898 0.4247819 0.9024765 0.07138919 0.4558751 0.8892961 -0.0364713 0.5718499 0.8174051 0.06954681 0.5780357 0.8147058 0.04614305 0.5750089 0.8152946 0.06825894 0.5020867 0.861786 0.07234507 0.6574738 0.7505127 0.0667752 0.6428724 0.7490887 0.1599412 0.6395336 0.7652142 0.07378244 0.5949378 0.8037261 0.00856316 0.7307465 0.679462 0.06588602 0.7279499 0.6706284 0.1426408 0.6989412 0.7110821 0.07644277 0.7056348 0.7084876 0.01117837 0.7522895 0.6544551 0.07582241 0.7499823 0.6612619 0.01610296 0.7903806 0.601239 0.117517 0.6936861 0.706951 0.1379129 0.6468939 0.7622819 0.0213229 0.7016325 0.704895 0.1040905 0.5409237 0.8213915 0.18088 0.5215867 0.8529461 0.02074426 0.5603315 0.8160788 0.1415774 0.406264 0.907625 0.1056702 -0.04406625 0.845865 0.5315738 0.2902309 0.9565484 0.02794402 0.4008561 0.9138504 0.06474423 0.07866722 0.9797829 0.183948 0.1874228 0.9819891 0.0238763 0.2086455 0.975499 0.06977611 0.1711452 0.9847247 0.0320419 0.1671485 0.9851964 0.0380699 0.2016782 0.9789423 0.03158825 0.3698826 0.9233722 -0.1028148 0.3302556 0.943016 0.04064607 0.2328937 0.972087 0.02841562 0.4676912 0.8800378 -0.08245265 0.4509781 0.8909014 0.05397534 0.4359771 0.8989305 -0.04298996 0.5157684 0.8565037 0.01960545 0.5877287 0.8037107 -0.09286671 0.5898573 0.8061577 0.04667145 0.5289087 0.8479785 0.03446745 0.6320222 0.7741208 -0.0358473 0.6385608 0.768271 0.04472059 0.6070178 0.7935879 0.04180479 0.6498053 0.7586645 0.04670298 0.646353 0.7626045 0.02573239 0.661238 0.7490701 0.04072266 0.6716141 0.7390735 0.0520097 0.6641365 0.7469667 0.03103876 0.6839647 0.7277016 0.05140608 0.6806637 0.731975 0.03015702 0.696933 0.7154898 0.04856735 0.6954066 0.7177374 0.03553372 0.7100398 0.7024331 0.04930585 0.708967 0.7041065 0.0399993 0.7232709 0.6883832 0.05484384 0.7212858 0.6914874 0.03989887 0.7365103 0.6736432 0.06129926 0.7321497 0.6801675 0.0364536 0.7490915 0.659753 0.05989986 0.7416287 0.6698721 0.0354762 0.7560222 0.6531133 0.04328459 0.7502315 0.659569 0.04606062 0.759596 0.648782 0.04578161 0.7568315 0.6525112 0.0378822 0.7625608 0.6456032 0.04120218 0.7657326 0.6415241 0.04582977 0.7626441 0.6455599 0.04032951 0.7682253 0.6386163 0.04471397 0.7670699 0.6403011 0.0402283 0.7703267 0.6361384 0.04386991 0.771882 0.6341828 0.04483711 0.7704818 0.6360689 0.04212117 0.7726599 0.6333889 0.04260653 0.7732823 0.6325798 0.04332774 0.7726683 0.6333869 0.0424835 0.7734486 0.6324259 0.04260122 0.7732917 0.6325764 0.04321056 0.7734175 0.6324195 0.04325491 0.7729293 0.6328055 0.04623091 0.7728741 0.6328858 0.04605591 0.7721611 0.6336974 0.04684871 0.7717713 0.6342835 0.04531532 0.7722077 0.6336712 0.04643434 0.7722212 0.6337921 0.04452067 0.7737209 0.6319892 0.0441116 0.7723281 0.633783 0.04276216 0.7762093 0.628844 0.04532498 0.7743499 0.6315153 0.03963273 0.7789621 0.625739 0.04085195 0.7831668 0.620069 0.04652178 0.7790583 0.6257128 0.03939157 0.7861647 0.617083 0.03396707 0.79703 0.6018614 0.05006134 0.7859623 0.6169415 0.04057735 0.8143548 0.5763279 0.06835573 0.7973195 0.5993546 0.07110381 0.803498 0.5944595 0.03176337 0.8290598 0.5561695 0.05775171 0.8149045 0.5786355 0.03333812 0.5819733 -0.8131209 -0.01190108 0.6886532 -0.7193941 -0.09071391 0.5959361 -0.8020874 -0.03893661 0.8283725 0.5587428 0.04007023 0.4195334 -0.9073925 -0.02511435 0.303151 -0.9516829 0.04897993 0.3031501 -0.9516834 0.04897683 0.4656068 -0.8826828 0.06388568 0.3577703 -0.9272426 0.1105513 0.7046201 0.7068391 -0.06236183 0.4656999 -0.8830219 0.05827373 0.4195389 -0.9073899 -0.02511203 0.5368338 -0.837051 -0.1056164 -0.3498711 -0.9344627 -0.06610369 -0.4001277 -0.9163748 0.01246118 -0.3498928 -0.934454 -0.06610983 -0.5543162 -0.8292537 -0.07121628 -0.5939109 -0.8000004 0.08526045 -0.590098 -0.8072751 0.009557127 0.04658186 -0.997714 -0.04895937 -0.04944878 -0.9984163 0.0268312 0.04660141 -0.9977133 -0.04895299 -0.4001269 -0.9163751 0.01246172 -0.04944169 -0.9984163 0.02684068 0.1608412 -0.9771614 -0.1388731 0.536834 -0.8370512 -0.1056161 -0.2805101 -0.9453133 -0.1664234 0.160838 -0.9771608 -0.138881 -0.5559084 -0.8278986 -0.07449734 -0.5214645 -0.8345463 -0.1777845 -0.2805052 -0.9453158 -0.1664174 -0.8537997 -0.5173108 -0.05844426 -0.8522638 -0.5208318 -0.04879355 -0.8605254 -0.5045388 -0.07026118 -0.8263024 -0.5598396 -0.0616765 -0.8192347 -0.5733129 -0.01291483 -0.8432387 -0.5321196 -0.07613968 -0.8273685 -0.5602598 0.03962886 -0.8287473 -0.5584571 0.0361045 -0.8317897 -0.5543861 0.02796244 -0.8385593 -0.5447598 0.007429778 -0.8450261 -0.534489 -0.01588565 -0.7982525 -0.5990231 -0.062963 -0.7928869 -0.6092129 -0.01378494 -0.8160441 -0.5704309 -0.09316962 -0.7990707 -0.5998308 0.04110085 -0.7710268 -0.6323075 -0.075531 -0.7658283 -0.6430417 -0.002077281 -0.7751735 -0.625883 -0.08588731 -0.7690532 -0.6379327 0.03998768 -0.74338 -0.6652007 -0.0699594 -0.739416 -0.6728503 0.02316218 -0.7167743 -0.6941782 -0.06596529 -0.7171952 -0.6968649 -0.003207623 -0.7355338 -0.6720165 -0.08592844 -0.738292 -0.6739035 0.02790939 -0.6909087 -0.7194885 -0.07057988 -0.6943786 -0.7196016 0.003459811 -0.6979061 -0.7112702 -0.08379566 -0.7039414 -0.7091093 0.04038184 -0.6675999 -0.7403973 -0.0782448 -0.6752765 -0.7374081 0.01520311 -0.6664181 -0.7418076 -0.07489013 -0.6503179 -0.7564507 -0.06977754 -0.6585642 -0.75252 0.002616584 -0.6725008 -0.7394187 0.03166538 -0.6357986 -0.768644 -0.07033216 -0.6477451 -0.7616044 0.01962339 -0.641989 -0.7627847 -0.07752251 -0.6243512 -0.7777746 -0.07247233 -0.6366377 -0.7711408 0.005853772 -0.6254891 -0.7766556 -0.07462877 -0.6473377 -0.7618409 0.02349966 -0.6163651 -0.7841742 -0.07186663 -0.6308717 -0.7757483 0.01468008 -0.610968 -0.7884287 -0.07140296 -0.6252493 -0.7803795 0.008425951 -0.6146104 -0.7853958 -0.0735355 -0.6305628 -0.7759285 0.01804345 -0.6076369 -0.7909609 -0.0718221 -0.622654 -0.7824371 0.009703993 -0.6085037 -0.7902041 -0.07280689 -0.6062887 -0.7919806 -0.07197749 -0.6220982 -0.7828258 0.01333099 -0.6063367 -0.7919365 -0.07205957 -0.6066609 -0.7916886 -0.07205468 -0.6218284 -0.7830956 0.009525954 -0.622143 -0.7828425 0.009780943 -0.6064237 -0.7919152 -0.0715599 -0.621614 -0.7832595 0.01003259 -0.6069403 -0.7914928 -0.07185196 -0.5994901 -0.7972809 -0.07039064 -0.6149756 -0.7885115 0.007403254 -0.6027768 -0.7945246 -0.07342237 -0.621081 -0.7835452 0.01775377 -0.583159 -0.8093588 -0.06974226 -0.6020272 -0.7983531 0.01397907 -0.5867837 -0.8062958 -0.07464522 -0.5595278 -0.8106946 -0.1723455 -0.5082148 -0.8226168 -0.2549889 -0.5744191 -0.7975671 -0.1841995 -0.5802246 -0.7943705 -0.1797635 -0.5737635 -0.7963593 -0.1913306 -0.5796806 -0.79486 -0.1793544 -0.5832572 -0.7929088 -0.1763712 -0.5793187 -0.7942411 -0.1832238 -0.587476 -0.7871422 -0.1878277 -0.6052191 -0.7777653 -0.1696791 -0.586916 -0.786553 -0.192 -0.6258738 -0.7623236 -0.1647561 -0.6046655 -0.7676072 -0.2125064 -0.6436744 -0.734588 -0.214625 -0.6883512 -0.7035382 -0.1766541 -0.6466174 -0.7403029 -0.1839497 -0.7328593 -0.6631418 -0.152185 -0.6873342 -0.6948058 -0.2116995 -0.7760751 -0.6147223 -0.1407973 -0.7348842 -0.6419465 -0.2187461 -0.8191406 -0.5540642 -0.1483972 -0.7808356 -0.5893805 -0.2071868 -0.8510758 -0.4934458 -0.1793906 -0.8217512 -0.5425649 -0.1742071 -0.8696546 -0.4669891 -0.1600691 -0.8577719 -0.455561 -0.2380997 -0.8210581 -0.5663627 -0.07139283 -0.8210953 -0.5663042 -0.07142984 -0.8211104 -0.5662797 -0.07145047 -0.8211818 -0.5661314 -0.07180356 -0.8211085 -0.5662729 -0.07152611 -0.7923899 -0.5909503 0.1513141 -0.813683 -0.5740769 0.09140884 -0.8236256 -0.5642873 0.05675268 0.8210791 0.5663343 -0.07137656 0.6197258 0.6197035 0.4815676 0.6197029 0.6197128 0.4815851 0.6197099 0.6197083 0.4815819 0.6197162 0.6197023 0.4815819 0.6197109 0.6197091 0.4815796 0.7461533 0.6020671 0.2842016 0.734099 0.606586 0.3052082 0.8210823 0.566325 -0.07141274 0.8210865 0.5663181 -0.07141911 0.8210784 0.5663334 -0.0713914 0.8210728 0.5663406 -0.07139867 0.8211975 0.566138 -0.07157182 0.8212721 0.5660164 -0.07167559 0.8210529 0.5664016 -0.07114481 0.8210949 0.5662958 -0.07150077 0.8210776 0.5663379 -0.07136559 0.8211477 0.566177 -0.07183265 0.8210778 0.5663361 -0.07137805 0.8210792 0.5663328 -0.07138633 0.8211302 0.5662295 -0.0716204 0.3615596 0.5016734 0.7858743 0.3571586 0.4073626 0.8405317 0.4250733 0.5284305 0.7348971 0.423831 0.3524608 0.8343492 0.5065822 0.5008584 0.7017944 0.5456768 0.4110352 0.7302648 0.6197132 0.6197076 0.4815787 0.54543 0.2215872 0.808335 0.5681036 0.4470738 0.6909294 0.6197166 0.6197047 0.4815782 0.6350082 0.3760446 0.6748001 0.6197096 0.6197109 0.481579 0.6613509 0.1631262 0.7321236 0.6197116 0.6197096 0.4815781 0.6397046 0.4054003 0.653015 0.6197075 0.6197125 0.4815797 0.6951645 0.2530967 0.6728212 0.6197031 0.6197162 0.4815806 0.7135633 0.1778244 0.6776472 0.6956049 0.308843 0.6486524 0.6197125 0.6197076 0.4815797 0.7207946 0.1826291 0.6686569 0.6196991 0.6197208 0.4815798 0.720172 0.165918 0.6736642 0.6197189 0.619702 0.4815787 0.7094137 0.201609 0.6753414 0.6197113 0.6197081 0.4815806 0.7201288 0.162813 0.6744676 0.6197096 0.6197099 0.4815803 0.5919719 -0.2709047 0.7590651 0.6197139 0.619706 0.4815799 0.646788 0.2874976 0.7064066 0.6805605 0.05467295 0.7306493 0.6197163 0.6197037 0.4815798 0.5977863 0.3074037 0.7403745 0.4538297 -0.2185359 0.8638753 0.6197071 0.6197127 0.48158 0.5312367 0.284909 0.7978813 0.61971 0.6197103 0.4815794 0.6197104 0.6197097 0.4815796 0.5265465 0.3910506 0.7548695 0.4856233 0.1986061 0.8513082 0.6197158 0.6197044 0.4815796 0.4962418 0.3961997 0.7725088 0.4517426 0.2966584 0.8413812 0.6197094 0.6197105 0.4815798 0.4772982 0.3968766 0.7840123 0.619713 0.6197074 0.4815792 0.4601553 0.3658248 0.8089681 0.619708 0.6197119 0.48158 0.4650774 0.403485 0.7879739 0.4564905 0.3898972 0.7997478 0.6197166 0.6197038 0.4815793 0.4562031 0.4170171 0.7861142 0.6197119 0.6197078 0.4815801 0.4491611 0.4070013 0.7953642 0.619709 0.6197109 0.4815797 0.4513928 0.4358511 0.7786388 0.4359083 0.4155827 0.798295 0.6197134 0.6197066 0.4815797 0.4468805 0.4543606 0.7706193 0.6197113 0.6197086 0.4815799 0.4191169 0.4199205 0.8049893 0.6197122 0.619708 0.4815796 0.4367363 0.4668281 0.7689818 0.6197118 0.6197082 0.4815796 0.4055911 0.4269559 0.8082106 0.6197088 0.6197112 0.4815797 0.4106621 0.4663098 0.7835252 0.6197103 0.6197099 0.4815796 0.4066799 0.4457227 0.7974602 0.6197147 0.6197052 0.4815799 0.41803 0.4909455 0.7643451 0.6197142 0.6197057 0.48158 0.3841454 0.4575034 0.8019496 0.4298577 0.4795126 0.7650426 0.6197115 0.6197088 0.4815793 0.4098864 0.5017277 0.7617497 0.619711 0.6197093 0.4815794 0.6197103 0.6197099 0.4815794 0.3807491 0.4783682 0.7913241 0.3928471 0.476128 0.7867485 0.6197092 0.6197105 0.48158 0.3782804 0.4962925 0.7814075 0.6197136 0.6197069 0.4815791 0.6197111 0.6197093 0.4815793 0.3743296 0.4834455 0.7913014 0.6197123 0.6197075 0.48158 0.3703121 0.5028607 0.7810249 0.6197135 0.6197066 0.4815797 0.61971 0.6197095 0.4815803 0.6197116 0.6197079 0.4815801 0.3665649 0.4933064 0.7888466 0.4158433 0.5163323 0.7486491 0.6197128 0.6197075 0.4815793 0.3737421 0.5114058 0.7738094 0.6197086 0.6197105 0.4815809 0.6197153 0.6197053 0.4815791 0.6197085 0.6197111 0.4815803 0.6197123 0.6197077 0.48158 0.3614895 0.5032676 0.7848866 0.3652344 0.5022298 0.7838171 0.4048935 0.5203371 0.7518714 0.6197111 0.6197087 0.48158 0.3584398 0.5041404 0.7857247 0.6197103 0.6197093 0.4815804 0.6197183 0.6197035 0.4815775 0.6197078 0.6197121 0.48158 0.6197136 0.6197067 0.4815794 0.3608596 0.5059497 0.7834508 0.365713 0.507615 0.780116 0.6197113 0.6197085 0.4815801 0.3298226 0.4809855 0.8123238 0.6197189 0.6197063 0.4815729 0.6197128 0.6197084 0.4815782 0.6196981 0.619714 0.4815896 0.6197031 0.619712 0.4815861 0.6197131 0.6197072 0.4815793 0.6197115 0.6197082 0.4815801 0.6197122 0.6197077 0.4815799 0.6197109 0.6197088 0.48158 0.3647528 0.5047202 0.7824404 0.3619965 0.5053809 0.7832934 0.3489018 0.4993605 0.7930365 0.001973986 0.953359 0.3018321 0.2760989 0.8838368 0.3776267 0.3829969 0.5059365 0.7728788 0.318445 0.474826 0.8204469 0.07683867 0.9568587 0.2802094 0.2513012 0.9326121 0.2590025 0.07415139 0.9629779 0.2591812 0.4019856 0.8841761 0.2379918 0.292921 0.9305189 0.2198449 0.5304669 0.8245518 0.1967722 0.6207522 0.7181395 0.3145509 0.4245194 0.8480046 0.3172874 0.624123 0.7322329 0.2725903 0.6192288 0.771879 0.1440779 0.6336193 0.7063881 0.3155033 0.6257424 0.7228705 0.293095 0.6362923 0.7065927 0.3096107 0.6387929 0.7113803 0.2930559 0.6407865 0.7186546 0.2700523 0.6399682 0.7013739 0.3138716 0.6379545 0.7056413 0.3083574 0.6401116 0.7014054 0.3135083 0.640143 0.7014572 0.3133285 0.6403862 0.7020963 0.3113942 0.6405349 0.7008717 0.3138372 0.6402002 0.701476 0.3131697 0.6410761 0.7011373 0.3121343 0.6421324 0.7031728 0.3053099 0.6425163 0.6987993 0.3144078 0.6416597 0.7018035 0.3094264 0.6440194 0.6990897 0.3106647 0.6471232 0.7048434 0.2905642 0.6473337 0.6941862 0.3147454 0.644698 0.6983323 0.3109605 0.6524022 0.699831 0.2908745 0.6530391 0.688036 0.3164591 0.6503042 0.6957099 0.3051102 0.6629105 0.6963146 0.2751289 0.6624554 0.6796424 0.3150224 0.6566844 0.6874415 0.310145 0.6663081 0.6708062 0.325657 0.6699422 0.6853733 0.2853786 0.6759921 0.6652916 0.316894 0.6820112 0.6735747 0.284882 0.6897851 0.6570125 0.3041893 0.6925789 0.6431201 0.3266973 0.6913716 0.6573828 0.2997549 0.6990947 0.631589 0.3352043 0.7145822 0.6427711 0.2760756 0.7130932 0.6200333 0.3271953 0.7412376 0.6211254 0.2545001 -0.6197181 -0.6197003 -0.481582 -0.6161165 -0.2501806 -0.7468668 -0.6197118 -0.6197081 -0.48158 -0.6197105 -0.6197092 -0.4815802 0.4573287 0.8350647 -0.3058062 -0.5257459 -0.3388484 -0.7802391 -0.6196848 -0.6197398 -0.4815739 -0.6306315 0.4204655 -0.6523133 -0.2415749 0.8592986 -0.4508298 -0.309073 0.5796676 -0.7539624 -0.6197029 -0.6197191 -0.4815771 -0.7904911 0.3415122 -0.5084224 -0.6570863 0.5406955 -0.5252486 -0.6198549 -0.6195512 -0.4815975 -0.86496 0.3383228 -0.3706505 -0.8606853 -0.2104579 -0.4636036 -0.8652052 0.2871721 -0.4110378 -0.9111372 0.1852954 -0.3680961 -0.8658632 0.4049833 -0.2937169 -0.7041327 -0.6398975 -0.3077796 -0.6987817 -0.6406354 -0.3182616 -0.6197102 -0.6197094 -0.4815801 -0.7045742 -0.639334 -0.3079402 -0.6197109 -0.6197087 -0.4815802 -0.704844 -0.6387141 -0.3086087 -0.6197101 -0.6197096 -0.4815801 -0.7043511 -0.6392146 -0.3086977 -0.61971 -0.6197094 -0.4815804 -0.7039049 -0.6377562 -0.3127061 -0.6197096 -0.6197099 -0.4815804 -0.7035949 -0.6379942 -0.3129178 -0.6197112 -0.6197097 -0.4815785 -0.7037527 -0.6367835 -0.3150224 -0.6197203 -0.6196989 -0.4815808 -0.6197095 -0.61971 -0.4815806 -0.7030499 -0.6371854 -0.3157778 -0.6197129 -0.619707 -0.4815799 -0.70425 -0.6367109 -0.314056 -0.6197063 -0.6197146 -0.4815786 -0.7038618 -0.6368756 -0.3145918 -0.6197127 -0.6197072 -0.4815799 -0.7037776 -0.6372232 -0.3140757 -0.6197131 -0.6197068 -0.4815799 -0.7044907 -0.6368939 -0.3131437 -0.619715 -0.6197052 -0.4815794 -0.7031447 -0.6374391 -0.3150538 -0.6197158 -0.6197045 -0.4815796 -0.7037141 -0.6371743 -0.3143176 -0.6197091 -0.619711 -0.4815796 -0.7024216 -0.6384023 -0.3147166 -0.6197161 -0.6197031 -0.4815807 -0.6197065 -0.6197128 -0.4815807 -0.7036581 -0.6378734 -0.313022 -0.6197122 -0.6197074 -0.4815803 -0.7012719 -0.6394765 -0.3150992 -0.6197075 -0.6197126 -0.4815796 -0.7028863 -0.6388971 -0.3126685 -0.6197096 -0.6197108 -0.4815792 -0.7002369 -0.6406576 -0.3150018 -0.6197163 -0.6197033 -0.4815803 -0.7017199 -0.6402485 -0.3125238 -0.6197131 -0.6197073 -0.4815792 -0.6992186 -0.6421878 -0.3141468 -0.700371 -0.6419681 -0.3120216 -0.6197106 -0.6197097 -0.4815792 -0.6982617 -0.6439054 -0.3127565 -0.6197122 -0.6197081 -0.4815793 -0.6197125 -0.6197075 -0.4815798 -0.692525 -0.6476273 -0.317786 -0.6197109 -0.6197094 -0.4815793 -0.6197106 -0.6197099 -0.4815792 -0.6983301 -0.6439616 -0.3124878 -0.6197101 -0.6197096 -0.48158 -0.6833044 -0.65391 -0.3248027 -0.6197097 -0.61971 -0.48158 -0.6823063 -0.6426752 -0.3484633 -0.690142 -0.647959 -0.3222625 -0.691822 -0.6523663 -0.3095168 -0.6197115 -0.6197091 -0.481579 -0.6776116 -0.6615477 -0.3212432 -0.6197159 -0.6197046 -0.4815792 -0.6820522 -0.6528343 -0.3295636 -0.6850747 -0.6594143 -0.3095891 -0.619714 -0.6197065 -0.4815793 -0.6705919 -0.6680075 -0.3226028 -0.6197108 -0.6197097 -0.4815791 -0.67682 -0.660523 -0.3249986 -0.6774892 -0.6680118 -0.3078452 -0.6197118 -0.6197081 -0.4815798 -0.6663727 -0.6763723 -0.3137963 -0.6197106 -0.6197094 -0.4815797 -0.6718245 -0.6714733 -0.3126906 -0.6197086 -0.6197124 -0.4815785 -0.6597328 -0.6808356 -0.3181437 -0.6197128 -0.6197071 -0.4815798 -0.6657781 -0.6745514 -0.3189359 -0.6627359 -0.682219 -0.3088012 -0.6197115 -0.6197091 -0.481579 -0.6550043 -0.6863507 -0.316057 -0.6573618 -0.687652 -0.3082375 -0.6197172 -0.6197032 -0.4815791 -0.6512087 -0.6930739 -0.3091531 -0.6197122 -0.6197075 -0.4815803 -0.6445467 -0.6964316 -0.3155037 -0.61971 -0.6197102 -0.4815797 -0.6512292 -0.6920667 -0.3113588 -0.6197035 -0.6197171 -0.481579 -0.6325606 -0.7032042 -0.3246088 -0.6425144 -0.7064622 -0.2967937 -0.6197113 -0.619709 -0.4815793 -0.6085298 -0.7489072 -0.2623543 -0.6197187 -0.6196997 -0.4815818 -0.5935019 -0.7383648 -0.3202701 -0.6197111 -0.6197092 -0.4815793 -0.6184273 -0.7230529 -0.3078021 -0.6197164 -0.6197025 -0.4815812 -0.4705571 -0.8752918 -0.1115362 -0.6197025 -0.6197179 -0.481579 -0.5341632 -0.7809813 -0.3236321 -0.577776 -0.7525759 -0.3159183 -0.6197143 -0.6197057 -0.4815798 -0.5174182 -0.7853713 -0.3398096 -0.4912404 -0.8268746 -0.2737907 -0.6197076 -0.6197132 -0.4815786 -0.4980424 -0.8045088 -0.3236035 -0.6197108 -0.619709 -0.48158 -0.4987002 -0.8036546 -0.3247114 -0.619708 -0.6197128 -0.4815788 -0.5287689 -0.7770249 -0.3415198 -0.6197142 -0.6197062 -0.4815794 -0.5402685 -0.7835801 -0.306777 -0.5287423 -0.777056 -0.3414902 -0.6197172 -0.6196984 -0.4815852 -0.6011658 -0.7008771 -0.3838892 -0.6197118 -0.6197084 -0.4815796 -0.6197037 -0.6197192 -0.4815761 -0.6169719 -0.7224095 -0.312202 -0.5717539 -0.7542398 -0.322831 -0.6197169 -0.619704 -0.4815785 -0.6498852 -0.7028065 -0.2893306 -0.6280347 -0.6937116 -0.3526143 -0.6197226 -0.6197347 -0.4815317 -0.6778755 -0.6690204 -0.3047892 -0.6197101 -0.6197092 -0.4815807 -0.6633 -0.6665493 -0.3402134 -0.6197115 -0.6197004 -0.4815902 -0.6976125 -0.6396824 -0.3227124 -0.7003232 -0.6413434 -0.3134104 0.8211038 0.5662676 -0.07162278 0.8210828 0.5663225 -0.07142692 0.8210703 0.5663669 -0.07121932 0.8210816 0.5663282 -0.07139629 0.8210786 0.566337 -0.0713613 0.8210834 0.5663236 -0.07141143 -0.02070653 -0.4450168 -0.8952829 0.8210516 0.5663886 -0.07126158 -0.3725124 -0.5538158 -0.7446628 -0.2136061 -0.5334391 -0.8184223 -0.4373394 -0.5495015 -0.7118865 -0.07863026 -0.3973691 -0.914284 -0.465212 -0.5325239 -0.707104 -0.1205705 -0.3366453 -0.9338805 -0.4752129 -0.5057396 -0.7200002 -0.1976078 -0.3087564 -0.9303874 -0.4758989 -0.4724051 -0.7418583 -0.2686865 -0.2930713 -0.9175602 -0.4659056 -0.4295177 -0.7735933 -0.3475331 -0.3071346 -0.8859396 -0.4380656 -0.3653832 -0.8213365 -0.4853476 -0.4056659 -0.7745146 -0.4246884 -0.3468887 -0.8362463 -0.3958969 -0.2586155 -0.8811263 -0.4881099 -0.3784413 -0.7864673 -0.4739899 -0.3770726 -0.7957071 -0.4367259 -0.2869399 -0.8526054 -0.4952668 -0.371921 -0.7851023 -0.483508 -0.3650047 -0.7956078 -0.4817703 -0.3439146 -0.8059902 -0.497666 -0.367241 -0.7857879 -0.4861088 -0.3519077 -0.7999119 -0.4976394 -0.3651296 -0.7867881 -0.4953181 -0.3601712 -0.7905293 -0.4951151 -0.3597792 -0.790835 -0.4990735 -0.3642497 -0.7862874 -0.4979465 -0.3650727 -0.78662 -0.4813593 -0.3253042 -0.813923 -0.3482294 -0.09480255 -0.9326033 -0.5167847 -0.3572131 -0.7780311 -0.4935182 -0.3434228 -0.7990623 -0.4644234 -0.2250914 -0.8565307 -0.8205294 -0.5697114 0.0464822 -0.8210808 -0.5663269 0.0714159 -0.8210838 -0.5663232 0.07141077 -0.8158578 -0.5774822 0.02984142 -0.822788 -0.5614098 0.08853697 -0.7933552 -0.6044921 0.07194966 -0.7936669 -0.6035529 0.07626831 -0.7893282 -0.6022154 0.1195725 -0.7912306 -0.6069824 0.0743407 -0.7873986 -0.6156948 0.03038847 -0.7885112 -0.6107775 0.07211786 -0.7908256 -0.6000377 0.1206211 -0.7886161 -0.6106532 0.07202327 -0.5819673 0.8131252 -0.01189815 -0.5256178 0.850328 0.02584767 -0.7907807 -0.6078594 0.07192218 -0.7932462 -0.5968237 0.1206728 -0.791656 -0.5997275 0.1166525 -0.7927165 -0.6053403 0.07185947 -0.7951961 -0.5948467 0.1175605 -0.7910841 -0.6074416 0.07211565 -0.7943168 -0.6032426 0.0718258 -0.7969835 -0.5919154 0.1202229 -0.7931331 -0.6047663 0.07209408 -0.7951495 -0.5948432 0.1178936 -0.7956185 -0.6015259 0.07181763 -0.7982152 -0.5910264 0.1163629 -0.7947962 -0.6025831 0.07206028 -0.7967197 -0.6000704 0.07178544 -0.7995055 -0.5886313 0.1195999 -0.7960897 -0.6008787 0.07201367 -0.7979038 -0.5908696 0.1192585 -0.7975528 -0.5989577 0.07182663 -0.800393 -0.5873699 0.119865 -0.7970457 -0.5996176 0.07195043 -0.7997114 -0.588595 0.1183961 -0.797994 -0.5983659 0.07186031 -0.8008403 -0.5868413 0.119466 -0.7976801 -0.5987792 0.07190185 -0.8007134 -0.5871152 0.1189702 -0.7980617 -0.5982737 0.071877 -0.8009104 -0.5867476 0.119456 -0.7980265 -0.5983198 0.07188218 -0.7977921 -0.5986298 0.07190304 -0.8006122 -0.5872105 0.1191792 -0.798039 -0.5983058 0.07186245 -0.8008654 -0.5867547 0.1197231 -0.797196 -0.5994198 0.0719338 -0.8000332 -0.5877171 0.1205631 -0.797694 -0.5987677 0.0718435 -0.7963035 -0.6006006 0.07197064 -0.7990362 -0.589343 0.1192312 -0.7970165 -0.599671 0.07183057 -0.8001209 -0.5877566 0.1197858 -0.7951254 -0.6021544 0.07201135 -0.79778 -0.5910849 0.1190195 -0.7960321 -0.6009777 0.07182294 -0.7985602 -0.5895594 0.1213316 -0.7936921 -0.6040369 0.07205778 -0.7963094 -0.5927934 0.120363 -0.7947674 -0.6026489 0.07182669 -0.7920101 -0.606232 0.07213079 -0.7944657 -0.595612 0.1186189 -0.793062 -0.6049007 0.07174795 -0.7960724 -0.5928228 0.1217771 -0.7900921 -0.6087267 0.07215553 -0.79255 -0.5973865 0.1224488 -0.7909011 -0.6077229 0.07175314 -0.7879566 -0.6114924 0.07212179 -0.7901825 -0.6012762 0.1186528 -0.7884407 -0.6109032 0.07182389 -0.7926602 -0.5973957 0.121688 -0.78522 -0.6149792 0.07231795 -0.7872859 -0.6049782 0.1190897 -0.7857246 -0.614377 0.07195663 -0.7883706 -0.6026806 0.1234823 -0.7817716 -0.61934 0.07246577 -0.7836539 -0.6093944 0.1205202 -0.7827762 -0.6181364 0.07189637 -0.7780122 -0.6240527 0.07249325 -0.7796162 -0.6151195 0.1175868 -0.7792291 -0.6226167 0.07176691 -0.7830813 -0.6094895 0.1237186 -0.7739691 -0.6290575 0.07251548 -0.7753582 -0.6201156 0.1194833 -0.7750521 -0.627799 0.07185357 -0.776822 -0.6171224 0.1253295 -0.7696685 -0.6343089 0.07254308 -0.7707962 -0.6256019 0.120397 -0.7706556 -0.6331777 0.07194447 -0.7651359 -0.6397647 0.07258385 -0.7659753 -0.6320162 0.1176321 -0.7660892 -0.6386863 0.07202219 -0.7695197 -0.6260676 0.1260112 -0.7603858 -0.6454532 0.07213646 -0.7608792 -0.6365599 0.1259136 -0.7605797 -0.6452419 0.07198321 -0.7554735 -0.6511466 0.07258099 -0.7557179 -0.6441704 0.1180458 -0.7611829 -0.6365065 0.1243388 -0.7503907 -0.6569689 0.07283967 -0.749969 -0.6481745 0.1319711 -0.754101 -0.65282 0.07181715 -0.7399044 -0.668436 0.07572823 -0.7391985 -0.6632755 0.1168378 -0.7408444 -0.6675158 0.07464909 -0.7475005 -0.6603673 0.07181996 -0.751811 -0.647957 0.1221963 -0.7232378 -0.6864243 0.07582235 -0.7222797 -0.6839734 0.1024333 -0.7274696 -0.6822605 0.07286083 -0.7341499 -0.6751271 0.07229995 -0.7419318 -0.6635414 0.09617763 -0.7292672 -0.6717787 0.1299335 -0.7060704 -0.7041094 0.07546216 -0.7035529 -0.7014782 0.1137617 -0.7147616 -0.6959941 0.06861573 -0.7166561 -0.6860886 0.1252458 -0.6887924 -0.7210728 0.07496011 -0.6857358 -0.7196787 0.1087616 -0.6958754 -0.7147777 0.06964427 -0.7035693 -0.7014734 0.1136898 -0.6872824 -0.7154257 0.1257335 -0.6718355 -0.7369404 0.07453781 -0.6677867 -0.7363174 0.1090764 -0.678279 -0.7314276 0.07036542 -0.6701632 -0.7306653 0.1304209 -0.655716 -0.7513586 0.07414019 -0.650201 -0.751406 0.1123727 -0.6621837 -0.7459897 0.07079517 -0.6521269 -0.7466086 0.1315535 -0.6402574 -0.7645945 0.07392996 -0.6330472 -0.7653507 0.1161444 -0.647753 -0.7585264 0.07109069 -0.6336712 -0.762683 0.1295196 -0.6157859 -0.7843238 0.07512593 -0.6049922 -0.78629 0.1254292 -0.6334566 -0.7705339 0.07078403 -0.566596 -0.8205963 0.07477033 -0.5587158 -0.8230752 0.1019016 -0.6065735 -0.7919627 0.06973928 -0.599919 -0.7882913 0.1367257 -0.4923037 -0.8673725 0.07281404 -0.4887173 -0.868629 0.08148103 -0.4948918 -0.865988 0.07174313 -0.5593252 -0.8259916 0.06995028 -0.4997906 -0.8450562 0.1899721 -0.3917639 -0.9170869 0.0739783 -0.2929744 -0.9280853 0.2298339 -0.4219115 -0.9042308 0.06600958 -0.2782101 -0.9579832 0.06976568 -0.2624503 -0.960757 0.08980947 -0.3312569 -0.9416321 0.05998373 -0.3577162 -0.9206199 0.1565195 -0.1962466 -0.9785841 0.0621311 0.02387863 -0.9574029 0.2877662 -0.2261264 -0.9724978 0.05580985 -0.1569666 -0.9859822 0.05657434 -0.1136226 -0.9884656 0.1001288 -0.1547659 -0.9862903 0.05726158 -0.1782685 -0.9764114 0.1218242 -0.142624 -0.9880676 0.05814594 -0.07826274 -0.9895239 0.1213158 -0.1555252 -0.9860014 0.06010949 -0.106831 -0.9882782 0.1090573 -0.1531816 -0.9863311 0.06071573 -0.1035339 -0.9893506 0.1023036 -0.2007327 -0.9778583 0.05915606 -0.2014868 -0.9777528 0.05833202 -0.2751279 -0.9595618 0.05954682 -0.2158661 -0.967405 0.1323989 -0.2174653 -0.9737854 0.06671452 -0.2028188 -0.9775398 0.05727595 -0.3737735 -0.9254253 0.0623008 -0.3899836 -0.92012 0.03594511 -0.3232908 -0.9436041 0.07137447 -0.4769705 -0.8764941 0.06524831 -0.4379718 -0.8865438 0.1490665 -0.4412174 -0.8943461 0.07397556 -0.4062962 -0.9135439 0.01900303 -0.5718236 -0.8176085 0.06733554 -0.5768057 -0.8154361 0.04857027 -0.5462536 -0.8341594 0.07606095 -0.6565827 -0.7510931 0.06897997 -0.6430016 -0.7499105 0.1555095 -0.6401684 -0.7643666 0.07699364 -0.5728412 -0.8177551 0.05594182 -0.7300422 -0.67976 0.0704602 -0.7266991 -0.6703335 0.1502048 -0.7217572 -0.6879141 0.07642382 -0.7004941 -0.712155 0.04629641 -0.7221542 -0.6915771 0.01463925 -0.7855479 -0.616699 0.05095839 -0.6504178 -0.7595765 -5.36757e-4 -0.6976593 -0.7102006 0.09426891 -0.520367 -0.8403251 0.1518944 -0.4694135 -0.8828417 0.01554048 -0.5735914 -0.8174098 0.05323535 -0.1714667 -0.94739 0.2702805 -0.2580255 -0.9659289 0.02010583 -0.4004377 -0.9158653 0.02898699 -0.2065976 -0.9784078 0.005971014 -0.1900808 -0.97918 0.07124382 -0.183268 -0.9826569 0.0282517 -0.1904173 -0.9815852 0.01523149 -0.2766839 -0.9609571 -0.002743065 -0.3373144 -0.9399946 0.05127507 -0.3054463 -0.9518325 -0.0267874 -0.478992 -0.8765286 -0.04758602 -0.5047082 -0.8620019 0.04714322 -0.4563925 -0.8895522 -0.02007085 -0.5863687 -0.8093413 -0.03374415 -0.614039 -0.7886118 0.03236687 -0.5568333 -0.8302416 0.02521198 -0.6386437 -0.7685902 0.03746318 -0.6255738 -0.7801106 0.009213507 -0.6526015 -0.7569402 0.03395235 -0.6500443 -0.7595984 0.02127486 -0.6662894 -0.7450044 0.03204387 -0.6655095 -0.7459232 0.02637714 -0.6811366 -0.7313252 0.03487825 -0.6803908 -0.7322592 0.02940773 -0.6973424 -0.7154524 0.04291182 -0.6946403 -0.7188402 0.02727043 -0.7152904 -0.6970952 0.04917013 -0.7078202 -0.7060177 0.02301317 -0.7275918 -0.6852508 0.03227484 -0.7198613 -0.6935563 0.02791792 -0.7338493 -0.6785696 0.0317592 -0.7308933 -0.6820824 0.02363741 -0.7400636 -0.6718865 0.02956926 -0.7464857 -0.6645486 0.03367996 -0.7410303 -0.6709983 0.02520787 -0.7526478 -0.6576334 0.03224396 -0.7501518 -0.6607959 0.02492469 -0.7585253 -0.6510169 0.02857005 -0.7639284 -0.6445143 0.03185415 -0.7585676 -0.6509813 0.02825891 -0.7682396 -0.6393718 0.03180599 -0.7656806 -0.6427097 0.0256381 -0.7721367 -0.634809 0.02868276 -0.7763774 -0.6294506 0.03209537 -0.7722532 -0.6347075 0.02777284 -0.7796391 -0.6254547 0.03113436 -0.7776817 -0.628092 0.02668029 -0.7822576 -0.6222587 0.0294454 -0.7850422 -0.6186391 0.03153276 -0.7824711 -0.6220638 0.02784752 -0.7872706 -0.6158525 0.03050833 -0.7863242 -0.6171826 0.0279271 -0.7892745 -0.613301 0.03012615 -0.7909653 -0.6110818 0.03087151 -0.7894422 -0.6131525 0.0287218 -0.7919007 -0.6099832 0.02852869 -0.7930426 -0.6084071 0.03040069 -0.791811 -0.6100313 0.02995502 -0.7936871 -0.6075644 0.03043705 -0.7932052 -0.6082413 0.02946531 -0.793963 -0.6072253 0.03000086 -0.7939714 -0.6072051 0.03019022 -0.7939506 -0.6072329 0.03017652 -0.7936283 -0.6076593 0.03007185 -0.7938957 -0.6072826 0.03061914 -0.7930899 -0.6083325 0.03065824 -0.7920837 -0.6096846 0.02979755 -0.7930573 -0.6083586 0.03098315 -0.7908978 -0.6112042 0.03016686 -0.7914896 -0.6103589 0.0317226 -0.789351 -0.6131875 0.03043162 -0.7872884 -0.6158899 0.02926814 -0.7891079 -0.6134095 0.0322082 -0.7849987 -0.6187899 0.02959913 -0.7860406 -0.6173196 0.03251022 -0.5819671 0.8131253 -0.01189738 -0.6886491 0.7193984 -0.09071093 -0.6185157 0.7841111 -0.05106943 -0.419534 0.9073922 -0.02511036 -0.3031701 0.9516775 0.04897123 -0.3031696 0.9516776 0.04896932 -0.4656744 0.8826476 0.06387966 -0.3554778 0.9280151 0.1114608 -0.4390127 0.8956186 0.07166057 -0.4195287 0.9073947 -0.02511262 -0.536825 0.8370568 -0.1056169 0.3498494 0.9344706 -0.06610673 0.3759239 0.9262846 -0.02603918 0.349855 0.9344685 -0.06610828 0.5462074 0.8346291 -0.07107591 0.5949313 0.7949731 0.1186362 0.5768392 0.8163123 -0.02984815 -0.04658055 0.9977141 -0.04895806 0.04944872 0.9984162 0.02683132 -0.04658633 0.9977139 -0.04895615 0.3498893 0.935334 0.0522266 0.4001133 0.916381 0.01246368 0.04944914 0.9984161 0.02683079 -0.160827 0.9771634 -0.1388754 -0.536825 0.8370567 -0.1056168 0.280471 0.9453256 -0.1664197 -0.160826 0.9771632 -0.1388776 0.5481911 0.8331732 -0.0728628 0.5332339 0.8376311 -0.1184726 0.2320895 0.9668256 -0.1066901 0.8817756 0.4661983 -0.07163113 0.8756539 0.481489 -0.03739756 0.8804852 0.4689568 -0.0694645 0.8602535 0.505277 -0.06825762 0.8569701 0.5131601 -0.04763257 0.8659257 0.5001387 -0.005826294 0.8483895 0.5277562 0.04133719 0.8356804 0.5451507 -0.06669944 0.8254523 0.5644689 -0.00181961 0.8579958 0.5081763 -0.07483339 0.8078346 0.5858458 -0.06471437 0.8076966 0.5861879 -0.06332391 0.8307904 0.5509762 -0.07881993 0.8208981 0.5708885 0.01458561 0.7777959 0.6253241 -0.06327211 0.7784857 0.6231116 -0.07544595 0.7987768 0.5958827 -0.08294177 0.7836634 0.6204352 0.03052437 0.7477966 0.6607921 -0.0644505 0.7476357 0.66167 -0.05686634 0.7631958 0.6405666 -0.08489203 0.7519112 0.6589341 0.02086412 0.7204048 0.690158 -0.06854742 0.7204433 0.6935138 4.01423e-4 0.72845 0.6801649 -0.08207571 0.6970147 0.7133588 -0.07273113 0.6987211 0.7142442 -0.04054695 0.6990941 0.7108815 -0.07690799 0.7220895 0.6916361 -0.01504546 0.6779375 0.7315416 -0.0724405 0.6803052 0.7315759 -0.04451543 0.6934665 0.7204358 0.008746445 0.6626088 0.7456143 -0.07077324 0.6686454 0.7435295 -0.008786141 0.6758834 0.7331637 -0.0751841 0.6500711 0.7565808 -0.07066154 0.6541525 0.7553644 -0.0388469 0.6578047 0.7494165 -0.07528495 0.6685637 0.7436265 -0.006508409 0.639863 0.7651894 -0.07113832 0.6483073 0.7613282 -0.008772432 0.6439362 0.7614392 -0.07454335 0.6316233 0.771947 -0.07176291 0.6374711 0.7696912 -0.03473019 0.6333457 0.7703637 -0.07357418 0.6483109 0.7612915 -0.01131796 0.6250746 0.7772082 -0.07231354 0.6333339 0.7735599 -0.02221238 0.6253654 0.7769404 -0.07267504 0.6200879 0.7812188 -0.07202899 0.6330569 0.7740718 0.007194519 0.6162903 0.784237 -0.07182329 0.6237182 0.7810277 -0.03117084 0.6193552 0.7817518 -0.07254952 0.6312145 0.7751245 -0.0273928 0.6134449 0.7864634 -0.0718376 0.6225969 0.7822256 -0.02227324 0.6150491 0.7851519 -0.0724647 0.6114021 0.7880455 -0.07191514 0.6228508 0.7822803 -0.009709358 0.6121225 0.7874518 -0.07229024 0.6099964 0.7891276 -0.0719859 0.6179679 0.7856018 -0.0307492 0.6102293 0.7889339 -0.07213574 0.6216673 0.7828195 -0.0268945 0.609095 0.7898198 -0.07202744 0.6174055 0.7861005 -0.02926748 0.6091011 0.7898147 -0.07203215 0.6086322 0.7901798 -0.0719915 0.6173388 0.7862262 -0.02722525 0.6085492 0.7902423 -0.07200515 0.6173654 0.7862245 -0.02666485 0.6085855 0.7902138 -0.07201284 0.6083153 0.7904303 -0.07192099 0.6164051 0.7868314 -0.03067779 0.6085485 0.790243 -0.07200545 0.6170753 0.7863289 -0.03008484 0.6063068 0.7919829 -0.07179939 0.6151626 0.7879319 -0.02717143 0.6071032 0.7913349 -0.07221335 0.6021694 0.795124 -0.07190167 0.6146166 0.7887672 -0.009628832 0.6026682 0.7947153 -0.07224059 0.5959129 0.7997784 -0.07240432 0.6158863 0.7873271 0.0282889 0.5952741 0.8003022 -0.07186788 0.5880525 0.8056729 -0.0713126 0.5969796 0.8015864 -0.03278195 0.612185 0.7904469 -0.02057063 0.5777866 0.8131157 -0.0707497 0.5912509 0.8063371 -0.01558059 0.5844072 0.8081955 -0.07272118 0.5643742 0.8225126 -0.07038962 0.5908743 0.8060042 0.03499823 0.5694588 0.8187664 -0.07306367 0.5114628 0.8230589 -0.246941 0.5727258 0.8113826 -0.1168059 0.5260595 0.8280115 -0.1940571 0.5828779 0.8033753 -0.1218255 0.5812762 0.7981006 -0.1585986 0.5731565 0.7934044 -0.2049422 0.5978873 0.7926328 -0.1194319 0.5893495 0.7983309 -0.1238343 0.5978952 0.792606 -0.1195712 0.5974603 0.7922992 -0.1237062 0.5998735 0.7912211 -0.1188316 0.597844 0.7923957 -0.1212093 0.6006658 0.7897813 -0.1242823 0.5980424 0.7875767 -0.1485529 0.6099013 0.7835844 -0.1183893 0.6023418 0.7888399 -0.1221305 0.6083986 0.7785109 -0.1541813 0.6259721 0.7714399 -0.1141905 0.6119281 0.7801659 -0.1299439 0.6366523 0.7619876 -0.1185266 0.6246688 0.7652431 -0.155538 0.6510335 0.7491501 -0.1221852 0.6739528 0.7328358 -0.09348392 0.6482523 0.7435356 -0.1640849 0.6984186 0.7103871 -0.0869587 0.6773723 0.7132868 -0.1799685 0.7283456 0.6797494 -0.08633363 0.7154605 0.676915 -0.1729231 0.7633011 0.6397775 -0.08975571 0.7567857 0.6324639 -0.1651208 0.8016976 0.5755139 -0.1614457 0.8342585 0.5390219 -0.1160526 0.7987814 0.588991 -0.1226292 0.8584285 0.5069733 -0.07796478 0.8427202 0.501191 -0.1965465 0.8860443 0.4506316 -0.1088889 0.8835515 0.4073369 -0.2311134 0.820984 0.5664747 -0.07135629 0.8210709 0.5663429 -0.07140332 0.883558 0.423483 -0.199968 0.8207873 0.5668608 -0.07055032 0.8210862 0.5663222 -0.07139021 0.8543255 0.3025732 -0.4225842 0.8748769 0.3722124 -0.3099166 0.6663616 0.04843044 -0.7440542 0.7934328 0.5807351 0.1822388 0.8118532 0.5666836 0.1405848 0.7956556 0.579405 0.1766976 0.8308327 0.5491275 0.09042215 0.840183 0.5389912 0.0598421 0.8472809 0.5295085 0.04166507 0.8365256 0.5431309 0.07234573 0.8569946 0.5152714 0.007453143 0.6117977 0.7774131 0.1460567 0.4785062 0.8655025 0.1481125 0.6341769 0.7590845 0.1470051 0.6116155 0.7780286 0.1435204 0.6388298 0.7554263 0.1456967 0.6341568 0.7596496 0.1441447 0.6413114 0.7531665 0.1464923 0.6388329 0.7555102 0.1452476 0.6474094 0.7476456 0.1479433 0.6413503 0.7536448 0.1438375 0.6570255 0.7388145 0.1499021 0.6476123 0.7486755 0.141715 0.6699798 0.7265619 0.1524306 0.6576873 0.7403653 0.1389479 0.6860135 0.7107855 0.1554652 0.6716339 0.7283888 0.1354904 0.7047663 0.6913913 0.159005 0.6894669 0.7123008 0.1313884 0.7257428 0.6683705 0.1630284 0.7110962 0.6915705 0.1267774 0.7483447 0.6418384 0.167403 0.7362412 0.6656681 0.1217985 0.7718888 0.6120528 0.1719861 0.7643273 0.6341762 0.1167232 0.7944182 0.5969643 0.111952 0.595079 0.802132 0.04965406 0.6236822 0.7800655 0.0501852 0.594887 0.8023726 0.04803967 0.6293989 0.7755163 0.04931181 0.6235787 0.7802638 0.04835349 0.6327773 0.7727265 0.04986613 0.6293859 0.7755455 0.04901546 0.6409124 0.7659299 0.0508213 0.6327118 0.7728956 0.0480439 0.6536906 0.7549628 0.05215287 0.6408352 0.7662631 0.04659748 0.6709143 0.7395743 0.05388712 0.6537576 0.7553835 0.04468446 0.6922585 0.7194705 0.05604058 0.6714377 0.7398518 0.04231554 0.7172313 0.6943638 0.05863428 0.693733 0.7191461 0.03954291 0.7451386 0.6640554 0.06163567 0.7203325 0.6926715 0.03643035 0.7750601 0.6285338 0.0650165 0.7506525 0.6598649 0.03315544 0.8059144 0.5880419 0.06862163 0.7837673 0.6203354 0.02988314 0.8183539 0.574084 0.026919 -0.1329268 0.9617494 0.2395171 -0.2741502 0.9461599 0.1721135 -0.617779 -0.3163264 0.7199213 -0.6849128 -0.3800498 0.6216564 -0.7542133 -0.4847467 0.4429254 -0.7816436 -0.5531743 0.2881518 -0.7874681 -0.5586341 0.2604265 -0.7915122 -0.5804821 0.1911782 -0.7846811 -0.5623565 0.260827 -0.7846143 -0.5622927 0.2611653 -0.6804414 -0.3862178 0.6227643 -0.6797618 -0.3855397 0.6239254 -0.7912916 -0.552718 0.2614582 -0.7943911 -0.5483732 0.2612082 -0.791486 -0.5529156 0.2604501 -0.796505 -0.5454175 0.2609587 -0.7945326 -0.5485231 0.2604622 -0.7976295 -0.5438604 0.2607737 -0.7965871 -0.545507 0.2605212 -0.7977806 -0.5437046 0.2606363 -0.7976602 -0.5438945 0.2606084 -0.7969418 -0.5449697 0.2605605 -0.7977608 -0.5436826 0.260743 -0.7951106 -0.547657 0.2605205 -0.7968788 -0.5449005 0.2608976 -0.7922759 -0.5517504 0.2605195 -0.795006 -0.5475447 0.261075 -0.788398 -0.5572441 0.2605907 -0.7921241 -0.551593 0.2613131 -0.7834627 -0.5641296 0.2606609 -0.7882135 -0.557062 0.2615367 -0.7774158 -0.572373 0.2607946 -0.783232 -0.563916 0.2618134 -0.7702293 -0.5819473 0.2609294 -0.7771507 -0.5721462 0.2620792 -0.7618436 -0.5928102 0.2610946 -0.7699218 -0.581708 0.2623665 -0.7522162 -0.6049044 0.2612692 -0.761496 -0.5925682 0.2626532 -0.7412893 -0.6181666 0.2614582 -0.7518243 -0.6046649 0.2629464 -0.7290244 -0.6325269 0.2615971 -0.7408652 -0.6179435 0.2631815 -0.7153587 -0.6478872 0.2617333 -0.7285537 -0.6323185 0.2634065 -0.7002568 -0.6641392 0.2618392 -0.7148445 -0.6477004 0.2635936 -0.6836845 -0.6811692 0.2618855 -0.6997041 -0.6639796 0.2637141 -0.6656091 -0.698843 0.2618835 -0.6830875 -0.6810374 0.2637795 -0.6460483 -0.7170119 0.2617547 -0.6649914 -0.6987441 0.2637104 -0.6249604 -0.7355533 0.2615073 -0.6454067 -0.7169428 0.2635208 -0.6026709 -0.7540108 0.2612577 -0.6242641 -0.7355091 0.2632881 -0.564971 -0.7832311 0.2595317 -0.6019652 -0.7539914 0.2629352 -0.4725294 -0.8437358 0.2546091 -0.5632616 -0.7832548 0.2631507 -0.3016887 -0.9216343 0.2440783 -0.4686001 -0.8439354 0.2611266 -0.07960444 -0.9702417 0.2286791 -0.2943994 -0.9216791 0.2526589 0.02319973 -0.9743492 0.2238424 -0.0724048 -0.9693174 0.234907 -0.03654998 -0.9722343 0.2311379 0.02390712 -0.9742051 0.2243945 -0.2563078 -0.9341987 0.2481517 -0.04049563 -0.9728493 0.2278692 -0.5044333 -0.8232665 0.2603445 -0.260807 -0.9342532 0.2432094 -0.6743587 -0.6899009 0.2632051 -0.5061289 -0.8231846 0.2572949 -0.674818 -0.6899877 0.2617969 -0.6871854 -0.3715682 0.6242703 -0.6912094 -0.3660905 0.6230629 -0.6891877 -0.3735783 0.620854 -0.6939375 -0.3623848 0.6221961 -0.6925532 -0.3674511 0.6207655 -0.6954864 -0.3605872 0.6215108 -0.6947541 -0.3632162 0.6207984 -0.6958816 -0.3607134 0.620995 -0.6958201 -0.3609282 0.620939 -0.6950199 -0.3626638 0.6208239 -0.6956623 -0.3604896 0.6213703 -0.6929608 -0.3665331 0.6208533 -0.6943579 -0.3619884 0.6219577 -0.6896858 -0.3723088 0.6210633 -0.6918932 -0.3654488 0.6226804 -0.685124 -0.3799701 0.6214722 -0.6882193 -0.3708298 0.62357 -0.6791635 -0.3894387 0.6221532 -0.6832308 -0.3780798 0.624701 -0.6718119 -0.4007579 0.6229461 -0.676949 -0.3872555 0.6259181 -0.6629475 -0.4138568 0.6238775 -0.6692652 -0.3982864 0.6272575 -0.6524717 -0.4286779 0.6249128 -0.6600908 -0.4111362 0.6286869 -0.6403557 -0.4451984 0.6258937 -0.6493979 -0.4258146 0.6300511 -0.6264308 -0.4632524 0.6268825 -0.6370219 -0.4421709 0.6314176 -0.6105716 -0.4826926 0.6278616 -0.622838 -0.4600823 0.6327694 -0.5927833 -0.5035023 0.6285645 -0.6068648 -0.4795249 0.633854 -0.5729209 -0.5253887 0.6290695 -0.5889056 -0.500303 0.6347339 -0.5508946 -0.5481683 0.6293066 -0.5688958 -0.5221912 0.6353534 -0.5267443 -0.5716564 0.6290862 -0.5468299 -0.5450664 0.6355152 -0.5003892 -0.5955168 0.6284667 -0.5225929 -0.5686178 0.635272 -0.4718838 -0.6196231 0.6272102 -0.4962902 -0.5926413 0.634407 -0.441562 -0.6431056 0.6256502 -0.4676995 -0.6168089 0.6330908 -0.3917282 -0.681371 0.61829 -0.4374433 -0.6404435 0.6312492 -0.2706508 -0.7552476 0.5969498 -0.3823406 -0.675644 0.6303339 -0.05641657 -0.8322402 0.5515372 -0.2524697 -0.7450758 0.6173501 0.1963149 -0.8483257 0.4917355 -0.02938044 -0.8168758 0.576065 0.3068737 -0.8263759 0.4721563 0.2168216 -0.8341541 0.5071245 0.2498681 -0.8321042 0.495145 0.3084357 -0.8251589 0.4732654 0.008559286 -0.8280698 0.5605596 0.2389353 -0.840007 0.4871324 -0.3066134 -0.7239105 0.6180145 -0.007448673 -0.8373692 0.5465871 -0.5365948 -0.5568717 0.6340032 -0.3148297 -0.7286045 0.6082908 -0.5397635 -0.5592505 0.6292014 0.5009309 0.8257501 -0.2592393 0.2255235 0.9441618 -0.2402032 0.5488381 0.7949209 -0.258607 0.5022844 0.8261483 -0.2553223 0.5470706 0.7947223 -0.2629261 0.5576601 0.7881181 -0.2605478 0.5573518 0.7880793 -0.2613238 0.5640591 0.7842388 -0.2584704 0.5623559 0.7840116 -0.262834 0.5785919 0.7745403 -0.2555754 0.5748075 0.7739463 -0.2657131 0.600952 0.7585923 -0.2517828 0.5947149 0.7573236 -0.2697687 0.6305932 0.7357528 -0.2470224 0.6218978 0.7332528 -0.2749242 0.6666581 0.7052623 -0.241189 0.6559119 0.7005587 -0.2810639 0.7078518 0.6663745 -0.2342883 0.6959049 0.6579024 -0.2878901 0.7524251 0.6185501 -0.2263899 0.7403916 0.603994 -0.2949771 0.7981878 0.5616997 -0.2176917 0.7871148 0.5380377 -0.3016056 0.8426947 0.4963445 -0.2085852 0.8330718 0.46024 -0.3068725 0.6383185 0.1727626 -0.750135 0.8048733 0.3835813 -0.4528182 0.6008594 0.2891171 -0.7452377 0.7472274 0.4573628 -0.4821519 0.558403 0.3916774 -0.731283 0.684022 0.520646 -0.5109221 0.5153775 0.4771035 -0.7118695 0.6192856 0.5725792 -0.5372508 0.4753055 0.5448457 -0.6908168 0.5571284 0.6131883 -0.5600072 0.4408332 0.5965424 -0.6706736 0.5010482 0.6432598 -0.5789366 0.4134737 0.6344419 -0.6530873 0.4538137 0.6641515 -0.594101 0.3938533 0.660609 -0.6391208 0.4172934 0.6773086 -0.6059036 0.3823461 0.6767861 -0.6291041 0.39253 0.6839138 -0.6149651 0.3784924 0.6837005 -0.6239367 0.3802409 0.6849186 -0.6215331 0.3604202 0.6887861 -0.6290238 0.3715392 0.6964377 -0.6139488 0.3121132 0.7360872 -0.6006339 0.3029819 0.7289842 -0.6138272 -0.6948695 0.7119192 -0.1016237 -0.7596576 0.6325978 -0.1507986 -0.8227322 0.5268555 -0.2133891 -0.06677871 -0.9957411 0.06356149 -0.7745692 -0.6304707 -0.05049055 -0.1216635 -0.9910561 0.054825 -0.7539641 -0.6397638 -0.1491324 -0.7751031 -0.6299369 -0.0489366 -0.7555364 -0.6387963 -0.1452726 -0.7535552 -0.6411173 -0.1453379 -0.7535355 -0.6410949 -0.1455382 -0.7731716 -0.6322993 -0.04902338 -0.7731723 -0.6322864 -0.0491783 -0.7574763 -0.6364856 -0.1453121 -0.7572284 -0.6366409 -0.1459223 -0.7591528 -0.6344572 -0.1454339 -0.758973 -0.6345716 -0.1458731 -0.7602791 -0.633085 -0.1455304 -0.7601664 -0.6331573 -0.1458039 -0.7608385 -0.6323847 -0.1456513 -0.7608106 -0.6324025 -0.1457188 -0.7608625 -0.6323386 -0.1457262 -0.7608866 -0.632323 -0.1456678 -0.7603288 -0.6329692 -0.1457741 -0.7604101 -0.6329169 -0.1455766 -0.7592374 -0.6342673 -0.1458206 -0.7593796 -0.6341769 -0.1454728 -0.7575834 -0.6362377 -0.1458391 -0.7577716 -0.6361199 -0.1453748 -0.7553585 -0.6388736 -0.145856 -0.7555961 -0.638728 -0.1452624 -0.7525624 -0.6421684 -0.1458415 -0.7528311 -0.642008 -0.145159 -0.7491763 -0.6461185 -0.1458276 -0.7494813 -0.6459426 -0.1450368 -0.745193 -0.6507123 -0.145811 -0.7455255 -0.6505286 -0.1449283 -0.7406101 -0.6559299 -0.1457824 -0.7409582 -0.6557475 -0.1448315 -0.7354111 -0.6617656 -0.1457294 -0.7357629 -0.6615926 -0.1447345 -0.7295832 -0.66819 -0.1457072 -0.7299491 -0.6680242 -0.1446307 -0.7231251 -0.675182 -0.1456688 -0.7234811 -0.6750365 -0.1445713 -0.7160274 -0.6827121 -0.1456328 -0.7163715 -0.6825892 -0.1445125 -0.7082874 -0.6907443 -0.1456066 -0.708614 -0.6906474 -0.1444726 -0.6999031 -0.6992434 -0.1455832 -0.7002033 -0.699176 -0.1444587 -0.6908688 -0.7081691 -0.1455919 -0.6911439 -0.7081314 -0.1444646 -0.6812051 -0.7174676 -0.1456021 -0.6814424 -0.7174609 -0.1445197 -0.6709151 -0.7270882 -0.1456553 -0.6711198 -0.7271116 -0.144593 -0.6599972 -0.7369908 -0.1457678 -0.6601683 -0.7370433 -0.1447235 -0.6416771 -0.7528113 -0.1467167 -0.6419404 -0.7530288 -0.1444309 -0.5971357 -0.7883029 -0.1483495 -0.5971077 -0.7890908 -0.144216 -0.5157748 -0.8432163 -0.1515346 -0.5144044 -0.8450698 -0.1457567 -0.4058735 -0.9004604 -0.1563254 -0.4032389 -0.9024608 -0.1515347 -0.353967 -0.9218019 -0.1580788 -0.3537024 -0.9219688 -0.1576966 -0.3865795 -0.909251 -0.1543344 -0.3881108 -0.9081596 -0.1568955 -0.4968732 -0.8551785 -0.1476029 -0.4978737 -0.8539848 -0.1511012 -0.6143288 -0.7756615 -0.1447391 -0.6142528 -0.7753672 -0.1466262 -0.6960069 -0.703358 -0.1444368 -0.6957831 -0.7033981 -0.1453169 -0.701355 -0.7111313 -0.0489223 -0.7014809 -0.7110471 -0.04833823 -0.5976786 -0.8001718 -0.0500555 -0.5976988 -0.8002378 -0.0487405 -0.4474028 -0.8927139 -0.05378246 -0.4467269 -0.8931852 -0.05152952 -0.3057929 -0.9502804 -0.05880343 -0.3047768 -0.9507102 -0.0571084 -0.2627359 -0.9630181 -0.05971592 -0.2629149 -0.962953 -0.05997633 -0.32836 -0.9429528 -0.05495148 -0.3301504 -0.9421334 -0.05818438 -0.4712538 -0.8805775 -0.05003106 -0.4722347 -0.8798231 -0.05390459 -0.5767846 -0.815457 -0.04847091 -0.5768696 -0.8152278 -0.05123859 -0.6336236 -0.7721231 -0.04844731 -0.6334933 -0.7721327 -0.04997122 -0.6565992 -0.7526729 -0.04859089 -0.6565069 -0.7527076 -0.04929524 -0.6704562 -0.7403625 -0.04849457 -0.670345 -0.7404168 -0.04919993 -0.6834916 -0.7283518 -0.04840576 -0.6833532 -0.7284306 -0.04916411 -0.6956983 -0.7167043 -0.04836255 -0.695542 -0.7168041 -0.04912471 -0.7070674 -0.7054911 -0.0483542 -0.7068947 -0.7056112 -0.04911899 -0.7175914 -0.6947823 -0.04837751 -0.717406 -0.6949205 -0.04913556 -0.7272741 -0.6846382 -0.04840427 -0.7270736 -0.6847965 -0.04917109 -0.7361195 -0.6751151 -0.0484547 -0.7359136 -0.6752855 -0.04919832 -0.7441353 -0.6662636 -0.04853254 -0.7439308 -0.6664403 -0.04923725 -0.7513442 -0.6581192 -0.04859083 -0.7511326 -0.6583086 -0.04929131 -0.7577516 -0.650725 -0.04867714 -0.7575521 -0.6509091 -0.04931545 -0.7633786 -0.6441085 -0.04875934 -0.7631868 -0.6442902 -0.04935598 -0.7682409 -0.6382944 -0.04884803 -0.768065 -0.6384651 -0.04938238 -0.7723573 -0.6333007 -0.04893159 -0.7721984 -0.6334578 -0.04940551 -0.7757418 -0.6291438 -0.04901844 -0.7756069 -0.6292792 -0.04941433 -0.77841 -0.6258339 -0.04909062 -0.7782972 -0.6259484 -0.04941743 -0.7803683 -0.6233838 -0.04917305 -0.7802901 -0.6234638 -0.04939758 -0.7816399 -0.6217845 -0.04922497 -0.7815855 -0.6218406 -0.0493803 -0.7822144 -0.6210562 -0.04929465 -0.7822038 -0.6210672 -0.04932457 -0.7821102 -0.6211827 -0.04935491 -0.7821362 -0.6211557 -0.0492804 -0.7813259 -0.6221653 -0.04939824 -0.7813887 -0.6221007 -0.04921895 -0.7798673 -0.6239904 -0.04942679 -0.7799686 -0.6238867 -0.04913562 -0.7777193 -0.6266626 -0.04946595 -0.7778695 -0.6265102 -0.04903072 -0.01869487 -0.9542014 0.2985801 0.1896144 -0.9583734 0.2134636 0.2771113 -0.9455772 0.1705672 0.3299453 -0.1340122 0.9344393 0.3455785 -0.1225321 0.9303555 0.7565645 0.3061971 0.5778006 0.7806707 0.3376796 0.5258574 0.8125329 0.3988166 0.4251301 0.8371971 0.470506 0.2787926 0.8345525 0.4641614 0.2967768 0.7045232 0.7068854 -0.06293016 0.8388968 0.5142934 0.178198 0.839453 0.5185176 0.1626594 0.7906498 0.5856022 0.1787254 0.7906377 0.5855843 0.1788384 0.7820023 0.5481498 0.2966549 0.7819295 0.5480479 0.297035 0.7248696 0.442603 0.527889 0.7244469 0.442111 0.5288805 0.294474 -0.01203048 0.9555838 0.2927498 -0.01342761 0.9560948 0.8257387 0.5356028 0.1768764 0.8127131 0.5549761 0.1774795 0.8256099 0.5351849 0.1787332 0.8010044 0.5715997 0.1779491 0.8125833 0.554665 0.1790397 0.7910205 0.5852116 0.1783648 0.8008779 0.5713661 0.1792632 0.7830175 0.5957858 0.1786703 0.7909126 0.5850512 0.179367 0.7773415 0.6031062 0.1788948 0.7829352 0.5956831 0.1793711 0.7746196 0.6065248 0.1791423 0.7772837 0.6030423 0.17936 0.7745227 0.6066143 0.1792587 0.774604 0.6065087 0.1792649 0.7751493 0.605808 0.1792771 0.7745263 0.606618 0.1792305 0.7758044 0.6049555 0.1793218 0.7751496 0.6058082 0.1792752 0.7751196 0.605883 0.1791523 0.7758198 0.6049721 0.1791993 0.7726297 0.6090579 0.1791424 0.7751007 0.6058631 0.1793008 0.7687023 0.6139969 0.1791771 0.7725943 0.6090224 0.1794143 0.7634299 0.6205312 0.1792085 0.7686573 0.6139554 0.179512 0.7566378 0.6287711 0.1792933 0.7633655 0.6204783 0.1796661 0.7483058 0.6386402 0.1793803 0.7565594 0.6287156 0.1798177 0.7383993 0.6500531 0.1794368 0.7482168 0.638588 0.1799355 0.72685 0.6629191 0.1795201 0.7382878 0.6500014 0.1800817 0.7135975 0.6771594 0.1795377 0.7267293 0.6628775 0.1801612 0.6985878 0.6926382 0.1795195 0.7134596 0.677127 0.1802067 0.6817435 0.7092224 0.179526 0.6984156 0.6926146 0.1802795 0.663023 0.726769 0.1794641 0.6815531 0.7092125 0.1802863 0.6423917 0.7451104 0.1792861 0.6628233 0.7267729 0.1801843 0.6192161 0.7645377 0.1790355 0.6421611 0.7451281 0.1800369 0.5733841 0.7997681 0.1777688 0.6189388 0.7645715 0.1798473 0.4741284 0.8629776 0.174562 0.5726501 0.7998947 0.1795558 0.3049649 0.9375618 0.1672559 0.4725828 0.8632674 0.1772983 0.1133785 0.9809445 0.1577761 0.3021158 0.9378654 0.1706879 0.04810214 0.9866917 0.1553241 0.110965 0.9808698 0.1599411 0.1253816 0.9790112 0.1606755 0.04821926 0.9867013 0.1552267 0.3361034 0.9260963 0.1714063 0.1270897 0.9790449 0.1591198 0.5486666 0.8167949 0.1783562 0.3375913 0.9259048 0.1695064 0.6937144 0.6973816 0.1800531 0.5491303 0.8167078 0.177326 0.693847 0.6973956 0.1794874 0.8205079 0.4913194 0.292185 0.8063299 0.5135653 0.2933987 0.8196419 0.4895598 0.2975202 0.7934736 0.5326246 0.2944668 0.805532 0.5121567 0.298016 0.7824457 0.5482133 0.2953661 0.7927775 0.5315443 0.298269 0.7735462 0.5602591 0.2962029 0.7818552 0.5473932 0.2984344 0.7672047 0.5685682 0.2968621 0.77311 0.5597051 0.2983807 0.7641386 0.5723538 0.2974948 0.7669328 0.568244 0.2981826 0.7640067 0.5723635 0.2978151 0.7640687 0.5722729 0.2978298 0.7647007 0.5714364 0.2978144 0.764038 0.5723998 0.2976651 0.7654526 0.5704716 0.2977323 0.7647492 0.571493 0.2975811 0.7646837 0.5715935 0.2975567 0.7654561 0.5704758 0.2977152 0.7619231 0.5753363 0.2974246 0.7646027 0.5714991 0.2979459 0.7575456 0.581075 0.2974501 0.761754 0.5751446 0.2982274 0.7516565 0.5886762 0.2974438 0.7573336 0.5808451 0.2984374 0.7440397 0.5982048 0.2975834 0.7513586 0.5883718 0.2987957 0.73468 0.6096122 0.2976881 0.7436942 0.5978776 0.2991007 0.7235013 0.6227689 0.2978335 0.7342673 0.6092567 0.2994295 0.7104443 0.6375815 0.2979241 0.7230394 0.6224133 0.2996929 0.6953948 0.6539302 0.2979955 0.7099186 0.6372265 0.2999299 0.6782817 0.6716602 0.2980043 0.6948108 0.653591 0.3000943 0.6590213 0.6905844 0.2979667 0.6776264 0.6713395 0.3002097 0.6375792 0.7105332 0.2977167 0.6583396 0.6903089 0.3001041 0.6138301 0.7312606 0.2974401 0.6368051 0.7102804 0.2999681 0.5871068 0.7530877 0.2969251 0.6130005 0.7310463 0.2996696 0.5344188 0.7924661 0.2939288 0.5861047 0.7528879 0.2994014 0.420442 0.8607422 0.2869693 0.5319153 0.7921623 0.2992409 0.228689 0.9345862 0.2724884 0.4154053 0.8604446 0.2950826 0.01656538 0.9665457 0.2559589 0.2200005 0.9337332 0.2823863 -0.05539548 0.9659422 0.2527587 0.01013922 0.9651305 0.2615728 0.02679556 0.9644254 0.2629936 -0.0551632 0.9660052 0.2525689 0.2608949 0.9228943 0.2831959 0.03149706 0.9654107 0.2588242 0.5051821 0.8104526 0.2965764 0.2653921 0.9232602 0.2777729 0.6725967 0.6766568 0.299582 0.5068624 0.8106092 0.2932631 0.6730726 0.6768773 0.2980107 0.7693809 0.3757059 0.5166218 0.7534406 0.4024459 0.5199659 0.7645636 0.3693052 0.5282576 0.7387202 0.4253146 0.5228766 0.7492053 0.3970934 0.5301021 0.7258973 0.4439682 0.5253239 0.7351672 0.4210299 0.5312841 0.7154307 0.4583287 0.527346 0.7230609 0.4406851 0.5319581 0.7078683 0.468091 0.5289739 0.7133711 0.4560227 0.5321136 0.7040293 0.4722351 0.5304119 0.7066307 0.4667376 0.5318167 0.7037467 0.4720225 0.5309758 0.7037761 0.4719613 0.5309912 0.7045414 0.4708503 0.5309627 0.7038903 0.4721778 0.5306473 0.7054392 0.469741 0.5307533 0.7047673 0.4710953 0.5304454 0.7046504 0.471309 0.5304108 0.7054397 0.4697417 0.5307518 0.7015695 0.4761386 0.5301813 0.704272 0.4708985 0.5312772 0.6965028 0.4832592 0.5304193 0.7007556 0.4752649 0.5320385 0.6896483 0.4926949 0.5306947 0.6954649 0.4821639 0.5327725 0.6807801 0.5045323 0.5310232 0.6883713 0.4913773 0.5335668 0.6698259 0.5186928 0.5313107 0.6793089 0.5030583 0.5342956 0.6565932 0.5348919 0.531767 0.6680675 0.5169933 0.535167 0.6409907 0.5530419 0.5322366 0.6546084 0.5330536 0.5360426 0.6229362 0.5730487 0.5325089 0.6388583 0.5511622 0.5367311 0.6022307 0.5946198 0.5326777 0.6205981 0.5710998 0.5373109 0.578917 0.6176052 0.5323712 0.5998522 0.5927562 0.5374172 0.5526804 0.6415501 0.5319377 0.5762986 0.6156868 0.5374101 0.5236035 0.6662678 0.5309677 0.5500094 0.6397268 0.5368794 0.4908633 0.6920713 0.5292358 0.5208914 0.6645466 0.5357705 0.4270634 0.7387098 0.5214641 0.4875578 0.6901236 0.5348054 0.2899211 0.8143342 0.5027977 0.419395 0.7347164 0.5331975 0.06763941 0.882657 0.4651252 0.2762057 0.8081802 0.5201493 -0.1632053 0.8907409 0.4241988 0.04772448 0.873439 0.4845892 -0.2395752 0.877447 0.4155606 -0.1759178 0.8833674 0.4344133 -0.1570514 0.8850665 0.4381691 -0.2390453 0.8777838 0.4151539 0.09845906 0.8668243 0.4887961 -0.1476582 0.8904141 0.4305343 0.3892054 0.7557197 0.5266944 0.1093046 0.8717023 0.4776899 0.5946118 0.599236 0.5360534 0.3942169 0.7581956 0.5193578 0.59632 0.6005526 0.5326716 0.3515876 -0.07328563 0.9332821 0.3324352 -0.04752588 0.9419279 0.3289209 -0.09066903 0.9399948 0.3142959 -0.02566289 0.9489781 0.3126325 -0.06302422 0.947781 0.2989657 -0.007346689 0.9542356 0.298628 -0.03814578 0.953607 0.2859507 0.006344079 0.9582233 0.2864096 -0.01750057 0.9579474 0.2761763 0.01526725 0.9609857 0.2769238 -0.001041293 0.9608913 0.2704803 0.0182752 0.9625521 0.2709773 0.01097893 0.9625232 0.2694261 0.01737153 0.9628643 0.2694237 0.01740044 0.9628645 0.2699263 0.01578718 0.9627516 0.2697384 0.01762998 0.9627722 0.2710195 0.01475769 0.9624608 0.270813 0.0165205 0.9624902 0.2710736 0.01726078 0.9624039 0.2713723 0.01504892 0.9623568 0.2679498 0.02259343 0.9631679 0.2690424 0.01558011 0.9630023 0.2628347 0.03057384 0.9643564 0.2647497 0.01993578 0.9641111 0.2554414 0.04074943 0.9659654 0.2583295 0.0268104 0.9656848 0.2458387 0.05354791 0.9678306 0.2499755 0.03614819 0.9675772 0.2337842 0.06878036 0.9698528 0.2394051 0.04807919 0.9697287 0.2192561 0.0863561 0.9718381 0.2265902 0.06259244 0.9719769 0.2022209 0.106245 0.9735599 0.2115321 0.07961934 0.9741227 0.1821671 0.1279616 0.9749056 0.193709 0.0987026 0.9760813 0.1595959 0.151813 0.9754393 0.1736038 0.1202367 0.9774482 0.1338501 0.1769918 0.9750682 0.1505223 0.1434631 0.9781419 0.105578 0.2037614 0.9733111 0.1250622 0.1687254 0.9776968 0.07421946 0.2311928 0.9700729 0.09662348 0.1951345 0.9760053 0.03967911 0.2603762 0.9646915 0.06573855 0.2228082 0.9726433 -0.02350312 0.317712 0.947896 0.02968215 0.2502031 0.9677384 -0.1542401 0.4098542 0.8990158 -0.04317152 0.2965483 0.9540416 -0.3468101 0.4912557 0.7989935 -0.1827006 0.3755866 0.9086006 -0.5219234 0.4982913 0.6923163 -0.3759281 0.4493592 0.8104038 -0.5757984 0.4773584 0.663766 -0.5356231 0.4741442 0.6987811 -0.5214204 0.4755632 0.7084916 -0.5751547 0.4785821 0.6634427 -0.3306315 0.447294 0.83103 -0.5108665 0.4938787 0.7036329 -0.06831771 0.3241918 0.9435213 -0.3135958 0.4708628 0.8245882 0.1470392 0.1516822 0.9774312 -0.05613362 0.337621 0.9396069 0.1536781 0.157828 0.975435 0.6819565 -0.7255816 -0.09201401 0.6091238 0.7905961 -0.06265735 0.7659288 -0.6235687 -0.1565731 0.8212036 -0.5299044 -0.2117214 0.6091575 0.7904699 -0.06391012 0.820152 0.5720995 -0.007273852 0.8075692 0.5863274 -0.06365638 0.8192424 0.5733551 -0.01028388 0.1732322 0.983376 0.05442756 0.7897771 0.5998094 -0.1283774 0.8071195 0.5868065 -0.06493264 0.7587258 0.6138934 -0.217876 0.7895654 0.5999762 -0.1288994 0.7595751 0.6134744 -0.2160899 0.7355439 0.642935 -0.2135639 0.7355034 0.6429193 -0.2137513 0.7587207 0.6389977 -0.1265891 0.7586945 0.6389876 -0.1267965 0.7716373 0.6329261 -0.06309193 0.7716299 0.6329234 -0.06320995 0.7800505 0.6256539 -0.008866429 0.7800489 0.6256543 -0.008961915 0.7057237 0.708435 -0.008591353 0.7057645 0.7083979 -0.008295774 0.5987868 0.8008531 -0.009419202 0.598754 0.8008846 -0.008807361 0.4435371 0.896166 -0.01270049 0.4431263 0.8963849 -0.01154404 0.2850567 0.9583435 -0.01790088 0.2843738 0.9585649 -0.01687252 0.2239221 0.9744035 -0.01992189 0.2238746 0.9744156 -0.01986086 0.2729928 0.9618659 -0.01699995 0.2739517 0.9615676 -0.01839184 0.4181379 0.9083077 -0.01173657 0.4190207 0.9078705 -0.01389205 0.543484 0.8393688 -0.009230017 0.5437493 0.8391774 -0.0108577 0.6164287 0.7873644 -0.008542418 0.6164527 0.7873338 -0.009574949 0.6502717 0.7596541 -0.008512139 0.6502528 0.7596647 -0.008990406 0.6674046 0.7446478 -0.008406162 0.667375 0.7446695 -0.008826673 0.6827145 0.7306372 -0.008369326 0.6826764 0.7306683 -0.008761286 0.6966726 0.7173405 -0.008346855 0.6966224 0.7173845 -0.008760631 0.7093112 0.7048464 -0.008327662 0.7092494 0.7049034 -0.008761167 0.7206391 0.6932601 -0.008353888 0.7205747 0.6933221 -0.008753001 0.730689 0.6826586 -0.008420586 0.7306254 0.6827222 -0.008778572 0.7395095 0.6730936 -0.008414328 0.7394292 0.6731764 -0.008833408 0.7471072 0.66465 -0.008445918 0.7470343 0.6647272 -0.008804142 0.7535215 0.6573678 -0.008550286 0.7534675 0.6574263 -0.008803486 0.7587696 0.6513018 -0.008645236 0.758721 0.6513553 -0.008864343 0.7628711 0.6464927 -0.008660435 0.7628153 0.6465551 -0.008905649 0.7658962 0.6429045 -0.008765935 0.7658733 0.6429305 -0.008864939 0.7678902 0.6405211 -0.008793532 0.7678635 0.6405515 -0.00890696 0.7685201 0.6397641 -0.008872866 0.7685275 0.6397556 -0.008841097 0.7678339 0.6405873 -0.008886039 0.7678493 0.6405697 -0.008820652 0.7672017 0.641345 -0.008848726 0.7672045 0.6413415 -0.008835971 0.7675607 0.6409165 -0.008763074 0.7675341 0.6409467 -0.008876085 0.7696493 0.6384068 -0.008760869 0.7696072 0.638455 -0.008938074 0.7740486 0.6330664 -0.008700668 0.7739404 0.6331924 -0.009144961 0.7803718 0.6252558 -0.008662879 0.7802155 0.625442 -0.009282171 0.788306 0.6152219 -0.00870043 0.7881122 0.6154593 -0.009436905 0.7976871 0.6030075 -0.008791506 0.7974438 0.6033157 -0.009674727 0.8082385 0.5887876 -0.008931398 0.8079412 0.589179 -0.009961307 0.7521947 0.6226961 -0.2155289 0.7533628 0.6221814 -0.2129195 0.7456274 0.6306917 -0.2150995 0.7465845 0.6303188 -0.2128607 0.7398605 0.6375622 -0.2147576 0.7406316 0.6372982 -0.212875 0.7350779 0.6432082 -0.2143446 0.7356161 0.6430462 -0.2129803 0.7312715 0.6475964 -0.2141517 0.7317077 0.64748 -0.2130107 0.7287335 0.6505492 -0.2138531 0.7289485 0.6504971 -0.2132781 0.7276134 0.6518869 -0.2135933 0.7276599 0.6518763 -0.2134678 0.7274726 0.6520701 -0.2135144 0.7274626 0.6520723 -0.2135413 0.7279003 0.651593 -0.2135128 0.7278529 0.651604 -0.2136409 0.7282802 0.6511498 -0.2135699 0.7282587 0.6511548 -0.2136277 0.7277633 0.6516727 -0.2137363 0.7278714 0.6516476 -0.2134444 0.7264901 0.6530954 -0.2137256 0.72661 0.653069 -0.2133983 0.7245492 0.6552346 -0.213766 0.7247392 0.6551964 -0.2132388 0.7219722 0.6580644 -0.2137929 0.722199 0.6580245 -0.2131488 0.7187048 0.6616379 -0.2137722 0.7189521 0.6616029 -0.2130483 0.7147368 0.6659323 -0.2137415 0.7150064 0.6659056 -0.2129216 0.7100694 0.6709095 -0.2137327 0.7103597 0.6708965 -0.2128072 0.7047052 0.6765486 -0.2137116 0.704994 0.6765552 -0.2127361 0.6986215 0.6828411 -0.2136734 0.6988984 0.6828709 -0.2126697 0.6918151 0.6897358 -0.2136737 0.6920841 0.689794 -0.212612 0.6842736 0.6972038 -0.2137209 0.684526 0.6972943 -0.2126141 0.6760075 0.7052199 -0.2137259 0.6762158 0.705335 -0.2126848 0.6669982 0.713712 -0.2138427 0.6671853 0.7138674 -0.2127375 0.6569203 0.722908 -0.2141487 0.6570892 0.7231249 -0.2128948 0.6369553 0.7402511 -0.2152117 0.6371259 0.7408634 -0.2125846 0.5950834 0.7737872 -0.2170924 0.5947287 0.7752114 -0.212944 0.5247633 0.8220149 -0.2211671 0.5228501 0.8246989 -0.2156369 0.4438771 0.866963 -0.2266017 0.441586 0.8690465 -0.2230692 0.4159857 0.8803615 -0.2278586 0.4161205 0.8802513 -0.2280384 0.4499991 0.8647097 -0.2231097 0.451644 0.8631607 -0.225768 0.5394635 0.8138378 -0.2159791 0.540332 0.8124506 -0.2190097 0.6278451 0.7486425 -0.2129436 0.6277914 0.7482036 -0.2146371 0.6903326 0.6915385 -0.212639 0.69015 0.6914925 -0.2133804 0.7803441 0.6120223 -0.1284207 0.7812938 0.6113259 -0.1259391 0.7719569 0.6226272 -0.1281328 0.7727775 0.6220667 -0.1258882 0.7646051 0.6317113 -0.1277492 0.7652124 0.6313242 -0.1260149 0.7584145 0.6391911 -0.1274453 0.7588828 0.6389108 -0.1260548 0.7535651 0.6449688 -0.1271024 0.753869 0.6447966 -0.1261707 0.7502106 0.6489047 -0.1269127 0.7504176 0.648792 -0.1262633 0.748701 0.6507002 -0.1266342 0.7487321 0.6506835 -0.1265354 0.7484866 0.6509571 -0.1265808 0.7484862 0.6509573 -0.1265816 0.7490295 0.6503428 -0.1265269 0.7489759 0.6503714 -0.1266965 0.7495212 0.6497579 -0.1266195 0.7495155 0.6497611 -0.1266378 0.748941 0.6504061 -0.1267253 0.7490097 0.6503693 -0.1265072 0.7473141 0.6522656 -0.1267725 0.7474277 0.6522063 -0.1264083 0.7448745 0.655044 -0.1268039 0.7450238 0.6549685 -0.1263164 0.7416077 0.6587363 -0.1268251 0.7417879 0.6586491 -0.1262226 0.7374386 0.6633996 -0.1268272 0.7376426 0.6633072 -0.1261234 0.7323681 0.6689962 -0.1268113 0.7325869 0.6689054 -0.1260247 0.7264024 0.6754776 -0.1267653 0.7266235 0.6753964 -0.1259288 0.7195094 0.6828169 -0.1267567 0.7197417 0.682745 -0.1258215 0.7116673 0.6909876 -0.1267511 0.7118931 0.6909345 -0.1257691 0.7028778 0.6999232 -0.1267688 0.7030919 0.6998931 -0.1257439 0.6931204 0.7095891 -0.1267574 0.6933055 0.7095859 -0.125759 0.6823694 0.7199245 -0.12681 0.6825351 0.7199503 -0.1257672 0.6706436 0.7308514 -0.126859 0.670773 0.7309051 -0.1258627 0.6575122 0.7426436 -0.1271147 0.6576253 0.7427427 -0.1259461 0.6315367 0.7646841 -0.128139 0.6316128 0.7650426 -0.125599 0.5764253 0.8067631 -0.1298738 0.5759577 0.8077342 -0.1258503 0.4827317 0.8655632 -0.1333053 0.4807957 0.8674262 -0.1280921 0.3737131 0.9172645 -0.1377112 0.3714898 0.9186624 -0.1343678 0.3359059 0.9316312 -0.1386744 0.3359894 0.9315847 -0.1387838 0.3817512 0.9144127 -0.1345931 0.3833368 0.9133796 -0.1370792 0.5015798 0.8555154 -0.1284962 0.5024895 0.8545418 -0.1313872 0.6188943 0.7752935 -0.1260552 0.6188982 0.7750416 -0.1275755 0.7006176 0.7023606 -0.1257959 0.7004666 0.7023772 -0.1265422 0.7967327 0.6008675 -0.06461828 0.7974136 0.600179 -0.06258529 0.7871896 0.6133542 -0.0642594 0.7877265 0.6128382 -0.06258153 0.7787126 0.6241082 -0.06399679 0.7791544 0.623703 -0.06255418 0.7715779 0.6329317 -0.06375807 0.7719082 0.6326408 -0.06263571 0.7659391 0.6397694 -0.0635007 0.7661582 0.6395831 -0.06273126 0.7620597 0.6444093 -0.0632584 0.7621807 0.6443089 -0.06282323 0.7602165 0.6465935 -0.06314849 0.760271 0.6465488 -0.06294995 0.7599627 0.6469032 -0.06303155 0.7599431 0.6469192 -0.0631029 0.7605539 0.6462096 -0.06301617 0.7605249 0.6462334 -0.06312179 0.761141 0.6455078 -0.06311941 0.7611444 0.645505 -0.06310737 0.7605242 0.6462303 -0.06316137 0.7605594 0.6462014 -0.06303304 0.758679 0.648388 -0.06323951 0.7587682 0.6483155 -0.06291115 0.7559094 0.6516166 -0.06322073 0.7560013 0.6515433 -0.06287622 0.7521805 0.6559171 -0.06322425 0.7523017 0.6558228 -0.06275814 0.7474045 0.6613522 -0.06324243 0.7475495 0.6612432 -0.06266587 0.7415824 0.667875 -0.06323337 0.7417343 0.6677658 -0.06260311 0.7347121 0.675427 -0.06321811 0.7348687 0.6753204 -0.06253206 0.7267745 0.6839649 -0.06317478 0.7269251 0.6838696 -0.06246918 0.7177141 0.6934646 -0.0631935 0.7178711 0.6933745 -0.062393 0.7075428 0.7038414 -0.063169 0.7076791 0.7037734 -0.06239664 0.6962133 0.7150499 -0.06317305 0.6963364 0.7150002 -0.06237316 0.6837195 0.726999 -0.06324648 0.6838289 0.7269694 -0.06239789 0.6700495 0.7396136 -0.06328809 0.6701284 0.7396085 -0.06250762 0.6547505 0.753172 -0.06351113 0.6548146 0.7531938 -0.06258481 0.6245333 0.7783465 -0.06430292 0.6245422 0.7784968 -0.06236678 0.5598968 0.8259456 -0.06579786 0.5594633 0.8264837 -0.06265634 0.449366 0.8906841 -0.06893503 0.4477571 0.8918046 -0.06479376 0.3204184 0.9444591 -0.07300078 0.3186644 0.9452496 -0.07040101 0.2756452 0.9584078 -0.07398974 0.2757288 0.9583752 -0.07409846 0.3296456 0.9414656 -0.07054358 0.330876 0.9408897 -0.07243967 0.4709377 0.8797622 -0.06508523 0.4716893 0.8791898 -0.06733965 7.28585e-6 1.08621e-5 -1 -0.8191649 0.573558 3.47442e-7 -5.04933e-6 7.21156e-6 -1 -0.5735554 0.819164 -0.002123713 -7.77305e-6 4.48782e-6 -1 -0.6835545 0.7298996 4.42148e-7 -0.3581179 0.9335708 -0.01403653 -0.4993295 0.8663817 -0.007271826 -0.636164 0.7715531 -0.001138627 -3.30614e-6 8.85918e-7 -1 -0.9659229 0.2588302 0 6.41091e-5 4.80876e-5 -1 0 0 -1 0 0 -1 -0.8934404 0.4491817 0 -0.8593913 0.5113174 -0.001122653 -0.8178657 0.5753986 -0.003474354 -0.878708 0.4773595 -4.11063e-4 -0.7565946 0.6538164 -0.009415626 -7.03788e-6 -6.1585e-7 -1 -0.9961933 -0.08717197 0 4.02067e-7 4.59412e-6 -1 -0.9659229 0.2588302 0 2.70277e-5 2.70279e-5 -1 -0.9063079 -0.4226182 0 5.61121e-6 1.20333e-5 -1 -0.9961926 -0.08717846 2.16726e-7 -0.7071035 -0.70711 -1.68588e-7 -0.9063104 -0.4226128 0 -0.4226182 -0.9063079 -2.16081e-7 -0.7071035 -0.70711 -1.68588e-7 -0.08718436 -0.9961922 -2.37511e-7 -0.4226182 -0.9063079 -2.16081e-7 0 0 -1 0.2588379 -0.9659208 -2.30293e-7 -2.75039e-5 -1.07899e-5 -1 -0.08718436 -0.9961922 -2.37511e-7 -5.04938e-6 7.21161e-6 -1 0.5735567 -0.8191631 -0.002124667 1.53349e-5 1.02861e-5 -1 0 0 -1 0.2588379 -0.9659208 -2.30293e-7 0.4609841 -0.8874084 -2.11575e-7 7.28586e-6 1.08622e-5 -1 0.8191628 -0.5735611 -3.47444e-7 -7.7732e-6 4.48779e-6 -1 0.3580748 -0.9335873 -0.01403993 0.4993907 -0.8663464 -0.007270038 0.6361486 -0.7715657 -0.001139998 0.6835557 -0.7298984 -4.42463e-7 -3.30611e-6 8.85939e-7 -1 0.9659208 -0.2588379 0 6.41164e-5 4.80928e-5 -1 0 0 -1 0 0 -1 0.8934638 -0.4491352 0 0.7565962 -0.6538146 -0.009415805 0.8594092 -0.5112873 -0.001121401 0.8178723 -0.5753895 -0.003473877 0.8785657 -0.4776216 -4.15826e-4 -7.03792e-6 -6.15892e-7 -1 0.9961929 0.08717733 0 4.02001e-7 4.59406e-6 -1 0.9659208 -0.2588379 0 2.70277e-5 2.70279e-5 -1 0.9063079 0.4226182 0 5.61121e-6 1.20333e-5 -1 0.9961929 0.08717733 0 0.7071035 0.70711 1.68588e-7 0.9063079 0.4226182 0 0.4226182 0.9063079 2.16081e-7 0.7071035 0.70711 1.68588e-7 0.08717137 0.9961933 2.37511e-7 0.4226182 0.9063079 2.16081e-7 -2.05349e-6 7.66338e-6 -1 -0.2588302 0.9659229 2.30294e-7 6.32135e-6 1.09489e-5 -1 0.08717137 0.9961933 2.37511e-7 -4.23456e-6 7.33445e-6 -1 0 1.01748e-5 -1 -0.2588302 0.9659229 2.30294e-7 -0.4610134 0.8873931 2.11571e-7 0.500001 -0.8660249 -2.06476e-7 0.8660231 -0.5000039 -1.1921e-7 0.8660231 -0.5000039 -1.1921e-7 9.21175e-6 -1 -2.38419e-7 0.500001 -0.8660249 -2.05782e-7 -0.500001 -0.8660249 -2.06476e-7 9.21175e-6 -1 -2.38419e-7 -0.8660295 -0.499993 -2.38415e-7 -0.5000079 -0.8660209 -4.12951e-7 -1 0 0 -0.8660271 -0.499997 0 -0.8660288 0.4999941 0 -1 0 0 -0.499993 0.8660295 2.06477e-7 -0.8660288 0.4999941 0 0 1 2.38419e-7 -0.499993 0.8660295 2.06477e-7 0.5000119 0.8660185 2.06475e-7 0 1 2.38419e-7 0.8660231 0.5000039 2.3842e-7 0.500005 0.8660225 4.12952e-7 1 -9.21183e-6 0 0.8660254 0.5 0 1 -9.21183e-6 0 4.84754e-6 -6.92328e-6 1 -0.5735611 0.8191629 0 -2.17776e-6 -1.44388e-5 1 -0.8191616 0.5735602 0.00173366 4.48782e-6 -7.77311e-6 1 -0.9912634 0.1287614 0.02858853 -0.9638335 0.2656313 0.02157068 -0.8286886 0.5596889 0.00484693 -0.7850836 0.6193873 0.001776397 -0.7504184 0.6609631 4.89315e-4 -0.7221366 0.6917504 0 8.85917e-7 -3.30614e-6 1 -3.5786e-5 -5.56825e-5 1 -1.99914e-5 -3.46253e-5 1 0 -1.01748e-5 1 -0.6468507 0.7625685 0.008569538 -0.5510272 0.8344846 0.002117872 -6.15848e-7 -7.0379e-6 1 4.59407e-6 4.0203e-7 1 0 0 1 -1.49948e-5 -2.14169e-5 1 0 0 1 0 0 1 -2.17778e-6 -1.44388e-5 1 0.8191615 -0.5735602 0.001734077 0 0 1 0 0 1 0 0 1 0.573558 -0.8191649 0 -8.99912e-6 -2.12601e-5 1 0.7221103 -0.691778 0 0.9912407 -0.1289378 0.02857995 0.9638834 -0.2654489 0.02158051 0.8287063 -0.5596626 0.004849135 0.7850049 -0.6194871 0.001771986 0.7505183 -0.6608495 4.91549e-4 8.8594e-7 -3.30611e-6 1 -3.57849e-5 -5.56808e-5 1 7.23938e-5 8.85408e-5 1 0 0 1 0.646843 -0.762575 0.008569002 0.5510345 -0.8344798 0.002118289 -6.15949e-7 -7.038e-6 1 4.59409e-6 4.02037e-7 1 0 0 1 -1.49947e-5 -2.14167e-5 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.7387027 -0.6240398 -0.2547405 -0.6197143 -0.6197062 -0.481579 -0.7945364 -0.6032962 -0.06888794 -0.7035477 -0.6377044 -0.3136142 -0.7786459 -0.6102126 -0.1461204 -0.7052088 -0.7052721 0.07260656 -0.8124459 -0.5829879 0.007533729 -0.801564 -0.5958421 -0.0496717 -0.7051738 -0.7053077 0.07260167 -0.7051466 -0.7053346 0.07260382 -0.7051477 -0.7053336 0.07260394 -0.8216065 -0.5065032 0.2615668 -0.7047814 -0.7057096 0.07250708 -0.8271973 -0.5481703 0.1235069 -0.8265091 -0.5502392 0.1188253 -0.07461965 0.2527787 0.9646424 -0.8215268 -0.5076957 0.2594972 -0.7312266 -0.2983458 0.613431 0.6196941 0.6197097 0.4816005 0.3398155 0.525156 0.7802157 0.6197235 0.619721 0.4815482 0.6197627 0.6196561 0.4815811 0.6197115 0.6197075 0.481581 0.619705 0.6197082 0.4815886 -0.619706 -0.6197116 0.4815828 -0.6197158 -0.619718 0.4815621 -0.6197053 -0.6197121 0.4815831 -0.6197071 -0.619712 0.4815811 -0.6197088 -0.6197085 0.4815832 -0.7052406 -0.7052406 -0.07260507 -0.7053957 -0.7050859 -0.07260024 0.6197034 0.6197034 -0.4815968 -0.7052407 -0.7052407 -0.07260125 0.6199865 0.6194247 -0.481591 0.6197153 0.6197149 -0.4815666 0.6197117 0.6196995 -0.4815912 -0.6197152 -0.6197069 -0.481577 -0.6197543 -0.6196603 -0.4815866 -0.6197137 -0.6197009 -0.4815866 0.7387024 0.6240437 -0.2547319 0.6197113 0.6197113 -0.4815764 0.7945311 0.6033015 -0.06890368 0.6738271 0.6461821 -0.3583375 0.7525894 0.6226474 -0.2142879 0.7829896 0.6088725 -0.1272858 0.7052035 0.7052772 0.07260942 0.8122752 0.5832242 0.00765109 0.7964703 0.6013124 -0.06370556 0.8101316 0.5861715 -0.009471476 0.7052256 0.7052563 0.0725978 0.7051995 0.7052811 0.07260924 0.7051513 0.70533 0.07260435 0.8196486 0.5094613 0.2619645 0.705153 0.7053307 0.07258027 0.8253728 0.5511231 0.122569 0.8275167 0.5325608 0.1777499 0.08320587 -0.2591043 0.9622586 0.819246 0.4917362 0.2950111 0.7710923 0.36478 0.5218739 -0.6197099 -0.6197158 0.4815724 -0.4722442 -0.5791018 0.66455 0.3223111 -0.05477732 0.9450476 0.6196793 0.619737 0.4815843 0.7052077 0.7052735 -0.07260423 0.7053581 0.7051236 -0.07259964 -0.619707 -0.619707 -0.4815876 0.7052408 0.7052408 -0.07260042 -0.8210923 -0.5663011 -0.07148748 -0.6197089 -0.6197116 0.4815791 -0.61971 -0.6197113 0.481578 -0.6197098 -0.6197114 0.4815781 -0.6197066 -0.6197134 0.4815798 -0.6197098 -0.6197108 0.4815791 -0.6197084 -0.6197121 0.481579 -0.7520723 -0.6153445 0.2360897 -0.7538459 -0.6142585 0.2332442 -0.8210837 -0.5663229 -0.07141375 -0.8210849 -0.5663211 -0.07141518 -0.82108 -0.5663302 -0.07139873 -0.8210877 -0.5663166 -0.07141929 -0.8210809 -0.5663305 -0.07138532 -0.821092 -0.5663034 -0.07147407 -0.8210838 -0.5663226 -0.07141548 -0.8210614 -0.5663736 -0.07126748 -0.8210801 -0.5663315 -0.07138758 -0.821092 -0.5663056 -0.07145535 -0.8210834 -0.5663234 -0.07141321 -0.4846062 -0.5659946 0.6669386 -0.4761807 -0.5104435 0.7160303 -0.5219079 -0.5790489 0.6263503 -0.5157269 -0.4775448 0.7113205 -0.5643524 -0.5637287 0.6030889 -0.5868108 -0.5196151 0.6210099 -0.5898385 -0.3970866 0.703145 -0.5950804 -0.5346247 0.6000466 -0.6197119 -0.6197104 0.4815767 -0.6323623 -0.5070878 0.5856449 -0.6197073 -0.6197133 0.4815793 -0.6626586 -0.3508808 0.661639 -0.6326664 -0.5122236 0.5808272 -0.6197106 -0.6197109 0.4815779 -0.6717317 -0.4397454 0.5961548 -0.6197058 -0.6197146 0.4815791 -0.6958257 -0.3597394 0.6216222 -0.6684109 -0.4630076 0.5821091 -0.61972 -0.6197023 0.4815768 -0.6984227 -0.3762695 0.6087914 -0.6197026 -0.6197187 0.4815781 -0.6968204 -0.3867722 0.604027 -0.6197139 -0.6197088 0.4815762 -0.6950866 -0.3737093 0.6141628 -0.6197084 -0.6197127 0.4815781 -0.7007498 -0.3635275 0.6138383 -0.6197017 -0.6197184 0.4815797 -0.6738584 0.04141515 0.7376989 -0.6197047 -0.6197158 0.481579 -0.6626764 -0.4218207 0.6188113 -0.6979965 -0.2779961 0.6599388 -0.6197066 -0.6197142 0.4815787 -0.5468616 0.0885806 0.8325237 -0.6197109 -0.6197102 0.4815784 -0.6209973 -0.4639908 0.6317238 -0.6031391 -0.08691066 0.7928869 -0.6197125 -0.6197086 0.4815782 -0.5414964 -0.2818303 0.7920564 -0.6197162 -0.6197064 0.4815763 -0.5821406 -0.493574 0.6461401 -0.6197083 -0.619713 0.4815781 -0.5784636 -0.3803018 0.7216304 -0.6197038 -0.6197175 0.4815781 -0.5639821 -0.495246 0.6607992 -0.5331519 -0.4137082 0.7379665 -0.6197093 -0.6197122 0.4815777 -0.5494787 -0.4920688 0.6752343 -0.6197034 -0.6197171 0.481579 -0.5510016 -0.506805 0.6629827 -0.6197093 -0.6197123 0.4815777 -0.541473 -0.4817758 0.6889841 -0.6197078 -0.6197133 0.4815784 -0.5335493 -0.4933164 0.6869964 -0.619708 -0.619713 0.4815783 -0.5403912 -0.5146847 0.6656404 -0.5414766 -0.5026428 0.673909 -0.6197097 -0.6197115 0.4815781 -0.5389268 -0.5246002 0.6590543 -0.619709 -0.6197121 0.4815784 -0.5283822 -0.5027583 0.6841391 -0.6197099 -0.6197113 0.4815781 -0.535111 -0.5319075 0.6563007 -0.520463 -0.5090483 0.6855568 -0.6197085 -0.6197124 0.4815785 -0.5305519 -0.5387101 0.654451 -0.6197102 -0.6197109 0.4815782 -0.5147324 -0.5165672 0.6842579 -0.6197062 -0.6197147 0.4815787 -0.5232869 -0.5433036 0.6564998 -0.5115516 -0.5251109 0.6801275 -0.619714 -0.6197072 0.4815784 -0.520882 -0.5514007 0.6516435 -0.6197087 -0.6197119 0.4815789 -0.508533 -0.5404177 0.6703305 -0.5152798 -0.5377884 0.6672859 -0.6197057 -0.6197152 0.4815784 -0.5145577 -0.5555788 0.6531174 -0.6197093 -0.6197121 0.4815781 -0.498725 -0.5401892 0.6778415 -0.6197084 -0.6197123 0.4815788 -0.5104188 -0.5596755 0.6528675 -0.6197091 -0.6197116 0.4815787 -0.4971247 -0.5496015 0.6714203 -0.5061851 -0.5509142 0.6635287 -0.6197137 -0.6197081 0.4815773 -0.4968919 -0.5563495 0.6660133 -0.6197066 -0.619714 0.481579 -0.6197088 -0.6197119 0.4815788 -0.4972053 -0.5531845 0.6684114 -0.6197075 -0.6197139 0.4815779 -0.4954527 -0.5565912 0.666883 -0.619706 -0.6197151 0.4815784 -0.6197133 -0.6197087 0.4815773 -0.495442 -0.5564268 0.667028 -0.5100637 -0.5631698 0.6501345 -0.6197086 -0.6197118 0.4815792 -0.4936781 -0.5552517 0.6693112 -0.6197152 -0.6197062 0.4815779 -0.4926958 -0.5545697 0.6705992 -0.4918716 -0.5545302 0.6712366 -0.486693 -0.5519922 0.677078 -0.6197081 -0.6197127 0.4815787 -0.5064715 -0.5666153 0.649949 -0.6197075 -0.6197133 0.4815788 -0.6197068 -0.6197139 0.4815788 -0.4889162 -0.5540469 0.67379 -0.4954829 -0.5561532 0.6672258 -0.6197091 -0.6197121 0.4815783 -0.5074554 -0.5755209 0.6412993 -0.6197095 -0.6197118 0.4815781 -0.6197065 -0.6197146 0.4815783 -0.4815521 -0.558992 0.6750078 -0.5014584 -0.5643531 0.6557783 -0.6197082 -0.619713 0.4815784 -0.5015907 -0.5830707 0.6390895 -0.6197087 -0.6197126 0.4815782 -0.4770243 -0.5708981 0.6682237 -0.4866343 -0.5677918 0.6639273 -0.6197066 -0.6197119 0.4815816 -0.4899546 -0.5894981 0.6422123 -0.6197304 -0.6196982 0.4815688 -0.6197116 -0.6197099 0.4815776 -0.6197211 -0.6197035 0.4815738 -0.6196824 -0.6197319 0.4815871 -0.6197108 -0.6197098 0.481579 -0.4588521 -0.5722508 0.6796938 -0.001962661 -0.9533601 0.3018288 -0.3811589 -0.8336353 0.3997127 -0.4760141 -0.5862385 0.6555418 -0.07685196 -0.9568609 0.2801982 -0.2512893 -0.9326189 0.2589897 -0.07416468 -0.9629803 0.2591688 -0.4020177 -0.8841601 0.2379971 -0.2928979 -0.9305269 0.219842 -0.5304563 -0.8245545 0.1967892 -0.6156992 -0.7582153 0.2145323 -0.5140517 -0.8298847 0.2168923 -0.6207842 -0.7682771 0.1561328 -0.637004 -0.7403366 0.2147732 -0.6210455 -0.7579354 0.1995906 -0.6396308 -0.7406135 0.205825 -0.6409738 -0.7373657 0.2131767 -0.6393411 -0.7401337 0.2084351 -0.6405556 -0.7376551 0.2134323 -0.6408345 -0.7378013 0.212086 -0.6422696 -0.7357902 0.2147153 -0.6408252 -0.7377822 0.2121801 -0.6442262 -0.7353787 0.2102164 -0.6478345 -0.730831 0.2149336 -0.6449645 -0.7362481 0.2048403 -0.6527459 -0.7278568 0.2101132 -0.6583492 -0.7213746 0.2149299 -0.6549895 -0.729278 0.1978443 -0.6672143 -0.7151585 0.2082627 -0.6760225 -0.7031012 0.2205499 -0.6712909 -0.7165861 0.1894018 -0.6901477 -0.6956363 0.1994652 -0.6999873 -0.6783583 0.223266 -0.6923962 -0.695946 0.1903852 -0.7142392 -0.6645309 0.2196842 -0.7169964 -0.6727849 0.1824187 -0.7319678 -0.649405 0.2061462 -0.7418757 -0.6311438 0.2264463 -0.7371899 -0.647723 0.1923694 -0.7597252 -0.6220012 0.1895574 0.6197091 0.6197141 -0.4815754 0.6711478 0.6326791 -0.3863648 0.6816915 0.6375168 -0.3589832 0.6197076 0.619713 -0.4815791 -0.8210802 -0.566332 -0.07138109 0.6197242 0.6197464 -0.4815146 0.6197084 0.6197109 -0.4815806 -0.8210836 -0.5663224 -0.07141995 -0.8210828 -0.5663278 -0.0713846 -0.8210879 -0.5663081 -0.07148343 -0.8210871 -0.5663107 -0.07147127 -0.8210768 -0.566344 -0.07132583 -0.8210886 -0.5663097 -0.07146245 0.6197094 0.6197112 -0.481579 -0.08546727 0.3011156 -0.9497498 0.6196874 0.6197486 -0.4815592 0.6197244 0.6196877 -0.4815897 0.6197062 0.6197167 -0.481576 0.6197031 0.6197213 -0.4815741 0.6197215 0.6196954 -0.4815837 0.6197108 0.6197091 -0.4815798 0.619705 0.6197157 -0.4815789 0.6197003 0.6197202 -0.4815792 0.6197162 0.6197081 -0.4815742 -0.8210852 -0.5663204 -0.07141757 -0.6096023 -0.04770517 -0.7912707 0.6197094 0.6197116 -0.4815785 -0.067649 0.2077465 -0.9758407 0.6197066 0.6197153 -0.4815773 0.6197155 0.6197039 -0.4815805 0.6197178 0.619701 -0.4815811 0.6196946 0.6197279 -0.4815766 0.6197168 0.6197034 -0.4815794 0.619709 0.6197118 -0.481579 -0.5209568 -0.09034627 -0.8487883 0.6197066 0.6197144 -0.4815784 -0.05903279 0.1006901 -0.993165 0.6197097 0.6197105 -0.4815795 0.6197075 0.619713 -0.481579 0.6197016 0.6197195 -0.4815783 0.6197092 0.6197118 -0.4815785 -0.4509449 -0.1620686 -0.8777143 0.6197122 0.6197081 -0.4815795 -0.03100854 0.007005691 -0.9994946 0.6197049 0.6197164 -0.481578 0.6197091 0.6197121 -0.4815783 -0.4276972 -0.2877544 -0.856897 0.619704 0.619717 -0.4815785 0.007530093 -0.0648356 -0.9978675 0.6197081 0.6197123 -0.4815794 0.6197124 0.6197078 -0.4815795 -0.3792129 -0.3905671 -0.8388414 0.6197113 0.6197102 -0.4815778 -0.01886707 -0.1834324 -0.9828513 0.6197116 0.6197099 -0.4815778 -0.2513565 -0.3983982 -0.8820992 0.6197081 0.6197127 -0.4815785 -0.0629217 -0.2966327 -0.9529165 0.6197069 0.6197141 -0.4815785 0.6197109 0.6197103 -0.4815782 0.02390515 -0.246173 -0.968931 0.6197105 0.6197108 -0.4815782 -0.1081017 -0.350314 -0.9303731 0.6197092 0.6197114 -0.481579 -0.1007916 -0.4136699 -0.9048305 0.619708 0.6197128 -0.4815786 0.6197101 0.6197102 -0.4815794 0.01818054 -0.2986764 -0.9541812 0.6197094 0.6197113 -0.481579 -0.001889705 -0.2965177 -0.9550254 0.6197074 0.6197132 -0.4815789 0.017632 -0.3028106 -0.9528877 0.007855176 -0.3123884 -0.9499219 0.6197094 0.6197109 -0.4815795 0.0168699 -0.3012625 -0.953392 0.6197078 0.6197129 -0.4815788 0.6197072 0.619713 -0.4815794 -0.07649362 -0.4221639 -0.9032865 0.6197097 0.6197119 -0.4815776 0.06641161 -0.3137297 -0.947187 0.6197122 0.6197092 -0.4815779 0.01323062 -0.3147176 -0.9490931 0.61971 0.6197099 -0.4815799 -0.320127 -0.7577974 -0.5685613 0.6197053 0.6197156 -0.4815787 0.6197127 0.6197069 -0.4815804 0.3195291 -0.4669959 -0.8245096 0.6197107 0.6197094 -0.4815797 0.08201974 -0.3402857 -0.9367382 0.6196773 0.6197488 -0.4815719 0.6306403 -0.4204499 -0.652315 0.3090924 -0.5796534 -0.7539656 0.6197128 0.6197084 -0.4815782 0.7904865 -0.3415108 -0.5084307 0.6570977 -0.5406753 -0.525255 0.6197766 0.6196381 -0.4815866 0.8649533 -0.3383213 -0.3706675 0.800184 0.3569937 -0.4819347 0.865199 -0.2872006 -0.4110312 0.911361 -0.1847243 -0.3678287 0.8367054 -0.4811359 -0.261596 0.9085448 -0.1894474 -0.3723655 0.6865109 0.6250447 -0.3715131 0.6912644 0.62436 -0.3637694 0.6813446 0.6304001 -0.3719747 0.6934871 0.6281758 -0.3528044 0.6763707 0.635089 -0.3730746 0.6858155 0.6316975 -0.3614074 0.684402 0.635074 -0.3581549 0.6779378 0.6400426 -0.3615882 0.6817312 0.6376703 -0.3586351 0.6774667 0.6415788 -0.3597438 0.6717883 0.6375533 -0.377129 0.6778004 0.6408911 -0.3603402 0.6774187 0.641574 -0.3598428 0.6778035 0.6414534 -0.3593327 0.6781467 0.6419021 -0.3578809 0.6776669 0.6414617 -0.3595757 0.6730678 0.6417552 -0.3676003 0.676096 0.6407292 -0.3638134 0.6773326 0.641416 -0.360286 0.6770788 0.6421955 -0.3593735 0.6702322 0.6444127 -0.3681321 0.6746926 0.6426763 -0.3629835 0.6759291 0.6449043 -0.3566769 0.6666666 0.6476368 -0.3689475 0.6718564 0.6455478 -0.3631491 0.6725517 0.6487607 -0.356067 0.6655427 0.6529514 -0.3615345 0.6698468 0.6509225 -0.3572185 0.6602289 0.6556121 -0.3664293 0.6642526 0.651617 -0.3662838 0.6652628 0.6574384 -0.3538367 0.6568942 0.6596717 -0.3651345 0.6623785 0.6613409 -0.3519703 0.6535711 0.6634836 -0.36419 0.6586704 0.6651836 -0.3516876 0.6504208 0.6671265 -0.3631737 0.6546523 0.6694325 -0.3511274 0.6480391 0.6716904 -0.3589947 0.6500186 0.6735293 -0.3519005 0.6450625 0.6747674 -0.3585852 0.6405934 0.6761392 -0.3639724 0.6453893 0.6792814 -0.3493558 0.6357295 0.6927376 -0.3405327 0.6250402 0.6883731 -0.3680587 0.6357745 0.6917499 -0.3424512 0.6036107 0.7438218 -0.2870249 0.6020033 0.7074918 -0.370199 0.6122158 0.7188009 -0.3294196 0.5655539 0.7647131 -0.3088089 0.5727981 0.7279031 -0.3769075 0.5446701 0.7954006 -0.2658426 0.5362683 0.7683834 -0.3492897 0.544073 0.7487545 -0.3786177 0.5205192 0.7875835 -0.3298059 0.5377646 0.756099 -0.3729926 0.5437641 0.754029 -0.3684571 0.5374073 0.7565487 -0.3725953 0.5579891 0.7460809 -0.3633337 0.5717694 0.7161573 -0.4002482 0.5819828 0.7242599 -0.3697884 0.6119808 0.6673117 -0.4244699 0.6185821 0.7024255 -0.3520719 0.5954472 0.7083153 -0.3791204 0.6311498 0.6574412 -0.411608 0.6547963 0.6680611 -0.3534631 0.6302067 0.6837642 -0.3678396 0.6755751 0.6542582 -0.3399186 0.6506392 0.6510655 -0.390874 0.8185522 0.5725045 0.04701948 0.8210826 0.5663242 0.07141655 0.8210845 0.5663217 0.07141327 0.8177236 0.5739763 0.04334926 0.8227909 0.5614035 0.08855044 0.8246286 0.5563923 0.1020553 0.7996051 0.5962127 0.07184755 0.7932842 0.6051394 0.06712871 0.7919241 0.6084758 0.05112212 0.7898469 0.6046441 0.1027005 0.7969768 0.6024221 0.04376721 0.8297256 0.5533427 0.07326102 0.8329319 0.5432714 0.1052643 0.8307274 0.5521104 0.07117748 0.5819708 -0.8131226 -0.0119006 0.5442599 -0.8388063 0.01360857 0.8112123 0.5798535 0.07552844 0.8103939 0.5820437 0.06698453 0.8145041 0.5759417 0.06981635 0.8310341 0.5531989 0.05790728 0.8235826 0.5545907 0.1189151 0.7985905 0.5979053 0.06901019 0.8010172 0.5894423 0.1045431 0.7987428 0.5977276 0.06878834 0.8100395 0.5779553 0.09901356 0.793168 0.6046933 0.07232266 0.7948073 0.5988063 0.09855079 0.7999808 0.5890215 0.1143874 0.7878575 0.6115768 0.07248783 0.7898625 0.6028727 0.1125255 0.7893589 0.6097298 0.07170981 0.7830958 0.617655 0.07254904 0.7844698 0.6119474 0.1006354 0.7850245 0.615298 0.07172858 0.7903405 0.6033912 0.1062126 0.7790654 0.622735 0.07251274 0.7802752 0.617393 0.09998285 0.7811624 0.6201834 0.07181745 0.783062 0.6121016 0.1102076 0.7759367 0.6266406 0.07241356 0.7771472 0.6206811 0.1039093 0.7779311 0.6242166 0.07195085 0.7777365 0.6193504 0.1073834 0.7741148 0.6289064 0.07227081 0.7752705 0.6229299 0.1044696 0.7754528 0.6272745 0.07210904 0.7734077 0.6297777 0.07225358 0.7744947 0.6241843 0.1027218 0.7738652 0.6292291 0.07213538 0.7751822 0.62294 0.1050636 0.7735012 0.6296699 0.0721932 0.7745902 0.6240963 0.1025375 0.7733427 0.6298606 0.07222652 0.7743017 0.6286897 0.07215452 0.775359 0.6235578 0.09997028 0.7736456 0.6294845 0.07226115 0.7749541 0.6241846 0.09919506 0.7750176 0.6278037 0.07218331 0.7760211 0.6231614 0.09726828 0.774473 0.6284681 0.07224458 0.775286 0.6274697 0.07220393 0.7764463 0.6217816 0.1025615 0.7750852 0.6277157 0.07222157 0.7756093 0.6228506 0.1024073 0.7751092 0.6276866 0.07221728 0.7762952 0.6217519 0.1038771 0.7752825 0.6274742 0.07220196 0.7762556 0.6218267 0.1037247 0.7745583 0.6283639 0.0722382 0.775735 0.6223461 0.1045012 0.7750644 0.6277448 0.0721926 0.7734531 0.6297159 0.07230508 0.7745168 0.6243132 0.1017684 0.7734988 0.6296637 0.07227128 0.7744598 0.6284913 0.07218557 0.775646 0.6223463 0.1051585 0.7716753 0.63189 0.0723353 0.7726811 0.6264849 0.1023744 0.7719404 0.6315878 0.07214397 0.7733716 0.6250157 0.1060747 0.7694016 0.6346521 0.07237333 0.770332 0.6292197 0.1033008 0.7697021 0.6343113 0.07216501 0.7666723 0.6379402 0.07242882 0.7674505 0.633126 0.1008532 0.7670434 0.6375216 0.07218581 0.7697812 0.629221 0.1073216 0.7635111 0.6417122 0.07249963 0.7642467 0.6353178 0.1108984 0.7640157 0.6411459 0.07219362 0.760006 0.6458516 0.07257193 0.7605311 0.6412193 0.1021278 0.7606788 0.6451007 0.07220077 0.7649026 0.6355689 0.1047669 0.7561366 0.6503683 0.07265281 0.7565025 0.6460541 0.1015789 0.7570804 0.649321 0.07219135 0.7586888 0.6418919 0.1112035 0.7518522 0.6558541 0.06763052 0.7521255 0.6505113 0.1055564 0.7493196 0.6583337 0.0715329 0.7474946 0.6604065 0.07151943 0.7475341 0.6565541 0.1006458 0.7509898 0.6507501 0.1119756 0.7380307 0.670678 0.07417267 0.7380092 0.6702017 0.07856315 0.7419245 0.6614018 0.1099802 0.7227377 0.6872241 0.07330214 0.7223255 0.6860671 0.08693528 0.7229422 0.6870365 0.07304465 0.7365081 0.672576 0.07209116 0.731173 0.6725434 0.1143306 0.7071119 0.7032245 0.07394552 0.7054181 0.701362 0.1023564 0.7092048 0.7013153 0.0720098 0.7195219 0.6865935 0.104296 0.6918167 0.7182603 0.07410603 0.6897791 0.7172276 0.09894096 0.695605 0.7148546 0.07153016 0.7064713 0.701157 0.09631836 0.6902159 0.715247 0.1096522 0.6771867 0.7320829 0.07397848 0.6734787 0.7312426 0.1082159 0.6823744 0.7275085 0.07139033 0.6634165 0.7446136 0.07368284 0.6601603 0.7445349 0.09927904 0.669657 0.7392272 0.0714336 0.6733046 0.7313011 0.1089024 0.6506925 0.7557922 0.07333099 0.647445 0.7561075 0.09547996 0.6576476 0.7499174 0.07158041 0.6526766 0.7478505 0.121379 0.6380566 0.7665056 0.07316368 0.6287666 0.7673995 0.1255016 0.6463775 0.7596419 0.07169657 0.6167281 0.7838575 0.07220685 0.6125469 0.7849581 0.09288221 0.6139836 0.7858748 0.07365411 0.6343452 0.7697298 0.07156932 0.6327885 0.7659785 0.1133835 0.5751951 0.81458 0.07490026 0.5756449 0.8144156 0.07321196 0.5838055 0.8087339 0.07155847 0.5767812 0.7998536 0.1660051 0.5135304 0.8547846 0.07503187 0.4729802 0.8635171 0.1750085 0.5441859 0.8361334 0.06886786 0.4389333 0.8956704 0.0714994 0.4406213 0.8951025 0.0681495 0.4428712 0.8938174 0.07039594 0.4965956 0.8652381 0.06896227 0.4764555 0.8627603 0.1692187 0.3541241 0.9325498 0.07033431 0.1852298 0.9345933 0.3036865 0.3852825 0.9204839 0.06532174 0.2649542 0.9619327 0.06696915 0.2674943 0.9614443 0.06380963 0.3150045 0.9470727 0.06185007 0.2827496 0.9382866 0.1991754 0.1943296 0.9789113 0.06299817 0.06695395 0.9782075 0.1965383 0.2379284 0.9694818 0.05911844 0.1539738 0.9862588 0.05988061 0.1358384 0.9876413 0.07818406 0.1772429 0.9824939 0.0573641 0.1144132 0.9809994 0.1566839 0.1427726 0.9880486 0.05810433 0.1053471 0.9898835 0.09504073 0.1456225 0.9876595 0.05764424 0.157299 0.9858176 0.05848628 0.1191509 0.9881309 0.09695583 0.1524388 0.9865199 0.05950641 0.1277375 0.9887739 0.07752102 0.2002989 0.9778982 0.05996096 0.2010411 0.9777953 0.0591498 0.1955838 0.9787869 0.0610184 0.2742701 0.9597082 0.06112354 0.2268894 0.9665443 0.1196377 0.2613977 0.9631195 0.06381297 0.2662485 0.963896 0.004040956 0.3743545 0.9251989 0.06217408 0.3841296 0.9221157 0.04633641 0.341275 0.9375012 0.06799209 0.4779086 0.8760382 0.06450128 0.444766 0.8851767 0.1365481 0.4247834 0.9024755 0.07139408 0.4559002 0.889282 -0.03650534 0.5718468 0.8174071 0.06954813 0.5780397 0.8147044 0.04611665 0.5750051 0.8152973 0.06826055 0.5020878 0.8617853 0.07234644 0.6574739 0.7505126 0.06677514 0.6428702 0.7490872 0.1599571 0.63953 0.7652171 0.07378387 0.5949337 0.8037293 0.008553206 0.7307441 0.6794645 0.06588822 0.7279502 0.6706371 0.1425987 0.6989443 0.711079 0.07644319 0.7056386 0.7084839 0.01116895 0.7522951 0.6544479 0.07582843 0.7499867 0.6612571 0.01609081 0.7903816 0.6012424 0.1174934 0.6936894 0.7069481 0.1379116 0.6468894 0.7622854 0.02133095 0.7016334 0.7048929 0.1040986 0.5409259 0.8213919 0.1808716 0.5215846 0.852947 0.0207588 0.560324 0.8160818 0.1415885 0.4062643 0.9076241 0.1056777 -0.04406917 0.8458644 0.5315747 0.290218 0.9565522 0.02795374 0.4008561 0.9138498 0.06475299 0.07865208 0.9797827 0.1839562 0.1874267 0.9819882 0.02388471 0.2086442 0.9754995 0.06977313 0.1711413 0.9847253 0.03204196 0.1671274 0.985199 0.03809577 0.2016837 0.9789412 0.03158813 0.3698714 0.9233779 -0.1028038 0.3302384 0.9430215 0.04065626 0.2328812 0.9720896 0.02842891 0.4677036 0.8800299 -0.08246743 0.4509654 0.8909071 0.05398833 0.4359633 0.898938 -0.04297256 0.515777 0.8564985 0.01960813 0.5876935 0.8037455 -0.09278798 0.5898673 0.8061509 0.04666185 0.5289114 0.8479773 0.03445732 0.6320255 0.7741182 -0.0358451 0.6385493 0.7682803 0.04472196 0.6070202 0.7935858 0.0418086 0.6498077 0.7586634 0.04668843 0.6463529 0.7626055 0.02570611 0.6612431 0.7490664 0.04070681 0.6716102 0.7390763 0.05201816 0.6641336 0.7469689 0.03104972 0.6839678 0.7276973 0.0514267 0.6806638 0.7319749 0.03015697 0.6969319 0.7154916 0.04855549 0.6954094 0.7177338 0.03555476 0.7100403 0.7024298 0.04934597 0.7089619 0.7041121 0.03999 0.7232723 0.6883803 0.05486112 0.72129 0.6914809 0.03993523 0.7365074 0.6736467 0.06129491 0.7321513 0.6801651 0.03647148 0.7490934 0.6597509 0.05989968 0.7416269 0.6698746 0.03546446 0.7560235 0.6531108 0.04329842 0.7502321 0.6595672 0.04607474 0.7596054 0.6487675 0.04582959 0.7568318 0.6525097 0.03790372 0.7625572 0.6456031 0.04127049 0.765737 0.6415181 0.04584097 0.7626463 0.6455567 0.0403372 0.7682296 0.6386092 0.04474002 0.7670726 0.6402966 0.04024803 0.7703273 0.6361359 0.04389768 0.7718862 0.6341766 0.0448516 0.7704839 0.6360656 0.04213172 0.772657 0.63339 0.0426414 0.7732893 0.6325694 0.04335528 0.7726668 0.6333876 0.04249972 0.7734473 0.6324231 0.0426644 0.7732955 0.6325737 0.04318183 0.7734206 0.6324176 0.04322612 0.7729228 0.6328136 0.04623252 0.7728715 0.6328879 0.04607063 0.7721659 0.6336921 0.04684126 0.7717702 0.634285 0.04531514 0.7722105 0.6336671 0.04644429 0.7722222 0.6337912 0.04451674 0.7737255 0.6319802 0.04415804 0.7723264 0.6337823 0.04280221 0.7762051 0.6288506 0.04530519 0.7743585 0.6315035 0.03965169 0.7789632 0.6257396 0.04082381 0.7831634 0.6200742 0.04651099 0.7790579 0.6257137 0.03938567 0.7861631 0.6170862 0.03394627 0.7970308 0.601859 0.05007588 0.7859598 0.616944 0.04058873 0.8143545 0.5763288 0.06835162 0.7973201 0.5993515 0.07112252 0.8035011 0.594455 0.03176921 0.8290611 0.5561682 0.05774772 0.814904 0.5786367 0.03333157 0.5819702 -0.8131231 -0.01189839 0.6886586 -0.7193884 -0.09071749 0.5959348 -0.8020884 -0.03893667 0.8283737 0.5587408 0.04007017 0.4195438 -0.9073877 -0.02511143 0.3031456 -0.9516842 0.04899126 0.3031387 -0.9516875 0.048967 0.4656297 -0.8826716 0.0638746 0.3578263 -0.9272239 0.1105276 0.7046147 0.7068409 -0.06240195 0.4656975 -0.883023 0.05827683 0.419543 -0.907388 -0.02511173 0.5368471 -0.8370419 -0.1056232 -0.3498458 -0.9344721 -0.06610465 -0.4001053 -0.9163844 0.01246398 -0.3498693 -0.9344628 -0.06611126 -0.5543205 -0.8292506 -0.07121986 -0.5939128 -0.8000009 0.08524191 -0.5901006 -0.807273 0.009560763 0.04655611 -0.9977151 -0.04896074 -0.04947304 -0.9984151 0.02683067 0.04657655 -0.9977144 -0.04895412 -0.4001035 -0.9163852 0.01246541 -0.04945635 -0.9984152 0.02685314 0.1608382 -0.9771593 -0.1388909 0.5368457 -0.8370416 -0.1056311 -0.2804871 -0.9453203 -0.1664228 0.1608425 -0.9771601 -0.1388806 -0.5559104 -0.8278972 -0.07449668 -0.5214707 -0.8345448 -0.1777731 -0.2804692 -0.9453296 -0.1664006 -0.8537996 -0.5173109 -0.05844533 -0.852262 -0.5208355 -0.04878461 -0.8605255 -0.5045384 -0.07026249 -0.8263024 -0.5598395 -0.06167846 -0.8192339 -0.5733142 -0.01291221 -0.8432381 -0.5321204 -0.07614141 -0.8274068 -0.5602098 0.03953206 -0.8287463 -0.5584584 0.03610688 -0.8317792 -0.5544003 0.02799367 -0.838573 -0.5447393 0.007385015 -0.8450174 -0.5345038 -0.01584953 -0.7982534 -0.5990215 -0.06296521 -0.7928877 -0.6092119 -0.01378369 -0.8160443 -0.5704304 -0.09317094 -0.7990713 -0.59983 0.04109901 -0.7710257 -0.6323089 -0.07553005 -0.7658275 -0.6430428 -0.002080261 -0.775174 -0.6258819 -0.08589023 -0.7690526 -0.6379331 0.03999221 -0.7433809 -0.6651996 -0.06995904 -0.7394169 -0.6728495 0.02315777 -0.7167762 -0.694176 -0.06596761 -0.7171981 -0.6968619 -0.003217399 -0.7355343 -0.6720159 -0.08592927 -0.7382946 -0.6739011 0.02789807 -0.690905 -0.719492 -0.07057833 -0.6943745 -0.7196055 0.003453195 -0.6979057 -0.7112701 -0.08379995 -0.7039401 -0.7091103 0.04038661 -0.6676005 -0.7403959 -0.07825225 -0.6752771 -0.7374076 0.01519352 -0.6664154 -0.7418102 -0.07488816 -0.6503161 -0.7564516 -0.0697841 -0.6585646 -0.7525196 0.002630233 -0.6724985 -0.7394205 0.03167366 -0.6358012 -0.768642 -0.07033061 -0.6477481 -0.7616016 0.01963257 -0.6419934 -0.7627807 -0.07752311 -0.6243535 -0.7777719 -0.07248049 -0.636642 -0.7711372 0.005851626 -0.6254874 -0.7766569 -0.07462906 -0.6473418 -0.7618374 0.02349728 -0.6163629 -0.7841753 -0.07187449 -0.6308711 -0.7757486 0.01468598 -0.6109655 -0.7884306 -0.07140326 -0.6252484 -0.7803802 0.008432745 -0.614613 -0.7853934 -0.07353872 -0.6305621 -0.7759289 0.01805084 -0.6076377 -0.7909601 -0.07182395 -0.6226555 -0.7824358 0.009709596 -0.6085025 -0.7902051 -0.07280647 -0.6062893 -0.7919796 -0.07198351 -0.6221005 -0.7828239 0.01333147 -0.606335 -0.7919375 -0.07206183 -0.6066617 -0.7916874 -0.07206082 -0.6218294 -0.783095 0.009523391 -0.6221453 -0.7828407 0.009779453 -0.606422 -0.7919158 -0.07156616 -0.621614 -0.7832595 0.01003229 -0.6069399 -0.7914925 -0.07185888 -0.5994877 -0.7972826 -0.07039237 -0.6149751 -0.7885117 0.007412135 -0.602778 -0.7945232 -0.07342725 -0.6210804 -0.7835456 0.01776242 -0.5831556 -0.8093613 -0.0697425 -0.6020259 -0.7983541 0.01398861 -0.5867815 -0.8062973 -0.074647 -0.5595253 -0.8106961 -0.1723465 -0.5082222 -0.8226168 -0.2549743 -0.5744198 -0.7975657 -0.1842029 -0.580232 -0.7943695 -0.1797442 -0.5737654 -0.7963601 -0.1913215 -0.5796855 -0.7948613 -0.179333 -0.5832555 -0.7929101 -0.1763708 -0.5793224 -0.7942407 -0.183214 -0.5874775 -0.7871389 -0.1878364 -0.6052172 -0.777767 -0.1696781 -0.5869199 -0.786552 -0.1919922 -0.6258817 -0.762321 -0.1647387 -0.604663 -0.7676075 -0.2125118 -0.6436782 -0.734593 -0.2145959 -0.6883507 -0.7035385 -0.1766542 -0.6466181 -0.7403023 -0.1839501 -0.7328598 -0.6631413 -0.1521848 -0.6873338 -0.694806 -0.2116997 -0.7760758 -0.6147238 -0.1407874 -0.7348846 -0.6419485 -0.2187388 -0.8191402 -0.5540688 -0.1483817 -0.7808366 -0.5893852 -0.2071701 -0.8510743 -0.4934513 -0.1793834 -0.821752 -0.5425661 -0.1741999 -0.8696557 -0.466983 -0.1600807 -0.8577722 -0.4555528 -0.2381142 -0.8210805 -0.5663275 -0.07141512 -0.8211072 -0.5662854 -0.0714417 -0.8210453 -0.5663856 -0.0713573 -0.8212707 -0.5659659 -0.07209056 -0.8210452 -0.5664009 -0.0712378 -0.7923877 -0.5909522 0.1513187 -0.8136965 -0.5740647 0.09136623 -0.823605 -0.5643094 0.05683076 0.8210672 0.5663657 -0.07126343 0.6197203 0.6197041 0.4815739 0.6197188 0.6197048 0.4815751 0.6197082 0.6197117 0.4815798 0.6197046 0.6197153 0.4815799 0.6197099 0.6197082 0.4815822 0.746148 0.602068 0.2842136 0.7340719 0.6065944 0.3052569 0.8210838 0.5663229 -0.07141268 0.821085 0.5663212 -0.07141315 0.8210861 0.5663189 -0.07141697 0.8210934 0.5663072 -0.07142585 0.8211492 0.5662168 -0.07150328 0.8211045 0.5662895 -0.07144027 0.8210937 0.5662977 -0.07149833 0.8210782 0.5663369 -0.07136625 0.8210884 0.5663118 -0.07144677 0.8210806 0.5663298 -0.07139462 0.821076 0.56634 -0.07136511 0.82109 0.5663103 -0.07144135 0.8210498 0.5663918 -0.07125687 0.361576 0.5016848 0.7858595 0.3572297 0.4074037 0.8404816 0.4251368 0.5284603 0.7348392 0.4238135 0.3524424 0.8343659 0.5065659 0.5008413 0.7018184 0.5456489 0.4110101 0.7302998 0.619722 0.6196996 0.4815775 0.5454303 0.2215667 0.8083403 0.5681118 0.4471067 0.6909013 0.6197102 0.61971 0.4815797 0.6349995 0.3760022 0.6748319 0.6197069 0.6197116 0.4815814 0.6613508 0.1631335 0.732122 0.6197109 0.6197091 0.4815797 0.6397039 0.4054048 0.6530131 0.6197144 0.6197061 0.4815791 0.6951658 0.2531141 0.6728134 0.6197089 0.6197108 0.4815801 0.7135741 0.1777234 0.6776624 0.6956058 0.3088462 0.6486499 0.6197126 0.6197074 0.4815798 0.7207941 0.1825211 0.6686867 0.6197219 0.6196982 0.4815797 0.7201827 0.166095 0.6736093 0.6196914 0.6197253 0.481584 0.7093959 0.201534 0.6753824 0.6197107 0.6197099 0.481579 0.7201346 0.1626387 0.6745035 0.6197158 0.6197045 0.4815794 0.5920605 -0.2706778 0.759077 0.6197069 0.6197125 0.4815804 0.6467853 0.2875692 0.70638 0.6805676 0.05473208 0.7306383 0.6197201 0.6196997 0.48158 0.5977944 0.3074183 0.7403621 0.4539176 -0.2183427 0.863878 0.6197102 0.6197098 0.4815796 0.5312352 0.2849084 0.7978824 0.619711 0.6197091 0.4815795 0.6197074 0.6197124 0.48158 0.5265553 0.3910647 0.7548563 0.4856469 0.198651 0.8512843 0.6197147 0.6197053 0.4815798 0.4961917 0.3961308 0.7725763 0.451687 0.2965918 0.8414345 0.6197121 0.6197075 0.4815803 0.4772576 0.3968089 0.7840714 0.6197149 0.619705 0.4815798 0.4601203 0.3657681 0.8090136 0.6197103 0.6197091 0.4815804 0.465008 0.4033856 0.7880657 0.4564367 0.3898236 0.7998144 0.6197136 0.6197067 0.4815794 0.4562288 0.4170604 0.7860762 0.6197082 0.6197114 0.4815804 0.4490863 0.406902 0.7954573 0.6197111 0.6197091 0.4815796 0.4512942 0.435739 0.7787587 0.4359294 0.4156274 0.7982602 0.6197116 0.6197084 0.4815797 0.4469006 0.4543824 0.7705948 0.6197122 0.6197078 0.4815796 0.4190322 0.419813 0.8050894 0.6197092 0.6197105 0.4815803 0.4367059 0.4668107 0.7690095 0.6197128 0.6197071 0.4815797 0.4055682 0.4269487 0.8082259 0.619713 0.6197066 0.4815802 0.4106323 0.4662761 0.7835609 0.6197121 0.6197074 0.4815803 0.4066547 0.445709 0.7974808 0.6197122 0.619708 0.4815793 0.417984 0.4909204 0.7643863 0.6197071 0.6197128 0.4815799 0.3841428 0.4575209 0.8019407 0.4299956 0.4795939 0.764914 0.6197121 0.619708 0.4815797 0.4099759 0.5017841 0.7616643 0.619713 0.6197072 0.4815796 0.6197136 0.6197065 0.4815795 0.3808798 0.4784587 0.7912065 0.3929896 0.4762149 0.7866248 0.6197113 0.6197082 0.4815803 0.3783403 0.4963226 0.7813594 0.6197126 0.6197072 0.4815801 0.6197147 0.6197052 0.4815798 0.3743951 0.483492 0.7912419 0.61971 0.6197094 0.4815803 0.3702062 0.502803 0.7811123 0.6197169 0.6197043 0.4815784 0.6197052 0.6197142 0.4815805 0.6197099 0.6197098 0.4815802 0.3664608 0.4932559 0.7889265 0.4158752 0.5163467 0.7486213 0.6197142 0.6197055 0.4815801 0.3736965 0.5113795 0.7738487 0.6197174 0.6197034 0.4815788 0.6197152 0.6197051 0.4815795 0.6197072 0.6197119 0.4815809 0.6197132 0.6197061 0.4815805 0.3614932 0.503274 0.7848809 0.3652462 0.5022338 0.783809 0.4049273 0.5203512 0.7518434 0.6197088 0.6197103 0.4815809 0.3584655 0.5041561 0.785703 0.6197143 0.6197069 0.4815784 0.6197092 0.6197105 0.4815801 0.619709 0.6197106 0.4815802 0.6197112 0.6197086 0.48158 0.3608156 0.5059131 0.7834947 0.3655903 0.5075517 0.7802147 0.6197151 0.6197066 0.4815775 0.329852 0.4809991 0.8123038 0.6197046 0.6197094 0.4815874 0.6197112 0.6197073 0.4815817 0.6197319 0.6196991 0.4815654 0.6196947 0.6197155 0.4815924 0.6197152 0.6197058 0.4815787 0.6197115 0.6197081 0.4815803 0.6197071 0.6197115 0.4815816 0.6197109 0.619708 0.4815812 0.3647861 0.5047362 0.7824145 0.3620216 0.5053989 0.7832702 0.3489987 0.4994121 0.7929612 0.001958429 0.9533618 0.3018234 0.2760783 0.883847 0.3776178 0.3829762 0.5059309 0.7728927 0.3185967 0.4749063 0.8203415 0.07679653 0.9568624 0.2802084 0.2512874 0.9326192 0.2589904 0.07410812 0.962985 0.2591676 0.4020194 0.8841624 0.2379859 0.292909 0.9305258 0.2198318 0.5304568 0.8245558 0.1967828 0.6207539 0.7181382 0.314551 0.4245178 0.8480038 0.3172919 0.6241238 0.7322289 0.272599 0.6192348 0.7718607 0.1441501 0.6336178 0.7063785 0.3155282 0.6257417 0.7228603 0.2931218 0.6362959 0.7065836 0.3096245 0.6387847 0.7113478 0.2931528 0.6407856 0.7186454 0.270079 0.6399641 0.7013792 0.3138682 0.6379544 0.7056382 0.3083651 0.6401234 0.7014141 0.3134649 0.640141 0.7014433 0.3133638 0.6403826 0.7020777 0.3114436 0.6405363 0.7008726 0.3138324 0.6402021 0.701476 0.3131659 0.6410806 0.7011398 0.31212 0.6421228 0.7031479 0.3053873 0.6425142 0.6987937 0.3144247 0.6416573 0.7017997 0.3094401 0.6440172 0.6990841 0.3106819 0.6471284 0.7048512 0.2905333 0.6473347 0.6941802 0.3147563 0.6446985 0.6983273 0.3109707 0.6524025 0.6998241 0.2908907 0.6530309 0.6880366 0.316475 0.6503013 0.6956968 0.3051463 0.6629228 0.6963323 0.2750539 0.6624559 0.6796419 0.3150223 0.6566846 0.6874417 0.3101439 0.6663103 0.6708068 0.3256513 0.6699444 0.6853742 0.2853713 0.6759951 0.6652998 0.3168703 0.6820077 0.6735742 0.2848918 0.6897972 0.6570144 0.3041579 0.6925688 0.6431168 0.3267252 0.691362 0.6573795 0.2997848 0.6991083 0.6315916 0.3351711 0.7145884 0.6427679 0.2760667 0.7130903 0.6200326 0.3272032 0.7412535 0.6211243 0.2544558 -0.6197344 -0.6196793 -0.481588 -0.6161242 -0.2501574 -0.7468682 -0.6197114 -0.619708 -0.4815806 -0.6197145 -0.6197053 -0.4815801 0.4573553 0.8350725 -0.3057451 -0.5257385 -0.3388274 -0.7802532 -0.6196804 -0.6197432 -0.481575 -0.6306434 0.4204381 -0.6523194 -0.2415814 0.8592854 -0.4508514 -0.3090788 0.57966 -0.7539659 -0.619696 -0.6197255 -0.4815778 -0.7904796 0.3415308 -0.5084276 -0.6570968 0.540679 -0.5252524 -0.619796 -0.6196151 -0.4815911 -0.8649576 0.3383514 -0.3706302 -0.8607119 -0.2103761 -0.4635913 -0.8652038 0.2871726 -0.4110406 -0.9111377 0.185292 -0.3680962 -0.8658682 0.4049686 -0.2937219 -0.7041358 -0.6398978 -0.3077719 -0.6987957 -0.6406344 -0.3182328 -0.6197121 -0.6197081 -0.4815796 -0.7045788 -0.6393324 -0.307933 -0.6197087 -0.6197112 -0.4815798 -0.7048531 -0.6387191 -0.3085778 -0.6197092 -0.6197106 -0.48158 -0.7043627 -0.6392167 -0.3086666 -0.6197122 -0.619708 -0.4815794 -0.7039105 -0.6377548 -0.3126963 -0.6197116 -0.6197085 -0.4815794 -0.7035973 -0.6379954 -0.3129104 -0.6197129 -0.6197068 -0.4815801 -0.7037524 -0.6367816 -0.3150267 -0.6197134 -0.6197061 -0.4815802 -0.6197085 -0.6197112 -0.4815801 -0.7030524 -0.6371819 -0.3157793 -0.6197093 -0.6197105 -0.48158 -0.7042233 -0.6367132 -0.3141112 -0.6197099 -0.6197099 -0.4815801 -0.7038559 -0.6368691 -0.3146182 -0.6197128 -0.6197062 -0.4815809 -0.7037552 -0.6372202 -0.3141322 -0.6197062 -0.6197135 -0.4815803 -0.7044613 -0.6368942 -0.3132094 -0.6197129 -0.6197067 -0.4815802 -0.7031398 -0.6374385 -0.3150661 -0.6197177 -0.6197019 -0.4815804 -0.7037002 -0.6371778 -0.3143415 -0.6197087 -0.6197118 -0.481579 -0.7024117 -0.6384033 -0.3147365 -0.6197145 -0.6197054 -0.48158 -0.6197143 -0.6197054 -0.48158 -0.7036527 -0.6378725 -0.3130359 -0.6197116 -0.6197084 -0.4815797 -0.7012688 -0.6394761 -0.3151071 -0.6197076 -0.619713 -0.4815791 -0.7028771 -0.6388987 -0.3126856 -0.619712 -0.6197079 -0.48158 -0.7002282 -0.6406555 -0.3150253 -0.6197104 -0.6197097 -0.4815797 -0.7017154 -0.6402454 -0.31254 -0.619708 -0.6197119 -0.4815799 -0.6991959 -0.6421871 -0.3141987 -0.7003621 -0.6419648 -0.3120481 -0.6197173 -0.6197027 -0.4815796 -0.6982449 -0.6438944 -0.3128163 -0.6197129 -0.6197074 -0.4815794 -0.6197134 -0.6197062 -0.48158 -0.6925398 -0.6476299 -0.3177486 -0.619714 -0.6197057 -0.4815803 -0.6197116 -0.6197082 -0.48158 -0.6983361 -0.6439695 -0.312458 -0.6197108 -0.6197087 -0.4815803 -0.6833045 -0.6539101 -0.3248024 -0.6197103 -0.6197094 -0.4815803 -0.6823124 -0.6426739 -0.3484538 -0.690166 -0.6479694 -0.3221901 -0.6918404 -0.6523629 -0.3094824 -0.6197106 -0.6197091 -0.4815802 -0.6776182 -0.6615527 -0.3212187 -0.6197114 -0.6197082 -0.4815803 -0.6820604 -0.6528414 -0.3295326 -0.685081 -0.6594188 -0.3095654 -0.6197127 -0.6197073 -0.4815797 -0.6705957 -0.6680119 -0.3225857 -0.6197135 -0.6197065 -0.4815797 -0.6768175 -0.6605162 -0.3250178 -0.6774871 -0.6680158 -0.3078411 -0.6197083 -0.6197118 -0.4815798 -0.66637 -0.6763741 -0.313798 -0.61971 -0.6197097 -0.48158 -0.671826 -0.6714717 -0.3126911 -0.6197137 -0.6197058 -0.4815804 -0.6597425 -0.6808403 -0.3181137 -0.6197113 -0.6197087 -0.4815797 -0.6657742 -0.6745502 -0.3189464 -0.6627324 -0.6822175 -0.3088122 -0.6197128 -0.6197068 -0.4815803 -0.6550114 -0.6863615 -0.3160188 -0.6573691 -0.6876626 -0.3081983 -0.6197131 -0.6197065 -0.4815803 -0.6512099 -0.6930941 -0.3091052 -0.619715 -0.6197041 -0.4815809 -0.6445482 -0.6964138 -0.31554 -0.6197127 -0.6197067 -0.4815803 -0.6512312 -0.6920484 -0.3113952 -0.6197025 -0.619718 -0.481579 -0.6325578 -0.703192 -0.3246409 -0.6425151 -0.7064523 -0.2968155 -0.6197076 -0.6197129 -0.4815793 -0.6085329 -0.7488903 -0.2623946 -0.6197264 -0.6196902 -0.4815841 -0.5935033 -0.7383717 -0.3202516 -0.6197112 -0.6197093 -0.4815791 -0.6184183 -0.7230656 -0.3077905 -0.6197063 -0.6197141 -0.4815793 -0.4705219 -0.8753186 -0.1114742 -0.6197086 -0.6197115 -0.4815796 -0.5341866 -0.7809526 -0.3236629 -0.5777909 -0.752552 -0.315948 -0.6197046 -0.6197158 -0.4815794 -0.5174375 -0.7853429 -0.3398455 -0.4912545 -0.82686 -0.2738094 -0.6197197 -0.619699 -0.4815816 -0.498057 -0.8044973 -0.32361 -0.6197133 -0.6197075 -0.4815788 -0.4987437 -0.8036054 -0.3247666 -0.6197106 -0.6197099 -0.481579 -0.5287674 -0.7770276 -0.3415159 -0.6197112 -0.6197093 -0.4815791 -0.5402489 -0.7836074 -0.3067422 -0.5287211 -0.7770819 -0.3414643 -0.6197113 -0.619706 -0.4815831 -0.601153 -0.7009034 -0.3838612 -0.6197078 -0.6197125 -0.4815794 -0.6197058 -0.6197143 -0.4815794 -0.6169769 -0.7223932 -0.3122301 -0.5717671 -0.7542186 -0.3228572 -0.6197152 -0.6197038 -0.4815812 -0.6498855 -0.7028058 -0.2893317 -0.6280328 -0.6937108 -0.3526189 -0.619717 -0.6197193 -0.4815587 -0.6778813 -0.6690188 -0.3047797 -0.6197111 -0.6197069 -0.4815824 -0.6633008 -0.6665468 -0.3402167 -0.6197128 -0.6197063 -0.481581 -0.6976152 -0.6396864 -0.3226985 -0.7003257 -0.6413475 -0.3133966 0.8210704 0.5663585 -0.07128465 0.8210836 0.5663241 -0.0714057 0.8210837 0.5663238 -0.07140725 0.8210851 0.5663189 -0.07142949 0.8210858 0.5663169 -0.07143765 0.8210959 0.5662891 -0.07154214 -0.02088141 -0.4451072 -0.8952338 0.8211351 0.5662086 -0.07172876 -0.3724743 -0.5537998 -0.7446938 -0.213561 -0.533421 -0.8184458 -0.4373624 -0.5495126 -0.7118638 -0.07864952 -0.3973808 -0.9142772 -0.465211 -0.532517 -0.7071099 -0.1204993 -0.3365914 -0.9339091 -0.4752693 -0.5057896 -0.7199277 -0.1977868 -0.3089067 -0.9302994 -0.4759064 -0.472415 -0.7418472 -0.268777 -0.2931564 -0.9175065 -0.4659276 -0.4295344 -0.7735708 -0.3475058 -0.3071 -0.8859624 -0.4381216 -0.3654713 -0.8212674 -0.4853612 -0.4056811 -0.7744982 -0.4246667 -0.3468694 -0.8362655 -0.3958951 -0.2586029 -0.8811308 -0.4881252 -0.3784632 -0.7864474 -0.474011 -0.3770965 -0.7956833 -0.4367579 -0.2869869 -0.8525731 -0.4952757 -0.3719523 -0.785082 -0.4835339 -0.3650452 -0.7955733 -0.4817394 -0.3438637 -0.8060303 -0.4976305 -0.3671841 -0.7858369 -0.486079 -0.3518581 -0.7999519 -0.4976035 -0.3650518 -0.7868469 -0.4952885 -0.3601071 -0.7905771 -0.4952157 -0.3599672 -0.7906864 -0.499077 -0.3642471 -0.7862864 -0.4979464 -0.3650729 -0.7866202 -0.4814369 -0.3254604 -0.8138146 -0.3481497 -0.09468322 -0.932645 -0.5167742 -0.3571874 -0.7780498 -0.4935003 -0.3433934 -0.7990859 -0.4644253 -0.2250987 -0.8565277 -0.8205307 -0.5697094 0.04648184 -0.821083 -0.5663236 0.07141619 -0.8210838 -0.5663227 0.07141494 -0.8158554 -0.5774861 0.02982836 -0.822788 -0.5614137 0.08851313 -0.7933517 -0.6044963 0.07195377 -0.7936628 -0.6035587 0.07626402 -0.7893247 -0.6022216 0.1195648 -0.7912293 -0.6069839 0.07434225 -0.7873959 -0.6156988 0.03037667 -0.7885122 -0.610776 0.07211977 -0.7908264 -0.6000348 0.1206308 -0.7886165 -0.6106525 0.07202565 -0.5819745 0.81312 -0.01189702 -0.525628 0.8503218 0.02584683 -0.7907862 -0.6078522 0.07192373 -0.793251 -0.5968201 0.1206588 -0.7916615 -0.5997228 0.1166402 -0.7927116 -0.6053471 0.07185542 -0.795192 -0.5948523 0.1175607 -0.7910804 -0.6074468 0.07211142 -0.794321 -0.6032372 0.07182794 -0.7969869 -0.591909 0.1202319 -0.7931386 -0.6047589 0.07209587 -0.7951454 -0.5948488 0.117893 -0.7956156 -0.60153 0.07181596 -0.7982134 -0.5910238 0.1163882 -0.7947926 -0.602588 0.07205873 -0.7967175 -0.600073 0.07178843 -0.7995039 -0.5886308 0.1196134 -0.7960931 -0.6008741 0.07201462 -0.7979033 -0.5908677 0.1192721 -0.7975555 -0.598954 0.07182806 -0.8003955 -0.5873649 0.1198735 -0.797043 -0.5996209 0.07195317 -0.7997115 -0.5885941 0.1183993 -0.7979911 -0.5983697 0.07186073 -0.8008369 -0.5868485 0.1194534 -0.7976803 -0.5987789 0.07190185 -0.8007155 -0.5871104 0.1189795 -0.7980622 -0.5982728 0.07187813 -0.8009106 -0.58675 0.1194428 -0.7980251 -0.5983214 0.07188367 -0.7977916 -0.5986307 0.07190114 -0.8006111 -0.587212 0.1191806 -0.7980354 -0.5983107 0.07186102 -0.8008633 -0.5867575 0.1197229 -0.7971943 -0.599422 0.07193487 -0.8000318 -0.5877186 0.1205648 -0.797697 -0.5987637 0.07184374 -0.7963019 -0.6006027 0.07196992 -0.7990343 -0.5893487 0.1192145 -0.7970124 -0.5996763 0.07183033 -0.8001215 -0.587759 0.1197702 -0.7951312 -0.602146 0.07201737 -0.7977867 -0.5910716 0.1190412 -0.7960416 -0.6009646 0.07182824 -0.7985566 -0.589566 0.121323 -0.7936909 -0.6040388 0.07205533 -0.7963088 -0.5927886 0.1203915 -0.7947596 -0.6026592 0.07182568 -0.7920067 -0.6062361 0.07213342 -0.7944617 -0.5956199 0.118606 -0.7930659 -0.6048957 0.07174795 -0.7960762 -0.5928174 0.1217792 -0.7900924 -0.6087259 0.07215791 -0.7925494 -0.5973915 0.1224294 -0.7908996 -0.6077243 0.07175648 -0.7879632 -0.6114836 0.07212346 -0.7901893 -0.6012674 0.1186525 -0.7884449 -0.6108973 0.07182705 -0.7926585 -0.5974005 0.1216772 -0.7852164 -0.6149837 0.07232058 -0.7872821 -0.6049834 0.1190887 -0.785723 -0.6143788 0.07195776 -0.7883711 -0.6026766 0.1234987 -0.7817739 -0.619337 0.07246375 -0.7836563 -0.609392 0.1205165 -0.7827708 -0.6181428 0.07189875 -0.7780143 -0.6240504 0.07248997 -0.779618 -0.6151188 0.1175782 -0.7792299 -0.622616 0.07176434 -0.7830843 -0.6094871 0.1237119 -0.7739642 -0.6290637 0.07251256 -0.7753533 -0.6201232 0.1194766 -0.7750493 -0.6278027 0.07184934 -0.7768196 -0.6171248 0.1253324 -0.7696708 -0.6343062 0.07254338 -0.7707987 -0.6256006 0.1203884 -0.7706604 -0.6331721 0.07194322 -0.7651374 -0.6397628 0.07258242 -0.7659773 -0.6320107 0.1176487 -0.7660886 -0.6386871 0.07202214 -0.7695183 -0.6260678 0.1260194 -0.7603833 -0.6454562 0.0721367 -0.7608761 -0.6365588 0.1259381 -0.7605796 -0.645242 0.07198154 -0.755476 -0.6511436 0.07258075 -0.7557206 -0.6441701 0.1180309 -0.7611871 -0.6365041 0.1243253 -0.7503945 -0.656965 0.07283675 -0.7499743 -0.6481726 0.1319499 -0.7541007 -0.6528207 0.07181531 -0.7399024 -0.6684383 0.07572734 -0.7391967 -0.6632781 0.1168359 -0.7408398 -0.6675204 0.07465118 -0.7475061 -0.660361 0.07181769 -0.7518123 -0.6479555 0.1221955 -0.7232367 -0.6864252 0.07582294 -0.7222792 -0.6839755 0.1024215 -0.727466 -0.682264 0.07286322 -0.7341527 -0.675124 0.07230174 -0.741931 -0.6635438 0.09616607 -0.729267 -0.6717814 0.1299214 -0.7060714 -0.7041085 0.07546132 -0.7035543 -0.7014778 0.1137557 -0.7147607 -0.6959949 0.0686165 -0.7166551 -0.6860911 0.1252379 -0.6887925 -0.7210724 0.07496207 -0.6857362 -0.7196783 0.1087608 -0.695878 -0.714775 0.06964427 -0.7035633 -0.7014752 0.1137159 -0.6872848 -0.71542 0.1257534 -0.6718414 -0.7369355 0.07453387 -0.6677923 -0.7363122 0.1090765 -0.6782771 -0.7314292 0.07036656 -0.6701683 -0.7306619 0.1304141 -0.6557137 -0.7513608 0.07413679 -0.6501948 -0.7514084 0.112393 -0.6621857 -0.7459886 0.07078957 -0.6521199 -0.7466114 0.1315713 -0.64025 -0.7646005 0.07393246 -0.633043 -0.7653567 0.1161274 -0.647756 -0.7585239 0.07108926 -0.6336685 -0.7626826 0.1295355 -0.6157918 -0.7843193 0.07512408 -0.6050034 -0.7862848 0.1254073 -0.6334477 -0.7705408 0.07078588 -0.5665997 -0.8205944 0.07476514 -0.5587065 -0.8230768 0.1019397 -0.6065746 -0.7919624 0.06973463 -0.5999053 -0.7882959 0.1367598 -0.4923043 -0.8673724 0.07281285 -0.4887173 -0.868629 0.08148103 -0.4948956 -0.865986 0.0717405 -0.5593325 -0.8259871 0.06994765 -0.4997922 -0.8450506 0.1899926 -0.391761 -0.9170882 0.07397681 -0.2929698 -0.928086 0.229837 -0.4219086 -0.9042323 0.06600821 -0.2782139 -0.9579821 0.06976586 -0.2624627 -0.9607547 0.08979827 -0.3312599 -0.9416308 0.05998373 -0.3577249 -0.9206186 0.1565067 -0.1962389 -0.9785857 0.06213283 0.02385652 -0.9574096 0.2877463 -0.2261278 -0.9724976 0.05580955 -0.1569833 -0.9859796 0.05657249 -0.113661 -0.9884636 0.1001046 -0.1547675 -0.98629 0.05726444 -0.1782971 -0.9764097 0.1217959 -0.1426059 -0.9880701 0.0581479 -0.07822495 -0.9895242 0.121337 -0.1555351 -0.986 0.06010931 -0.1068501 -0.9882772 0.1090472 -0.1531735 -0.9863321 0.0607202 -0.1035488 -0.989351 0.1022853 -0.2007398 -0.977857 0.05915594 -0.2015007 -0.9777504 0.05832445 -0.2751277 -0.9595621 0.05954205 -0.2158543 -0.9674062 0.1324087 -0.2174628 -0.9737862 0.06671005 -0.2028075 -0.9775413 0.05728834 -0.3737834 -0.9254217 0.06229507 -0.3899897 -0.9201173 0.03594523 -0.3232939 -0.9436033 0.07137018 -0.4769555 -0.876502 0.06525081 -0.4379526 -0.8865518 0.149075 -0.4412328 -0.8943388 0.07397049 -0.4062833 -0.9135491 0.01902294 -0.5718341 -0.8176016 0.06733095 -0.5768175 -0.8154285 0.04855853 -0.5462414 -0.834167 0.0760641 -0.6565676 -0.7511063 0.06897997 -0.6429859 -0.7499248 0.1555054 -0.6401659 -0.7643695 0.07698726 -0.5728394 -0.8177555 0.05595558 -0.7300541 -0.6797471 0.0704624 -0.7267132 -0.6703225 0.1501848 -0.7217682 -0.6879023 0.07642692 -0.7004994 -0.7121526 0.04625147 -0.7221649 -0.6915664 0.01462805 -0.7855461 -0.616703 0.05094027 -0.6504134 -0.7595802 -5.23357e-4 -0.697659 -0.7101975 0.09429389 -0.5203459 -0.8403329 0.1519241 -0.4694398 -0.8828282 0.01551228 -0.5736032 -0.8174037 0.05320221 -0.1714696 -0.9473904 0.2702769 -0.2580067 -0.9659337 0.02012026 -0.4004228 -0.9158715 0.02900284 -0.2065899 -0.9784094 0.005975365 -0.1900725 -0.9791812 0.07124996 -0.1832837 -0.9826543 0.0282405 -0.1904309 -0.9815825 0.01522374 -0.2766898 -0.9609553 -0.00274837 -0.3373004 -0.9399983 0.05129945 -0.3054307 -0.9518378 -0.02677416 -0.4789818 -0.876535 -0.04756826 -0.5047114 -0.8620001 0.04714083 -0.4563978 -0.8895493 -0.02007174 -0.5863761 -0.8093354 -0.0337525 -0.6140357 -0.7886136 0.03238427 -0.5568286 -0.8302443 0.02522909 -0.6386348 -0.7685973 0.03746795 -0.625571 -0.7801126 0.009230375 -0.6526058 -0.7569368 0.03394705 -0.6500473 -0.7595963 0.02126294 -0.6662893 -0.7450041 0.03205376 -0.6655078 -0.7459247 0.02637594 -0.6811342 -0.7313269 0.03488785 -0.6803885 -0.732261 0.02941781 -0.6973445 -0.7154496 0.04292333 -0.6946418 -0.7188384 0.02727818 -0.7152892 -0.6970951 0.04919397 -0.7078182 -0.7060191 0.02303344 -0.7275883 -0.6852545 0.03226906 -0.7198655 -0.6935521 0.02791601 -0.7338522 -0.6785661 0.03176575 -0.7308908 -0.6820853 0.02362966 -0.7400598 -0.6718903 0.02957838 -0.7464909 -0.6645427 0.03367877 -0.7410305 -0.6709983 0.02519911 -0.7526475 -0.6576338 0.03224283 -0.7501538 -0.6607932 0.02493071 -0.7585252 -0.6510171 0.02856874 -0.7639274 -0.6445161 0.03184741 -0.7585681 -0.6509809 0.02825349 -0.7682458 -0.6393636 0.03182297 -0.7656785 -0.6427125 0.0256347 -0.7721364 -0.6348083 0.028705 -0.77638 -0.6294466 0.03211128 -0.772254 -0.634706 0.02778667 -0.7796313 -0.6254655 0.03111302 -0.7776862 -0.6280858 0.0266878 -0.7822537 -0.6222648 0.0294215 -0.785046 -0.6186346 0.03152984 -0.7824661 -0.6220709 0.02783209 -0.7872673 -0.6158577 0.03049027 -0.7863273 -0.6171789 0.0279262 -0.7892763 -0.6132997 0.03010696 -0.7909585 -0.6110903 0.03087997 -0.7894399 -0.6131548 0.02873677 -0.7919065 -0.6099767 0.02850532 -0.7930393 -0.6084111 0.03040885 -0.7918147 -0.6100258 0.02996581 -0.7936909 -0.6075591 0.03044247 -0.793204 -0.6082431 0.02946066 -0.7939615 -0.6072267 0.03001493 -0.793969 -0.6072084 0.03018689 -0.7939502 -0.6072335 0.03017443 -0.7936296 -0.6076573 0.030079 -0.7938929 -0.6072863 0.03061807 -0.7930886 -0.6083338 0.03066813 -0.7920867 -0.609681 0.02979487 -0.7930576 -0.6083586 0.03097724 -0.7908942 -0.6112092 0.03016054 -0.7914901 -0.6103579 0.03172737 -0.7893553 -0.6131823 0.03042405 -0.7872858 -0.615893 0.02927511 -0.7891094 -0.613407 0.03222173 -0.784998 -0.6187911 0.02959042 -0.7860418 -0.6173182 0.03250694 -0.5819748 0.8131199 -0.0118981 -0.6886637 0.7193836 -0.09071791 -0.6185171 0.7841101 -0.05106836 -0.4195244 0.9073967 -0.02511304 -0.3031509 0.9516833 0.04897427 -0.3031541 0.9516817 0.0489856 -0.4656423 0.8826635 0.06389385 -0.3555604 0.9279876 0.1114262 -0.4390251 0.8956127 0.07165819 -0.419524 0.9073967 -0.02511316 -0.5368285 0.8370537 -0.1056229 0.3498598 0.9344666 -0.06610983 0.3759251 0.9262837 -0.02605688 0.3498544 0.9344687 -0.06610828 0.546204 0.8346312 -0.07107657 0.5949347 0.7949659 0.1186678 0.576838 0.8163126 -0.02986049 -0.0465942 0.9977133 -0.04895871 0.04945105 0.9984158 0.02684384 -0.04659605 0.9977133 -0.04895812 0.3498806 0.9353366 0.05223965 0.4001062 0.9163839 0.01247441 0.04945892 0.9984157 0.02683329 -0.1608311 0.9771632 -0.1388723 -0.5368287 0.8370538 -0.1056218 0.2804697 0.9453255 -0.1664223 -0.1608272 0.9771625 -0.1388821 0.5481883 0.833175 -0.07286381 0.5332339 0.8376323 -0.1184645 0.2320763 0.9668301 -0.1066774 0.8817759 0.4661974 -0.07163232 0.87566 0.4814758 -0.03742629 0.8804818 0.4689641 -0.06945925 0.8602551 0.505274 -0.06825911 0.8569664 0.5131691 -0.04760205 0.8658143 0.5003353 -0.005493342 0.8483853 0.5277616 0.04135328 0.8356785 0.5451539 -0.06669807 0.8254433 0.5644823 -0.001782953 0.857998 0.5081727 -0.07483345 0.8078347 0.5858459 -0.06471252 0.8076983 0.586184 -0.06333833 0.830789 0.5509787 -0.07881706 0.8209013 0.5708841 0.01457703 0.7777974 0.6253226 -0.06326955 0.7784875 0.623109 -0.07544869 0.7987778 0.5958821 -0.08293837 0.783665 0.6204336 0.03051543 0.7477974 0.6607909 -0.06445473 0.7476361 0.6616699 -0.05686014 0.7631945 0.640568 -0.0848934 0.7519114 0.6589338 0.02086919 0.7204043 0.6901589 -0.06854403 0.7204422 0.693515 4.11739e-4 0.7284529 0.6801615 -0.08207786 0.6970153 0.7133584 -0.0727303 0.6987216 0.7142438 -0.04054617 0.6990935 0.7108825 -0.07690477 0.7220895 0.691636 -0.01504582 0.6779394 0.73154 -0.07243973 0.6803078 0.7315739 -0.04450845 0.6934672 0.7204352 0.00874561 0.662608 0.745615 -0.07077527 0.6686454 0.7435297 -0.008771181 0.675883 0.7331638 -0.07518631 0.6500689 0.756583 -0.0706582 0.6541512 0.7553662 -0.03883534 0.6578069 0.7494148 -0.07528418 0.6685636 0.7436267 -0.006492018 0.6398621 0.7651904 -0.07113498 0.6483071 0.7613285 -0.008764743 0.6439347 0.7614408 -0.0745396 0.6316307 0.7719408 -0.07176351 0.6374762 0.7696862 -0.03474587 0.6333481 0.770362 -0.07356953 0.6483107 0.7612914 -0.01134568 0.6250725 0.7772094 -0.07231795 0.6333332 0.7735604 -0.02221041 0.6253616 0.7769432 -0.07267731 0.6200816 0.7812235 -0.07203322 0.6330558 0.7740725 0.007226645 0.6162912 0.7842364 -0.07182323 0.623719 0.781027 -0.03116971 0.619355 0.7817519 -0.07254928 0.6312118 0.7751266 -0.02739351 0.6134536 0.7864569 -0.07183587 0.622601 0.7822217 -0.02229815 0.6150553 0.7851473 -0.07246196 0.6113982 0.7880483 -0.07191628 0.6228563 0.7822767 -0.009655833 0.6121203 0.7874533 -0.07229226 0.609993 0.7891303 -0.07198578 0.6179667 0.7856033 -0.03073471 0.6102273 0.7889355 -0.07213652 0.6216709 0.7828174 -0.02687484 0.6090922 0.7898222 -0.07202434 0.6174045 0.7861016 -0.02925401 0.609102 0.7898141 -0.07203185 0.608635 0.7901778 -0.07198882 0.6173387 0.7862258 -0.02723634 0.6085453 0.7902454 -0.07200568 0.6173671 0.786224 -0.02663815 0.6085814 0.7902169 -0.07201337 0.6083222 0.790425 -0.07192099 0.6164094 0.7868274 -0.03069198 0.6085508 0.7902413 -0.07200378 0.6170731 0.7863298 -0.03010487 0.60631 0.7919803 -0.07180017 0.6151645 0.7879301 -0.027179 0.6071065 0.7913323 -0.07221418 0.6021621 0.7951294 -0.07190239 0.6146167 0.7887678 -0.009586215 0.6026627 0.7947193 -0.07224249 0.5959087 0.799782 -0.07239776 0.6158848 0.7873274 0.02831441 0.5952787 0.8002988 -0.07186865 0.5880661 0.8056633 -0.07130855 0.5969929 0.8015765 -0.03278058 0.612181 0.7904497 -0.02058333 0.577787 0.8131154 -0.07075053 0.5912567 0.8063336 -0.01555591 0.584408 0.8081948 -0.07272213 0.5643723 0.8225139 -0.0703907 0.5908792 0.8059994 0.03502792 0.5694574 0.8187673 -0.07306498 0.5114594 0.823059 -0.2469477 0.572724 0.8113824 -0.1168158 0.5260546 0.8280113 -0.1940715 0.5828793 0.8033725 -0.1218376 0.5812792 0.7981038 -0.1585716 0.5731471 0.7934 -0.2049852 0.5978885 0.7926316 -0.1194337 0.5893493 0.7983307 -0.1238366 0.5978951 0.7926087 -0.1195527 0.5974559 0.7922988 -0.1237294 0.5998698 0.7912228 -0.118839 0.5978424 0.7923961 -0.1212142 0.6006621 0.789783 -0.1242901 0.5980319 0.7875723 -0.1486191 0.6099072 0.7835839 -0.1183625 0.6023467 0.7888403 -0.1221045 0.6084061 0.7785146 -0.1541336 0.6259735 0.7714385 -0.1141924 0.6119278 0.7801654 -0.1299474 0.6366475 0.7619892 -0.1185424 0.6246704 0.7652427 -0.1555327 0.6510331 0.7491479 -0.1222021 0.673951 0.7328357 -0.0934996 0.648252 0.7435337 -0.1640941 0.6984179 0.7103881 -0.08695572 0.6773689 0.713288 -0.1799764 0.7283489 0.6797471 -0.08632445 0.7154616 0.6769118 -0.1729311 0.7633 0.6397777 -0.08976459 0.7567866 0.6324662 -0.1651076 0.8016987 0.5755081 -0.1614611 0.8342586 0.5390181 -0.1160686 0.798783 0.5889859 -0.1226433 0.8584305 0.5069701 -0.07796388 0.8427192 0.5011851 -0.1965649 0.8860431 0.4506313 -0.1088995 0.8835517 0.4073497 -0.2310901 0.8210536 0.5663673 -0.0714069 0.8210952 0.5663043 -0.07142895 0.8835576 0.4234916 -0.1999521 0.8210481 0.566386 -0.07132315 0.8210777 0.5663328 -0.07140582 0.85431 0.3025419 -0.422638 0.8748718 0.372199 -0.3099471 0.6664476 0.04852235 -0.7439712 0.7935675 0.5806531 0.1819137 0.8118046 0.5667232 0.1407057 0.7956587 0.5794006 0.176698 0.8308571 0.5491017 0.09035378 0.8400539 0.539142 0.0602954 0.8472786 0.5295119 0.04166865 0.8365339 0.5431215 0.07232022 0.8570069 0.5152518 0.007402241 0.611797 0.7774115 0.1460685 0.4785029 0.8655021 0.1481246 0.6341757 0.7590897 0.1469833 0.6116124 0.7780351 0.1434982 0.6388309 0.7554264 0.1456916 0.6341556 0.7596516 0.1441389 0.6413109 0.7531638 0.1465082 0.6388338 0.7555063 0.1452639 0.6474097 0.7476484 0.1479278 0.6413503 0.7536479 0.1438216 0.6570264 0.7388105 0.1499179 0.6476116 0.7486735 0.1417294 0.6699803 0.7265633 0.1524213 0.6576897 0.7403647 0.1389406 0.6860139 0.710784 0.1554702 0.6716334 0.7283888 0.135493 0.704762 0.6913906 0.1590272 0.6894645 0.7122986 0.1314132 0.7257438 0.668371 0.1630223 0.7110975 0.6915702 0.1267714 0.7483523 0.6418343 0.1673846 0.7362461 0.6656671 0.1217743 0.7718862 0.6120557 0.1719875 0.7643258 0.6341762 0.1167329 0.7944217 0.5969627 0.111936 0.5950814 0.8021293 0.04966533 0.6236799 0.7800678 0.05017411 0.5948868 0.8023733 0.0480287 0.6293989 0.775516 0.04931569 0.6235775 0.7802646 0.04835754 0.6327761 0.7727289 0.04984498 0.6293849 0.7755478 0.04899424 0.6409102 0.7659319 0.05081671 0.6327112 0.7728962 0.04804009 0.6536932 0.7549602 0.05215674 0.640833 0.7662647 0.04659903 0.6709141 0.7395752 0.05387836 0.6537603 0.7553815 0.04467815 0.6922574 0.7194706 0.0560519 0.6714366 0.7398522 0.04232776 0.7172327 0.6943632 0.05862486 0.6937338 0.7191458 0.03953337 0.7451392 0.6640546 0.06163632 0.7203325 0.6926716 0.03643035 0.7750607 0.628533 0.06501734 0.7506531 0.6598641 0.03315573 0.8059113 0.588045 0.06863009 0.7837657 0.6203368 0.02989357 0.8183611 0.574075 0.02689236 -0.1329752 0.9617486 0.239494 -0.2738705 0.9462155 0.1722539 -0.617797 -0.3163422 0.7198989 -0.6849224 -0.3800584 0.6216405 -0.7541977 -0.4847176 0.442984 -0.7816476 -0.553169 0.2881512 -0.7874665 -0.5586238 0.2604536 -0.7915206 -0.5804979 0.1910949 -0.7846859 -0.56235 0.2608269 -0.7846028 -0.5622704 0.2612475 -0.680433 -0.3862133 0.6227762 -0.6798242 -0.3856058 0.6238169 -0.7912847 -0.5527154 0.2614844 -0.7943916 -0.5483834 0.2611851 -0.7914885 -0.5529226 0.2604277 -0.7965083 -0.5454308 0.2609208 -0.7945359 -0.5485363 0.2604243 -0.7976343 -0.5438677 0.260744 -0.7965889 -0.5455188 0.2604907 -0.7977778 -0.5437119 0.2606303 -0.7976606 -0.5438969 0.260603 -0.7969433 -0.54497 0.2605556 -0.7977578 -0.5436897 0.2607372 -0.7951065 -0.5476545 0.2605385 -0.796876 -0.544896 0.2609157 -0.7922818 -0.551752 0.2604981 -0.7950095 -0.5475502 0.2610529 -0.7883965 -0.5572462 0.260591 -0.7921258 -0.5515902 0.2613139 -0.7834644 -0.5641378 0.2606379 -0.7882165 -0.5570685 0.2615139 -0.7774184 -0.5723653 0.2608036 -0.7832278 -0.5639187 0.2618209 -0.7702238 -0.5819412 0.2609593 -0.7771489 -0.5721347 0.2621098 -0.7618405 -0.5928048 0.2611162 -0.769918 -0.5817033 0.2623882 -0.7522223 -0.6049066 0.2612465 -0.7615026 -0.5925697 0.2626308 -0.7412911 -0.6181643 0.2614584 -0.751825 -0.6046638 0.2629467 -0.7290217 -0.6325289 0.2615998 -0.7408664 -0.6179407 0.2631846 -0.7153565 -0.6478863 0.2617413 -0.7285494 -0.6323198 0.2634148 -0.7002503 -0.6641346 0.2618678 -0.7148367 -0.6476976 0.2636216 -0.6836803 -0.6811738 0.261885 -0.6997063 -0.6639776 0.2637137 -0.6656171 -0.6988393 0.2618735 -0.6830863 -0.6810427 0.2637689 -0.6460589 -0.7170118 0.2617291 -0.6650046 -0.6987411 0.263685 -0.6249591 -0.7355588 0.2614946 -0.6454121 -0.716942 0.2635095 -0.6026666 -0.7540103 0.261269 -0.6242542 -0.7355141 0.263298 -0.5649698 -0.7832358 0.2595205 -0.6019704 -0.7539911 0.2629239 -0.4725614 -0.8437327 0.2545598 -0.5632792 -0.7832592 0.2631 -0.3016887 -0.9216336 0.2440806 -0.4685978 -0.8439343 0.2611343 -0.07959002 -0.9702385 0.2286977 -0.2943824 -0.9216785 0.2526811 0.02325654 -0.9743368 0.2238907 -0.07235205 -0.9693089 0.2349585 -0.03652322 -0.9722288 0.2311647 0.02393347 -0.9741988 0.2244189 -0.2563193 -0.9342 0.2481346 -0.04052013 -0.972852 0.2278537 -0.5044299 -0.8232637 0.2603603 -0.2607883 -0.9342542 0.2432255 -0.6743593 -0.6898953 0.2632184 -0.5061256 -0.8231816 0.2573106 -0.6747951 -0.6899777 0.2618824 -0.6871946 -0.3715792 0.6242536 -0.691223 -0.3661084 0.6230372 -0.6892014 -0.373594 0.6208292 -0.6939033 -0.3623414 0.6222595 -0.6925166 -0.367418 0.620826 -0.6954881 -0.3605941 0.6215049 -0.6947587 -0.3632125 0.6207954 -0.6958447 -0.3606808 0.6210552 -0.6957833 -0.3608955 0.6209993 -0.695007 -0.3626414 0.6208513 -0.6956464 -0.3604782 0.6213948 -0.692965 -0.3665314 0.6208496 -0.6943628 -0.3619841 0.6219549 -0.6896975 -0.3723197 0.6210439 -0.6919061 -0.3654559 0.622662 -0.6850818 -0.3799263 0.6215458 -0.6881765 -0.3707858 0.6236434 -0.6791325 -0.3893986 0.6222121 -0.6831974 -0.378045 0.6247586 -0.671817 -0.4007655 0.6229357 -0.6769575 -0.3872542 0.6259095 -0.6629313 -0.4138444 0.623903 -0.6692493 -0.3982737 0.6272827 -0.6525155 -0.4287143 0.6248421 -0.660133 -0.4111794 0.6286144 -0.640328 -0.4451637 0.6259468 -0.6493686 -0.4257829 0.6301027 -0.6264215 -0.4632385 0.6269022 -0.6370137 -0.4421541 0.6314375 -0.6106081 -0.4827435 0.6277869 -0.6228836 -0.4601168 0.6326994 -0.5927816 -0.503502 0.6285665 -0.6068561 -0.4795373 0.6338531 -0.5729419 -0.5254111 0.6290316 -0.5889282 -0.5003226 0.6346975 -0.5509048 -0.5481837 0.6292841 -0.5689061 -0.5222051 0.6353327 -0.5267778 -0.5716727 0.6290434 -0.5468554 -0.5450935 0.63547 -0.5003745 -0.5954917 0.6285022 -0.5225747 -0.5685963 0.6353061 -0.4717822 -0.6195592 0.62735 -0.4962025 -0.5925646 0.6345473 -0.4416131 -0.6431456 0.625573 -0.4677506 -0.6168476 0.6330153 -0.3917325 -0.6813673 0.6182914 -0.4374388 -0.6404479 0.6312478 -0.2706544 -0.7552454 0.596951 -0.3823452 -0.6756403 0.6303351 -0.05633586 -0.8321911 0.5516196 -0.2523909 -0.7450259 0.6174426 0.1963226 -0.8483218 0.4917393 -0.02938789 -0.8168747 0.5760661 0.3068822 -0.8263687 0.4721632 0.2168299 -0.8341491 0.5071291 0.2498536 -0.8321138 0.4951361 0.308423 -0.8251683 0.4732574 0.008586287 -0.8280556 0.5605803 0.2389592 -0.839989 0.4871519 -0.3066246 -0.723913 0.618006 -0.007446467 -0.8373698 0.5465861 -0.536586 -0.5568801 0.6340032 -0.3148331 -0.7286025 0.6082914 -0.539828 -0.5593138 0.6290897 0.5009229 0.8257486 -0.2592598 0.2255089 0.9441604 -0.2402222 0.5488384 0.7949205 -0.2586073 0.5022813 0.8261483 -0.2553281 0.547069 0.7947217 -0.2629313 0.5576596 0.7881185 -0.2605477 0.5573512 0.7880797 -0.2613236 0.5640469 0.7842364 -0.2585041 0.5623566 0.7840108 -0.2628349 0.578588 0.7745388 -0.2555887 0.5747956 0.7739434 -0.2657475 0.6009472 0.75859 -0.251801 0.5947114 0.7573215 -0.2697821 0.6305969 0.7357521 -0.2470151 0.6218927 0.7332494 -0.2749451 0.6666513 0.7052609 -0.2412117 0.6559133 0.7005609 -0.2810556 0.7078529 0.6663708 -0.2342953 0.6959007 0.6578947 -0.2879181 0.7524285 0.6185581 -0.226356 0.7403903 0.6039966 -0.2949749 0.7981913 0.5617153 -0.217639 0.7871195 0.5380518 -0.3015677 0.8426936 0.4963338 -0.2086148 0.83308 0.4602595 -0.3068208 0.6382751 0.1727163 -0.7501826 0.8048997 0.3836259 -0.4527336 0.6008142 0.2890665 -0.7452938 0.7472002 0.4573184 -0.4822363 0.5584288 0.3917036 -0.7312493 0.6840032 0.5206266 -0.5109674 0.5153861 0.4771103 -0.7118588 0.6192988 0.57259 -0.5372241 0.4753257 0.5448669 -0.6907862 0.5571387 0.6132 -0.5599842 0.4408686 0.5965697 -0.6706261 0.501065 0.6432721 -0.5789085 0.4135062 0.6344694 -0.65304 0.4538426 0.6641745 -0.5940531 0.3938614 0.6606199 -0.6391045 0.4173259 0.6773362 -0.6058505 0.382328 0.6767727 -0.6291295 0.392538 0.6839191 -0.6149541 0.3784886 0.6836968 -0.6239431 0.3802227 0.6849051 -0.6215592 0.3604293 0.6887905 -0.6290138 0.3715358 0.6964338 -0.6139552 0.3121173 0.7360945 -0.6006229 0.3029466 0.7289608 -0.6138726 -0.6947551 0.7120425 -0.101542 -0.759608 0.6326668 -0.1507595 -0.822919 0.5264782 -0.2136005 -0.06646502 -0.9957601 0.06359434 -0.7745767 -0.6304642 -0.0504561 -0.1212688 -0.9910985 0.05493414 -0.753947 -0.6397752 -0.1491701 -0.7750914 -0.6299497 -0.04895836 -0.7555453 -0.6387917 -0.1452463 -0.7535521 -0.641125 -0.1453205 -0.7535299 -0.6410997 -0.1455468 -0.7731671 -0.6323029 -0.04904896 -0.7731676 -0.632293 -0.04916787 -0.7574793 -0.6364856 -0.1452966 -0.7572361 -0.6366381 -0.1458955 -0.7591517 -0.6344588 -0.1454328 -0.7589775 -0.6345696 -0.1458584 -0.7602834 -0.633081 -0.145526 -0.7601687 -0.6331546 -0.1458042 -0.7608532 -0.6323761 -0.1456117 -0.7608115 -0.6324031 -0.1457129 -0.7608687 -0.6323385 -0.1456946 -0.7608968 -0.6323204 -0.1456266 -0.7603211 -0.6329761 -0.1457849 -0.7604194 -0.6329128 -0.145546 -0.7592452 -0.6342625 -0.1458006 -0.7593746 -0.6341802 -0.1454843 -0.7575803 -0.6362406 -0.1458427 -0.7577781 -0.6361166 -0.1453545 -0.7553592 -0.6388725 -0.1458576 -0.7555956 -0.6387276 -0.1452668 -0.752565 -0.6421676 -0.1458309 -0.7528293 -0.6420099 -0.1451597 -0.7491666 -0.6461242 -0.1458527 -0.7494854 -0.6459404 -0.1450266 -0.7451918 -0.6507101 -0.1458268 -0.7455205 -0.6505286 -0.1449544 -0.7406045 -0.6559329 -0.1457978 -0.7409528 -0.6557503 -0.1448463 -0.7354161 -0.6617584 -0.1457361 -0.7357645 -0.6615872 -0.1447513 -0.729581 -0.6681914 -0.1457116 -0.7299467 -0.6680256 -0.1446358 -0.7231271 -0.6751826 -0.1456567 -0.7234777 -0.6750392 -0.1445758 -0.7160304 -0.6827099 -0.1456283 -0.7163766 -0.6825864 -0.1445009 -0.7082837 -0.6907473 -0.1456105 -0.7086129 -0.6906496 -0.1444674 -0.6999064 -0.6992433 -0.1455669 -0.7002012 -0.6991772 -0.1444628 -0.690868 -0.7081697 -0.1455917 -0.6911472 -0.7081315 -0.1444481 -0.6812027 -0.7174676 -0.145613 -0.6814424 -0.7174609 -0.1445197 -0.670916 -0.7270855 -0.1456661 -0.6711204 -0.7271087 -0.1446048 -0.6600017 -0.7369906 -0.1457476 -0.6601678 -0.7370417 -0.1447344 -0.6416783 -0.7528121 -0.1467065 -0.6419429 -0.7530306 -0.1444104 -0.5971291 -0.7883085 -0.1483466 -0.5971009 -0.789098 -0.1442043 -0.5157644 -0.8432286 -0.1515009 -0.514401 -0.8450726 -0.1457527 -0.4058559 -0.9004728 -0.1563003 -0.4032154 -0.9024775 -0.1514989 -0.3539617 -0.9218046 -0.1580742 -0.3536819 -0.9219812 -0.1576698 -0.386564 -0.9092597 -0.154321 -0.3881008 -0.9081646 -0.1568911 -0.4968844 -0.8551695 -0.1476177 -0.4978769 -0.8539853 -0.1510882 -0.6143274 -0.7756634 -0.1447347 -0.6142505 -0.7753655 -0.1466445 -0.6960077 -0.7033554 -0.1444453 -0.6957873 -0.7033948 -0.1453126 -0.7013568 -0.71113 -0.04891467 -0.7014835 -0.7110453 -0.0483269 -0.597674 -0.8001773 -0.0500195 -0.5976938 -0.800242 -0.04873424 -0.4474123 -0.8927076 -0.05381041 -0.4467175 -0.8931919 -0.05149459 -0.3057954 -0.9502793 -0.05880874 -0.3047927 -0.9507034 -0.05713605 -0.2627453 -0.9630152 -0.05972051 -0.2629244 -0.9629502 -0.05998098 -0.3283836 -0.9429426 -0.05498552 -0.3301582 -0.9421303 -0.05818986 -0.4712631 -0.880572 -0.05004084 -0.4722495 -0.8798133 -0.05393612 -0.576781 -0.8154602 -0.04845875 -0.5768666 -0.8152292 -0.05124741 -0.6336248 -0.7721216 -0.04845589 -0.6334965 -0.7721311 -0.04995799 -0.6566004 -0.7526724 -0.04858154 -0.6565058 -0.752708 -0.04930335 -0.6704548 -0.740364 -0.04849445 -0.670345 -0.7404174 -0.0491907 -0.68349 -0.7283526 -0.04841434 -0.6833532 -0.7284306 -0.04916411 -0.6956992 -0.7167021 -0.04838031 -0.6955448 -0.7168008 -0.04913359 -0.7070653 -0.7054919 -0.04837065 -0.7068925 -0.7056124 -0.04913657 -0.7175961 -0.6947785 -0.0483613 -0.7174028 -0.6949226 -0.04915159 -0.72727 -0.6846411 -0.04842358 -0.7270787 -0.6847922 -0.04915493 -0.7361214 -0.6751134 -0.04844778 -0.7359083 -0.6752901 -0.04921764 -0.7441387 -0.6662611 -0.04851412 -0.7439309 -0.6664406 -0.04923003 -0.7513447 -0.6581184 -0.04859292 -0.7511394 -0.6583024 -0.04927295 -0.7577501 -0.6507267 -0.04867714 -0.7575501 -0.6509115 -0.04931718 -0.7633767 -0.6441099 -0.04876887 -0.763188 -0.6442888 -0.0493564 -0.7682455 -0.6382894 -0.04884278 -0.7680647 -0.6384647 -0.04939204 -0.7723538 -0.633305 -0.04893463 -0.7721977 -0.6334591 -0.04939955 -0.7757486 -0.629137 -0.04899883 -0.7756057 -0.6292803 -0.04941791 -0.7784031 -0.6258413 -0.04910564 -0.7783025 -0.6259434 -0.0493974 -0.7803708 -0.6233808 -0.04917138 -0.7802866 -0.623467 -0.04941338 -0.781638 -0.6217864 -0.0492317 -0.7815867 -0.6218392 -0.04937821 -0.7822139 -0.6210566 -0.0492959 -0.7822015 -0.6210694 -0.04933118 -0.7821051 -0.621188 -0.04936724 -0.7821352 -0.6211569 -0.04928147 -0.7813242 -0.6221661 -0.04941546 -0.7813882 -0.6221001 -0.04923224 -0.7798643 -0.6239926 -0.04944545 -0.7799663 -0.6238883 -0.04915261 -0.7777152 -0.6266657 -0.04948937 -0.7778671 -0.6265117 -0.04904943 -0.01869744 -0.9542005 0.2985831 0.1895849 -0.9583756 0.2134798 0.2771481 -0.9455693 0.1705507 0.3300133 -0.1339601 0.9344227 0.34572 -0.1224249 0.9303171 0.7565085 0.3061119 0.5779191 0.7806588 0.3376467 0.525896 0.812559 0.3988623 0.4250373 0.8371933 0.4704932 0.2788255 0.8345608 0.464178 0.2967272 0.7045218 0.7068853 -0.06294596 0.8388957 0.5142866 0.1782225 0.8394528 0.518515 0.1626691 0.790647 0.5856118 0.1787066 0.7906333 0.5855916 0.1788337 0.7820003 0.5481498 0.2966607 0.7819224 0.5480411 0.2970663 0.7248541 0.4425886 0.5279221 0.7244567 0.442126 0.5288543 0.2944711 -0.01203167 0.9555846 0.292639 -0.01351618 0.9561275 0.8257366 0.5355977 0.1769015 0.8127163 0.5549753 0.1774675 0.8256104 0.5351887 0.1787191 0.8010045 0.5716025 0.1779395 0.8125863 0.5546636 0.1790304 0.791022 0.5852178 0.1783379 0.8008797 0.5713719 0.1792368 0.7830196 0.59578 0.1786803 0.7909102 0.5850517 0.1793757 0.777338 0.6030964 0.178942 0.7829331 0.5956718 0.1794181 0.7746173 0.6065226 0.1791607 0.7772839 0.6030366 0.1793788 0.7745235 0.6066194 0.1792377 0.7746066 0.6065115 0.1792441 0.7751477 0.6058241 0.1792294 0.7745304 0.6066266 0.1791834 0.7758147 0.6049644 0.1792471 0.7751514 0.605828 0.1791999 0.7751181 0.6058794 0.1791707 0.7758184 0.6049684 0.1792178 0.7726261 0.6090542 0.1791707 0.7750981 0.6058583 0.1793287 0.7687044 0.6139917 0.1791864 0.7725932 0.6090213 0.1794236 0.7634262 0.6205327 0.1792197 0.7686591 0.61395 0.1795238 0.756645 0.6287684 0.1792725 0.7633664 0.6204835 0.1796441 0.7483007 0.6386471 0.179377 0.756564 0.6287111 0.1798146 0.7384038 0.6500613 0.1793881 0.7482191 0.6385993 0.1798869 0.7268577 0.6629199 0.1794857 0.7382901 0.6500086 0.1800464 0.7135942 0.6771584 0.1795548 0.7267273 0.662875 0.1801783 0.6985827 0.6926327 0.1795614 0.7134512 0.6771246 0.1802484 0.6817438 0.7092258 0.1795102 0.6984235 0.6926109 0.1802631 0.6630339 0.726768 0.179428 0.6815582 0.7092162 0.1802518 0.6423798 0.7451137 0.1793146 0.6628167 0.7267723 0.1802115 0.6192194 0.7645364 0.1790294 0.6421599 0.7451306 0.1800301 0.5733838 0.7997689 0.1777665 0.6189396 0.7645706 0.1798489 0.4741522 0.8629727 0.1745218 0.5726646 0.7998929 0.1795176 0.3049528 0.937563 0.1672704 0.4725729 0.863269 0.1773178 0.1133513 0.9809445 0.1577946 0.3021038 0.9378668 0.1707025 0.04810786 0.9866918 0.1553223 0.1109644 0.9808707 0.1599359 0.125361 0.9790102 0.1606974 0.04819673 0.9866991 0.1552482 0.3361032 0.9260949 0.1714145 0.1270854 0.9790444 0.159127 0.548645 0.8167999 0.1783995 0.337564 0.9259068 0.1695492 0.6937229 0.6973778 0.1800359 0.5491358 0.8167076 0.1773091 0.6938512 0.6973913 0.1794877 0.8205139 0.4913389 0.2921354 0.8063297 0.5135509 0.2934241 0.8196362 0.489555 0.2975441 0.7934695 0.5326036 0.2945158 0.8055275 0.5121349 0.298066 0.7824326 0.5481881 0.2954471 0.7927673 0.5315141 0.29835 0.7735434 0.5602555 0.2962164 0.7818548 0.5473856 0.2984494 0.7671999 0.5685536 0.2969027 0.7731024 0.559695 0.2984198 0.7641385 0.5723477 0.297507 0.7669338 0.5682362 0.2981951 0.7640126 0.5723673 0.2977923 0.764076 0.5722753 0.2978069 0.7646967 0.5714296 0.2978376 0.7640342 0.5723924 0.2976887 0.765461 0.5704945 0.297667 0.7647635 0.5715075 0.2975166 0.7646866 0.571608 0.297521 0.7654584 0.5704916 0.2976791 0.7619273 0.575349 0.297389 0.7646056 0.5715136 0.2979102 0.7575504 0.5810801 0.2974279 0.7617558 0.5751544 0.2982039 0.7516514 0.5886644 0.2974803 0.7573259 0.5808367 0.2984733 0.7440457 0.5982029 0.2975726 0.7513639 0.5883705 0.2987849 0.7346745 0.6096041 0.2977186 0.7436907 0.5978668 0.299131 0.7235009 0.6227679 0.2978366 0.7342679 0.609254 0.2994335 0.7104448 0.6375862 0.2979128 0.7230424 0.6224148 0.299682 0.6953887 0.6539313 0.2980075 0.7099131 0.6372272 0.2999415 0.678303 0.6716705 0.2979323 0.6948279 0.6536057 0.300023 0.6590214 0.6905843 0.2979667 0.6776264 0.6713395 0.3002098 0.6375665 0.7105274 0.2977581 0.6583265 0.6903035 0.3001458 0.6138189 0.7312564 0.2974736 0.6367942 0.710275 0.3000043 0.5871202 0.7530935 0.2968839 0.613017 0.7310492 0.2996286 0.5344249 0.792465 0.2939206 0.5861068 0.7528916 0.2993881 0.4204275 0.8607407 0.286995 0.531906 0.7921592 0.2992654 0.2286819 0.9345861 0.2724947 0.4153989 0.8604433 0.295095 0.01661312 0.9665589 0.2559066 0.220035 0.9337374 0.2823454 -0.05536758 0.9659504 0.252733 0.01015836 0.9651378 0.2615457 0.02684944 0.9644382 0.262941 -0.05510437 0.9660218 0.2525178 0.2609121 0.9228968 0.2831717 0.0315088 0.9654145 0.2588086 0.505195 0.8104561 0.296545 0.2654203 0.9232632 0.2777354 0.6726114 0.6766617 0.299538 0.5068783 0.8106128 0.2932256 0.6730676 0.6768731 0.2980315 0.7693672 0.3756901 0.5166537 0.7534657 0.4024837 0.5199003 0.7645888 0.3693413 0.528196 0.7387311 0.4253352 0.5228445 0.7492169 0.3971137 0.5300706 0.7259224 0.444007 0.5252564 0.7351929 0.4210681 0.5312185 0.7154834 0.4584016 0.5272112 0.7231156 0.4407579 0.5318236 0.7078693 0.4680891 0.5289743 0.7133672 0.4560318 0.5321113 0.7040712 0.4722841 0.5303125 0.7066748 0.4667828 0.5317186 0.7037435 0.4720156 0.5309862 0.7037709 0.4719591 0.531 0.7045163 0.4708005 0.5310403 0.7038589 0.4721404 0.5307222 0.7053614 0.4696428 0.5309433 0.7046926 0.4709916 0.5306366 0.7046658 0.4713382 0.5303645 0.7054638 0.4697542 0.5307089 0.7015351 0.4760941 0.5302669 0.7042309 0.4708665 0.5313602 0.6965035 0.4832723 0.5304062 0.7007626 0.475265 0.532029 0.6897 0.4927486 0.5305777 0.6955119 0.4822258 0.5326551 0.6808031 0.5045561 0.5309711 0.6883939 0.4914011 0.5335156 0.6698362 0.5187035 0.5312872 0.679318 0.503068 0.534275 0.6565684 0.5348564 0.5318332 0.6680377 0.5169652 0.5352314 0.6409937 0.5530549 0.5322192 0.654619 0.5330511 0.536032 0.6229332 0.5730432 0.5325183 0.638851 0.5511663 0.5367355 0.602208 0.5945968 0.5327292 0.6205754 0.5710779 0.5373604 0.5789144 0.6176081 0.5323705 0.5998549 0.5927532 0.5374177 0.552678 0.6415528 0.5319372 0.5762959 0.6156896 0.5374099 0.5236297 0.6662775 0.5309295 0.5500296 0.639745 0.5368369 0.4908491 0.6920658 0.5292562 0.520883 0.6645346 0.5357936 0.4270529 0.738703 0.5214822 0.4875437 0.6901181 0.5348254 0.2899808 0.814365 0.5027134 0.419443 0.7347404 0.5331267 0.06758522 0.8826281 0.465188 0.2761655 0.8081666 0.5201915 -0.1632128 0.8907398 0.4241983 0.04773569 0.8734394 0.4845873 -0.2395199 0.8774828 0.4155167 -0.1758729 0.8833975 0.4343703 -0.1570485 0.8850702 0.4381629 -0.2390367 0.8777899 0.4151461 0.09848427 0.8668382 0.4887662 -0.1476188 0.890438 0.4304986 0.3892037 0.7557186 0.5266973 0.1092767 0.8716923 0.4777145 0.5945467 0.5991666 0.5362029 0.3941224 0.7581493 0.5194972 0.5963404 0.6005492 0.5326526 0.3517209 -0.07318192 0.93324 0.3324022 -0.04755324 0.9419381 0.3288879 -0.09069335 0.9400039 0.3144655 -0.02551436 0.948926 0.3128079 -0.06288927 0.9477322 0.2988907 -0.007416605 0.9542586 0.2985565 -0.03818941 0.9536276 0.2859411 0.00634545 0.9582262 0.2864003 -0.01751691 0.9579499 0.2761605 0.01525092 0.9609905 0.2769051 -0.001047492 0.9608967 0.2705593 0.01833939 0.9625286 0.2710576 0.01104187 0.9624998 0.2692751 0.01723784 0.962909 0.2692723 0.01727378 0.9629091 0.2699634 0.01582038 0.9627406 0.2697767 0.01765304 0.9627611 0.2710571 0.01478642 0.9624497 0.2708502 0.01655375 0.9624791 0.270982 0.01719164 0.9624309 0.2712815 0.01497173 0.9623836 0.2679936 0.02262979 0.9631549 0.2690853 0.01562255 0.9629896 0.262847 0.03058582 0.9643526 0.2647615 0.01994508 0.9641076 0.2554405 0.04073852 0.9659661 0.2583275 0.02681046 0.9656853 0.2458252 0.05353611 0.9678347 0.2499601 0.036125 0.967582 0.2337792 0.06877845 0.9698539 0.2394023 0.04807609 0.9697294 0.2193061 0.08639174 0.9718238 0.226638 0.06263566 0.9719629 0.2020763 0.1061164 0.9736039 0.2113894 0.07948708 0.9741644 0.1821726 0.1279757 0.9749028 0.1937152 0.09870773 0.9760795 0.1596201 0.1518356 0.9754319 0.1736219 0.1202622 0.9774418 0.1338334 0.176976 0.9750733 0.1505032 0.1434458 0.9781473 0.1055842 0.2037684 0.9733091 0.1250701 0.1687328 0.9776946 0.07435268 0.2313247 0.9700312 0.09675639 0.1952637 0.9759664 0.039649 0.2603538 0.9646987 0.06571924 0.2227894 0.972649 -0.02346158 0.3177471 0.9478852 0.02970892 0.250239 0.9677282 -0.1543823 0.4096898 0.8990664 -0.0433017 0.2963982 0.9540823 -0.3467229 0.4913706 0.7989607 -0.1826415 0.3756629 0.9085811 -0.5220019 0.4981508 0.6923581 -0.37602 0.4492161 0.8104405 -0.5758779 0.4772014 0.6638098 -0.5357029 0.4739951 0.6988213 -0.5214422 0.4755247 0.7085015 -0.5751748 0.478539 0.6634564 -0.3306959 0.4472085 0.8310503 -0.5109314 0.4937681 0.7036634 -0.06843006 0.3240779 0.9435523 -0.3136668 0.4707702 0.8246142 0.1473089 0.1519135 0.9773548 -0.05589872 0.3378888 0.9395246 0.1535822 0.1577211 0.9754673 0.681936 -0.7256027 -0.09200108 0.6091229 0.7905958 -0.0626713 0.7659859 -0.6234862 -0.1566221 0.821078 -0.5301552 -0.2115806 0.6091562 0.7904709 -0.06391018 0.8201565 0.5720934 -0.007258594 0.8075706 0.5863255 -0.06365752 0.8192471 0.5733487 -0.01026767 0.1726185 0.983475 0.05458796 0.7897846 0.5998049 -0.1283526 0.8071156 0.5868101 -0.06494843 0.7587361 0.6138925 -0.217843 0.7895643 0.5999783 -0.1288961 0.7595582 0.6134868 -0.2161145 0.7355476 0.6429365 -0.2135473 0.7355105 0.6429221 -0.2137182 0.758725 0.6389963 -0.1265704 0.7587006 0.6389869 -0.1267642 0.77163 0.632931 -0.06313103 0.7716224 0.6329281 -0.06325137 0.7800501 0.625654 -0.008881032 0.7800489 0.6256544 -0.008961915 0.7057236 0.7084352 -0.008591711 0.7057645 0.7083981 -0.008295774 0.5987858 0.8008537 -0.009430468 0.5987524 0.8008857 -0.008807718 0.4435516 0.8961587 -0.01271706 0.4431378 0.896379 -0.01155245 0.285045 0.9583472 -0.01789069 0.2843809 0.9585626 -0.01689064 0.2239028 0.9744083 -0.01989692 0.2238684 0.9744172 -0.01985275 0.2730026 0.9618629 -0.01701241 0.2739346 0.9615729 -0.01836514 0.4181529 0.9083005 -0.01176965 0.4190258 0.9078679 -0.01390087 0.543501 0.8393571 -0.009285867 0.5437622 0.8391687 -0.01088821 0.6164333 0.7873609 -0.008548796 0.6164582 0.7873287 -0.009629249 0.6502696 0.7596558 -0.008524477 0.650251 0.7596663 -0.008994698 0.6674062 0.7446458 -0.008459508 0.6673795 0.7446653 -0.008839249 0.6827153 0.7306364 -0.008383333 0.6826733 0.7306706 -0.008814275 0.6966761 0.7173373 -0.008347094 0.6966243 0.7173825 -0.008773803 0.709306 0.7048514 -0.008346855 0.7092469 0.7049059 -0.008760988 0.7206436 0.6932556 -0.008341908 0.7205742 0.6933223 -0.008771777 0.7306922 0.6826556 -0.008389055 0.7306252 0.6827226 -0.008766412 0.7395059 0.6730971 -0.00844562 0.7394375 0.6731677 -0.008802354 0.7471042 0.6646528 -0.008484065 0.7470327 0.6647287 -0.008835256 0.7535194 0.6573699 -0.008563816 0.7534602 0.657434 -0.008841037 0.7587696 0.6513015 -0.008657932 0.7587209 0.6513553 -0.00887829 0.7628689 0.6464948 -0.008699715 0.762819 0.6465507 -0.008918762 0.7658967 0.6429038 -0.008773207 0.7658664 0.6429381 -0.008904218 0.7678869 0.6405249 -0.008800745 0.7678602 0.6405552 -0.008913815 0.7685278 0.6397551 -0.008852124 0.7685286 0.6397542 -0.008848547 0.7678295 0.6405926 -0.008892714 0.7678514 0.6405675 -0.008799612 0.7672047 0.6413416 -0.008839428 0.7672038 0.6413424 -0.008842945 0.7675514 0.6409268 -0.008804261 0.7675369 0.6409436 -0.008866846 0.7696627 0.6383913 -0.008707344 0.7695981 0.6384654 -0.008979499 0.7740496 0.6330654 -0.00869137 0.773952 0.633179 -0.009091794 0.7803674 0.6252613 -0.008669555 0.7802151 0.6254426 -0.009273111 0.7883052 0.6152228 -0.00870043 0.7881096 0.6154626 -0.009443938 0.7976908 0.6030028 -0.008784294 0.7974454 0.6033136 -0.009674906 0.8082414 0.588784 -0.008915841 0.8079413 0.5891789 -0.009955108 0.7521889 0.6226971 -0.2155467 0.7533526 0.6221842 -0.2129474 0.7456272 0.6306883 -0.2151103 0.7465812 0.6303167 -0.2128788 0.7398558 0.637565 -0.2147662 0.7406268 0.6373009 -0.2128838 0.7350702 0.6432062 -0.2143772 0.7356168 0.6430417 -0.2129912 0.731271 0.6475967 -0.2141523 0.7316957 0.6474834 -0.2130415 0.7287372 0.6505478 -0.2138445 0.7289485 0.6504966 -0.2132796 0.7276096 0.6518923 -0.2135903 0.7276589 0.6518809 -0.2134571 0.7274664 0.6520689 -0.2135393 0.7274658 0.652069 -0.2135406 0.7279304 0.6515867 -0.2134291 0.7278434 0.651607 -0.2136642 0.7282899 0.651153 -0.2135263 0.728284 0.6511545 -0.2135422 0.7277818 0.6516723 -0.213675 0.7278831 0.6516487 -0.2134013 0.7264839 0.6531015 -0.213728 0.7266272 0.6530699 -0.2133367 0.7245562 0.6552297 -0.2137579 0.7247415 0.6551923 -0.2132434 0.72197 0.6580642 -0.213801 0.7222027 0.6580233 -0.2131398 0.7187047 0.6616419 -0.2137604 0.7189457 0.6616076 -0.213055 0.7147377 0.6659327 -0.2137373 0.7150093 0.6659058 -0.2129107 0.7100835 0.6709084 -0.2136897 0.7103614 0.6708959 -0.2128036 0.7047026 0.6765516 -0.2137104 0.705004 0.6765584 -0.2126923 0.6986262 0.6828387 -0.2136651 0.6989009 0.6828683 -0.2126697 0.6918106 0.6897349 -0.2136911 0.6920863 0.6897945 -0.2126033 0.6842758 0.6972069 -0.2137034 0.6845204 0.6972946 -0.2126314 0.6760033 0.7052147 -0.2137563 0.6762211 0.705335 -0.2126677 0.6669981 0.7137115 -0.2138446 0.6671802 0.7138628 -0.212769 0.6569199 0.722903 -0.2141674 0.6570907 0.7231224 -0.2128984 0.6369558 0.7402541 -0.2152009 0.6371244 0.7408592 -0.2126036 0.595089 0.7737731 -0.2171273 0.5947308 0.7752113 -0.2129381 0.52478 0.8219957 -0.2211995 0.5228679 0.8246785 -0.2156719 0.4438679 0.8669704 -0.2265916 0.4416053 0.869028 -0.2231031 0.415996 0.8803538 -0.2278693 0.4161131 0.8802582 -0.2280252 0.4500261 0.8646872 -0.2231424 0.4516572 0.8631512 -0.2257781 0.5394672 0.8138329 -0.2159889 0.5403409 0.8124373 -0.2190376 0.6278486 0.7486294 -0.2129793 0.6277957 0.7481979 -0.2146452 0.6903387 0.6915435 -0.2126035 0.6901385 0.691493 -0.213416 0.7803429 0.612023 -0.1284245 0.7812952 0.6113247 -0.1259363 0.7719744 0.6226171 -0.1280764 0.772773 0.6220716 -0.1258918 0.7646133 0.6317098 -0.1277083 0.7652261 0.631319 -0.1259577 0.7584173 0.6391875 -0.1274465 0.758899 0.6388993 -0.1260164 0.7535527 0.6449744 -0.1271466 0.7538706 0.6447944 -0.126172 0.750227 0.6489005 -0.1268372 0.7503968 0.6488082 -0.1263045 0.7486875 0.6507063 -0.1266823 0.748757 0.6506692 -0.1264623 0.7484951 0.6509525 -0.1265537 0.7484712 0.6509653 -0.1266295 0.74903 0.6503455 -0.1265103 0.7489801 0.6503721 -0.1266684 0.7495149 0.6497582 -0.1266553 0.7495252 0.6497527 -0.1266233 0.7489446 0.650406 -0.1267054 0.7489961 0.6503784 -0.1265415 0.7473153 0.652265 -0.1267687 0.7474337 0.652203 -0.1263887 0.7448744 0.6550408 -0.1268211 0.7450299 0.6549621 -0.1263136 0.7416108 0.6587346 -0.1268154 0.7417833 0.6586511 -0.1262388 0.7374371 0.6634043 -0.1268117 0.7376397 0.6633124 -0.1261125 0.7323654 0.6689952 -0.1268324 0.732594 0.6689001 -0.1260101 0.726397 0.6754757 -0.126807 0.7266236 0.6753923 -0.1259502 0.7195049 0.682815 -0.1267927 0.7197356 0.6827438 -0.1258636 0.7116672 0.6909835 -0.126774 0.7118898 0.6909312 -0.1258059 0.7028791 0.6999228 -0.1267632 0.7030875 0.6998934 -0.1257661 0.6931153 0.7095897 -0.126782 0.6933059 0.7095865 -0.1257537 0.6823731 0.7199212 -0.1268084 0.6825348 0.7199463 -0.1257919 0.6706414 0.7308564 -0.1268431 0.6707689 0.7309092 -0.1258597 0.6575134 0.7426462 -0.1270936 0.6576259 0.7427447 -0.1259303 0.631531 0.7646943 -0.1281066 0.6316066 0.7650513 -0.1255771 0.576423 0.8067682 -0.1298518 0.5759539 0.8077422 -0.125816 0.4827293 0.865566 -0.1332975 0.4807861 0.8674353 -0.1280653 0.373716 0.9172616 -0.137723 0.3714835 0.9186652 -0.1343658 0.3358983 0.931636 -0.1386604 0.3360021 0.9315783 -0.1387965 0.3817381 0.9144217 -0.1345703 0.3833294 0.9133847 -0.1370655 0.5015822 0.8555124 -0.1285069 0.5024837 0.8545476 -0.1313723 0.6188924 0.7753019 -0.1260123 0.6188966 0.7750408 -0.1275886 0.7006144 0.7023691 -0.1257658 0.7004663 0.7023855 -0.1264975 0.7967349 0.600865 -0.0646134 0.7974092 0.6001833 -0.06260019 0.7871764 0.6133663 -0.06430363 0.7877291 0.6128352 -0.06257677 0.7787064 0.6241127 -0.06402802 0.7791442 0.6237111 -0.06259846 0.7715899 0.6329202 -0.06372523 0.7719016 0.6326459 -0.06266695 0.765944 0.639765 -0.06348657 0.7661685 0.6395739 -0.06269806 0.7620394 0.6444284 -0.06330978 0.7621788 0.6443125 -0.06280797 0.7602282 0.6465811 -0.0631352 0.7602642 0.6465514 -0.06300383 0.7599541 0.6469109 -0.06305551 0.7599452 0.6469183 -0.06308841 0.7605466 0.6462147 -0.06305205 0.7605206 0.646236 -0.06314635 0.7611482 0.6454996 -0.06311541 0.7611405 0.6455062 -0.0631439 0.7605119 0.6462414 -0.06319653 0.7605584 0.6462032 -0.06302744 0.7586818 0.6483851 -0.0632354 0.7587602 0.6483215 -0.06294697 0.7559169 0.6516091 -0.06320899 0.7560066 0.6515375 -0.06287282 0.7521772 0.6559196 -0.06323736 0.752305 0.6558203 -0.06274586 0.7473965 0.6613591 -0.06326514 0.7475441 0.6612483 -0.06267881 0.7415888 0.6678691 -0.06322109 0.741732 0.667766 -0.06262725 0.7347142 0.6754237 -0.06322884 0.7348761 0.6753136 -0.06251984 0.7267727 0.6839655 -0.0631861 0.7269235 0.6838702 -0.06247979 0.7177148 0.6934634 -0.06319773 0.7178704 0.6933742 -0.06240433 0.7075408 0.7038434 -0.06317126 0.7076767 0.7037755 -0.06240075 0.6962128 0.7150489 -0.06318902 0.6963381 0.7149983 -0.06237602 0.6837197 0.7270014 -0.06321644 0.6838232 0.7269734 -0.06241381 0.6700466 0.739614 -0.06331372 0.670131 0.7396086 -0.06247884 0.6547518 0.7531709 -0.06351125 0.6548142 0.7531921 -0.0626111 0.6245301 0.7783482 -0.06431466 0.6245392 0.7784993 -0.06236666 0.5599016 0.8259425 -0.06579792 0.5594695 0.8264786 -0.06266713 0.4493541 0.8906925 -0.06890392 0.4477571 0.8918046 -0.06479376 0.3204312 0.9444531 -0.07302218 0.3186365 0.9452618 -0.07036185 0.2756732 0.9583974 -0.07401823 0.2757505 0.9583674 -0.07411903 0.3296209 0.9414767 -0.0705105 0.3308928 0.9408815 -0.07247024 0.4709389 0.8797615 -0.06508523 0.4716781 0.8791986 -0.06730228 0.7773897 0.6186059 -0.113982 0.8958135 0.4310234 -0.1083364 0.9684453 0.2292396 -0.09779065 0.9961452 0.02680665 -0.08352404 0.9838025 -0.1663669 -0.06674313 0.937619 -0.3442725 -0.04844647 0.8631799 -0.5040441 -0.02932387 0.7646379 -0.6443853 -0.009819209 0.6444073 -0.7646194 0.009815156 0.504023 -0.8631923 0.02932596 0.3442539 -0.9376257 0.04844921 0.1663835 -0.9837997 0.06674206 -0.02674937 -0.996147 0.08351939 -0.2292535 -0.9684419 0.09779161 -0.4310435 -0.8958039 0.1083368 -0.6186183 -0.7773798 0.1139829 -0.7773694 -0.6186316 0.1139821 -0.8957971 -0.4310577 0.1083366 -0.9684505 -0.2292175 0.09779006 -0.9961459 -0.02678519 0.08352196 -0.9838085 0.16633 0.06674695 -0.9376164 0.3442797 0.04844605 -0.8632316 0.503955 0.029334 -0.7645633 0.644474 0.009806096 -0.644434 0.764597 -0.009812176 -0.5040162 0.8631962 -0.02932751 -0.3442591 0.9376238 -0.04844892 -0.1663375 0.9838072 -0.06674712 0.02679544 0.9961455 -0.08352303 0.2292275 0.9684482 -0.09779 0.6681811 0.6681593 0.3272572 0.6186125 0.7773845 -0.1139828 0.4310624 0.8957946 -0.1083376 -0.6682251 -0.6682019 -0.32708 0.7773832 0.618614 0.1139827 0.8957992 0.4310532 0.1083371 0.9684507 0.2292172 0.0977891 0.9961454 0.02679985 0.08352297 0.9838039 -0.1663585 0.06674396 0.9376317 -0.3442374 0.04845017 0.8631851 -0.5040354 0.02932417 0.7646104 -0.6444182 0.009813368 0.6444421 -0.7645902 -0.009810268 0.5040066 -0.8632018 -0.02932846 0.3442389 -0.9376311 -0.04845058 0.1663541 -0.9838045 -0.0667448 -0.02676182 -0.9961466 -0.08352059 -0.2292234 -0.9684492 -0.09778976 -0.4310522 -0.8957997 -0.1083375 -0.6185998 -0.7773945 -0.1139832 -0.777382 -0.6186155 -0.1139827 -0.8958016 -0.4310483 -0.1083368 -0.9684464 -0.2292349 -0.09779018 -0.9961465 -0.02676826 -0.08352047 -0.9838046 0.1663541 -0.06674432 -0.9376268 0.3442509 -0.04844868 -0.8631976 0.5040138 -0.02932697 -0.7646248 0.644401 -0.00981456 -0.6444147 0.7646133 0.009813606 -0.5040202 0.8631938 0.02932667 -0.3442494 0.9376273 0.04844939 -0.1663642 0.9838029 0.06674385 0.02679467 0.9961456 0.08352309 0.2292795 0.9684356 0.09779322 -0.6681382 -0.6681671 0.3273289 0.618592 0.7774007 0.1139831 0.4310327 0.8958092 0.1083365 0.6681088 0.6680751 -0.3275761 0.7646121 0.644416 0.009814262 0.8631847 0.5040359 0.02932471 0.9376416 0.34421 0.04845261 0.9838004 0.1663799 0.06674164 0.996146 -0.02678328 0.08352196 0.9684457 -0.2292369 0.09779173 0.8958113 -0.4310283 0.1083361 0.7773801 -0.6186179 0.1139819 0.6186097 -0.7773867 0.1139826 0.4310483 -0.8958017 0.1083368 0.229242 -0.9684446 0.09779059 0.02677273 -0.9961463 0.08352082 -0.1663707 -0.9838019 0.06674247 -0.3442209 -0.9376377 0.04845201 -0.5040101 -0.8631997 0.02932721 -0.644436 -0.7645953 0.009811878 -0.7646149 -0.6444126 -0.009813249 -0.8631942 -0.5040196 -0.02932637 -0.9376296 -0.3442431 -0.04844975 -0.9838042 -0.1663559 -0.06674534 -0.9961462 0.02677226 -0.08352243 -0.9684466 0.2292342 -0.09779059 -0.8957946 0.4310624 -0.1083385 -0.777397 0.6185967 -0.1139825 -0.618611 0.7773857 -0.1139826 -0.4310436 0.8958039 -0.1083366 -0.229242 0.9684446 -0.09779059 -0.02678054 0.996146 -0.08352142 0.166343 0.9838066 -0.06674402 0.3442404 0.9376305 -0.04845029 -0.6681699 0.6681358 0.3273276 0.64442 0.7646088 -0.00981301 0.5040196 0.8631942 -0.02932637 0.6682665 -0.6680417 -0.3273228 0.764612 0.6444162 -0.009814202 0.863189 0.5040285 -0.02932566 0.9376298 0.3442424 -0.04845017 0.9838055 0.1663482 -0.06674546 0.9961465 -0.02676767 -0.08352088 0.9684447 -0.2292416 -0.09779095 0.8958063 -0.4310387 -0.1083367 0.7773623 -0.6186401 -0.1139833 0.6186239 -0.7773752 -0.1139837 0.4309942 -0.895828 -0.1083337 0.2292509 -0.9684426 -0.09779036 0.02680695 -0.9961452 -0.08352285 -0.1663684 -0.9838023 -0.06674301 -0.3442354 -0.9376325 -0.04845041 -0.5040228 -0.8631923 -0.02932578 -0.6444184 -0.7646101 -0.009813308 -0.7646087 -0.6444201 0.009813666 -0.8631871 -0.5040318 0.02932524 -0.9376356 -0.3442268 0.04845196 -0.9838041 -0.1663572 0.06674456 -0.9961455 0.02679473 0.08352303 -0.9684486 0.2292258 0.09779 -0.8958085 0.4310341 0.1083365 -0.7773671 0.6186341 0.1139832 -0.6186435 0.7773596 0.1139843 -0.4309985 0.8958257 0.1083356 -0.2292628 0.9684396 0.09779119 -0.02676093 0.9961467 0.0835191 0.1663581 0.9838039 0.06674396 0.3442553 0.9376252 0.0484482 0.6679942 -0.6683032 0.3273447 0.6444224 0.7646068 0.009812712 0.5040149 0.8631969 0.02932679 -0.6677494 0.6685601 -0.3273198 -0.9951845 0.09801906 0 -0.9569399 0.2902859 0 -0.8819203 0.4713985 0 -0.7730091 0.634395 0 -0.6343917 0.7730117 0 -0.4713956 0.8819219 0 -0.2902829 0.9569408 0 -0.09801572 0.9951848 0 0.09801858 0.9951846 0 0.2902866 0.9569398 0 0.4713988 0.8819201 0 0.6343941 0.7730098 0 0.7730119 0.6343915 0 0.881922 0.4713954 0 0.956941 0.2902827 0 0.9951849 0.09801459 0 0.9951844 -0.09801959 0 0.9569401 -0.2902857 0 0.8819199 -0.4713992 0 0.7730093 -0.6343948 0 0.6343909 -0.7730125 0 0.4713945 -0.8819224 0 0.2902817 -0.9569413 0 0.09801459 -0.995185 0 -0.09801977 -0.9951845 0 -0.2902874 -0.9569395 0 -0.4713994 -0.8819198 0 -0.6343955 -0.7730087 0 -0.7730126 -0.6343907 0 -0.8819228 -0.4713938 0 -4.96326e-6 4.88848e-7 1 -0.995185 -0.09801453 0 -0.9569413 -0.2902817 0 -4.9633e-6 4.88853e-7 -1 -0.9951846 0.09801858 0 -0.9569398 0.2902865 0 -0.8819199 0.4713992 0 -0.7730098 0.6343941 0 -0.6343909 0.7730125 0 -0.4713972 0.8819211 0 -0.2902808 0.9569416 0 -0.09801667 0.9951848 0 0.09801858 0.9951846 0 0.2902858 0.95694 0 0.4713982 0.8819205 0 0.634395 0.7730091 0 0.7730121 0.6343913 0 0.8819221 0.4713952 0 0.9569409 0.2902829 0 0.995185 0.09801477 -1.48294e-7 0.9951845 -0.09801965 -1.48294e-7 0.9569399 -0.2902861 -1.42595e-7 0.8819202 -0.471399 0 0.773009 -0.6343951 0 0.6343913 -0.7730121 0 0.4713945 -0.8819224 0 0.2902817 -0.9569414 0 0.09801459 -0.995185 0 -0.09801989 -0.9951844 0 -0.2902872 -0.9569395 0 -0.4713992 -0.8819199 0 -0.6343963 -0.773008 0 -0.7730121 -0.6343914 0 -0.8819229 -0.4713935 0 -3.31203e-6 -3.97677e-6 1 -0.995185 -0.09801453 0 -0.9569414 -0.2902815 0 0 9.77679e-7 -1 -0.9951846 0.09801959 0 -0.9569404 0.2902846 0 -0.8819198 0.4713994 0 -0.7730094 0.6343947 0 -0.6343916 0.773012 0 -0.4713965 0.8819214 0 -0.2902821 0.9569411 0 -0.0980156 0.9951849 0 0.09801858 0.9951846 0 0.2902866 0.9569398 0 0.4713984 0.8819203 0 0.6343942 0.7730097 0 0.7730119 0.6343916 0 0.881922 0.4713953 0 0.956941 0.2902827 0 0.995185 0.09801483 -1.48294e-7 0.9951845 -0.09801954 -1.48294e-7 0.9569398 -0.2902865 -1.42595e-7 0.8819202 -0.471399 0 0.7730096 -0.6343944 0 0.6343903 -0.7730129 0 0.471395 -0.8819223 0 0.2902819 -0.9569411 0 0.09801465 -0.995185 0 -0.09801959 -0.9951846 0 -0.2902882 -0.9569393 0 -0.4713979 -0.8819207 0 -0.6343964 -0.773008 0 -0.7730131 -0.6343903 0 -0.8819224 -0.4713948 0 -3.31207e-6 -3.97679e-6 1 -0.9951851 -0.09801352 0 -0.9569411 -0.2902817 0 0 9.77678e-7 -1 -0.9951846 0.09801894 0 -0.9569399 0.290286 0 -0.8819202 0.4713989 0 -0.7730095 0.6343944 0 -0.6343913 0.7730121 0 -0.4713959 0.8819217 0 -0.2902826 0.9569409 0 -0.09801554 0.9951849 0 0.09801852 0.9951846 0 0.2902866 0.9569398 0 0.471398 0.8819206 0 0.634394 0.7730099 0 0.7730125 0.6343909 0 0.8819223 0.4713947 0 0.9569407 0.2902833 0 0.995185 0.09801471 0 0.9951846 -0.09801954 0 0.9569397 -0.2902867 0 0.8819202 -0.4713988 0 0.7730093 -0.6343948 0 0.634392 -0.7730115 0 0.471394 -0.8819228 0 0.2902808 -0.9569416 0 0.09801471 -0.995185 0 -0.09801858 -0.9951846 0 -0.2902875 -0.9569395 0 -0.4713992 -0.8819199 0 -0.6343958 -0.7730085 0 -0.7730128 -0.6343905 0 -0.8819227 -0.4713943 0 -4.96325e-6 4.88847e-7 1 -0.995185 -0.09801435 0 -0.9569413 -0.2902817 0 -4.96331e-6 4.88853e-7 -1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 7.94729e-7 -1 0 -1 -7.28502e-7 2.98022e-7 -7.28501e-7 1 -2.98023e-7 1 7.28502e-7 -2.98024e-7 -7.9473e-7 2.25173e-6 -1 6.62275e-7 -2.11928e-6 1 -0.7071048 -0.7071087 0 -0.7071089 0.7071046 0 0.7071049 0.7071087 0 0.7071089 -0.7071046 0 4.18545e-7 -1.13562e-6 -1 0 9.95134e-7 1 -0.7071087 0.7071048 0 0.7071051 0.7071086 0 0.7071086 -0.7071051 0 -0.7071051 -0.7071086 0 -5.38544e-7 4.85858e-7 -1 0 -6.67325e-7 1 0.7773786 0.6186198 -0.1139829 0.8957992 0.4310532 -0.1083371 0.968446 0.2292367 -0.09779036 0.9961463 0.02677321 -0.08352094 0.9838051 -0.1663506 -0.06674474 0.9376295 -0.3442435 -0.04844957 0.8631969 -0.5040151 -0.02932691 0.7646007 -0.6444296 -0.009811639 0.6444262 -0.7646037 0.009812653 0.504018 -0.8631951 0.02932691 0.3442574 -0.9376244 0.04844844 0.1663367 -0.9838074 0.06674647 -0.02679872 -0.9961454 0.08352327 -0.2292585 -0.9684407 0.09779191 -0.4310285 -0.8958113 0.1083362 -0.6186374 -0.7773645 0.1139832 -0.7773845 -0.6186125 0.1139827 -0.8958014 -0.4310486 0.1083369 -0.9684444 -0.2292427 0.09779071 -0.996146 -0.02677989 0.08352148 -0.9838004 0.1663798 0.066742 -0.9376308 0.34424 0.04844999 -0.8631868 0.5040324 0.02932465 -0.7646095 0.6444192 0.009813249 -0.6444424 0.7645899 -0.009810209 -0.503992 0.8632102 -0.02933025 -0.3442597 0.9376236 -0.0484482 -0.1663591 0.9838038 -0.06674432 0.02675324 0.9961469 -0.08351969 0.2292407 0.9684449 -0.09779083 0.6681511 0.6681662 0.327304 0.6681519 0.6681663 0.3273025 0.6681492 0.6681637 0.3273134 0.6681494 0.6681652 0.3273099 0.6681552 0.6681402 0.3273491 0.6681375 0.6681821 0.3272994 0.6681594 0.6681417 0.3273374 0.6681619 0.6681377 0.3273405 0.6681317 0.6681816 0.3273124 0.6681686 0.6681315 0.3273392 0.6681467 0.6681597 0.3273265 0.6681466 0.6681596 0.3273265 0.6681481 0.6681581 0.3273271 0.6681367 0.6681709 0.3273238 0.6681616 0.6681433 0.3273293 0.6681556 0.6681499 0.3273283 0.6681388 0.6681676 0.3273266 0.6681424 0.6681637 0.3273268 0.6681798 0.6681264 0.3273268 0.6681314 0.6681736 0.3273292 0.6681889 0.6681188 0.3273235 0.6681072 0.6681948 0.3273357 0.6681335 0.6681709 0.3273304 0.6681908 0.6681207 0.3273159 0.6681505 0.668155 0.3273285 0.6681793 0.6681314 0.3273175 0.6681916 0.6681219 0.3273121 0.6680908 0.6682004 0.3273575 0.6681895 0.6681234 0.3273133 0.6186288 0.7773714 -0.113983 0.4310292 0.8958109 -0.1083362 -0.6681529 -0.6681298 -0.3273749 -0.6681885 -0.6681337 -0.3272939 -0.6682078 -0.6681293 -0.3272636 -0.6681916 -0.6681362 -0.3272828 -0.6681088 -0.6681809 -0.3273606 -0.668138 -0.6681626 -0.3273381 -0.6681251 -0.6681715 -0.3273464 -0.668188 -0.668125 -0.3273128 -0.66815 -0.6681547 -0.3273298 -0.6681596 -0.6681469 -0.3273262 -0.6681693 -0.6681386 -0.3273231 -0.6681464 -0.6681588 -0.327329 -0.6681489 -0.6681565 -0.3273285 -0.6681265 -0.6681773 -0.3273319 -0.668148 -0.6680796 -0.3274872 -0.6680459 -0.6683523 -0.3271391 -0.6681827 -0.6680989 -0.3273769 -0.6681446 -0.66816 -0.3273301 -0.6680916 -0.6682037 -0.3273491 -0.6679948 -0.6682559 -0.3274399 -0.6681215 -0.6681769 -0.3273428 -0.6681893 -0.6681209 -0.3273187 -0.6681501 -0.6681573 -0.3273246 -0.6680937 -0.668215 -0.3273217 -0.6681389 -0.6681675 -0.3273263 -0.6681535 -0.6681519 -0.3273287 -0.6679803 -0.6683436 -0.3272905 -0.6682657 -0.6680179 -0.3273729 -0.66833 -0.6679419 -0.3273966 0.7773671 0.6186343 0.1139831 0.8958106 0.4310299 0.108336 0.9684488 0.2292251 0.09778958 0.9961457 0.02679115 0.08352231 0.983799 -0.1663885 0.0667411 0.9376388 -0.3442177 0.04845237 0.8631784 -0.5040469 0.02932268 0.7646289 -0.644396 0.009816706 0.6444178 -0.7646107 -0.009813964 0.5040019 -0.8632044 -0.02932906 0.344263 -0.9376224 -0.04844784 0.1663272 -0.9838089 -0.06674736 -0.02677243 -0.9961463 -0.08352118 -0.2292346 -0.9684465 -0.09779047 -0.4310432 -0.8958041 -0.1083368 -0.6186155 -0.777382 -0.1139828 -0.777393 -0.6186017 -0.1139826 -0.8957879 -0.4310766 -0.108338 -0.9684503 -0.229219 -0.09778922 -0.9961462 -0.02677589 -0.08352106 -0.983806 0.1663453 -0.06674516 -0.9376257 0.3442541 -0.04844832 -0.8631904 0.5040261 -0.02932536 -0.7646047 0.6444249 -0.009812295 -0.6444253 0.7646044 0.009812891 -0.5040025 0.8632041 0.029329 -0.3442135 0.9376403 0.04845333 -0.1664109 0.9837953 0.06673943 0.02681761 0.9961447 0.08352482 0.2292107 0.9684522 0.09778898 -0.6681449 -0.6681655 0.3273184 -0.668155 -0.6681666 0.3272953 -0.6681503 -0.6681619 0.3273148 -0.6681487 -0.6681479 0.3273464 -0.6681461 -0.6681593 0.3273287 -0.6681422 -0.6681684 0.3273178 -0.6681432 -0.6681665 0.3273196 -0.6681528 -0.6681513 0.3273313 -0.6681411 -0.6681682 0.3273205 -0.6681508 -0.6681551 0.3273275 -0.6681557 -0.6681489 0.3273303 -0.6681509 -0.6681547 0.3273281 -0.6681569 -0.6681477 0.3273304 -0.6681504 -0.6681551 0.3273285 -0.6681554 -0.6681494 0.3273295 -0.6681627 -0.6680997 0.3274165 -0.6681483 -0.6681613 0.32732 -0.6681508 -0.6681554 0.327327 -0.6681503 -0.6681562 0.3273262 -0.6681551 -0.6681485 0.3273321 -0.6681493 -0.668157 0.3273267 -0.6682475 -0.6680848 0.3272736 -0.668159 -0.6681455 0.3273301 -0.6681428 -0.6681657 0.3273221 -0.6681537 -0.6681519 0.3273283 -0.6681471 -0.6681599 0.3273252 -0.6681317 -0.6681767 0.3273223 -0.6681408 -0.6681673 0.3273229 -0.668169 -0.6681327 0.327336 0.6186257 0.7773739 0.113983 0.4310482 0.8958017 0.108337 0.6682134 0.6681797 -0.3271495 0.6681235 0.6681696 -0.3273538 0.6680836 0.6681788 -0.3274163 0.6681903 0.668134 -0.3272902 0.6681709 0.6681444 -0.3273083 0.6681401 0.6681637 -0.327332 0.6681259 0.6681735 -0.3273411 0.6681501 0.6681555 -0.3273281 0.6681877 0.6681262 -0.3273112 0.6681317 0.6681719 -0.3273323 0.6681452 0.6681606 -0.3273281 0.6682103 0.6681034 -0.3273115 0.6681231 0.668182 -0.3273289 0.6681482 0.6681588 -0.3273252 0.6680642 0.6682387 -0.3273335 0.6682426 0.6680647 -0.3273247 0.6681473 0.66816 -0.3273247 0.6681249 0.668183 -0.3273236 0.6681868 0.668118 -0.3273299 0.6680894 0.6682228 -0.3273144 0.6682223 0.6680757 -0.3273437 0.6681153 0.6681979 -0.3273128 0.6681163 0.6681965 -0.3273132 0.668206 0.6680868 -0.3273546 0.6682123 0.6680786 -0.3273581 0.6680944 0.6682383 -0.3272727 0.6681105 0.6682148 -0.3272877 0.6681622 0.6681321 -0.3273512 0.668273 0.6679268 -0.3275439 0.7646085 0.6444204 0.009813547 0.8631924 0.5040227 0.02932631 0.9376286 0.3442457 0.04844975 0.9838044 0.1663552 0.06674468 0.9961462 -0.02677631 0.08352148 0.9684458 -0.2292373 0.09779059 0.8958039 -0.4310435 0.1083368 0.7773833 -0.618614 0.1139827 0.618611 -0.7773857 0.1139827 0.4310387 -0.8958063 0.1083364 0.229242 -0.9684447 0.09779059 0.026784 -0.9961459 0.08352172 -0.1663544 -0.9838045 0.06674432 -0.344243 -0.9376297 0.04844957 -0.5040228 -0.8631923 0.02932584 -0.6444131 -0.7646147 0.009814143 -0.7646042 -0.6444256 -0.009812772 -0.8631991 -0.5040111 -0.0293278 -0.9376265 -0.3442518 -0.04844903 -0.9838063 -0.1663433 -0.06674575 -0.9961461 0.02678006 -0.08352178 -0.9684492 0.2292236 -0.09778976 -0.8958017 0.4310482 -0.1083369 -0.7773798 0.6186183 -0.1139828 -0.6186084 0.7773877 -0.1139826 -0.4310479 0.8958018 -0.1083368 -0.229242 0.9684447 -0.09779059 -0.02676129 0.9961467 -0.08351993 0.1663634 0.9838032 -0.06674349 0.3442449 0.937629 -0.04844939 -0.6681789 0.6681272 0.3273268 -0.6681714 0.6681348 0.3273271 -0.6681619 0.6681442 0.3273271 -0.6681403 0.6681663 0.327326 -0.6681765 0.6681283 0.3273297 -0.6681459 0.6681612 0.3273249 -0.6681607 0.6681449 0.3273281 -0.6681333 0.6681762 0.3273202 -0.6681652 0.6681385 0.3273319 -0.6681568 0.6681489 0.327328 -0.6681571 0.6681484 0.3273282 -0.6681461 0.6681634 0.3273202 -0.668151 0.6681562 0.3273248 -0.6681556 0.668149 0.3273304 -0.6681522 0.6681552 0.3273245 -0.6681619 0.6681506 0.3273137 -0.668164 0.6681527 0.3273054 -0.668161 0.6681524 0.3273122 -0.6681602 0.6681514 0.3273158 -0.6681526 0.6681506 0.327333 -0.6681525 0.6681504 0.3273336 -0.6681523 0.6681492 0.3273363 -0.6681556 0.6681524 0.3273233 -0.668155 0.6681524 0.3273245 -0.6681551 0.6681525 0.3273242 -0.668152 0.668152 0.3273311 -0.6681537 0.6681538 0.3273243 -0.6681525 0.6681543 0.3273256 -0.6681534 0.6681507 0.3273314 0.6444234 0.7646059 -0.009812593 0.5040228 0.8631923 -0.02932578 0.6682433 -0.668065 -0.3273226 0.6681717 -0.6681349 -0.3273261 0.6681634 -0.6681427 -0.327327 0.6680818 -0.6682184 -0.327339 0.6681641 -0.6681442 -0.3273226 0.6681908 -0.6681209 -0.3273159 0.6681762 -0.6681333 -0.3273205 0.6681324 -0.6681689 -0.3273369 0.6681289 -0.6681716 -0.3273385 0.6681485 -0.6681572 -0.327328 0.6681776 -0.668137 -0.3273094 0.6681503 -0.6681542 -0.3273304 0.6681559 -0.6681511 -0.3273251 0.6681469 -0.6681549 -0.3273357 0.6681624 -0.6681514 -0.3273115 0.6681499 -0.6681499 -0.3273399 0.6681523 -0.6681523 -0.3273302 0.6681535 -0.6681627 -0.3273066 0.6681569 -0.6681481 -0.3273294 0.6681595 -0.668142 -0.3273366 0.6681553 -0.6681497 -0.3273294 0.6681553 -0.6681497 -0.3273295 0.6681351 -0.668179 -0.3273108 0.6681886 -0.6681066 -0.3273495 0.6681334 -0.6681773 -0.3273177 0.6681442 -0.6681641 -0.3273226 0.668219 -0.6680757 -0.3273501 0.6681512 -0.6681531 -0.3273309 0.6681473 -0.6681577 -0.3273294 0.764639 0.644384 -0.00981909 0.8631818 0.504041 -0.02932405 0.9376318 0.3442369 -0.04845082 0.9838052 0.1663499 -0.06674528 0.9961462 -0.02677643 -0.0835216 0.9684447 -0.2292416 -0.09779095 0.89582 -0.4310104 -0.1083355 0.7773718 -0.6186282 -0.1139831 0.6186155 -0.777382 -0.1139828 0.4310815 -0.8957855 -0.1083383 0.2292374 -0.9684457 -0.09779042 0.02675735 -0.9961468 -0.08351963 -0.1663454 -0.983806 -0.06674522 -0.3442237 -0.9376366 -0.04845172 -0.5040509 -0.8631761 -0.0293222 -0.6444162 -0.764612 -0.009813606 -0.7646101 -0.6444185 0.009813904 -0.8631806 -0.504043 0.02932375 -0.9376359 -0.3442257 0.04845207 -0.9838027 -0.166366 0.06674373 -0.9961462 0.02677518 0.08352154 -0.9684424 0.229251 0.09779155 -0.8957925 0.4310671 0.1083378 -0.7773877 0.6186084 0.1139827 -0.6186356 0.7773661 0.1139832 -0.4310436 0.8958039 0.1083366 -0.2292301 0.9684475 0.09778994 -0.0267843 0.9961459 0.08352178 0.1663632 0.9838032 0.06674349 0.3442309 0.9376341 0.04845094 0.6682192 -0.668089 0.3273228 0.6681774 -0.6681298 0.3273249 0.6682134 -0.6680938 0.3273249 0.6681693 -0.6681389 0.3273227 0.6681494 -0.6681599 0.3273206 0.6681044 -0.6682084 0.3273134 0.6681598 -0.668147 0.3273257 0.6680943 -0.6682215 0.3273068 0.6682039 -0.6680924 0.327347 0.668133 -0.6681793 0.3273143 0.6681827 -0.6681156 0.3273429 0.6681553 -0.6681528 0.3273231 0.6681529 -0.6681563 0.3273209 0.6681514 -0.6681587 0.327319 0.6681559 -0.6681504 0.3273269 0.6681504 -0.6681633 0.3273115 0.6681556 -0.6681414 0.327346 0.6681566 -0.6681506 0.3273247 0.6681572 -0.6681513 0.3273221 0.6681455 -0.66815 0.327349 0.6681728 -0.6681436 0.3273062 0.6681579 -0.6681499 0.3273238 0.6681458 -0.6681563 0.327335 0.6681675 -0.6681429 0.3273184 0.668188 -0.6681287 0.3273053 0.668058 -0.6682246 0.3273748 0.6681497 -0.6681532 0.3273336 0.6683254 -0.6680099 0.3272675 0.6680397 -0.6682518 0.3273565 0.644396 0.7646288 0.009816646 0.5040283 0.8631891 0.02932506 -0.6684972 0.6678124 -0.3273197 -0.6681551 0.6681464 -0.3273365 -0.6679624 0.6683298 -0.3273555 -0.6681654 0.6681415 -0.3273255 -0.6681587 0.6681476 -0.3273268 -0.6681432 0.6681612 -0.3273307 -0.6682286 0.6680888 -0.3273041 -0.6680861 0.6682049 -0.3273577 -0.6681488 0.6681562 -0.3273296 -0.6681587 0.6681489 -0.3273243 -0.6681487 0.6681557 -0.3273307 -0.6681896 0.66813 -0.3272991 -0.6681605 0.6681458 -0.3273265 -0.6681333 0.6681573 -0.3273587 -0.6682381 0.6682034 -0.3270504 -0.6681661 0.6681314 -0.3273447 -0.6681675 0.6681445 -0.3273149 -0.6681839 0.6681609 -0.3272483 -0.6681487 0.6681568 -0.3273282 -0.668146 0.6681541 -0.3273394 -0.6681453 0.6681485 -0.3273521 -0.6681578 0.668161 -0.3273012 -0.668155 0.6681365 -0.3273568 -0.6681683 0.6681498 -0.3273028 -0.6681609 0.6681489 -0.3273196 -0.668163 0.6681509 -0.3273116 -0.6681493 0.6681493 -0.3273424 -0.6681744 0.6681477 -0.3272944 -0.6681443 0.6681443 -0.3273627 -0.9951845 0.09801906 0 -0.9569399 0.2902859 0 -0.8819203 0.4713985 0 -0.7730091 0.634395 0 -0.6343917 0.7730117 0 -0.4713956 0.8819219 0 -0.2902829 0.9569408 0 -0.09801572 0.9951848 0 0.09801864 0.9951846 0 0.2902866 0.9569398 0 0.4713988 0.8819201 0 0.6343942 0.7730098 0 0.7730119 0.6343915 0 0.881922 0.4713954 0 0.956941 0.2902827 0 0.995185 0.09801459 0 0.9951844 -0.09801959 0 0.9569401 -0.2902857 0 0.8819199 -0.4713992 0 0.7730093 -0.6343948 0 0.6343909 -0.7730125 0 0.4713945 -0.8819224 0 0.2902817 -0.9569413 0 0.09801459 -0.995185 0 -0.09801977 -0.9951845 0 -0.2902874 -0.9569395 0 -0.4713994 -0.8819198 0 -0.6343955 -0.7730087 0 -0.7730126 -0.6343907 0 -0.8819228 -0.4713938 0 -3.31205e-6 -3.97678e-6 1 -5.44452e-7 5.14664e-6 1 -3.16385e-6 3.85519e-6 1 0 0 1 0 -9.77674e-7 1 3.74136e-7 -9.03255e-7 1 -5.44476e-7 -5.14663e-6 1 -3.8552e-6 3.16389e-6 1 1.61151e-6 -8.18967e-7 1 8.87185e-7 -7.47625e-7 1 1.52075e-6 -7.47626e-7 1 1.97851e-6 -6.56574e-7 1 1.83173e-6 -7.011e-7 1 1.81925e-6 -7.06268e-7 1 8.57478e-7 -1.22034e-6 1 2.00033e-6 -4.56717e-7 1 1.8333e-6 -5.93798e-7 1 1.5862e-6 -8.94885e-7 1 1.69029e-6 -7.00145e-7 1 1.6061e-6 -9.77678e-7 1 1.66614e-6 -3.68092e-7 1 1.73739e-6 -1.09151e-6 1 1.71479e-6 -9.77912e-7 1 1.48967e-6 -2.35787e-7 1 1.86328e-6 -9.3476e-7 1 2.07925e-6 -1.25798e-6 1 9.99093e-7 0 1 8.12908e-7 5.43165e-7 1 1.41455e-6 -3.57253e-7 1 -0.995185 -0.09801453 0 -0.9569413 -0.2902817 0 -9.17084e-6 3.7987e-6 -1 -1.74028e-6 4.88844e-7 -1 -1.28776e-6 5.33412e-7 -1 -5.62976e-7 4.62025e-7 -1 -1.84754e-6 7.17544e-7 -1 -1.41695e-6 5.86925e-7 -1 -1.16286e-6 4.81677e-7 -1 -2.04946e-6 9.55578e-7 -1 -1.87285e-6 8.37571e-7 -1 -9.83964e-7 0 -1 -1.74299e-6 8.67104e-7 -1 -1.77436e-6 9.05329e-7 -1 -1.84161e-6 1.00597e-6 -1 -1.47281e-6 3.16001e-7 -1 -1.90737e-7 9.58888e-7 -1 -1.62124e-6 6.74346e-7 -1 -1.74091e-6 1.27594e-6 -1 -4.54652e-6 -2.47254e-6 -1 -1.52146e-6 5.52505e-7 -1 -6.32777e-6 7.71045e-6 -1 -8.84469e-7 -4.36064e-7 -1 -1.7163e-6 9.17038e-7 -1 -1.74313e-6 9.57191e-7 -1 -1.91471e-6 1.16626e-6 -1 -1.42409e-6 4.31995e-7 -1 -1.67044e-6 8.92872e-7 -1 -1.18055e-6 -2.89815e-7 -1 -2.14459e-6 1.92148e-6 -1 -1.04895e-6 -7.23657e-7 -1 -0.9951846 0.09801858 0 -0.9569398 0.2902865 0 -0.8819199 0.4713992 0 -0.7730098 0.6343941 0 -0.6343909 0.7730125 0 -0.4713972 0.8819211 0 -0.2902808 0.9569416 0 -0.09801667 0.9951848 0 0.09801858 0.9951846 0 0.2902858 0.95694 0 0.4713982 0.8819205 0 0.634395 0.773009 0 0.7730121 0.6343914 0 0.8819221 0.4713952 0 0.9569409 0.2902827 -1.52026e-7 0.9951849 0.09801477 -1.52026e-7 0.9951845 -0.09801971 -1.52026e-7 0.9569399 -0.2902861 0 0.8819202 -0.471399 0 0.773009 -0.6343951 0 0.6343913 -0.7730121 0 0.4713945 -0.8819224 0 0.2902817 -0.9569414 0 0.09801459 -0.995185 0 -0.09801989 -0.9951844 0 -0.2902872 -0.9569395 0 -0.4713992 -0.8819199 0 -0.6343963 -0.773008 0 -0.7730121 -0.6343914 0 -0.8819229 -0.4713935 0 0 -9.77674e-7 1 -3.31206e-6 -3.97679e-6 1 4.7725e-6 -1.44773e-6 1 1.61151e-6 -8.18967e-7 1 8.87184e-7 -7.47625e-7 1 1.52075e-6 -7.47626e-7 1 1.97851e-6 -6.56573e-7 1 1.83172e-6 -7.01101e-7 1 1.81925e-6 -7.06269e-7 1 8.57478e-7 -1.22034e-6 1 2.00033e-6 -4.56717e-7 1 1.32373e-6 -1.01199e-6 1 1.53254e-6 -8.03178e-7 1 1.72518e-6 -5.68446e-7 1 1.90267e-6 -3.02813e-7 1 1.60575e-6 -8.58299e-7 1 1.74235e-6 -5.28538e-7 1 1.6061e-6 -9.77678e-7 1 1.6516e-6 -5.15743e-7 1 1.6516e-6 -6.60198e-7 1 1.71479e-6 -9.77908e-7 1 1.70356e-6 -9.40877e-7 1 1.72926e-6 -1.00293e-6 1 1.01121e-6 3.40464e-7 1 2.07925e-6 -1.25798e-6 1 9.9909e-7 0 1 1.15599e-6 0 1 1.71857e-6 -5.60398e-7 1 4.39841e-6 -2.35101e-6 1 -0.995185 -0.09801453 0 -0.9569414 -0.2902815 0 -3.22298e-6 9.77686e-7 -1 -1.51425e-6 8.09387e-7 -1 -2.84167e-6 1.07343e-6 -1 -1.90689e-6 7.89867e-7 -1 -1.41696e-6 5.86927e-7 -1 -1.15179e-6 4.45193e-7 -1 -2.05889e-6 1.0513e-6 -1 -9.62733e-7 1.51702e-7 -1 -1.74897e-6 9.37946e-7 -1 -1.72242e-6 9.05592e-7 -1 -1.74563e-6 9.40331e-7 -1 -5.14665e-6 -5.4446e-7 -1 -1.93102e-6 7.8749e-7 -1 -9.84421e-7 1.07463e-6 -1 -2.52947e-6 7.67309e-7 -1 -3.35418e-7 9.834e-7 -1 -1.63092e-6 7.25712e-7 -1 -9.03253e-7 -3.74139e-7 -1 -1.61725e-6 8.64445e-7 -1 -1.68886e-6 5.04441e-7 -1 -8.53962e-7 -4.9314e-7 -1 -1.46653e-6 -4.96324e-6 -1 -1.46651e-6 6.52865e-7 -1 -1.65098e-6 1.26098e-6 -1 -1.61883e-6 1.09938e-6 -1 -1.61844e-6 1.09533e-6 -1 -1.61844e-6 0 -1 -1.60576e-6 1.34818e-6 -1 -1.60576e-6 0 -1 -0.9951846 0.09801959 0 -0.9569404 0.2902846 0 -0.8819198 0.4713994 0 -0.7730094 0.6343947 0 -0.6343916 0.773012 0 -0.4713965 0.8819214 0 -0.2902821 0.9569411 0 -0.0980156 0.9951849 0 0.09801858 0.9951846 0 0.2902866 0.9569398 0 0.4713985 0.8819203 0 0.6343942 0.7730097 0 0.7730119 0.6343916 0 0.881922 0.4713953 0 0.956941 0.2902826 -1.52026e-7 0.995185 0.09801483 -1.33023e-7 0.9951846 -0.09801954 -1.52026e-7 0.9569398 -0.2902864 0 0.8819202 -0.471399 0 0.7730096 -0.6343944 0 0.6343903 -0.7730129 0 0.471395 -0.8819223 0 0.2902819 -0.9569411 0 0.09801465 -0.995185 0 -0.09801959 -0.9951846 0 -0.2902881 -0.9569393 0 -0.4713979 -0.8819207 0 -0.6343964 -0.773008 0 -0.7730131 -0.6343903 0 -0.8819224 -0.4713948 0 -3.31206e-6 -3.97679e-6 1 4.77257e-6 -1.44774e-6 1 1.61152e-6 -8.18967e-7 1 8.87186e-7 -7.47625e-7 1 1.52075e-6 -7.47626e-7 1 1.97851e-6 -6.56575e-7 1 1.83173e-6 -7.011e-7 1 1.81925e-6 -7.06269e-7 1 8.57479e-7 -1.22034e-6 1 2.00033e-6 -4.56718e-7 1 1.32373e-6 -1.01199e-6 1 1.53254e-6 -8.03178e-7 1 1.72518e-6 -5.68447e-7 1 1.90267e-6 -3.02813e-7 1 1.60575e-6 -8.58299e-7 1 1.74235e-6 -5.28539e-7 1 1.55951e-6 -1.13128e-6 1 1.62183e-6 -8.17941e-7 1 1.6516e-6 -5.15743e-7 1 1.6516e-6 -6.60198e-7 1 1.71479e-6 -9.7791e-7 1 1.70356e-6 -9.40878e-7 1 1.72926e-6 -1.00293e-6 1 1.01121e-6 3.40463e-7 1 2.07925e-6 -1.25797e-6 1 9.9909e-7 0 1 1.15599e-6 0 1 1.71858e-6 -5.60404e-7 1 4.39839e-6 -2.35101e-6 1 -0.9951851 -0.09801352 0 -0.9569411 -0.2902818 0 -3.22301e-6 9.77689e-7 -1 -1.51424e-6 8.09386e-7 -1 -2.84167e-6 1.07343e-6 -1 -1.9069e-6 7.89868e-7 -1 -1.41696e-6 5.86927e-7 -1 -1.15179e-6 4.45194e-7 -1 -2.05889e-6 1.0513e-6 -1 -9.62734e-7 1.51703e-7 -1 -1.74897e-6 9.37946e-7 -1 -1.72242e-6 9.05593e-7 -1 -1.74563e-6 9.40332e-7 -1 -6.91328e-7 -6.91312e-7 -1 -4.70043e-7 5.15394e-6 -1 -1.62583e-6 1.08631e-6 -1 -1.13221e-6 1.82506e-6 -1 -1.53723e-6 5.50438e-7 -1 -1.29845e-6 1.93067e-7 -1 -1.84695e-6 1.21925e-6 -1 -1.90731e-7 9.58889e-7 -1 -3.60442e-6 2.79871e-7 -1 -1.62124e-6 8.81458e-7 -1 -1.38971e-6 0 -1 -9.03258e-7 -3.74128e-7 -1 -8.28833e-7 -5.53806e-7 -1 -1.61447e-6 6.60798e-7 -1 -2.14235e-6 1.18868e-6 -1 -2.08613e-6 1.32788e-6 -1 -1.5536e-6 4.71281e-7 -1 -1.92688e-6 1.02995e-6 -1 -0.9951846 0.09801894 0 -0.9569399 0.290286 0 -0.8819202 0.4713989 0 -0.7730095 0.6343944 0 -0.6343913 0.7730121 0 -0.4713959 0.8819217 0 -0.2902826 0.9569409 0 -0.09801554 0.9951849 0 0.09801852 0.9951846 0 0.2902865 0.9569398 0 0.4713981 0.8819206 0 0.634394 0.7730098 0 0.7730123 0.6343909 0 0.8819223 0.4713947 0 0.9569408 0.2902833 0 0.995185 0.09801471 0 0.9951846 -0.09801954 0 0.9569397 -0.2902867 0 0.8819202 -0.4713988 0 0.7730093 -0.6343948 0 0.634392 -0.7730115 0 0.471394 -0.8819228 0 0.2902808 -0.9569416 0 0.09801471 -0.995185 0 -0.09801858 -0.9951846 0 -0.2902875 -0.9569395 0 -0.4713992 -0.8819199 0 -0.6343957 -0.7730085 0 -0.7730129 -0.6343905 0 -0.8819226 -0.4713942 0 -3.31207e-6 -3.9768e-6 1 0 0 1 3.74144e-7 -9.03251e-7 1 -5.44482e-7 -5.14665e-6 1 -3.85522e-6 3.16391e-6 1 1.61151e-6 -8.18966e-7 1 8.87185e-7 -7.47625e-7 1 1.52075e-6 -7.47626e-7 1 1.97851e-6 -6.56574e-7 1 1.83172e-6 -7.01101e-7 1 1.81925e-6 -7.06267e-7 1 8.57479e-7 -1.22034e-6 1 2.00033e-6 -4.56717e-7 1 1.32373e-6 -1.01199e-6 1 1.53254e-6 -8.03179e-7 1 1.72518e-6 -5.68445e-7 1 1.90267e-6 -3.02814e-7 1 1.69029e-6 -7.00146e-7 1 1.55951e-6 -1.13128e-6 1 1.62183e-6 -8.17942e-7 1 1.66614e-6 -3.68091e-7 1 1.73739e-6 -1.09151e-6 1 1.71479e-6 -9.77909e-7 1 1.48968e-6 -2.35787e-7 1 1.86328e-6 -9.34761e-7 1 2.07925e-6 -1.25797e-6 1 9.99093e-7 0 1 8.12906e-7 5.43167e-7 1 1.41454e-6 -3.57252e-7 1 -0.995185 -0.09801435 0 -0.9569413 -0.2902817 0 -9.17083e-6 3.7987e-6 -1 -1.74028e-6 4.88844e-7 -1 -1.28776e-6 5.33412e-7 -1 -5.62977e-7 4.62025e-7 -1 -1.84754e-6 7.17543e-7 -1 -1.41695e-6 5.86925e-7 -1 -1.16286e-6 4.81676e-7 -1 -2.04946e-6 9.55578e-7 -1 -1.87286e-6 8.37572e-7 -1 -9.83964e-7 0 -1 -1.74299e-6 8.67105e-7 -1 -8.12904e-7 -5.43171e-7 -1 -1.38263e-6 1.38265e-6 -1 -1.81294e-6 9.5234e-7 -1 -1.90728e-7 9.5889e-7 -1 0 9.84017e-7 -1 -7.41349e-7 -6.50261e-7 -1 -1.93147e-6 1.17408e-6 -1 -1.3883e-6 3.61176e-7 -1 -1.63836e-6 8.28999e-7 -1 -1.48191e-6 0 -1 -4.70047e-7 5.15395e-6 -1 -1.80298e-6 -1.54708e-6 -1 -1.52503e-6 1.27487e-6 -1 -1.47689e-6 1.51691e-6 -1 -1.58865e-6 3.82188e-7 -1 -1.70864e-6 9.8541e-7 -1 -1.6179e-6 4.90788e-7 -1 -1.70114e-6 9.09284e-7 -1 -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array> + <technique_common> + <accessor source="#battery_001-mesh-normals-array" count="26008" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="battery_001-mesh-vertices"> + <input semantic="POSITION" source="#battery_001-mesh-positions"/> + </vertices> + <polylist material="mat_pc_embed-material" count="12"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>1 0 0 0 5 0 5 1 6 1 2 1 6 2 7 2 3 2 0 3 3 3 7 3 0 4 1 4 3 4 7 5 6 5 5 5 0 25258 4 25258 5 25258 1 25259 5 25259 2 25259 2 25260 6 25260 3 25260 4 25261 0 25261 7 25261 1 25262 2 25262 3 25262 4 25263 7 25263 5 25263</p> + </polylist> + <polylist material="mat_kinton_struct-material" count="13848"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>8 6 9 6 10 6 11 7 10 7 9 7 12 8 10 8 13 8 11 9 13 9 10 9 14 10 8 10 10 10 12 11 14 11 10 11 15 12 16 12 9 12 17 13 9 13 16 13 8 14 18 14 9 14 15 15 9 15 18 15 19 16 11 16 9 16 19 17 9 17 17 17 15 18 13 18 16 18 17 19 16 19 13 19 20 20 13 20 15 20 20 21 12 21 13 21 21 22 13 22 11 22 17 23 13 23 21 23 22 24 23 24 24 24 25 25 24 25 23 25 24 26 8 26 14 26 25 27 8 27 24 27 14 28 22 28 24 28 15 29 18 29 23 29 26 30 23 30 18 30 22 31 27 31 23 31 15 32 23 32 27 32 28 33 25 33 23 33 28 34 23 34 26 34 18 35 8 35 26 35 29 36 8 36 25 36 26 37 8 37 29 37 30 38 31 38 32 38 33 39 32 39 31 39 14 40 32 40 22 40 33 41 22 41 32 41 14 42 30 42 32 42 15 43 27 43 31 43 34 44 31 44 27 44 30 45 35 45 31 45 15 46 31 46 35 46 36 47 33 47 31 47 36 48 31 48 34 48 34 49 27 49 22 49 37 50 22 50 33 50 34 51 22 51 37 51 38 52 39 52 40 52 41 53 40 53 39 53 14 54 40 54 30 54 41 55 30 55 40 55 14 56 38 56 40 56 15 57 35 57 39 57 42 58 39 58 35 58 38 59 43 59 39 59 15 60 39 60 43 60 44 61 41 61 39 61 44 62 39 62 42 62 42 63 35 63 30 63 45 64 30 64 41 64 42 65 30 65 45 65 46 66 47 66 48 66 49 67 48 67 47 67 14 68 48 68 38 68 49 69 38 69 48 69 14 70 46 70 48 70 15 71 43 71 47 71 50 72 47 72 43 72 46 73 51 73 47 73 15 74 47 74 51 74 52 75 49 75 47 75 52 76 47 76 50 76 50 77 43 77 38 77 53 78 38 78 49 78 50 79 38 79 53 79 54 80 55 80 56 80 57 81 56 81 55 81 14 82 56 82 46 82 57 83 46 83 56 83 14 84 54 84 56 84 15 85 51 85 55 85 58 86 55 86 51 86 54 87 59 87 55 87 15 88 55 88 59 88 60 89 57 89 55 89 60 90 55 90 58 90 58 91 51 91 46 91 61 92 46 92 57 92 58 93 46 93 61 93 62 94 63 94 64 94 65 95 64 95 63 95 14 96 64 96 54 96 65 97 54 97 64 97 14 98 62 98 64 98 15 99 59 99 63 99 66 100 63 100 59 100 62 101 67 101 63 101 15 102 63 102 67 102 68 103 65 103 63 103 68 104 63 104 66 104 66 105 59 105 54 105 69 106 54 106 65 106 66 107 54 107 69 107 70 108 71 108 72 108 73 109 72 109 71 109 14 110 72 110 62 110 73 111 62 111 72 111 14 112 70 112 72 112 15 113 67 113 71 113 74 114 71 114 67 114 70 115 75 115 71 115 15 116 71 116 75 116 76 117 73 117 71 117 76 118 71 118 74 118 74 119 67 119 62 119 77 120 62 120 73 120 74 121 62 121 77 121 78 122 79 122 80 122 81 123 80 123 79 123 14 124 80 124 70 124 81 125 70 125 80 125 14 126 78 126 80 126 15 127 75 127 79 127 82 128 79 128 75 128 78 129 83 129 79 129 15 130 79 130 83 130 84 131 81 131 79 131 84 132 79 132 82 132 82 133 75 133 70 133 85 134 70 134 81 134 82 135 70 135 85 135 86 136 87 136 88 136 89 137 88 137 87 137 14 138 88 138 78 138 89 139 78 139 88 139 14 140 86 140 88 140 15 141 83 141 87 141 90 142 87 142 83 142 86 143 91 143 87 143 15 144 87 144 91 144 92 145 89 145 87 145 92 146 87 146 90 146 90 147 83 147 78 147 93 148 78 148 89 148 90 149 78 149 93 149 14 150 94 150 95 150 96 151 95 151 94 151 14 152 95 152 86 152 96 153 86 153 95 153 15 154 91 154 94 154 97 155 94 155 91 155 98 156 99 156 94 156 15 157 94 157 99 157 14 158 98 158 94 158 100 159 96 159 94 159 100 160 94 160 97 160 97 161 91 161 86 161 101 162 86 162 96 162 97 163 86 163 101 163 14 164 102 164 103 164 104 165 103 165 102 165 14 166 103 166 98 166 104 167 98 167 103 167 15 168 99 168 102 168 105 169 102 169 99 169 106 170 15 170 102 170 14 171 106 171 102 171 107 172 104 172 102 172 107 173 102 173 105 173 105 174 99 174 98 174 108 175 98 175 104 175 105 176 98 176 108 176 109 177 110 177 111 177 112 178 111 178 110 178 109 179 111 179 113 179 112 180 113 180 111 180 114 181 115 181 110 181 116 182 110 182 115 182 109 183 117 183 110 183 118 184 110 184 117 184 119 185 114 185 110 185 118 186 119 186 110 186 120 187 112 187 110 187 120 188 110 188 116 188 121 189 113 189 115 189 116 190 115 190 113 190 114 191 121 191 115 191 121 192 122 192 113 192 109 193 113 193 122 193 123 194 113 194 112 194 116 195 113 195 123 195 124 196 122 196 121 196 109 197 122 197 125 197 124 198 125 198 122 198 114 199 126 199 121 199 127 200 121 200 126 200 128 201 124 201 121 201 128 202 121 202 127 202 129 203 125 203 126 203 127 204 126 204 125 204 114 205 129 205 126 205 129 206 130 206 125 206 109 207 125 207 130 207 131 208 125 208 124 208 127 209 125 209 131 209 132 210 130 210 129 210 109 211 130 211 133 211 132 212 133 212 130 212 114 213 134 213 129 213 135 214 129 214 134 214 136 215 132 215 129 215 136 216 129 216 135 216 137 217 133 217 134 217 135 218 134 218 133 218 114 219 137 219 134 219 137 220 138 220 133 220 109 221 133 221 138 221 139 222 133 222 132 222 135 223 133 223 139 223 140 224 138 224 137 224 109 225 138 225 141 225 140 226 141 226 138 226 114 227 142 227 137 227 143 228 137 228 142 228 144 229 140 229 137 229 144 230 137 230 143 230 145 231 141 231 142 231 143 232 142 232 141 232 114 233 145 233 142 233 145 234 146 234 141 234 109 235 141 235 146 235 147 236 141 236 140 236 143 237 141 237 147 237 148 238 146 238 145 238 109 239 146 239 149 239 148 240 149 240 146 240 114 241 150 241 145 241 151 242 145 242 150 242 152 243 148 243 145 243 152 244 145 244 151 244 153 245 149 245 150 245 151 246 150 246 149 246 114 247 153 247 150 247 153 248 154 248 149 248 109 249 149 249 154 249 155 250 149 250 148 250 151 251 149 251 155 251 156 252 154 252 153 252 109 253 154 253 157 253 156 254 157 254 154 254 114 255 158 255 153 255 159 256 153 256 158 256 160 257 156 257 153 257 160 258 153 258 159 258 161 259 157 259 158 259 159 260 158 260 157 260 114 261 161 261 158 261 161 262 162 262 157 262 109 263 157 263 162 263 163 264 157 264 156 264 159 265 157 265 163 265 164 266 162 266 161 266 109 267 162 267 165 267 164 268 165 268 162 268 114 269 166 269 161 269 167 270 161 270 166 270 168 271 164 271 161 271 168 272 161 272 167 272 169 273 165 273 166 273 167 274 166 274 165 274 114 275 169 275 166 275 169 276 170 276 165 276 109 277 165 277 170 277 171 278 165 278 164 278 167 279 165 279 171 279 172 280 170 280 169 280 109 281 170 281 173 281 172 282 173 282 170 282 114 283 174 283 169 283 175 284 169 284 174 284 176 285 172 285 169 285 176 286 169 286 175 286 177 287 173 287 174 287 175 288 174 288 173 288 114 289 177 289 174 289 177 290 178 290 173 290 109 291 173 291 178 291 179 292 173 292 172 292 175 293 173 293 179 293 180 294 178 294 177 294 109 295 178 295 181 295 180 296 181 296 178 296 114 297 182 297 177 297 183 298 177 298 182 298 184 299 180 299 177 299 184 300 177 300 183 300 114 301 181 301 182 301 183 302 182 302 181 302 185 303 109 303 181 303 114 304 185 304 181 304 186 305 181 305 180 305 183 306 181 306 186 306 187 307 188 307 117 307 189 308 117 308 188 308 109 309 187 309 117 309 190 310 118 310 117 310 191 311 190 311 117 311 191 312 117 312 189 312 187 313 192 313 188 313 189 314 188 314 192 314 187 315 193 315 192 315 194 316 192 316 193 316 189 317 192 317 194 317 187 318 195 318 193 318 196 319 193 319 195 319 194 320 193 320 196 320 187 321 197 321 195 321 198 322 195 322 197 322 196 323 195 323 198 323 187 324 199 324 197 324 200 325 197 325 199 325 198 326 197 326 200 326 187 327 201 327 199 327 202 328 199 328 201 328 200 329 199 329 202 329 203 330 204 330 201 330 205 331 201 331 204 331 187 332 203 332 201 332 202 333 201 333 205 333 206 334 204 334 203 334 205 335 204 335 206 335 207 336 203 336 187 336 208 337 203 337 207 337 206 338 203 338 208 338 109 339 209 339 187 339 207 340 187 340 209 340 210 341 209 341 109 341 211 342 209 342 210 342 207 343 209 343 211 343 210 344 109 344 185 344 212 345 213 345 185 345 214 346 185 346 213 346 114 347 212 347 185 347 210 348 185 348 214 348 212 349 215 349 213 349 216 350 213 350 215 350 214 351 213 351 216 351 217 352 215 352 212 352 216 353 215 353 217 353 218 354 212 354 114 354 217 355 212 355 218 355 219 356 114 356 119 356 218 357 114 357 219 357 20 358 15 358 119 358 220 359 119 359 15 359 118 360 20 360 119 360 219 361 119 361 220 361 221 362 15 362 106 362 220 363 15 363 221 363 222 364 223 364 106 364 224 365 106 365 223 365 14 366 222 366 106 366 221 367 106 367 224 367 225 368 223 368 222 368 224 369 223 369 225 369 226 370 222 370 14 370 225 371 222 371 226 371 227 372 14 372 12 372 226 373 14 373 227 373 228 374 12 374 20 374 229 375 12 375 228 375 227 376 12 376 229 376 228 377 20 377 118 377 228 378 118 378 190 378 229 379 21 379 11 379 26 380 11 380 19 380 229 381 11 381 26 381 228 382 17 382 21 382 229 383 228 383 21 383 224 384 19 384 17 384 228 385 190 385 17 385 220 386 17 386 190 386 221 387 224 387 17 387 220 388 221 388 17 388 224 389 26 389 19 389 229 390 29 390 25 390 34 391 25 391 28 391 34 392 37 392 25 392 229 393 25 393 37 393 229 394 26 394 29 394 224 395 28 395 26 395 224 396 34 396 28 396 229 397 37 397 33 397 42 398 33 398 36 398 42 399 45 399 33 399 229 400 33 400 45 400 224 401 36 401 34 401 224 402 42 402 36 402 229 403 45 403 41 403 50 404 41 404 44 404 50 405 53 405 41 405 229 406 41 406 53 406 224 407 44 407 42 407 224 408 50 408 44 408 229 409 53 409 49 409 58 410 49 410 52 410 58 411 61 411 49 411 229 412 49 412 61 412 224 413 52 413 50 413 224 414 58 414 52 414 229 415 61 415 57 415 66 416 57 416 60 416 66 417 69 417 57 417 229 418 57 418 69 418 224 419 60 419 58 419 224 420 66 420 60 420 229 421 69 421 65 421 74 422 65 422 68 422 74 423 77 423 65 423 229 424 65 424 77 424 224 425 68 425 66 425 224 426 74 426 68 426 229 427 77 427 73 427 82 428 73 428 76 428 82 429 85 429 73 429 229 430 73 430 85 430 224 431 76 431 74 431 224 432 82 432 76 432 229 433 85 433 81 433 90 434 81 434 84 434 90 435 93 435 81 435 229 436 81 436 93 436 224 437 84 437 82 437 224 438 90 438 84 438 229 439 93 439 89 439 97 440 89 440 92 440 97 441 101 441 89 441 229 442 89 442 101 442 224 443 92 443 90 443 224 444 97 444 92 444 229 445 101 445 96 445 224 446 96 446 100 446 105 447 108 447 96 447 229 448 96 448 108 448 224 449 105 449 96 449 224 450 100 450 97 450 229 451 108 451 104 451 224 452 104 452 107 452 227 453 229 453 104 453 224 454 227 454 104 454 224 455 107 455 105 455 214 456 123 456 112 456 220 457 112 457 120 457 220 458 190 458 112 458 191 459 112 459 190 459 191 460 214 460 112 460 124 461 116 461 123 461 214 462 124 462 123 462 220 463 120 463 116 463 128 464 116 464 124 464 220 465 116 465 128 465 214 466 131 466 124 466 132 467 127 467 131 467 214 468 132 468 131 468 220 469 128 469 127 469 136 470 127 470 132 470 220 471 127 471 136 471 214 472 139 472 132 472 140 473 135 473 139 473 214 474 140 474 139 474 220 475 136 475 135 475 144 476 135 476 140 476 220 477 135 477 144 477 214 478 147 478 140 478 148 479 143 479 147 479 214 480 148 480 147 480 220 481 144 481 143 481 152 482 143 482 148 482 220 483 143 483 152 483 214 484 155 484 148 484 156 485 151 485 155 485 214 486 156 486 155 486 220 487 152 487 151 487 160 488 151 488 156 488 220 489 151 489 160 489 214 490 163 490 156 490 164 491 159 491 163 491 214 492 164 492 163 492 220 493 160 493 159 493 168 494 159 494 164 494 220 495 159 495 168 495 214 496 171 496 164 496 172 497 167 497 171 497 214 498 172 498 171 498 220 499 168 499 167 499 176 500 167 500 172 500 220 501 167 501 176 501 214 502 179 502 172 502 180 503 175 503 179 503 214 504 180 504 179 504 220 505 176 505 175 505 184 506 175 506 180 506 220 507 175 507 184 507 214 508 186 508 180 508 214 509 183 509 186 509 220 510 184 510 183 510 219 511 220 511 183 511 214 512 219 512 183 512 225 513 226 513 227 513 224 514 225 514 227 514 217 515 218 515 219 515 214 516 217 516 219 516 214 517 216 517 217 517 191 518 210 518 214 518 189 519 211 519 210 519 191 520 189 520 210 520 202 521 207 521 211 521 200 522 202 522 211 522 198 523 200 523 211 523 196 524 198 524 211 524 194 525 196 525 211 525 189 526 194 526 211 526 206 527 208 527 207 527 205 528 206 528 207 528 202 529 205 529 207 529 230 530 231 530 232 530 233 531 232 531 231 531 234 532 232 532 235 532 233 533 235 533 232 533 236 534 230 534 232 534 234 535 236 535 232 535 237 536 238 536 231 536 239 537 231 537 238 537 230 538 240 538 231 538 237 539 231 539 240 539 241 540 233 540 231 540 241 541 231 541 239 541 237 542 235 542 238 542 239 543 238 543 235 543 242 544 235 544 237 544 242 545 234 545 235 545 243 546 235 546 233 546 239 547 235 547 243 547 244 548 245 548 246 548 247 549 246 549 245 549 236 550 246 550 230 550 247 551 230 551 246 551 236 552 244 552 246 552 237 553 240 553 245 553 248 554 245 554 240 554 244 555 249 555 245 555 237 556 245 556 249 556 250 557 247 557 245 557 250 558 245 558 248 558 248 559 240 559 230 559 251 560 230 560 247 560 248 561 230 561 251 561 252 562 253 562 254 562 255 563 254 563 253 563 236 564 254 564 244 564 255 565 244 565 254 565 236 566 252 566 254 566 237 567 249 567 253 567 256 568 253 568 249 568 252 569 257 569 253 569 237 570 253 570 257 570 258 571 255 571 253 571 258 572 253 572 256 572 256 573 249 573 244 573 259 574 244 574 255 574 256 575 244 575 259 575 260 576 261 576 262 576 263 577 262 577 261 577 236 578 262 578 252 578 263 579 252 579 262 579 236 580 260 580 262 580 237 581 257 581 261 581 264 582 261 582 257 582 260 583 265 583 261 583 237 584 261 584 265 584 266 585 263 585 261 585 266 586 261 586 264 586 264 587 257 587 252 587 267 588 252 588 263 588 264 589 252 589 267 589 268 590 269 590 270 590 271 591 270 591 269 591 236 592 270 592 260 592 271 593 260 593 270 593 236 594 268 594 270 594 237 595 265 595 269 595 272 596 269 596 265 596 268 597 273 597 269 597 237 598 269 598 273 598 274 599 271 599 269 599 274 600 269 600 272 600 272 601 265 601 260 601 275 602 260 602 271 602 272 603 260 603 275 603 276 604 277 604 278 604 279 605 278 605 277 605 236 606 278 606 268 606 279 607 268 607 278 607 236 608 276 608 278 608 237 609 273 609 277 609 280 610 277 610 273 610 276 611 281 611 277 611 237 612 277 612 281 612 282 613 279 613 277 613 282 614 277 614 280 614 280 615 273 615 268 615 283 616 268 616 279 616 280 617 268 617 283 617 284 618 285 618 286 618 287 619 286 619 285 619 236 620 286 620 276 620 287 621 276 621 286 621 236 622 284 622 286 622 237 623 281 623 285 623 288 624 285 624 281 624 284 625 289 625 285 625 237 626 285 626 289 626 290 627 287 627 285 627 290 628 285 628 288 628 288 629 281 629 276 629 291 630 276 630 287 630 288 631 276 631 291 631 292 632 293 632 294 632 295 633 294 633 293 633 236 634 294 634 284 634 295 635 284 635 294 635 236 636 292 636 294 636 237 637 289 637 293 637 296 638 293 638 289 638 292 639 297 639 293 639 237 640 293 640 297 640 298 641 295 641 293 641 298 642 293 642 296 642 296 643 289 643 284 643 299 644 284 644 295 644 296 645 284 645 299 645 300 646 301 646 302 646 303 647 302 647 301 647 236 648 302 648 292 648 303 649 292 649 302 649 236 650 300 650 302 650 237 651 297 651 301 651 304 652 301 652 297 652 300 653 305 653 301 653 237 654 301 654 305 654 306 655 303 655 301 655 306 656 301 656 304 656 304 657 297 657 292 657 307 658 292 658 303 658 304 659 292 659 307 659 308 660 309 660 310 660 311 661 310 661 309 661 236 662 310 662 300 662 311 663 300 663 310 663 236 664 308 664 310 664 237 665 305 665 309 665 312 666 309 666 305 666 308 667 313 667 309 667 237 668 309 668 313 668 314 669 311 669 309 669 314 670 309 670 312 670 312 671 305 671 300 671 315 672 300 672 311 672 312 673 300 673 315 673 236 674 316 674 317 674 318 675 317 675 316 675 236 676 317 676 308 676 318 677 308 677 317 677 237 678 313 678 316 678 319 679 316 679 313 679 320 680 321 680 316 680 237 681 316 681 321 681 236 682 320 682 316 682 322 683 318 683 316 683 322 684 316 684 319 684 319 685 313 685 308 685 323 686 308 686 318 686 319 687 308 687 323 687 236 688 324 688 325 688 326 689 325 689 324 689 236 690 325 690 320 690 326 691 320 691 325 691 237 692 321 692 324 692 327 693 324 693 321 693 328 694 237 694 324 694 236 695 328 695 324 695 329 696 326 696 324 696 329 697 324 697 327 697 327 698 321 698 320 698 330 699 320 699 326 699 327 700 320 700 330 700 331 701 332 701 333 701 334 702 333 702 332 702 331 703 333 703 335 703 334 704 335 704 333 704 336 705 337 705 332 705 338 706 332 706 337 706 331 707 339 707 332 707 340 708 332 708 339 708 341 709 336 709 332 709 340 710 341 710 332 710 342 711 334 711 332 711 342 712 332 712 338 712 343 713 335 713 337 713 338 714 337 714 335 714 336 715 343 715 337 715 343 716 344 716 335 716 331 717 335 717 344 717 345 718 335 718 334 718 338 719 335 719 345 719 346 720 344 720 343 720 331 721 344 721 347 721 346 722 347 722 344 722 336 723 348 723 343 723 349 724 343 724 348 724 350 725 346 725 343 725 350 726 343 726 349 726 351 727 347 727 348 727 349 728 348 728 347 728 336 729 351 729 348 729 351 730 352 730 347 730 331 731 347 731 352 731 353 732 347 732 346 732 349 733 347 733 353 733 354 734 352 734 351 734 331 735 352 735 355 735 354 736 355 736 352 736 336 737 356 737 351 737 357 738 351 738 356 738 358 739 354 739 351 739 358 740 351 740 357 740 359 741 355 741 356 741 357 742 356 742 355 742 336 743 359 743 356 743 359 744 360 744 355 744 331 745 355 745 360 745 361 746 355 746 354 746 357 747 355 747 361 747 362 748 360 748 359 748 331 749 360 749 363 749 362 750 363 750 360 750 336 751 364 751 359 751 365 752 359 752 364 752 366 753 362 753 359 753 366 754 359 754 365 754 367 755 363 755 364 755 365 756 364 756 363 756 336 757 367 757 364 757 367 758 368 758 363 758 331 759 363 759 368 759 369 760 363 760 362 760 365 761 363 761 369 761 370 762 368 762 367 762 331 763 368 763 371 763 370 764 371 764 368 764 336 765 372 765 367 765 373 766 367 766 372 766 374 767 370 767 367 767 374 768 367 768 373 768 375 769 371 769 372 769 373 770 372 770 371 770 336 771 375 771 372 771 375 772 376 772 371 772 331 773 371 773 376 773 377 774 371 774 370 774 373 775 371 775 377 775 378 776 376 776 375 776 331 777 376 777 379 777 378 778 379 778 376 778 336 779 380 779 375 779 381 780 375 780 380 780 382 781 378 781 375 781 382 782 375 782 381 782 383 783 379 783 380 783 381 784 380 784 379 784 336 785 383 785 380 785 383 786 384 786 379 786 331 787 379 787 384 787 385 788 379 788 378 788 381 789 379 789 385 789 386 790 384 790 383 790 331 791 384 791 387 791 386 792 387 792 384 792 336 793 388 793 383 793 389 794 383 794 388 794 390 795 386 795 383 795 390 796 383 796 389 796 391 797 387 797 388 797 389 798 388 798 387 798 336 799 391 799 388 799 391 800 392 800 387 800 331 801 387 801 392 801 393 802 387 802 386 802 389 803 387 803 393 803 394 804 392 804 391 804 331 805 392 805 395 805 394 806 395 806 392 806 336 807 396 807 391 807 397 808 391 808 396 808 398 809 394 809 391 809 398 810 391 810 397 810 399 811 395 811 396 811 397 812 396 812 395 812 336 813 399 813 396 813 399 814 400 814 395 814 331 815 395 815 400 815 401 816 395 816 394 816 397 817 395 817 401 817 402 818 400 818 399 818 331 819 400 819 403 819 402 820 403 820 400 820 336 821 404 821 399 821 405 822 399 822 404 822 406 823 402 823 399 823 406 824 399 824 405 824 336 825 403 825 404 825 405 826 404 826 403 826 407 827 331 827 403 827 336 828 407 828 403 828 408 829 403 829 402 829 405 830 403 830 408 830 409 831 410 831 339 831 411 832 339 832 410 832 331 833 409 833 339 833 412 834 340 834 339 834 413 835 412 835 339 835 413 836 339 836 411 836 409 837 414 837 410 837 411 838 410 838 414 838 409 839 415 839 414 839 416 840 414 840 415 840 411 841 414 841 416 841 409 842 417 842 415 842 418 843 415 843 417 843 416 844 415 844 418 844 409 845 419 845 417 845 420 846 417 846 419 846 418 847 417 847 420 847 409 848 421 848 419 848 422 849 419 849 421 849 420 850 419 850 422 850 409 851 423 851 421 851 424 852 421 852 423 852 422 853 421 853 424 853 425 854 426 854 423 854 427 855 423 855 426 855 409 856 425 856 423 856 424 857 423 857 427 857 428 858 426 858 425 858 427 859 426 859 428 859 429 860 425 860 409 860 430 861 425 861 429 861 428 862 425 862 430 862 331 863 431 863 409 863 429 864 409 864 431 864 432 865 431 865 331 865 433 866 431 866 432 866 429 867 431 867 433 867 432 868 331 868 407 868 434 869 435 869 407 869 436 870 407 870 435 870 336 871 434 871 407 871 432 872 407 872 436 872 434 873 437 873 435 873 438 874 435 874 437 874 436 875 435 875 438 875 439 876 437 876 434 876 438 877 437 877 439 877 440 878 434 878 336 878 439 879 434 879 440 879 441 880 336 880 341 880 440 881 336 881 441 881 242 882 237 882 341 882 442 883 341 883 237 883 340 884 242 884 341 884 441 885 341 885 442 885 443 886 237 886 328 886 442 887 237 887 443 887 444 888 445 888 328 888 446 889 328 889 445 889 236 890 444 890 328 890 443 891 328 891 446 891 447 892 445 892 444 892 446 893 445 893 447 893 448 894 444 894 236 894 447 895 444 895 448 895 449 896 236 896 234 896 448 897 236 897 449 897 450 898 234 898 242 898 451 899 234 899 450 899 449 900 234 900 451 900 450 901 242 901 340 901 450 902 340 902 412 902 451 903 243 903 233 903 248 904 233 904 241 904 451 905 233 905 248 905 450 906 239 906 243 906 451 907 450 907 243 907 446 908 241 908 239 908 450 909 412 909 239 909 442 910 239 910 412 910 443 911 446 911 239 911 442 912 443 912 239 912 446 913 248 913 241 913 451 914 251 914 247 914 256 915 247 915 250 915 256 916 259 916 247 916 451 917 247 917 259 917 451 918 248 918 251 918 446 919 250 919 248 919 446 920 256 920 250 920 451 921 259 921 255 921 264 922 255 922 258 922 264 923 267 923 255 923 451 924 255 924 267 924 446 925 258 925 256 925 446 926 264 926 258 926 451 927 267 927 263 927 272 928 263 928 266 928 272 929 275 929 263 929 451 930 263 930 275 930 446 931 266 931 264 931 446 932 272 932 266 932 451 933 275 933 271 933 280 934 271 934 274 934 280 935 283 935 271 935 451 936 271 936 283 936 446 937 274 937 272 937 446 938 280 938 274 938 451 939 283 939 279 939 288 940 279 940 282 940 288 941 291 941 279 941 451 942 279 942 291 942 446 943 282 943 280 943 446 944 288 944 282 944 451 945 291 945 287 945 296 946 287 946 290 946 296 947 299 947 287 947 451 948 287 948 299 948 446 949 290 949 288 949 446 950 296 950 290 950 451 951 299 951 295 951 304 952 295 952 298 952 304 953 307 953 295 953 451 954 295 954 307 954 446 955 298 955 296 955 446 956 304 956 298 956 451 957 307 957 303 957 312 958 303 958 306 958 312 959 315 959 303 959 451 960 303 960 315 960 446 961 306 961 304 961 446 962 312 962 306 962 451 963 315 963 311 963 319 964 311 964 314 964 319 965 323 965 311 965 451 966 311 966 323 966 446 967 314 967 312 967 446 968 319 968 314 968 451 969 323 969 318 969 446 970 318 970 322 970 327 971 330 971 318 971 451 972 318 972 330 972 446 973 327 973 318 973 446 974 322 974 319 974 451 975 330 975 326 975 446 976 326 976 329 976 449 977 451 977 326 977 446 978 449 978 326 978 446 979 329 979 327 979 436 980 345 980 334 980 442 981 334 981 342 981 442 982 412 982 334 982 413 983 334 983 412 983 413 984 436 984 334 984 346 985 338 985 345 985 436 986 346 986 345 986 442 987 342 987 338 987 350 988 338 988 346 988 442 989 338 989 350 989 436 990 353 990 346 990 354 991 349 991 353 991 436 992 354 992 353 992 442 993 350 993 349 993 358 994 349 994 354 994 442 995 349 995 358 995 436 996 361 996 354 996 362 997 357 997 361 997 436 998 362 998 361 998 442 999 358 999 357 999 366 1000 357 1000 362 1000 442 1001 357 1001 366 1001 436 1002 369 1002 362 1002 370 1003 365 1003 369 1003 436 1004 370 1004 369 1004 442 1005 366 1005 365 1005 374 1006 365 1006 370 1006 442 1007 365 1007 374 1007 436 1008 377 1008 370 1008 378 1009 373 1009 377 1009 436 1010 378 1010 377 1010 442 1011 374 1011 373 1011 382 1012 373 1012 378 1012 442 1013 373 1013 382 1013 436 1014 385 1014 378 1014 386 1015 381 1015 385 1015 436 1016 386 1016 385 1016 442 1017 382 1017 381 1017 390 1018 381 1018 386 1018 442 1019 381 1019 390 1019 436 1020 393 1020 386 1020 394 1021 389 1021 393 1021 436 1022 394 1022 393 1022 442 1023 390 1023 389 1023 398 1024 389 1024 394 1024 442 1025 389 1025 398 1025 436 1026 401 1026 394 1026 402 1027 397 1027 401 1027 436 1028 402 1028 401 1028 442 1029 398 1029 397 1029 406 1030 397 1030 402 1030 442 1031 397 1031 406 1031 436 1032 408 1032 402 1032 436 1033 405 1033 408 1033 442 1034 406 1034 405 1034 441 1035 442 1035 405 1035 436 1036 441 1036 405 1036 447 1037 448 1037 449 1037 446 1038 447 1038 449 1038 439 1039 440 1039 441 1039 436 1040 439 1040 441 1040 436 1041 438 1041 439 1041 413 1042 432 1042 436 1042 411 1043 433 1043 432 1043 413 1044 411 1044 432 1044 424 1045 429 1045 433 1045 422 1046 424 1046 433 1046 420 1047 422 1047 433 1047 418 1048 420 1048 433 1048 416 1049 418 1049 433 1049 411 1050 416 1050 433 1050 428 1051 430 1051 429 1051 427 1052 428 1052 429 1052 424 1053 427 1053 429 1053 452 1054 453 1054 454 1054 455 1055 454 1055 453 1055 456 1056 454 1056 457 1056 455 1057 457 1057 454 1057 458 1058 452 1058 454 1058 456 1059 458 1059 454 1059 459 1060 460 1060 453 1060 461 1061 453 1061 460 1061 452 1062 462 1062 453 1062 459 1063 453 1063 462 1063 463 1064 455 1064 453 1064 463 1065 453 1065 461 1065 459 1066 457 1066 460 1066 461 1067 460 1067 457 1067 464 1068 457 1068 459 1068 464 1069 456 1069 457 1069 465 1070 457 1070 455 1070 461 1071 457 1071 465 1071 466 1072 467 1072 468 1072 469 1073 468 1073 467 1073 458 1074 468 1074 452 1074 469 1075 452 1075 468 1075 458 1076 466 1076 468 1076 459 1077 462 1077 467 1077 470 1078 467 1078 462 1078 466 1079 471 1079 467 1079 459 1080 467 1080 471 1080 472 1081 469 1081 467 1081 472 1082 467 1082 470 1082 470 1083 462 1083 452 1083 473 1084 452 1084 469 1084 470 1085 452 1085 473 1085 474 1086 475 1086 476 1086 477 1087 476 1087 475 1087 458 1088 476 1088 466 1088 477 1089 466 1089 476 1089 458 1090 474 1090 476 1090 459 1091 471 1091 475 1091 478 1092 475 1092 471 1092 474 1093 479 1093 475 1093 459 1094 475 1094 479 1094 480 1095 477 1095 475 1095 480 1096 475 1096 478 1096 478 1097 471 1097 466 1097 481 1098 466 1098 477 1098 478 1099 466 1099 481 1099 482 1100 483 1100 484 1100 485 1101 484 1101 483 1101 458 1102 484 1102 474 1102 485 1103 474 1103 484 1103 458 1104 482 1104 484 1104 459 1105 479 1105 483 1105 486 1106 483 1106 479 1106 482 1107 487 1107 483 1107 459 1108 483 1108 487 1108 488 1109 485 1109 483 1109 488 1110 483 1110 486 1110 486 1111 479 1111 474 1111 489 1112 474 1112 485 1112 486 1113 474 1113 489 1113 490 1114 491 1114 492 1114 493 1115 492 1115 491 1115 458 1116 492 1116 482 1116 493 1117 482 1117 492 1117 458 1118 490 1118 492 1118 459 1119 487 1119 491 1119 494 1120 491 1120 487 1120 490 1121 495 1121 491 1121 459 1122 491 1122 495 1122 496 1123 493 1123 491 1123 496 1124 491 1124 494 1124 494 1125 487 1125 482 1125 497 1126 482 1126 493 1126 494 1127 482 1127 497 1127 498 1128 499 1128 500 1128 501 1129 500 1129 499 1129 458 1130 500 1130 490 1130 501 1131 490 1131 500 1131 458 1132 498 1132 500 1132 459 1133 495 1133 499 1133 502 1134 499 1134 495 1134 498 1135 503 1135 499 1135 459 1136 499 1136 503 1136 504 1137 501 1137 499 1137 504 1138 499 1138 502 1138 502 1139 495 1139 490 1139 505 1140 490 1140 501 1140 502 1141 490 1141 505 1141 506 1142 507 1142 508 1142 509 1143 508 1143 507 1143 458 1144 508 1144 498 1144 509 1145 498 1145 508 1145 458 1146 506 1146 508 1146 459 1147 503 1147 507 1147 510 1148 507 1148 503 1148 506 1149 511 1149 507 1149 459 1150 507 1150 511 1150 512 1151 509 1151 507 1151 512 1152 507 1152 510 1152 510 1153 503 1153 498 1153 513 1154 498 1154 509 1154 510 1155 498 1155 513 1155 514 1156 515 1156 516 1156 517 1157 516 1157 515 1157 458 1158 516 1158 506 1158 517 1159 506 1159 516 1159 458 1160 514 1160 516 1160 459 1161 511 1161 515 1161 518 1162 515 1162 511 1162 514 1163 519 1163 515 1163 459 1164 515 1164 519 1164 520 1165 517 1165 515 1165 520 1166 515 1166 518 1166 518 1167 511 1167 506 1167 521 1168 506 1168 517 1168 518 1169 506 1169 521 1169 522 1170 523 1170 524 1170 525 1171 524 1171 523 1171 458 1172 524 1172 514 1172 525 1173 514 1173 524 1173 458 1174 522 1174 524 1174 459 1175 519 1175 523 1175 526 1176 523 1176 519 1176 522 1177 527 1177 523 1177 459 1178 523 1178 527 1178 528 1179 525 1179 523 1179 528 1180 523 1180 526 1180 526 1181 519 1181 514 1181 529 1182 514 1182 525 1182 526 1183 514 1183 529 1183 530 1184 531 1184 532 1184 533 1185 532 1185 531 1185 458 1186 532 1186 522 1186 533 1187 522 1187 532 1187 458 1188 530 1188 532 1188 459 1189 527 1189 531 1189 534 1190 531 1190 527 1190 530 1191 535 1191 531 1191 459 1192 531 1192 535 1192 536 1193 533 1193 531 1193 536 1194 531 1194 534 1194 534 1195 527 1195 522 1195 537 1196 522 1196 533 1196 534 1197 522 1197 537 1197 458 1198 538 1198 539 1198 540 1199 539 1199 538 1199 458 1200 539 1200 530 1200 540 1201 530 1201 539 1201 459 1202 535 1202 538 1202 541 1203 538 1203 535 1203 542 1204 543 1204 538 1204 459 1205 538 1205 543 1205 458 1206 542 1206 538 1206 544 1207 540 1207 538 1207 544 1208 538 1208 541 1208 541 1209 535 1209 530 1209 545 1210 530 1210 540 1210 541 1211 530 1211 545 1211 458 1212 546 1212 547 1212 548 1213 547 1213 546 1213 458 1214 547 1214 542 1214 548 1215 542 1215 547 1215 459 1216 543 1216 546 1216 549 1217 546 1217 543 1217 550 1218 459 1218 546 1218 458 1219 550 1219 546 1219 551 1220 548 1220 546 1220 551 1221 546 1221 549 1221 549 1222 543 1222 542 1222 552 1223 542 1223 548 1223 549 1224 542 1224 552 1224 553 1225 554 1225 555 1225 556 1226 555 1226 554 1226 553 1227 555 1227 557 1227 556 1228 557 1228 555 1228 558 1229 559 1229 554 1229 560 1230 554 1230 559 1230 553 1231 561 1231 554 1231 562 1232 554 1232 561 1232 563 1233 558 1233 554 1233 562 1234 563 1234 554 1234 564 1235 556 1235 554 1235 564 1236 554 1236 560 1236 565 1237 557 1237 559 1237 560 1238 559 1238 557 1238 558 1239 565 1239 559 1239 565 1240 566 1240 557 1240 553 1241 557 1241 566 1241 567 1242 557 1242 556 1242 560 1243 557 1243 567 1243 568 1244 566 1244 565 1244 553 1245 566 1245 569 1245 568 1246 569 1246 566 1246 558 1247 570 1247 565 1247 571 1248 565 1248 570 1248 572 1249 568 1249 565 1249 572 1250 565 1250 571 1250 573 1251 569 1251 570 1251 571 1252 570 1252 569 1252 558 1253 573 1253 570 1253 573 1254 574 1254 569 1254 553 1255 569 1255 574 1255 575 1256 569 1256 568 1256 571 1257 569 1257 575 1257 576 1258 574 1258 573 1258 553 1259 574 1259 577 1259 576 1260 577 1260 574 1260 558 1261 578 1261 573 1261 579 1262 573 1262 578 1262 580 1263 576 1263 573 1263 580 1264 573 1264 579 1264 581 1265 577 1265 578 1265 579 1266 578 1266 577 1266 558 1267 581 1267 578 1267 581 1268 582 1268 577 1268 553 1269 577 1269 582 1269 583 1270 577 1270 576 1270 579 1271 577 1271 583 1271 584 1272 582 1272 581 1272 553 1273 582 1273 585 1273 584 1274 585 1274 582 1274 558 1275 586 1275 581 1275 587 1276 581 1276 586 1276 588 1277 584 1277 581 1277 588 1278 581 1278 587 1278 589 1279 585 1279 586 1279 587 1280 586 1280 585 1280 558 1281 589 1281 586 1281 589 1282 590 1282 585 1282 553 1283 585 1283 590 1283 591 1284 585 1284 584 1284 587 1285 585 1285 591 1285 592 1286 590 1286 589 1286 553 1287 590 1287 593 1287 592 1288 593 1288 590 1288 558 1289 594 1289 589 1289 595 1290 589 1290 594 1290 596 1291 592 1291 589 1291 596 1292 589 1292 595 1292 597 1293 593 1293 594 1293 595 1294 594 1294 593 1294 558 1295 597 1295 594 1295 597 1296 598 1296 593 1296 553 1297 593 1297 598 1297 599 1298 593 1298 592 1298 595 1299 593 1299 599 1299 600 1300 598 1300 597 1300 553 1301 598 1301 601 1301 600 1302 601 1302 598 1302 558 1303 602 1303 597 1303 603 1304 597 1304 602 1304 604 1305 600 1305 597 1305 604 1306 597 1306 603 1306 605 1307 601 1307 602 1307 603 1308 602 1308 601 1308 558 1309 605 1309 602 1309 605 1310 606 1310 601 1310 553 1311 601 1311 606 1311 607 1312 601 1312 600 1312 603 1313 601 1313 607 1313 608 1314 606 1314 605 1314 553 1315 606 1315 609 1315 608 1316 609 1316 606 1316 558 1317 610 1317 605 1317 611 1318 605 1318 610 1318 612 1319 608 1319 605 1319 612 1320 605 1320 611 1320 613 1321 609 1321 610 1321 611 1322 610 1322 609 1322 558 1323 613 1323 610 1323 613 1324 614 1324 609 1324 553 1325 609 1325 614 1325 615 1326 609 1326 608 1326 611 1327 609 1327 615 1327 616 1328 614 1328 613 1328 553 1329 614 1329 617 1329 616 1330 617 1330 614 1330 558 1331 618 1331 613 1331 619 1332 613 1332 618 1332 620 1333 616 1333 613 1333 620 1334 613 1334 619 1334 621 1335 617 1335 618 1335 619 1336 618 1336 617 1336 558 1337 621 1337 618 1337 621 1338 622 1338 617 1338 553 1339 617 1339 622 1339 623 1340 617 1340 616 1340 619 1341 617 1341 623 1341 624 1342 622 1342 621 1342 553 1343 622 1343 625 1343 624 1344 625 1344 622 1344 558 1345 626 1345 621 1345 627 1346 621 1346 626 1346 628 1347 624 1347 621 1347 628 1348 621 1348 627 1348 558 1349 625 1349 626 1349 627 1350 626 1350 625 1350 629 1351 553 1351 625 1351 558 1352 629 1352 625 1352 630 1353 625 1353 624 1353 627 1354 625 1354 630 1354 631 1355 632 1355 561 1355 633 1356 561 1356 632 1356 553 1357 631 1357 561 1357 634 1358 562 1358 561 1358 635 1359 634 1359 561 1359 635 1360 561 1360 633 1360 631 1361 636 1361 632 1361 633 1362 632 1362 636 1362 631 1363 637 1363 636 1363 638 1364 636 1364 637 1364 633 1365 636 1365 638 1365 631 1366 639 1366 637 1366 640 1367 637 1367 639 1367 638 1368 637 1368 640 1368 631 1369 641 1369 639 1369 642 1370 639 1370 641 1370 640 1371 639 1371 642 1371 631 1372 643 1372 641 1372 644 1373 641 1373 643 1373 642 1374 641 1374 644 1374 631 1375 645 1375 643 1375 646 1376 643 1376 645 1376 644 1377 643 1377 646 1377 647 1378 648 1378 645 1378 649 1379 645 1379 648 1379 631 1380 647 1380 645 1380 646 1381 645 1381 649 1381 650 1382 648 1382 647 1382 649 1383 648 1383 650 1383 651 1384 647 1384 631 1384 652 1385 647 1385 651 1385 650 1386 647 1386 652 1386 553 1387 653 1387 631 1387 651 1388 631 1388 653 1388 654 1389 653 1389 553 1389 655 1390 653 1390 654 1390 651 1391 653 1391 655 1391 654 1392 553 1392 629 1392 656 1393 657 1393 629 1393 658 1394 629 1394 657 1394 558 1395 656 1395 629 1395 654 1396 629 1396 658 1396 656 1397 659 1397 657 1397 660 1398 657 1398 659 1398 658 1399 657 1399 660 1399 661 1400 659 1400 656 1400 660 1401 659 1401 661 1401 662 1402 656 1402 558 1402 661 1403 656 1403 662 1403 663 1404 558 1404 563 1404 662 1405 558 1405 663 1405 464 1406 459 1406 563 1406 664 1407 563 1407 459 1407 562 1408 464 1408 563 1408 663 1409 563 1409 664 1409 665 1410 459 1410 550 1410 664 1411 459 1411 665 1411 666 1412 667 1412 550 1412 668 1413 550 1413 667 1413 458 1414 666 1414 550 1414 665 1415 550 1415 668 1415 669 1416 667 1416 666 1416 668 1417 667 1417 669 1417 670 1418 666 1418 458 1418 669 1419 666 1419 670 1419 671 1420 458 1420 456 1420 670 1421 458 1421 671 1421 672 1422 456 1422 464 1422 673 1423 456 1423 672 1423 671 1424 456 1424 673 1424 672 1425 464 1425 562 1425 672 1426 562 1426 634 1426 673 1427 465 1427 455 1427 470 1428 455 1428 463 1428 673 1429 455 1429 470 1429 672 1430 461 1430 465 1430 673 1431 672 1431 465 1431 668 1432 463 1432 461 1432 672 1433 634 1433 461 1433 664 1434 461 1434 634 1434 665 1435 668 1435 461 1435 664 1436 665 1436 461 1436 668 1437 470 1437 463 1437 673 1438 473 1438 469 1438 478 1439 469 1439 472 1439 478 1440 481 1440 469 1440 673 1441 469 1441 481 1441 673 1442 470 1442 473 1442 668 1443 472 1443 470 1443 668 1444 478 1444 472 1444 673 1445 481 1445 477 1445 486 1446 477 1446 480 1446 486 1447 489 1447 477 1447 673 1448 477 1448 489 1448 668 1449 480 1449 478 1449 668 1450 486 1450 480 1450 673 1451 489 1451 485 1451 494 1452 485 1452 488 1452 494 1453 497 1453 485 1453 673 1454 485 1454 497 1454 668 1455 488 1455 486 1455 668 1456 494 1456 488 1456 673 1457 497 1457 493 1457 502 1458 493 1458 496 1458 502 1459 505 1459 493 1459 673 1460 493 1460 505 1460 668 1461 496 1461 494 1461 668 1462 502 1462 496 1462 673 1463 505 1463 501 1463 510 1464 501 1464 504 1464 510 1465 513 1465 501 1465 673 1466 501 1466 513 1466 668 1467 504 1467 502 1467 668 1468 510 1468 504 1468 673 1469 513 1469 509 1469 518 1470 509 1470 512 1470 518 1471 521 1471 509 1471 673 1472 509 1472 521 1472 668 1473 512 1473 510 1473 668 1474 518 1474 512 1474 673 1475 521 1475 517 1475 526 1476 517 1476 520 1476 526 1477 529 1477 517 1477 673 1478 517 1478 529 1478 668 1479 520 1479 518 1479 668 1480 526 1480 520 1480 673 1481 529 1481 525 1481 534 1482 525 1482 528 1482 534 1483 537 1483 525 1483 673 1484 525 1484 537 1484 668 1485 528 1485 526 1485 668 1486 534 1486 528 1486 673 1487 537 1487 533 1487 541 1488 533 1488 536 1488 541 1489 545 1489 533 1489 673 1490 533 1490 545 1490 668 1491 536 1491 534 1491 668 1492 541 1492 536 1492 673 1493 545 1493 540 1493 668 1494 540 1494 544 1494 549 1495 552 1495 540 1495 673 1496 540 1496 552 1496 668 1497 549 1497 540 1497 668 1498 544 1498 541 1498 673 1499 552 1499 548 1499 668 1500 548 1500 551 1500 671 1501 673 1501 548 1501 668 1502 671 1502 548 1502 668 1503 551 1503 549 1503 658 1504 567 1504 556 1504 664 1505 556 1505 564 1505 664 1506 634 1506 556 1506 635 1507 556 1507 634 1507 635 1508 658 1508 556 1508 568 1509 560 1509 567 1509 658 1510 568 1510 567 1510 664 1511 564 1511 560 1511 572 1512 560 1512 568 1512 664 1513 560 1513 572 1513 658 1514 575 1514 568 1514 576 1515 571 1515 575 1515 658 1516 576 1516 575 1516 664 1517 572 1517 571 1517 580 1518 571 1518 576 1518 664 1519 571 1519 580 1519 658 1520 583 1520 576 1520 584 1521 579 1521 583 1521 658 1522 584 1522 583 1522 664 1523 580 1523 579 1523 588 1524 579 1524 584 1524 664 1525 579 1525 588 1525 658 1526 591 1526 584 1526 592 1527 587 1527 591 1527 658 1528 592 1528 591 1528 664 1529 588 1529 587 1529 596 1530 587 1530 592 1530 664 1531 587 1531 596 1531 658 1532 599 1532 592 1532 600 1533 595 1533 599 1533 658 1534 600 1534 599 1534 664 1535 596 1535 595 1535 604 1536 595 1536 600 1536 664 1537 595 1537 604 1537 658 1538 607 1538 600 1538 608 1539 603 1539 607 1539 658 1540 608 1540 607 1540 664 1541 604 1541 603 1541 612 1542 603 1542 608 1542 664 1543 603 1543 612 1543 658 1544 615 1544 608 1544 616 1545 611 1545 615 1545 658 1546 616 1546 615 1546 664 1547 612 1547 611 1547 620 1548 611 1548 616 1548 664 1549 611 1549 620 1549 658 1550 623 1550 616 1550 624 1551 619 1551 623 1551 658 1552 624 1552 623 1552 664 1553 620 1553 619 1553 628 1554 619 1554 624 1554 664 1555 619 1555 628 1555 658 1556 630 1556 624 1556 658 1557 627 1557 630 1557 664 1558 628 1558 627 1558 663 1559 664 1559 627 1559 658 1560 663 1560 627 1560 669 1561 670 1561 671 1561 668 1562 669 1562 671 1562 661 1563 662 1563 663 1563 658 1564 661 1564 663 1564 658 1565 660 1565 661 1565 635 1566 654 1566 658 1566 633 1567 655 1567 654 1567 635 1568 633 1568 654 1568 646 1569 651 1569 655 1569 644 1570 646 1570 655 1570 642 1571 644 1571 655 1571 640 1572 642 1572 655 1572 638 1573 640 1573 655 1573 633 1574 638 1574 655 1574 650 1575 652 1575 651 1575 649 1576 650 1576 651 1576 646 1577 649 1577 651 1577 674 1578 675 1578 676 1578 677 1579 676 1579 675 1579 678 1580 676 1580 679 1580 677 1581 679 1581 676 1581 680 1582 674 1582 676 1582 678 1583 680 1583 676 1583 681 1584 682 1584 675 1584 683 1585 675 1585 682 1585 674 1586 684 1586 675 1586 681 1587 675 1587 684 1587 685 1588 677 1588 675 1588 685 1589 675 1589 683 1589 681 1590 679 1590 682 1590 683 1591 682 1591 679 1591 686 1592 679 1592 681 1592 686 1593 678 1593 679 1593 687 1594 679 1594 677 1594 683 1595 679 1595 687 1595 688 1596 689 1596 690 1596 691 1597 690 1597 689 1597 680 1598 690 1598 674 1598 691 1599 674 1599 690 1599 680 1600 688 1600 690 1600 681 1601 684 1601 689 1601 692 1602 689 1602 684 1602 688 1603 693 1603 689 1603 681 1604 689 1604 693 1604 694 1605 691 1605 689 1605 694 1606 689 1606 692 1606 692 1607 684 1607 674 1607 695 1608 674 1608 691 1608 692 1609 674 1609 695 1609 696 1610 697 1610 698 1610 699 1611 698 1611 697 1611 680 1612 698 1612 688 1612 699 1613 688 1613 698 1613 680 1614 696 1614 698 1614 681 1615 693 1615 697 1615 700 1616 697 1616 693 1616 696 1617 701 1617 697 1617 681 1618 697 1618 701 1618 702 1619 699 1619 697 1619 702 1620 697 1620 700 1620 700 1621 693 1621 688 1621 703 1622 688 1622 699 1622 700 1623 688 1623 703 1623 704 1624 705 1624 706 1624 707 1625 706 1625 705 1625 680 1626 706 1626 696 1626 707 1627 696 1627 706 1627 680 1628 704 1628 706 1628 681 1629 701 1629 705 1629 708 1630 705 1630 701 1630 704 1631 709 1631 705 1631 681 1632 705 1632 709 1632 710 1633 707 1633 705 1633 710 1634 705 1634 708 1634 708 1635 701 1635 696 1635 711 1636 696 1636 707 1636 708 1637 696 1637 711 1637 712 1638 713 1638 714 1638 715 1639 714 1639 713 1639 680 1640 714 1640 704 1640 715 1641 704 1641 714 1641 680 1642 712 1642 714 1642 681 1643 709 1643 713 1643 716 1644 713 1644 709 1644 712 1645 717 1645 713 1645 681 1646 713 1646 717 1646 718 1647 715 1647 713 1647 718 1648 713 1648 716 1648 716 1649 709 1649 704 1649 719 1650 704 1650 715 1650 716 1651 704 1651 719 1651 720 1652 721 1652 722 1652 723 1653 722 1653 721 1653 680 1654 722 1654 712 1654 723 1655 712 1655 722 1655 680 1656 720 1656 722 1656 681 1657 717 1657 721 1657 724 1658 721 1658 717 1658 720 1659 725 1659 721 1659 681 1660 721 1660 725 1660 726 1661 723 1661 721 1661 726 1662 721 1662 724 1662 724 1663 717 1663 712 1663 727 1664 712 1664 723 1664 724 1665 712 1665 727 1665 728 1666 729 1666 730 1666 731 1667 730 1667 729 1667 680 1668 730 1668 720 1668 731 1669 720 1669 730 1669 680 1670 728 1670 730 1670 681 1671 725 1671 729 1671 732 1672 729 1672 725 1672 728 1673 733 1673 729 1673 681 1674 729 1674 733 1674 734 1675 731 1675 729 1675 734 1676 729 1676 732 1676 732 1677 725 1677 720 1677 735 1678 720 1678 731 1678 732 1679 720 1679 735 1679 736 1680 737 1680 738 1680 739 1681 738 1681 737 1681 680 1682 738 1682 728 1682 739 1683 728 1683 738 1683 680 1684 736 1684 738 1684 681 1685 733 1685 737 1685 740 1686 737 1686 733 1686 736 1687 741 1687 737 1687 681 1688 737 1688 741 1688 742 1689 739 1689 737 1689 742 1690 737 1690 740 1690 740 1691 733 1691 728 1691 743 1692 728 1692 739 1692 740 1693 728 1693 743 1693 744 1694 745 1694 746 1694 747 1695 746 1695 745 1695 680 1696 746 1696 736 1696 747 1697 736 1697 746 1697 680 1698 744 1698 746 1698 681 1699 741 1699 745 1699 748 1700 745 1700 741 1700 744 1701 749 1701 745 1701 681 1702 745 1702 749 1702 750 1703 747 1703 745 1703 750 1704 745 1704 748 1704 748 1705 741 1705 736 1705 751 1706 736 1706 747 1706 748 1707 736 1707 751 1707 752 1708 753 1708 754 1708 755 1709 754 1709 753 1709 680 1710 754 1710 744 1710 755 1711 744 1711 754 1711 680 1712 752 1712 754 1712 681 1713 749 1713 753 1713 756 1714 753 1714 749 1714 752 1715 757 1715 753 1715 681 1716 753 1716 757 1716 758 1717 755 1717 753 1717 758 1718 753 1718 756 1718 756 1719 749 1719 744 1719 759 1720 744 1720 755 1720 756 1721 744 1721 759 1721 680 1722 760 1722 761 1722 762 1723 761 1723 760 1723 680 1724 761 1724 752 1724 762 1725 752 1725 761 1725 681 1726 757 1726 760 1726 763 1727 760 1727 757 1727 764 1728 765 1728 760 1728 681 1729 760 1729 765 1729 680 1730 764 1730 760 1730 766 1731 762 1731 760 1731 766 1732 760 1732 763 1732 763 1733 757 1733 752 1733 767 1734 752 1734 762 1734 763 1735 752 1735 767 1735 680 1736 768 1736 769 1736 770 1737 769 1737 768 1737 680 1738 769 1738 764 1738 770 1739 764 1739 769 1739 681 1740 765 1740 768 1740 771 1741 768 1741 765 1741 772 1742 681 1742 768 1742 680 1743 772 1743 768 1743 773 1744 770 1744 768 1744 773 1745 768 1745 771 1745 771 1746 765 1746 764 1746 774 1747 764 1747 770 1747 771 1748 764 1748 774 1748 775 1749 776 1749 777 1749 778 1750 777 1750 776 1750 775 1751 777 1751 779 1751 778 1752 779 1752 777 1752 780 1753 781 1753 776 1753 782 1754 776 1754 781 1754 775 1755 783 1755 776 1755 784 1756 776 1756 783 1756 785 1757 780 1757 776 1757 784 1758 785 1758 776 1758 786 1759 778 1759 776 1759 786 1760 776 1760 782 1760 787 1761 779 1761 781 1761 782 1762 781 1762 779 1762 780 1763 787 1763 781 1763 787 1764 788 1764 779 1764 775 1765 779 1765 788 1765 789 1766 779 1766 778 1766 782 1767 779 1767 789 1767 790 1768 788 1768 787 1768 775 1769 788 1769 791 1769 790 1770 791 1770 788 1770 780 1771 792 1771 787 1771 793 1772 787 1772 792 1772 794 1773 790 1773 787 1773 794 1774 787 1774 793 1774 795 1775 791 1775 792 1775 793 1776 792 1776 791 1776 780 1777 795 1777 792 1777 795 1778 796 1778 791 1778 775 1779 791 1779 796 1779 797 1780 791 1780 790 1780 793 1781 791 1781 797 1781 798 1782 796 1782 795 1782 775 1783 796 1783 799 1783 798 1784 799 1784 796 1784 780 1785 800 1785 795 1785 801 1786 795 1786 800 1786 802 1787 798 1787 795 1787 802 1788 795 1788 801 1788 803 1789 799 1789 800 1789 801 1790 800 1790 799 1790 780 1791 803 1791 800 1791 803 1792 804 1792 799 1792 775 1793 799 1793 804 1793 805 1794 799 1794 798 1794 801 1795 799 1795 805 1795 806 1796 804 1796 803 1796 775 1797 804 1797 807 1797 806 1798 807 1798 804 1798 780 1799 808 1799 803 1799 809 1800 803 1800 808 1800 810 1801 806 1801 803 1801 810 1802 803 1802 809 1802 811 1803 807 1803 808 1803 809 1804 808 1804 807 1804 780 1805 811 1805 808 1805 811 1806 812 1806 807 1806 775 1807 807 1807 812 1807 813 1808 807 1808 806 1808 809 1809 807 1809 813 1809 814 1810 812 1810 811 1810 775 1811 812 1811 815 1811 814 1812 815 1812 812 1812 780 1813 816 1813 811 1813 817 1814 811 1814 816 1814 818 1815 814 1815 811 1815 818 1816 811 1816 817 1816 819 1817 815 1817 816 1817 817 1818 816 1818 815 1818 780 1819 819 1819 816 1819 819 1820 820 1820 815 1820 775 1821 815 1821 820 1821 821 1822 815 1822 814 1822 817 1823 815 1823 821 1823 822 1824 820 1824 819 1824 775 1825 820 1825 823 1825 822 1826 823 1826 820 1826 780 1827 824 1827 819 1827 825 1828 819 1828 824 1828 826 1829 822 1829 819 1829 826 1830 819 1830 825 1830 827 1831 823 1831 824 1831 825 1832 824 1832 823 1832 780 1833 827 1833 824 1833 827 1834 828 1834 823 1834 775 1835 823 1835 828 1835 829 1836 823 1836 822 1836 825 1837 823 1837 829 1837 830 1838 828 1838 827 1838 775 1839 828 1839 831 1839 830 1840 831 1840 828 1840 780 1841 832 1841 827 1841 833 1842 827 1842 832 1842 834 1843 830 1843 827 1843 834 1844 827 1844 833 1844 835 1845 831 1845 832 1845 833 1846 832 1846 831 1846 780 1847 835 1847 832 1847 835 1848 836 1848 831 1848 775 1849 831 1849 836 1849 837 1850 831 1850 830 1850 833 1851 831 1851 837 1851 838 1852 836 1852 835 1852 775 1853 836 1853 839 1853 838 1854 839 1854 836 1854 780 1855 840 1855 835 1855 841 1856 835 1856 840 1856 842 1857 838 1857 835 1857 842 1858 835 1858 841 1858 843 1859 839 1859 840 1859 841 1860 840 1860 839 1860 780 1861 843 1861 840 1861 843 1862 844 1862 839 1862 775 1863 839 1863 844 1863 845 1864 839 1864 838 1864 841 1865 839 1865 845 1865 846 1866 844 1866 843 1866 775 1867 844 1867 847 1867 846 1868 847 1868 844 1868 780 1869 848 1869 843 1869 849 1870 843 1870 848 1870 850 1871 846 1871 843 1871 850 1872 843 1872 849 1872 780 1873 847 1873 848 1873 849 1874 848 1874 847 1874 851 1875 775 1875 847 1875 780 1876 851 1876 847 1876 852 1877 847 1877 846 1877 849 1878 847 1878 852 1878 853 1879 854 1879 783 1879 855 1880 783 1880 854 1880 775 1881 853 1881 783 1881 856 1882 784 1882 783 1882 857 1883 856 1883 783 1883 857 1884 783 1884 855 1884 853 1885 858 1885 854 1885 855 1886 854 1886 858 1886 853 1887 859 1887 858 1887 860 1888 858 1888 859 1888 855 1889 858 1889 860 1889 853 1890 861 1890 859 1890 862 1891 859 1891 861 1891 860 1892 859 1892 862 1892 853 1893 863 1893 861 1893 864 1894 861 1894 863 1894 862 1895 861 1895 864 1895 853 1896 865 1896 863 1896 866 1897 863 1897 865 1897 864 1898 863 1898 866 1898 853 1899 867 1899 865 1899 868 1900 865 1900 867 1900 866 1901 865 1901 868 1901 869 1902 870 1902 867 1902 871 1903 867 1903 870 1903 853 1904 869 1904 867 1904 868 1905 867 1905 871 1905 872 1906 870 1906 869 1906 871 1907 870 1907 872 1907 873 1908 869 1908 853 1908 874 1909 869 1909 873 1909 872 1910 869 1910 874 1910 775 1911 875 1911 853 1911 873 1912 853 1912 875 1912 876 1913 875 1913 775 1913 877 1914 875 1914 876 1914 873 1915 875 1915 877 1915 876 1916 775 1916 851 1916 878 1917 879 1917 851 1917 880 1918 851 1918 879 1918 780 1919 878 1919 851 1919 876 1920 851 1920 880 1920 878 1921 881 1921 879 1921 882 1922 879 1922 881 1922 880 1923 879 1923 882 1923 883 1924 881 1924 878 1924 882 1925 881 1925 883 1925 884 1926 878 1926 780 1926 883 1927 878 1927 884 1927 885 1928 780 1928 785 1928 884 1929 780 1929 885 1929 686 1930 681 1930 785 1930 886 1931 785 1931 681 1931 784 1932 686 1932 785 1932 885 1933 785 1933 886 1933 887 1934 681 1934 772 1934 886 1935 681 1935 887 1935 888 1936 889 1936 772 1936 890 1937 772 1937 889 1937 680 1938 888 1938 772 1938 887 1939 772 1939 890 1939 891 1940 889 1940 888 1940 890 1941 889 1941 891 1941 892 1942 888 1942 680 1942 891 1943 888 1943 892 1943 893 1944 680 1944 678 1944 892 1945 680 1945 893 1945 894 1946 678 1946 686 1946 895 1947 678 1947 894 1947 893 1948 678 1948 895 1948 894 1949 686 1949 784 1949 894 1950 784 1950 856 1950 895 1951 687 1951 677 1951 692 1952 677 1952 685 1952 895 1953 677 1953 692 1953 894 1954 683 1954 687 1954 895 1955 894 1955 687 1955 890 1956 685 1956 683 1956 894 1957 856 1957 683 1957 886 1958 683 1958 856 1958 887 1959 890 1959 683 1959 886 1960 887 1960 683 1960 890 1961 692 1961 685 1961 895 1962 695 1962 691 1962 700 1963 691 1963 694 1963 700 1964 703 1964 691 1964 895 1965 691 1965 703 1965 895 1966 692 1966 695 1966 890 1967 694 1967 692 1967 890 1968 700 1968 694 1968 895 1969 703 1969 699 1969 708 1970 699 1970 702 1970 708 1971 711 1971 699 1971 895 1972 699 1972 711 1972 890 1973 702 1973 700 1973 890 1974 708 1974 702 1974 895 1975 711 1975 707 1975 716 1976 707 1976 710 1976 716 1977 719 1977 707 1977 895 1978 707 1978 719 1978 890 1979 710 1979 708 1979 890 1980 716 1980 710 1980 895 1981 719 1981 715 1981 724 1982 715 1982 718 1982 724 1983 727 1983 715 1983 895 1984 715 1984 727 1984 890 1985 718 1985 716 1985 890 1986 724 1986 718 1986 895 1987 727 1987 723 1987 732 1988 723 1988 726 1988 732 1989 735 1989 723 1989 895 1990 723 1990 735 1990 890 1991 726 1991 724 1991 890 1992 732 1992 726 1992 895 1993 735 1993 731 1993 740 1994 731 1994 734 1994 740 1995 743 1995 731 1995 895 1996 731 1996 743 1996 890 1997 734 1997 732 1997 890 1998 740 1998 734 1998 895 1999 743 1999 739 1999 748 2000 739 2000 742 2000 748 2001 751 2001 739 2001 895 2002 739 2002 751 2002 890 2003 742 2003 740 2003 890 2004 748 2004 742 2004 895 2005 751 2005 747 2005 756 2006 747 2006 750 2006 756 2007 759 2007 747 2007 895 2008 747 2008 759 2008 890 2009 750 2009 748 2009 890 2010 756 2010 750 2010 895 2011 759 2011 755 2011 763 2012 755 2012 758 2012 763 2013 767 2013 755 2013 895 2014 755 2014 767 2014 890 2015 758 2015 756 2015 890 2016 763 2016 758 2016 895 2017 767 2017 762 2017 890 2018 762 2018 766 2018 771 2019 774 2019 762 2019 895 2020 762 2020 774 2020 890 2021 771 2021 762 2021 890 2022 766 2022 763 2022 895 2023 774 2023 770 2023 890 2024 770 2024 773 2024 893 2025 895 2025 770 2025 890 2026 893 2026 770 2026 890 2027 773 2027 771 2027 880 2028 789 2028 778 2028 886 2029 778 2029 786 2029 886 2030 856 2030 778 2030 857 2031 778 2031 856 2031 857 2032 880 2032 778 2032 790 2033 782 2033 789 2033 880 2034 790 2034 789 2034 886 2035 786 2035 782 2035 794 2036 782 2036 790 2036 886 2037 782 2037 794 2037 880 2038 797 2038 790 2038 798 2039 793 2039 797 2039 880 2040 798 2040 797 2040 886 2041 794 2041 793 2041 802 2042 793 2042 798 2042 886 2043 793 2043 802 2043 880 2044 805 2044 798 2044 806 2045 801 2045 805 2045 880 2046 806 2046 805 2046 886 2047 802 2047 801 2047 810 2048 801 2048 806 2048 886 2049 801 2049 810 2049 880 2050 813 2050 806 2050 814 2051 809 2051 813 2051 880 2052 814 2052 813 2052 886 2053 810 2053 809 2053 818 2054 809 2054 814 2054 886 2055 809 2055 818 2055 880 2056 821 2056 814 2056 822 2057 817 2057 821 2057 880 2058 822 2058 821 2058 886 2059 818 2059 817 2059 826 2060 817 2060 822 2060 886 2061 817 2061 826 2061 880 2062 829 2062 822 2062 830 2063 825 2063 829 2063 880 2064 830 2064 829 2064 886 2065 826 2065 825 2065 834 2066 825 2066 830 2066 886 2067 825 2067 834 2067 880 2068 837 2068 830 2068 838 2069 833 2069 837 2069 880 2070 838 2070 837 2070 886 2071 834 2071 833 2071 842 2072 833 2072 838 2072 886 2073 833 2073 842 2073 880 2074 845 2074 838 2074 846 2075 841 2075 845 2075 880 2076 846 2076 845 2076 886 2077 842 2077 841 2077 850 2078 841 2078 846 2078 886 2079 841 2079 850 2079 880 2080 852 2080 846 2080 880 2081 849 2081 852 2081 886 2082 850 2082 849 2082 885 2083 886 2083 849 2083 880 2084 885 2084 849 2084 891 2085 892 2085 893 2085 890 2086 891 2086 893 2086 883 2087 884 2087 885 2087 880 2088 883 2088 885 2088 880 2089 882 2089 883 2089 857 2090 876 2090 880 2090 855 2091 877 2091 876 2091 857 2092 855 2092 876 2092 868 2093 873 2093 877 2093 866 2094 868 2094 877 2094 864 2095 866 2095 877 2095 862 2096 864 2096 877 2096 860 2097 862 2097 877 2097 855 2098 860 2098 877 2098 872 2099 874 2099 873 2099 871 2100 872 2100 873 2100 868 2101 871 2101 873 2101 896 2102 897 2102 898 2102 899 2103 898 2103 897 2103 900 2104 898 2104 901 2104 902 2105 901 2105 898 2105 903 2106 896 2106 898 2106 900 2107 903 2107 898 2107 902 2108 898 2108 899 2108 896 2109 904 2109 897 2109 905 2110 897 2110 904 2110 905 2111 899 2111 897 2111 896 2112 906 2112 904 2112 907 2113 904 2113 906 2113 905 2114 904 2114 907 2114 908 2115 909 2115 906 2115 910 2116 906 2116 909 2116 911 2117 908 2117 906 2117 912 2118 911 2118 906 2118 913 2119 906 2119 896 2119 914 2120 912 2120 906 2120 913 2121 914 2121 906 2121 907 2122 906 2122 910 2122 915 2123 916 2123 909 2123 917 2124 909 2124 916 2124 908 2125 915 2125 909 2125 910 2126 909 2126 917 2126 918 2127 919 2127 916 2127 920 2128 916 2128 919 2128 918 2129 916 2129 915 2129 917 2130 916 2130 920 2130 921 2131 922 2131 919 2131 923 2132 919 2132 922 2132 918 2133 921 2133 919 2133 920 2134 919 2134 923 2134 924 2135 925 2135 922 2135 926 2136 922 2136 925 2136 924 2137 922 2137 921 2137 923 2138 922 2138 926 2138 927 2139 901 2139 925 2139 928 2140 925 2140 901 2140 924 2141 929 2141 925 2141 927 2142 925 2142 929 2142 926 2143 925 2143 928 2143 930 2144 900 2144 901 2144 931 2145 930 2145 901 2145 932 2146 931 2146 901 2146 927 2147 932 2147 901 2147 928 2148 901 2148 902 2148 896 2149 933 2149 934 2149 935 2150 934 2150 933 2150 936 2151 934 2151 937 2151 938 2152 937 2152 934 2152 936 2153 896 2153 934 2153 938 2154 934 2154 935 2154 896 2155 939 2155 933 2155 940 2156 933 2156 939 2156 940 2157 935 2157 933 2157 896 2158 941 2158 939 2158 942 2159 939 2159 941 2159 940 2160 939 2160 942 2160 943 2161 944 2161 941 2161 945 2162 941 2162 944 2162 946 2163 943 2163 941 2163 947 2164 946 2164 941 2164 948 2165 941 2165 896 2165 948 2166 947 2166 941 2166 942 2167 941 2167 945 2167 949 2168 950 2168 944 2168 951 2169 944 2169 950 2169 943 2170 949 2170 944 2170 945 2171 944 2171 951 2171 952 2172 953 2172 950 2172 954 2173 950 2173 953 2173 952 2174 950 2174 949 2174 951 2175 950 2175 954 2175 955 2176 956 2176 953 2176 957 2177 953 2177 956 2177 952 2178 955 2178 953 2178 954 2179 953 2179 957 2179 958 2180 959 2180 956 2180 960 2181 956 2181 959 2181 958 2182 956 2182 955 2182 957 2183 956 2183 960 2183 961 2184 937 2184 959 2184 962 2185 959 2185 937 2185 958 2186 963 2186 959 2186 961 2187 959 2187 963 2187 960 2188 959 2188 962 2188 964 2189 936 2189 937 2189 965 2190 964 2190 937 2190 966 2191 965 2191 937 2191 961 2192 966 2192 937 2192 962 2193 937 2193 938 2193 967 2194 949 2194 943 2194 968 2195 952 2195 949 2195 968 2196 949 2196 967 2196 969 2197 943 2197 946 2197 969 2198 967 2198 943 2198 947 2199 970 2199 946 2199 971 2200 946 2200 970 2200 969 2201 946 2201 971 2201 972 2202 973 2202 970 2202 974 2203 970 2203 973 2203 975 2204 976 2204 970 2204 972 2205 970 2205 976 2205 947 2206 975 2206 970 2206 971 2207 970 2207 974 2207 977 2208 978 2208 973 2208 979 2209 973 2209 978 2209 980 2210 977 2210 973 2210 981 2211 980 2211 973 2211 972 2212 981 2212 973 2212 974 2213 973 2213 979 2213 982 2214 983 2214 978 2214 984 2215 978 2215 983 2215 985 2216 982 2216 978 2216 977 2217 985 2217 978 2217 979 2218 978 2218 984 2218 982 2219 986 2219 983 2219 987 2220 983 2220 986 2220 984 2221 983 2221 987 2221 982 2222 955 2222 986 2222 988 2223 986 2223 955 2223 987 2224 986 2224 988 2224 989 2225 955 2225 952 2225 990 2226 955 2226 982 2226 991 2227 958 2227 955 2227 990 2228 991 2228 955 2228 988 2229 955 2229 989 2229 989 2230 952 2230 968 2230 992 2231 915 2231 908 2231 993 2232 918 2232 915 2232 993 2233 915 2233 992 2233 994 2234 908 2234 911 2234 994 2235 992 2235 908 2235 912 2236 995 2236 911 2236 996 2237 911 2237 995 2237 994 2238 911 2238 996 2238 997 2239 998 2239 995 2239 999 2240 995 2240 998 2240 1000 2241 1001 2241 995 2241 997 2242 995 2242 1001 2242 912 2243 1000 2243 995 2243 996 2244 995 2244 999 2244 1002 2245 1003 2245 998 2245 1004 2246 998 2246 1003 2246 1005 2247 1002 2247 998 2247 1006 2248 1005 2248 998 2248 997 2249 1006 2249 998 2249 999 2250 998 2250 1004 2250 982 2251 1007 2251 1003 2251 1008 2252 1003 2252 1007 2252 1002 2253 982 2253 1003 2253 1004 2254 1003 2254 1008 2254 982 2255 1009 2255 1007 2255 1010 2256 1007 2256 1009 2256 1008 2257 1007 2257 1010 2257 982 2258 921 2258 1009 2258 1011 2259 1009 2259 921 2259 1010 2260 1009 2260 1011 2260 1012 2261 921 2261 918 2261 1013 2262 921 2262 982 2262 1013 2263 924 2263 921 2263 1011 2264 921 2264 1012 2264 1012 2265 918 2265 993 2265 1014 2266 1015 2266 1016 2266 1017 2267 1016 2267 1015 2267 1014 2268 1016 2268 1018 2268 1019 2269 1018 2269 1016 2269 1019 2270 1016 2270 1017 2270 1020 2271 1021 2271 1015 2271 1022 2272 1015 2272 1021 2272 1014 2273 1020 2273 1015 2273 1022 2274 1017 2274 1015 2274 1020 2275 1023 2275 1021 2275 1024 2276 1021 2276 1023 2276 1022 2277 1021 2277 1024 2277 1020 2278 1025 2278 1023 2278 1026 2279 1023 2279 1025 2279 1024 2280 1023 2280 1026 2280 1020 2281 1027 2281 1025 2281 1028 2282 1025 2282 1027 2282 1026 2283 1025 2283 1028 2283 1029 2284 1030 2284 1027 2284 1031 2285 1027 2285 1030 2285 1020 2286 1029 2286 1027 2286 1028 2287 1027 2287 1031 2287 1029 2288 1032 2288 1030 2288 1033 2289 1030 2289 1032 2289 1031 2290 1030 2290 1033 2290 1029 2291 1034 2291 1032 2291 1035 2292 1032 2292 1034 2292 1033 2293 1032 2293 1035 2293 1036 2294 1037 2294 1034 2294 1038 2295 1034 2295 1037 2295 1039 2296 1040 2296 1034 2296 1036 2297 1034 2297 1040 2297 1029 2298 1039 2298 1034 2298 1035 2299 1034 2299 1038 2299 1036 2300 1041 2300 1037 2300 1042 2301 1037 2301 1041 2301 1038 2302 1037 2302 1042 2302 1036 2303 1043 2303 1041 2303 1044 2304 1041 2304 1043 2304 1042 2305 1041 2305 1044 2305 1036 2306 1045 2306 1043 2306 1046 2307 1043 2307 1045 2307 1044 2308 1043 2308 1046 2308 1047 2309 1048 2309 1045 2309 1049 2310 1045 2310 1048 2310 1036 2311 1047 2311 1045 2311 1046 2312 1045 2312 1049 2312 1047 2313 1050 2313 1048 2313 1051 2314 1048 2314 1050 2314 1049 2315 1048 2315 1051 2315 1047 2316 1052 2316 1050 2316 1053 2317 1050 2317 1052 2317 1051 2318 1050 2318 1053 2318 1047 2319 1054 2319 1052 2319 1055 2320 1052 2320 1054 2320 1053 2321 1052 2321 1055 2321 1056 2322 1057 2322 1054 2322 1058 2323 1054 2323 1057 2323 1047 2324 1056 2324 1054 2324 1055 2325 1054 2325 1058 2325 1056 2326 1059 2326 1057 2326 1060 2327 1057 2327 1059 2327 1058 2328 1057 2328 1060 2328 1056 2329 1061 2329 1059 2329 1062 2330 1059 2330 1061 2330 1060 2331 1059 2331 1062 2331 1056 2332 1063 2332 1061 2332 1064 2333 1061 2333 1063 2333 1062 2334 1061 2334 1064 2334 1065 2335 1066 2335 1063 2335 1067 2336 1063 2336 1066 2336 1056 2337 1065 2337 1063 2337 1064 2338 1063 2338 1067 2338 1068 2339 1069 2339 1066 2339 1070 2340 1066 2340 1069 2340 1065 2341 1068 2341 1066 2341 1067 2342 1066 2342 1070 2342 1068 2343 1071 2343 1069 2343 1072 2344 1069 2344 1071 2344 1070 2345 1069 2345 1072 2345 1068 2346 1073 2346 1071 2346 1074 2347 1071 2347 1073 2347 1072 2348 1071 2348 1074 2348 1075 2349 1076 2349 1073 2349 1077 2350 1073 2350 1076 2350 1078 2351 1075 2351 1073 2351 1068 2352 1078 2352 1073 2352 1074 2353 1073 2353 1077 2353 1079 2354 1080 2354 1076 2354 1081 2355 1076 2355 1080 2355 1079 2356 1076 2356 1075 2356 1077 2357 1076 2357 1081 2357 1079 2358 1082 2358 1080 2358 1083 2359 1080 2359 1082 2359 1081 2360 1080 2360 1083 2360 1079 2361 1084 2361 1082 2361 1085 2362 1082 2362 1084 2362 1083 2363 1082 2363 1085 2363 1079 2364 1086 2364 1084 2364 1087 2365 1084 2365 1086 2365 1085 2366 1084 2366 1087 2366 1014 2367 1088 2367 1086 2367 1089 2368 1086 2368 1088 2368 1079 2369 1014 2369 1086 2369 1087 2370 1086 2370 1089 2370 1014 2371 1018 2371 1088 2371 1090 2372 1088 2372 1018 2372 1089 2373 1088 2373 1090 2373 1090 2374 1018 2374 1019 2374 1091 2375 1092 2375 1093 2375 1094 2376 1093 2376 1092 2376 1091 2377 1093 2377 1095 2377 1096 2378 1095 2378 1093 2378 1096 2379 1093 2379 1094 2379 1079 2380 1097 2380 1092 2380 1098 2381 1092 2381 1097 2381 1091 2382 1079 2382 1092 2382 1098 2383 1094 2383 1092 2383 1079 2384 1075 2384 1097 2384 1099 2385 1097 2385 1075 2385 1098 2386 1097 2386 1099 2386 1100 2387 1101 2387 1075 2387 1102 2388 1075 2388 1101 2388 1078 2389 1100 2389 1075 2389 1099 2390 1075 2390 1102 2390 1103 2391 1104 2391 1101 2391 1105 2392 1101 2392 1104 2392 1100 2393 1103 2393 1101 2393 1102 2394 1101 2394 1105 2394 1106 2395 1107 2395 1104 2395 1108 2396 1104 2396 1107 2396 1106 2397 1104 2397 1103 2397 1105 2398 1104 2398 1108 2398 1109 2399 1110 2399 1107 2399 1111 2400 1107 2400 1110 2400 1106 2401 1109 2401 1107 2401 1108 2402 1107 2402 1111 2402 1112 2403 1113 2403 1110 2403 1114 2404 1110 2404 1113 2404 1112 2405 1110 2405 1109 2405 1111 2406 1110 2406 1114 2406 1091 2407 1095 2407 1113 2407 1115 2408 1113 2408 1095 2408 1116 2409 1113 2409 1112 2409 1116 2410 1091 2410 1113 2410 1114 2411 1113 2411 1115 2411 1115 2412 1095 2412 1096 2412 1117 2413 1103 2413 1100 2413 1118 2414 1106 2414 1103 2414 1118 2415 1103 2415 1117 2415 1119 2416 1100 2416 1078 2416 1119 2417 1117 2417 1100 2417 1120 2418 1078 2418 1068 2418 1119 2419 1078 2419 1120 2419 1065 2420 1121 2420 1068 2420 1122 2421 1068 2421 1121 2421 1120 2422 1068 2422 1122 2422 1065 2423 1123 2423 1121 2423 1124 2424 1121 2424 1123 2424 1122 2425 1121 2425 1124 2425 1112 2426 1125 2426 1123 2426 1126 2427 1123 2427 1125 2427 1065 2428 1112 2428 1123 2428 1124 2429 1123 2429 1126 2429 1112 2430 1127 2430 1125 2430 1128 2431 1125 2431 1127 2431 1126 2432 1125 2432 1128 2432 1112 2433 1109 2433 1127 2433 1129 2434 1127 2434 1109 2434 1128 2435 1127 2435 1129 2435 1130 2436 1109 2436 1106 2436 1129 2437 1109 2437 1130 2437 1130 2438 1106 2438 1118 2438 1131 2439 1132 2439 1133 2439 1134 2440 1133 2440 1132 2440 1135 2441 1133 2441 1136 2441 1137 2442 1136 2442 1133 2442 1135 2443 1131 2443 1133 2443 1137 2444 1133 2444 1134 2444 1138 2445 1139 2445 1132 2445 1140 2446 1132 2446 1139 2446 1131 2447 1138 2447 1132 2447 1140 2448 1134 2448 1132 2448 1141 2449 1142 2449 1139 2449 1143 2450 1139 2450 1142 2450 1141 2451 1139 2451 1138 2451 1140 2452 1139 2452 1143 2452 1144 2453 1145 2453 1142 2453 1146 2454 1142 2454 1145 2454 1141 2455 1144 2455 1142 2455 1143 2456 1142 2456 1146 2456 1144 2457 1147 2457 1145 2457 1148 2458 1145 2458 1147 2458 1146 2459 1145 2459 1148 2459 1036 2460 1149 2460 1147 2460 1150 2461 1147 2461 1149 2461 1144 2462 1036 2462 1147 2462 1148 2463 1147 2463 1150 2463 1036 2464 1151 2464 1149 2464 1152 2465 1149 2465 1151 2465 1150 2466 1149 2466 1152 2466 1036 2467 1040 2467 1151 2467 1153 2468 1151 2468 1040 2468 1152 2469 1151 2469 1153 2469 1154 2470 1136 2470 1040 2470 1155 2471 1040 2471 1136 2471 1039 2472 1154 2472 1040 2472 1153 2473 1040 2473 1155 2473 1154 2474 1135 2474 1136 2474 1155 2475 1136 2475 1137 2475 1156 2476 1157 2476 1158 2476 1159 2477 1158 2477 1157 2477 1156 2478 1158 2478 1160 2478 1161 2479 1160 2479 1158 2479 1161 2480 1158 2480 1159 2480 1141 2481 1162 2481 1157 2481 1163 2482 1157 2482 1162 2482 1156 2483 1141 2483 1157 2483 1163 2484 1159 2484 1157 2484 1141 2485 1138 2485 1162 2485 1164 2486 1162 2486 1138 2486 1163 2487 1162 2487 1164 2487 1165 2488 1138 2488 1131 2488 1164 2489 1138 2489 1165 2489 1166 2490 1131 2490 1135 2490 1165 2491 1131 2491 1166 2491 1167 2492 1135 2492 1154 2492 1166 2493 1135 2493 1167 2493 1168 2494 1154 2494 1039 2494 1167 2495 1154 2495 1168 2495 1169 2496 1039 2496 1029 2496 1168 2497 1039 2497 1169 2497 1156 2498 1160 2498 1029 2498 1170 2499 1029 2499 1160 2499 1020 2500 1156 2500 1029 2500 1169 2501 1029 2501 1170 2501 1170 2502 1160 2502 1161 2502 1171 2503 1172 2503 1173 2503 1174 2504 1173 2504 1172 2504 1171 2505 1173 2505 1175 2505 1176 2506 1175 2506 1173 2506 1176 2507 1173 2507 1174 2507 1116 2508 1177 2508 1172 2508 1178 2509 1172 2509 1177 2509 1171 2510 1116 2510 1172 2510 1178 2511 1174 2511 1172 2511 1116 2512 1179 2512 1177 2512 1180 2513 1177 2513 1179 2513 1178 2514 1177 2514 1180 2514 1116 2515 1181 2515 1179 2515 1182 2516 1179 2516 1181 2516 1180 2517 1179 2517 1182 2517 1112 2518 1183 2518 1181 2518 1184 2519 1181 2519 1183 2519 1116 2520 1112 2520 1181 2520 1182 2521 1181 2521 1184 2521 1185 2522 1186 2522 1183 2522 1187 2523 1183 2523 1186 2523 1112 2524 1185 2524 1183 2524 1184 2525 1183 2525 1187 2525 1185 2526 1188 2526 1186 2526 1189 2527 1186 2527 1188 2527 1187 2528 1186 2528 1189 2528 1185 2529 1190 2529 1188 2529 1191 2530 1188 2530 1190 2530 1189 2531 1188 2531 1191 2531 1192 2532 1193 2532 1190 2532 1194 2533 1190 2533 1193 2533 1185 2534 1192 2534 1190 2534 1191 2535 1190 2535 1194 2535 1192 2536 1195 2536 1193 2536 1196 2537 1193 2537 1195 2537 1194 2538 1193 2538 1196 2538 1192 2539 1197 2539 1195 2539 1198 2540 1195 2540 1197 2540 1196 2541 1195 2541 1198 2541 1192 2542 1199 2542 1197 2542 1200 2543 1197 2543 1199 2543 1198 2544 1197 2544 1200 2544 1201 2545 1202 2545 1199 2545 1203 2546 1199 2546 1202 2546 1192 2547 1204 2547 1199 2547 1201 2548 1199 2548 1204 2548 1200 2549 1199 2549 1203 2549 1171 2550 1205 2550 1202 2550 1206 2551 1202 2551 1205 2551 1201 2552 1171 2552 1202 2552 1203 2553 1202 2553 1206 2553 1171 2554 1175 2554 1205 2554 1207 2555 1205 2555 1175 2555 1206 2556 1205 2556 1207 2556 1207 2557 1175 2557 1176 2557 1208 2558 1209 2558 1210 2558 1211 2559 1210 2559 1209 2559 1208 2560 1210 2560 1212 2560 1213 2561 1212 2561 1210 2561 1213 2562 1210 2562 1211 2562 1214 2563 1215 2563 1209 2563 1216 2564 1209 2564 1215 2564 1208 2565 1214 2565 1209 2565 1216 2566 1211 2566 1209 2566 1214 2567 1217 2567 1215 2567 1218 2568 1215 2568 1217 2568 1216 2569 1215 2569 1218 2569 1219 2570 1220 2570 1217 2570 1221 2571 1217 2571 1220 2571 1219 2572 1217 2572 1214 2572 1218 2573 1217 2573 1221 2573 1222 2574 1223 2574 1220 2574 1224 2575 1220 2575 1223 2575 1219 2576 1222 2576 1220 2576 1221 2577 1220 2577 1224 2577 1222 2578 1225 2578 1223 2578 1226 2579 1223 2579 1225 2579 1224 2580 1223 2580 1226 2580 1222 2581 1227 2581 1225 2581 1228 2582 1225 2582 1227 2582 1226 2583 1225 2583 1228 2583 1222 2584 1229 2584 1227 2584 1230 2585 1227 2585 1229 2585 1228 2586 1227 2586 1230 2586 1231 2587 1212 2587 1229 2587 1232 2588 1229 2588 1212 2588 1233 2589 1231 2589 1229 2589 1222 2590 1233 2590 1229 2590 1230 2591 1229 2591 1232 2591 1231 2592 1208 2592 1212 2592 1232 2593 1212 2593 1213 2593 1234 2594 1235 2594 1236 2594 1237 2595 1236 2595 1235 2595 1234 2596 1236 2596 1238 2596 1239 2597 1238 2597 1236 2597 1239 2598 1236 2598 1237 2598 1234 2599 1240 2599 1235 2599 1241 2600 1235 2600 1240 2600 1241 2601 1237 2601 1235 2601 1234 2602 1242 2602 1240 2602 1243 2603 1240 2603 1242 2603 1241 2604 1240 2604 1243 2604 1244 2605 1245 2605 1242 2605 1246 2606 1242 2606 1245 2606 1234 2607 1244 2607 1242 2607 1243 2608 1242 2608 1246 2608 1244 2609 1247 2609 1245 2609 1248 2610 1245 2610 1247 2610 1246 2611 1245 2611 1248 2611 1249 2612 1250 2612 1247 2612 1251 2613 1247 2613 1250 2613 1244 2614 1249 2614 1247 2614 1248 2615 1247 2615 1251 2615 1249 2616 1252 2616 1250 2616 1253 2617 1250 2617 1252 2617 1251 2618 1250 2618 1253 2618 1254 2619 1255 2619 1252 2619 1256 2620 1252 2620 1255 2620 1249 2621 1254 2621 1252 2621 1253 2622 1252 2622 1256 2622 1257 2623 1238 2623 1255 2623 1258 2624 1255 2624 1238 2624 1259 2625 1257 2625 1255 2625 1260 2626 1259 2626 1255 2626 1254 2627 1260 2627 1255 2627 1256 2628 1255 2628 1258 2628 1257 2629 1261 2629 1238 2629 1234 2630 1238 2630 1261 2630 1258 2631 1238 2631 1239 2631 1214 2632 1262 2632 1263 2632 1264 2633 1263 2633 1262 2633 1214 2634 1263 2634 1265 2634 1266 2635 1265 2635 1263 2635 1266 2636 1263 2636 1264 2636 1267 2637 1268 2637 1262 2637 1269 2638 1262 2638 1268 2638 1214 2639 1267 2639 1262 2639 1269 2640 1264 2640 1262 2640 1267 2641 1270 2641 1268 2641 1271 2642 1268 2642 1270 2642 1269 2643 1268 2643 1271 2643 1272 2644 1273 2644 1270 2644 1274 2645 1270 2645 1273 2645 1272 2646 1270 2646 1267 2646 1271 2647 1270 2647 1274 2647 1272 2648 1275 2648 1273 2648 1276 2649 1273 2649 1275 2649 1274 2650 1273 2650 1276 2650 1277 2651 1278 2651 1275 2651 1279 2652 1275 2652 1278 2652 1277 2653 1275 2653 1280 2653 1272 2654 1280 2654 1275 2654 1276 2655 1275 2655 1279 2655 1281 2656 1282 2656 1278 2656 1283 2657 1278 2657 1282 2657 1277 2658 1281 2658 1278 2658 1279 2659 1278 2659 1283 2659 1234 2660 1284 2660 1282 2660 1285 2661 1282 2661 1284 2661 1234 2662 1282 2662 1281 2662 1283 2663 1282 2663 1285 2663 1214 2664 1265 2664 1284 2664 1286 2665 1284 2665 1265 2665 1219 2666 1214 2666 1284 2666 1234 2667 1219 2667 1284 2667 1285 2668 1284 2668 1286 2668 1286 2669 1265 2669 1266 2669 1287 2670 1288 2670 1280 2670 1289 2671 1280 2671 1288 2671 1290 2672 1277 2672 1280 2672 1272 2673 1287 2673 1280 2673 1290 2674 1280 2674 1289 2674 1291 2675 1292 2675 1288 2675 1293 2676 1288 2676 1292 2676 1287 2677 1291 2677 1288 2677 1293 2678 1289 2678 1288 2678 1291 2679 1294 2679 1292 2679 1295 2680 1292 2680 1294 2680 1293 2681 1292 2681 1295 2681 1296 2682 1297 2682 1294 2682 1298 2683 1294 2683 1297 2683 1299 2684 1296 2684 1294 2684 1291 2685 1299 2685 1294 2685 1295 2686 1294 2686 1298 2686 1296 2687 1300 2687 1297 2687 1301 2688 1297 2688 1300 2688 1298 2689 1297 2689 1301 2689 1244 2690 1302 2690 1300 2690 1303 2691 1300 2691 1302 2691 1296 2692 1244 2692 1300 2692 1301 2693 1300 2693 1303 2693 1244 2694 1304 2694 1302 2694 1305 2695 1302 2695 1304 2695 1303 2696 1302 2696 1305 2696 1244 2697 1281 2697 1304 2697 1306 2698 1304 2698 1281 2698 1305 2699 1304 2699 1306 2699 1307 2700 1281 2700 1277 2700 1234 2701 1281 2701 1244 2701 1306 2702 1281 2702 1307 2702 1307 2703 1277 2703 1290 2703 903 2704 1308 2704 1309 2704 1310 2705 1309 2705 1308 2705 903 2706 1309 2706 1311 2706 1312 2707 1311 2707 1309 2707 1312 2708 1309 2708 1310 2708 903 2709 1313 2709 1308 2709 1314 2710 1308 2710 1313 2710 1314 2711 1310 2711 1308 2711 903 2712 1315 2712 1313 2712 1316 2713 1313 2713 1315 2713 1314 2714 1313 2714 1316 2714 903 2715 1317 2715 1315 2715 1318 2716 1315 2716 1317 2716 1316 2717 1315 2717 1318 2717 903 2718 1319 2718 1317 2718 1320 2719 1317 2719 1319 2719 1318 2720 1317 2720 1320 2720 982 2721 1321 2721 1319 2721 1322 2722 1319 2722 1321 2722 903 2723 982 2723 1319 2723 1320 2724 1319 2724 1322 2724 1323 2725 1324 2725 1321 2725 1325 2726 1321 2726 1324 2726 982 2727 1323 2727 1321 2727 1322 2728 1321 2728 1325 2728 1323 2729 1326 2729 1324 2729 1327 2730 1324 2730 1326 2730 1325 2731 1324 2731 1327 2731 1323 2732 1328 2732 1326 2732 1329 2733 1326 2733 1328 2733 1327 2734 1326 2734 1329 2734 1323 2735 1330 2735 1328 2735 1331 2736 1328 2736 1330 2736 1329 2737 1328 2737 1331 2737 1323 2738 1332 2738 1330 2738 1333 2739 1330 2739 1332 2739 1331 2740 1330 2740 1333 2740 1323 2741 1334 2741 1332 2741 1335 2742 1332 2742 1334 2742 1333 2743 1332 2743 1335 2743 1336 2744 1337 2744 1334 2744 1338 2745 1334 2745 1337 2745 1323 2746 1336 2746 1334 2746 1335 2747 1334 2747 1338 2747 1336 2748 1339 2748 1337 2748 1340 2749 1337 2749 1339 2749 1338 2750 1337 2750 1340 2750 1336 2751 1341 2751 1339 2751 1342 2752 1339 2752 1341 2752 1340 2753 1339 2753 1342 2753 1343 2754 1344 2754 1341 2754 1345 2755 1341 2755 1344 2755 1343 2756 1341 2756 1336 2756 1342 2757 1341 2757 1345 2757 1343 2758 1346 2758 1344 2758 1347 2759 1344 2759 1346 2759 1345 2760 1344 2760 1347 2760 1343 2761 1348 2761 1346 2761 1349 2762 1346 2762 1348 2762 1347 2763 1346 2763 1349 2763 1343 2764 1311 2764 1348 2764 1350 2765 1348 2765 1311 2765 1349 2766 1348 2766 1350 2766 1343 2767 903 2767 1311 2767 1350 2768 1311 2768 1312 2768 1234 2769 1351 2769 1352 2769 1353 2770 1352 2770 1351 2770 1354 2771 1234 2771 1352 2771 1353 2772 1354 2772 1352 2772 1234 2773 1355 2773 1351 2773 1356 2774 1351 2774 1355 2774 1356 2775 1353 2775 1351 2775 1234 2776 1261 2776 1355 2776 1357 2777 1355 2777 1261 2777 1356 2778 1355 2778 1357 2778 1358 2779 1261 2779 1257 2779 1357 2780 1261 2780 1358 2780 1359 2781 1257 2781 1259 2781 1360 2782 1257 2782 1359 2782 1358 2783 1257 2783 1360 2783 1359 2784 1259 2784 1260 2784 1361 2785 1260 2785 1254 2785 1359 2786 1260 2786 1361 2786 1362 2787 1254 2787 1249 2787 1361 2788 1254 2788 1362 2788 1363 2789 1249 2789 1244 2789 1362 2790 1249 2790 1363 2790 1364 2791 1244 2791 1296 2791 1363 2792 1244 2792 1364 2792 1365 2793 1296 2793 1299 2793 1364 2794 1296 2794 1365 2794 1291 2795 1366 2795 1299 2795 1367 2796 1299 2796 1366 2796 1365 2797 1299 2797 1367 2797 1291 2798 1368 2798 1366 2798 1369 2799 1366 2799 1368 2799 1367 2800 1366 2800 1369 2800 1370 2801 1336 2801 1368 2801 1371 2802 1368 2802 1336 2802 1291 2803 1370 2803 1368 2803 1369 2804 1368 2804 1371 2804 1372 2805 1336 2805 1323 2805 1370 2806 1343 2806 1336 2806 1371 2807 1336 2807 1372 2807 1373 2808 1323 2808 982 2808 1372 2809 1323 2809 1373 2809 1374 2810 982 2810 985 2810 1375 2811 982 2811 903 2811 1376 2812 990 2812 982 2812 1377 2813 1376 2813 982 2813 1378 2814 1377 2814 982 2814 1002 2815 1378 2815 982 2815 1379 2816 1013 2816 982 2816 1380 2817 1379 2817 982 2817 1381 2818 1380 2818 982 2818 1382 2819 1381 2819 982 2819 1383 2820 1382 2820 982 2820 1375 2821 1383 2821 982 2821 1373 2822 982 2822 1374 2822 1384 2823 1204 2823 985 2823 1385 2824 985 2824 1204 2824 896 2825 1384 2825 985 2825 1386 2826 896 2826 985 2826 1387 2827 1386 2827 985 2827 1388 2828 1387 2828 985 2828 977 2829 1388 2829 985 2829 1374 2830 985 2830 1385 2830 1389 2831 1204 2831 1192 2831 1384 2832 1201 2832 1204 2832 1385 2833 1204 2833 1389 2833 1390 2834 1192 2834 1185 2834 1389 2835 1192 2835 1390 2835 1391 2836 1185 2836 1112 2836 1390 2837 1185 2837 1391 2837 1392 2838 1112 2838 1065 2838 1391 2839 1112 2839 1392 2839 1393 2840 1065 2840 1056 2840 1392 2841 1065 2841 1393 2841 1394 2842 1056 2842 1047 2842 1393 2843 1056 2843 1394 2843 1395 2844 1047 2844 1036 2844 1394 2845 1047 2845 1395 2845 1396 2846 1036 2846 1144 2846 1395 2847 1036 2847 1396 2847 1141 2848 1397 2848 1144 2848 1398 2849 1144 2849 1397 2849 1396 2850 1144 2850 1398 2850 1399 2851 1400 2851 1397 2851 1401 2852 1397 2852 1400 2852 1141 2853 1399 2853 1397 2853 1398 2854 1397 2854 1401 2854 1402 2855 1403 2855 1400 2855 1404 2856 1400 2856 1403 2856 1399 2857 1402 2857 1400 2857 1401 2858 1400 2858 1404 2858 1405 2859 1406 2859 1403 2859 1407 2860 1403 2860 1406 2860 1402 2861 1405 2861 1403 2861 1404 2862 1403 2862 1407 2862 1408 2863 1409 2863 1406 2863 1410 2864 1406 2864 1409 2864 1405 2865 1408 2865 1406 2865 1407 2866 1406 2866 1410 2866 1411 2867 1409 2867 1408 2867 1410 2868 1409 2868 1411 2868 1412 2869 1408 2869 1405 2869 1411 2870 1408 2870 1412 2870 1413 2871 1405 2871 1402 2871 1412 2872 1405 2872 1413 2872 1414 2873 1402 2873 1399 2873 1413 2874 1402 2874 1414 2874 1415 2875 1399 2875 1141 2875 1414 2876 1399 2876 1415 2876 1416 2877 1141 2877 1156 2877 1415 2878 1141 2878 1416 2878 1417 2879 1156 2879 1020 2879 1416 2880 1156 2880 1417 2880 1418 2881 1020 2881 1014 2881 1417 2882 1020 2882 1418 2882 1419 2883 1014 2883 1079 2883 1418 2884 1014 2884 1419 2884 1420 2885 1079 2885 1091 2885 1419 2886 1079 2886 1420 2886 1421 2887 1091 2887 1116 2887 1420 2888 1091 2888 1421 2888 1422 2889 1116 2889 1171 2889 1421 2890 1116 2890 1422 2890 1423 2891 1171 2891 1201 2891 1422 2892 1171 2892 1423 2892 1424 2893 1201 2893 1384 2893 1423 2894 1201 2894 1424 2894 1425 2895 1384 2895 896 2895 1424 2896 1384 2896 1425 2896 1426 2897 896 2897 903 2897 1427 2898 948 2898 896 2898 1428 2899 1427 2899 896 2899 1429 2900 1428 2900 896 2900 1430 2901 1429 2901 896 2901 1431 2902 1430 2902 896 2902 1386 2903 1431 2903 896 2903 1432 2904 896 2904 936 2904 1433 2905 913 2905 896 2905 1434 2906 1433 2906 896 2906 1432 2907 1434 2907 896 2907 1425 2908 896 2908 1426 2908 1435 2909 903 2909 1343 2909 1436 2910 1375 2910 903 2910 1437 2911 1436 2911 903 2911 900 2912 1437 2912 903 2912 1426 2913 903 2913 1435 2913 1438 2914 1343 2914 1370 2914 1435 2915 1343 2915 1438 2915 1439 2916 1440 2916 1370 2916 1441 2917 1370 2917 1440 2917 1439 2918 1370 2918 1291 2918 1438 2919 1370 2919 1441 2919 1272 2920 1442 2920 1440 2920 1443 2921 1440 2921 1442 2921 1439 2922 1272 2922 1440 2922 1441 2923 1440 2923 1443 2923 1272 2924 1267 2924 1442 2924 1444 2925 1442 2925 1267 2925 1443 2926 1442 2926 1444 2926 1445 2927 1267 2927 1214 2927 1444 2928 1267 2928 1445 2928 1446 2929 1214 2929 1208 2929 1445 2930 1214 2930 1446 2930 1447 2931 1208 2931 1231 2931 1446 2932 1208 2932 1447 2932 1448 2933 1231 2933 1233 2933 1447 2934 1231 2934 1448 2934 1222 2935 1449 2935 1233 2935 1450 2936 1233 2936 1449 2936 1448 2937 1233 2937 1450 2937 1222 2938 1451 2938 1449 2938 1452 2939 1449 2939 1451 2939 1450 2940 1449 2940 1452 2940 1222 2941 1453 2941 1451 2941 1454 2942 1451 2942 1453 2942 1455 2943 1451 2943 1454 2943 1452 2944 1451 2944 1455 2944 1222 2945 1456 2945 1453 2945 1454 2946 1453 2946 1456 2946 1222 2947 1457 2947 1456 2947 1458 2948 1456 2948 1457 2948 1454 2949 1456 2949 1458 2949 1222 2950 1459 2950 1457 2950 1460 2951 1457 2951 1459 2951 1458 2952 1457 2952 1460 2952 1222 2953 1461 2953 1459 2953 1462 2954 1459 2954 1461 2954 1460 2955 1459 2955 1462 2955 1463 2956 1461 2956 1222 2956 1464 2957 1461 2957 1463 2957 1462 2958 1461 2958 1464 2958 1463 2959 1222 2959 1219 2959 1465 2960 1219 2960 1234 2960 1463 2961 1219 2961 1465 2961 1466 2962 1234 2962 1354 2962 1465 2963 1234 2963 1466 2963 1467 2964 1354 2964 1353 2964 1466 2965 1354 2965 1467 2965 1468 2966 976 2966 975 2966 1469 2967 972 2967 976 2967 1469 2968 976 2968 1470 2968 1468 2969 1470 2969 976 2969 1468 2970 975 2970 947 2970 1471 2971 947 2971 948 2971 1468 2972 947 2972 1471 2972 1472 2973 948 2973 1427 2973 1471 2974 948 2974 1472 2974 1473 2975 1427 2975 1428 2975 1472 2976 1427 2976 1473 2976 1474 2977 1428 2977 1429 2977 1473 2978 1428 2978 1474 2978 1475 2979 1429 2979 1430 2979 1474 2980 1429 2980 1475 2980 1476 2981 1430 2981 1431 2981 1475 2982 1430 2982 1476 2982 1477 2983 1431 2983 1386 2983 1478 2984 1431 2984 1477 2984 1476 2985 1431 2985 1478 2985 1477 2986 1386 2986 1387 2986 1479 2987 1387 2987 1388 2987 1477 2988 1387 2988 1479 2988 1480 2989 1388 2989 977 2989 1479 2990 1388 2990 1480 2990 1481 2991 977 2991 980 2991 1480 2992 977 2992 1481 2992 1482 2993 980 2993 981 2993 1481 2994 980 2994 1482 2994 1483 2995 981 2995 972 2995 1482 2996 981 2996 1483 2996 1483 2997 972 2997 1469 2997 1484 2998 963 2998 958 2998 1484 2999 961 2999 963 2999 1485 3000 958 3000 991 3000 1485 3001 1484 3001 958 3001 1486 3002 991 3002 990 3002 1485 3003 991 3003 1486 3003 1487 3004 990 3004 1376 3004 1486 3005 990 3005 1487 3005 1488 3006 1376 3006 1377 3006 1487 3007 1376 3007 1488 3007 1489 3008 1377 3008 1378 3008 1488 3009 1377 3009 1489 3009 1002 3010 1490 3010 1378 3010 1491 3011 1378 3011 1490 3011 1489 3012 1378 3012 1491 3012 1492 3013 1493 3013 1490 3013 1494 3014 1490 3014 1493 3014 1002 3015 1492 3015 1490 3015 1495 3016 1490 3016 1494 3016 1491 3017 1490 3017 1495 3017 1496 3018 1497 3018 1493 3018 1494 3019 1493 3019 1497 3019 1498 3020 1496 3020 1493 3020 1492 3021 1498 3021 1493 3021 1496 3022 1499 3022 1497 3022 1500 3023 1497 3023 1499 3023 1494 3024 1497 3024 1500 3024 1501 3025 936 3025 1499 3025 1502 3026 1499 3026 936 3026 1496 3027 1501 3027 1499 3027 1500 3028 1499 3028 1502 3028 1503 3029 936 3029 964 3029 1501 3030 1432 3030 936 3030 1502 3031 936 3031 1503 3031 1504 3032 964 3032 965 3032 1503 3033 964 3033 1504 3033 1505 3034 965 3034 966 3034 1504 3035 965 3035 1505 3035 1506 3036 966 3036 961 3036 1505 3037 966 3037 1506 3037 1507 3038 961 3038 1484 3038 1506 3039 961 3039 1507 3039 1508 3040 1001 3040 1000 3040 1509 3041 997 3041 1001 3041 1509 3042 1001 3042 1510 3042 1508 3043 1510 3043 1001 3043 1508 3044 1000 3044 912 3044 1511 3045 912 3045 914 3045 1508 3046 912 3046 1511 3046 1512 3047 914 3047 913 3047 1511 3048 914 3048 1512 3048 1513 3049 913 3049 1433 3049 1512 3050 913 3050 1513 3050 1514 3051 1433 3051 1434 3051 1513 3052 1433 3052 1514 3052 1515 3053 1434 3053 1432 3053 1514 3054 1434 3054 1515 3054 1516 3055 1432 3055 1501 3055 1515 3056 1432 3056 1516 3056 1517 3057 1501 3057 1496 3057 1518 3058 1501 3058 1517 3058 1516 3059 1501 3059 1518 3059 1517 3060 1496 3060 1498 3060 1519 3061 1498 3061 1492 3061 1517 3062 1498 3062 1519 3062 1520 3063 1492 3063 1002 3063 1519 3064 1492 3064 1520 3064 1521 3065 1002 3065 1005 3065 1520 3066 1002 3066 1521 3066 1522 3067 1005 3067 1006 3067 1521 3068 1005 3068 1522 3068 1523 3069 1006 3069 997 3069 1522 3070 1006 3070 1523 3070 1523 3071 997 3071 1509 3071 1524 3072 929 3072 924 3072 1524 3073 927 3073 929 3073 1525 3074 924 3074 1013 3074 1525 3075 1524 3075 924 3075 1526 3076 1013 3076 1379 3076 1525 3077 1013 3077 1526 3077 1527 3078 1379 3078 1380 3078 1528 3079 1379 3079 1527 3079 1526 3080 1379 3080 1528 3080 1527 3081 1380 3081 1381 3081 1529 3082 1381 3082 1382 3082 1527 3083 1381 3083 1529 3083 1530 3084 1382 3084 1383 3084 1529 3085 1382 3085 1530 3085 1531 3086 1383 3086 1375 3086 1532 3087 1383 3087 1531 3087 1530 3088 1383 3088 1532 3088 1531 3089 1375 3089 1436 3089 1533 3090 1436 3090 1437 3090 1531 3091 1436 3091 1533 3091 1534 3092 1437 3092 900 3092 1533 3093 1437 3093 1534 3093 1535 3094 900 3094 930 3094 1536 3095 900 3095 1535 3095 1534 3096 900 3096 1536 3096 1535 3097 930 3097 931 3097 1537 3098 931 3098 932 3098 1535 3099 931 3099 1537 3099 1538 3100 932 3100 927 3100 1537 3101 932 3101 1538 3101 1539 3102 927 3102 1524 3102 1538 3103 927 3103 1539 3103 1540 3104 1291 3104 1287 3104 1541 3105 1439 3105 1291 3105 1541 3106 1291 3106 1540 3106 1542 3107 1287 3107 1272 3107 1542 3108 1540 3108 1287 3108 1543 3109 1272 3109 1439 3109 1542 3110 1272 3110 1543 3110 1543 3111 1439 3111 1541 3111 1435 3112 902 3112 899 3112 1514 3113 899 3113 905 3113 1514 3114 1435 3114 899 3114 1435 3115 928 3115 902 3115 1435 3116 926 3116 928 3116 993 3117 923 3117 926 3117 1012 3118 993 3118 926 3118 1538 3119 1012 3119 926 3119 1537 3120 926 3120 1435 3120 1537 3121 1538 3121 926 3121 992 3122 920 3122 923 3122 993 3123 992 3123 923 3123 994 3124 917 3124 920 3124 994 3125 920 3125 992 3125 996 3126 910 3126 917 3126 994 3127 996 3127 917 3127 1509 3128 907 3128 910 3128 1509 3129 910 3129 996 3129 1511 3130 905 3130 907 3130 1509 3131 1510 3131 907 3131 1508 3132 907 3132 1510 3132 1508 3133 1511 3133 907 3133 1513 3134 1514 3134 905 3134 1512 3135 1513 3135 905 3135 1511 3136 1512 3136 905 3136 1435 3137 938 3137 935 3137 1474 3138 935 3138 940 3138 1426 3139 1435 3139 935 3139 1474 3140 1426 3140 935 3140 1435 3141 962 3141 938 3141 1435 3142 960 3142 962 3142 968 3143 957 3143 960 3143 989 3144 968 3144 960 3144 1506 3145 989 3145 960 3145 1504 3146 960 3146 1435 3146 1505 3147 1506 3147 960 3147 1504 3148 1505 3148 960 3148 967 3149 954 3149 957 3149 968 3150 967 3150 957 3150 969 3151 951 3151 954 3151 969 3152 954 3152 967 3152 971 3153 945 3153 951 3153 969 3154 971 3154 951 3154 1469 3155 942 3155 945 3155 1469 3156 945 3156 971 3156 1471 3157 940 3157 942 3157 1469 3158 1470 3158 942 3158 1468 3159 942 3159 1470 3159 1468 3160 1471 3160 942 3160 1473 3161 1474 3161 940 3161 1472 3162 1473 3162 940 3162 1471 3163 1472 3163 940 3163 1506 3164 988 3164 989 3164 1484 3165 987 3165 988 3165 1507 3166 1484 3166 988 3166 1506 3167 1507 3167 988 3167 1488 3168 984 3168 987 3168 1485 3169 987 3169 1484 3169 1487 3170 1488 3170 987 3170 1486 3171 1487 3171 987 3171 1485 3172 1486 3172 987 3172 1385 3173 979 3173 984 3173 1488 3174 1385 3174 984 3174 1385 3175 974 3175 979 3175 1385 3176 971 3176 974 3176 1483 3177 971 3177 1385 3177 1483 3178 1469 3178 971 3178 1538 3179 1011 3179 1012 3179 1524 3180 1010 3180 1011 3180 1539 3181 1524 3181 1011 3181 1538 3182 1539 3182 1011 3182 1527 3183 1008 3183 1010 3183 1525 3184 1010 3184 1524 3184 1528 3185 1527 3185 1010 3185 1526 3186 1528 3186 1010 3186 1525 3187 1526 3187 1010 3187 1385 3188 1004 3188 1008 3188 1374 3189 1385 3189 1008 3189 1527 3190 1374 3190 1008 3190 1385 3191 999 3191 1004 3191 1385 3192 996 3192 999 3192 1522 3193 996 3193 1385 3193 1523 3194 1509 3194 996 3194 1522 3195 1523 3195 996 3195 1420 3196 1019 3196 1017 3196 1419 3197 1017 3197 1022 3197 1419 3198 1420 3198 1017 3198 1420 3199 1090 3199 1019 3199 1420 3200 1089 3200 1090 3200 1420 3201 1087 3201 1089 3201 1421 3202 1085 3202 1087 3202 1420 3203 1421 3203 1087 3203 1099 3204 1083 3204 1085 3204 1421 3205 1099 3205 1085 3205 1099 3206 1081 3206 1083 3206 1099 3207 1077 3207 1081 3207 1120 3208 1074 3208 1077 3208 1099 3209 1102 3209 1077 3209 1120 3210 1077 3210 1102 3210 1394 3211 1072 3211 1074 3211 1394 3212 1074 3212 1120 3212 1394 3213 1070 3213 1072 3213 1394 3214 1067 3214 1070 3214 1394 3215 1064 3215 1067 3215 1395 3216 1062 3216 1064 3216 1394 3217 1395 3217 1064 3217 1395 3218 1060 3218 1062 3218 1395 3219 1058 3219 1060 3219 1395 3220 1055 3220 1058 3220 1396 3221 1053 3221 1055 3221 1395 3222 1396 3222 1055 3222 1396 3223 1051 3223 1053 3223 1396 3224 1049 3224 1051 3224 1396 3225 1046 3225 1049 3225 1153 3226 1044 3226 1046 3226 1396 3227 1153 3227 1046 3227 1153 3228 1042 3228 1044 3228 1153 3229 1038 3229 1042 3229 1418 3230 1035 3230 1038 3230 1153 3231 1155 3231 1038 3231 1169 3232 1038 3232 1155 3232 1418 3233 1038 3233 1169 3233 1418 3234 1033 3234 1035 3234 1418 3235 1031 3235 1033 3235 1418 3236 1028 3236 1031 3236 1419 3237 1026 3237 1028 3237 1418 3238 1419 3238 1028 3238 1419 3239 1024 3239 1026 3239 1419 3240 1022 3240 1024 3240 1422 3241 1096 3241 1094 3241 1421 3242 1094 3242 1098 3242 1421 3243 1422 3243 1094 3243 1422 3244 1115 3244 1096 3244 1422 3245 1114 3245 1115 3245 1118 3246 1111 3246 1114 3246 1130 3247 1118 3247 1114 3247 1422 3248 1130 3248 1114 3248 1117 3249 1108 3249 1111 3249 1118 3250 1117 3250 1111 3250 1119 3251 1105 3251 1108 3251 1119 3252 1108 3252 1117 3252 1120 3253 1102 3253 1105 3253 1119 3254 1120 3254 1105 3254 1421 3255 1098 3255 1099 3255 1422 3256 1129 3256 1130 3256 1393 3257 1128 3257 1129 3257 1392 3258 1129 3258 1422 3258 1392 3259 1393 3259 1129 3259 1393 3260 1126 3260 1128 3260 1393 3261 1124 3261 1126 3261 1394 3262 1122 3262 1124 3262 1393 3263 1394 3263 1124 3263 1394 3264 1120 3264 1122 3264 1168 3265 1137 3265 1134 3265 1167 3266 1134 3266 1140 3266 1167 3267 1168 3267 1134 3267 1169 3268 1155 3268 1137 3268 1168 3269 1169 3269 1137 3269 1398 3270 1152 3270 1153 3270 1396 3271 1398 3271 1153 3271 1398 3272 1150 3272 1152 3272 1398 3273 1148 3273 1150 3273 1401 3274 1146 3274 1148 3274 1398 3275 1401 3275 1148 3275 1401 3276 1143 3276 1146 3276 1166 3277 1140 3277 1143 3277 1165 3278 1166 3278 1143 3278 1401 3279 1165 3279 1143 3279 1166 3280 1167 3280 1140 3280 1418 3281 1161 3281 1159 3281 1417 3282 1159 3282 1163 3282 1417 3283 1418 3283 1159 3283 1418 3284 1170 3284 1161 3284 1418 3285 1169 3285 1170 3285 1401 3286 1164 3286 1165 3286 1417 3287 1163 3287 1164 3287 1401 3288 1417 3288 1164 3288 1424 3289 1176 3289 1174 3289 1423 3290 1174 3290 1178 3290 1423 3291 1424 3291 1174 3291 1424 3292 1207 3292 1176 3292 1424 3293 1206 3293 1207 3293 1424 3294 1203 3294 1206 3294 1390 3295 1200 3295 1203 3295 1424 3296 1425 3296 1203 3296 1390 3297 1203 3297 1425 3297 1391 3298 1198 3298 1200 3298 1390 3299 1391 3299 1200 3299 1391 3300 1196 3300 1198 3300 1391 3301 1194 3301 1196 3301 1391 3302 1191 3302 1194 3302 1392 3303 1189 3303 1191 3303 1391 3304 1392 3304 1191 3304 1392 3305 1187 3305 1189 3305 1392 3306 1184 3306 1187 3306 1422 3307 1182 3307 1184 3307 1392 3308 1422 3308 1184 3308 1423 3309 1180 3309 1182 3309 1422 3310 1423 3310 1182 3310 1423 3311 1178 3311 1180 3311 1448 3312 1213 3312 1211 3312 1447 3313 1211 3313 1216 3313 1447 3314 1448 3314 1211 3314 1448 3315 1232 3315 1213 3315 1450 3316 1230 3316 1232 3316 1448 3317 1450 3317 1232 3317 1454 3318 1228 3318 1230 3318 1455 3319 1454 3319 1230 3319 1452 3320 1455 3320 1230 3320 1450 3321 1452 3321 1230 3321 1465 3322 1226 3322 1228 3322 1458 3323 1465 3323 1228 3323 1454 3324 1458 3324 1228 3324 1465 3325 1224 3325 1226 3325 1465 3326 1221 3326 1224 3326 1465 3327 1218 3327 1221 3327 1447 3328 1216 3328 1218 3328 1447 3329 1218 3329 1465 3329 1467 3330 1239 3330 1237 3330 1467 3331 1237 3331 1241 3331 1467 3332 1258 3332 1239 3332 1467 3333 1256 3333 1258 3333 1363 3334 1253 3334 1256 3334 1362 3335 1256 3335 1467 3335 1362 3336 1363 3336 1256 3336 1364 3337 1251 3337 1253 3337 1363 3338 1364 3338 1253 3338 1364 3339 1248 3339 1251 3339 1365 3340 1246 3340 1248 3340 1364 3341 1365 3341 1248 3341 1365 3342 1243 3342 1246 3342 1466 3343 1241 3343 1243 3343 1365 3344 1466 3344 1243 3344 1466 3345 1467 3345 1241 3345 1447 3346 1266 3346 1264 3346 1446 3347 1264 3347 1269 3347 1446 3348 1447 3348 1264 3348 1447 3349 1286 3349 1266 3349 1447 3350 1285 3350 1286 3350 1290 3351 1283 3351 1285 3351 1307 3352 1290 3352 1285 3352 1465 3353 1307 3353 1285 3353 1447 3354 1465 3354 1285 3354 1289 3355 1279 3355 1283 3355 1290 3356 1289 3356 1283 3356 1543 3357 1276 3357 1279 3357 1542 3358 1279 3358 1289 3358 1542 3359 1543 3359 1279 3359 1541 3360 1274 3360 1276 3360 1543 3361 1541 3361 1276 3361 1541 3362 1271 3362 1274 3362 1446 3363 1269 3363 1271 3363 1445 3364 1446 3364 1271 3364 1541 3365 1445 3365 1271 3365 1542 3366 1289 3366 1293 3366 1465 3367 1306 3367 1307 3367 1365 3368 1305 3368 1306 3368 1465 3369 1466 3369 1306 3369 1365 3370 1306 3370 1466 3370 1365 3371 1303 3371 1305 3371 1365 3372 1301 3372 1303 3372 1367 3373 1298 3373 1301 3373 1365 3374 1367 3374 1301 3374 1367 3375 1295 3375 1298 3375 1542 3376 1293 3376 1295 3376 1542 3377 1295 3377 1367 3377 1438 3378 1312 3378 1310 3378 1438 3379 1310 3379 1314 3379 1438 3380 1350 3380 1312 3380 1441 3381 1349 3381 1350 3381 1438 3382 1441 3382 1350 3382 1441 3383 1347 3383 1349 3383 1441 3384 1345 3384 1347 3384 1373 3385 1342 3385 1345 3385 1373 3386 1345 3386 1441 3386 1373 3387 1340 3387 1342 3387 1373 3388 1338 3388 1340 3388 1373 3389 1335 3389 1338 3389 1374 3390 1333 3390 1335 3390 1373 3391 1374 3391 1335 3391 1374 3392 1331 3392 1333 3392 1374 3393 1329 3393 1331 3393 1374 3394 1327 3394 1329 3394 1374 3395 1325 3395 1327 3395 1374 3396 1322 3396 1325 3396 1435 3397 1320 3397 1322 3397 1374 3398 1435 3398 1322 3398 1438 3399 1318 3399 1320 3399 1435 3400 1438 3400 1320 3400 1438 3401 1316 3401 1318 3401 1438 3402 1314 3402 1316 3402 1356 3403 1467 3403 1353 3403 1361 3404 1362 3404 1467 3404 1359 3405 1361 3405 1467 3405 1360 3406 1359 3406 1467 3406 1358 3407 1360 3407 1467 3407 1357 3408 1358 3408 1467 3408 1356 3409 1357 3409 1467 3409 1464 3410 1463 3410 1465 3410 1462 3411 1464 3411 1465 3411 1460 3412 1462 3412 1465 3412 1458 3413 1460 3413 1465 3413 1541 3414 1444 3414 1445 3414 1541 3415 1443 3415 1444 3415 1372 3416 1441 3416 1443 3416 1541 3417 1372 3417 1443 3417 1372 3418 1373 3418 1441 3418 1532 3419 1435 3419 1374 3419 1503 3420 1504 3420 1435 3420 1502 3421 1503 3421 1435 3421 1500 3422 1502 3422 1435 3422 1514 3423 1500 3423 1435 3423 1535 3424 1537 3424 1435 3424 1536 3425 1535 3425 1435 3425 1534 3426 1536 3426 1435 3426 1533 3427 1534 3427 1435 3427 1531 3428 1533 3428 1435 3428 1532 3429 1531 3429 1435 3429 1389 3430 1425 3430 1426 3430 1385 3431 1389 3431 1426 3431 1478 3432 1385 3432 1426 3432 1476 3433 1478 3433 1426 3433 1475 3434 1476 3434 1426 3434 1474 3435 1475 3435 1426 3435 1389 3436 1390 3436 1425 3436 1401 3437 1416 3437 1417 3437 1404 3438 1415 3438 1416 3438 1401 3439 1404 3439 1416 3439 1407 3440 1414 3440 1415 3440 1404 3441 1407 3441 1415 3441 1410 3442 1413 3442 1414 3442 1407 3443 1410 3443 1414 3443 1411 3444 1412 3444 1413 3444 1410 3445 1411 3445 1413 3445 1482 3446 1483 3446 1385 3446 1481 3447 1482 3447 1385 3447 1480 3448 1481 3448 1385 3448 1479 3449 1480 3449 1385 3449 1477 3450 1479 3450 1385 3450 1478 3451 1477 3451 1385 3451 1519 3452 1385 3452 1488 3452 1521 3453 1522 3453 1385 3453 1520 3454 1521 3454 1385 3454 1519 3455 1520 3455 1385 3455 1530 3456 1532 3456 1374 3456 1529 3457 1530 3457 1374 3457 1527 3458 1529 3458 1374 3458 1540 3459 1371 3459 1372 3459 1541 3460 1540 3460 1372 3460 1542 3461 1369 3461 1371 3461 1542 3462 1371 3462 1540 3462 1542 3463 1367 3463 1369 3463 1514 3464 1494 3464 1500 3464 1515 3465 1495 3465 1494 3465 1514 3466 1515 3466 1494 3466 1518 3467 1491 3467 1495 3467 1516 3468 1518 3468 1495 3468 1515 3469 1516 3469 1495 3469 1518 3470 1489 3470 1491 3470 1517 3471 1488 3471 1489 3471 1518 3472 1517 3472 1489 3472 1517 3473 1519 3473 1488 3473 1544 3474 1545 3474 1546 3474 1547 3475 1546 3475 1545 3475 1548 3476 1546 3476 1549 3476 1550 3477 1549 3477 1546 3477 1551 3478 1544 3478 1546 3478 1548 3479 1551 3479 1546 3479 1550 3480 1546 3480 1547 3480 1544 3481 1552 3481 1545 3481 1553 3482 1545 3482 1552 3482 1553 3483 1547 3483 1545 3483 1544 3484 1554 3484 1552 3484 1555 3485 1552 3485 1554 3485 1553 3486 1552 3486 1555 3486 1556 3487 1557 3487 1554 3487 1558 3488 1554 3488 1557 3488 1559 3489 1556 3489 1554 3489 1560 3490 1559 3490 1554 3490 1561 3491 1554 3491 1544 3491 1562 3492 1560 3492 1554 3492 1561 3493 1562 3493 1554 3493 1555 3494 1554 3494 1558 3494 1563 3495 1564 3495 1557 3495 1565 3496 1557 3496 1564 3496 1556 3497 1563 3497 1557 3497 1558 3498 1557 3498 1565 3498 1566 3499 1567 3499 1564 3499 1568 3500 1564 3500 1567 3500 1566 3501 1564 3501 1563 3501 1565 3502 1564 3502 1568 3502 1569 3503 1570 3503 1567 3503 1571 3504 1567 3504 1570 3504 1566 3505 1569 3505 1567 3505 1568 3506 1567 3506 1571 3506 1572 3507 1573 3507 1570 3507 1574 3508 1570 3508 1573 3508 1572 3509 1570 3509 1569 3509 1571 3510 1570 3510 1574 3510 1575 3511 1549 3511 1573 3511 1576 3512 1573 3512 1549 3512 1572 3513 1577 3513 1573 3513 1575 3514 1573 3514 1577 3514 1574 3515 1573 3515 1576 3515 1578 3516 1548 3516 1549 3516 1579 3517 1578 3517 1549 3517 1580 3518 1579 3518 1549 3518 1575 3519 1580 3519 1549 3519 1576 3520 1549 3520 1550 3520 1544 3521 1581 3521 1582 3521 1583 3522 1582 3522 1581 3522 1584 3523 1582 3523 1585 3523 1586 3524 1585 3524 1582 3524 1584 3525 1544 3525 1582 3525 1586 3526 1582 3526 1583 3526 1544 3527 1587 3527 1581 3527 1588 3528 1581 3528 1587 3528 1588 3529 1583 3529 1581 3529 1544 3530 1589 3530 1587 3530 1590 3531 1587 3531 1589 3531 1588 3532 1587 3532 1590 3532 1591 3533 1592 3533 1589 3533 1593 3534 1589 3534 1592 3534 1594 3535 1591 3535 1589 3535 1595 3536 1594 3536 1589 3536 1596 3537 1589 3537 1544 3537 1596 3538 1595 3538 1589 3538 1590 3539 1589 3539 1593 3539 1597 3540 1598 3540 1592 3540 1599 3541 1592 3541 1598 3541 1591 3542 1597 3542 1592 3542 1593 3543 1592 3543 1599 3543 1600 3544 1601 3544 1598 3544 1602 3545 1598 3545 1601 3545 1600 3546 1598 3546 1597 3546 1599 3547 1598 3547 1602 3547 1603 3548 1604 3548 1601 3548 1605 3549 1601 3549 1604 3549 1600 3550 1603 3550 1601 3550 1602 3551 1601 3551 1605 3551 1606 3552 1607 3552 1604 3552 1608 3553 1604 3553 1607 3553 1606 3554 1604 3554 1603 3554 1605 3555 1604 3555 1608 3555 1609 3556 1585 3556 1607 3556 1610 3557 1607 3557 1585 3557 1606 3558 1611 3558 1607 3558 1609 3559 1607 3559 1611 3559 1608 3560 1607 3560 1610 3560 1612 3561 1584 3561 1585 3561 1613 3562 1612 3562 1585 3562 1614 3563 1613 3563 1585 3563 1609 3564 1614 3564 1585 3564 1610 3565 1585 3565 1586 3565 1615 3566 1597 3566 1591 3566 1616 3567 1600 3567 1597 3567 1616 3568 1597 3568 1615 3568 1617 3569 1591 3569 1594 3569 1617 3570 1615 3570 1591 3570 1595 3571 1618 3571 1594 3571 1619 3572 1594 3572 1618 3572 1617 3573 1594 3573 1619 3573 1620 3574 1621 3574 1618 3574 1622 3575 1618 3575 1621 3575 1623 3576 1624 3576 1618 3576 1620 3577 1618 3577 1624 3577 1595 3578 1623 3578 1618 3578 1619 3579 1618 3579 1622 3579 1625 3580 1626 3580 1621 3580 1627 3581 1621 3581 1626 3581 1628 3582 1625 3582 1621 3582 1629 3583 1628 3583 1621 3583 1620 3584 1629 3584 1621 3584 1622 3585 1621 3585 1627 3585 1630 3586 1631 3586 1626 3586 1632 3587 1626 3587 1631 3587 1633 3588 1630 3588 1626 3588 1625 3589 1633 3589 1626 3589 1627 3590 1626 3590 1632 3590 1630 3591 1634 3591 1631 3591 1635 3592 1631 3592 1634 3592 1632 3593 1631 3593 1635 3593 1630 3594 1603 3594 1634 3594 1636 3595 1634 3595 1603 3595 1635 3596 1634 3596 1636 3596 1637 3597 1603 3597 1600 3597 1638 3598 1603 3598 1630 3598 1639 3599 1606 3599 1603 3599 1638 3600 1639 3600 1603 3600 1636 3601 1603 3601 1637 3601 1637 3602 1600 3602 1616 3602 1640 3603 1563 3603 1556 3603 1641 3604 1566 3604 1563 3604 1641 3605 1563 3605 1640 3605 1642 3606 1556 3606 1559 3606 1642 3607 1640 3607 1556 3607 1560 3608 1643 3608 1559 3608 1644 3609 1559 3609 1643 3609 1642 3610 1559 3610 1644 3610 1645 3611 1646 3611 1643 3611 1647 3612 1643 3612 1646 3612 1648 3613 1649 3613 1643 3613 1645 3614 1643 3614 1649 3614 1560 3615 1648 3615 1643 3615 1644 3616 1643 3616 1647 3616 1650 3617 1651 3617 1646 3617 1652 3618 1646 3618 1651 3618 1653 3619 1650 3619 1646 3619 1654 3620 1653 3620 1646 3620 1645 3621 1654 3621 1646 3621 1647 3622 1646 3622 1652 3622 1630 3623 1655 3623 1651 3623 1656 3624 1651 3624 1655 3624 1650 3625 1630 3625 1651 3625 1652 3626 1651 3626 1656 3626 1630 3627 1657 3627 1655 3627 1658 3628 1655 3628 1657 3628 1656 3629 1655 3629 1658 3629 1630 3630 1569 3630 1657 3630 1659 3631 1657 3631 1569 3631 1658 3632 1657 3632 1659 3632 1660 3633 1569 3633 1566 3633 1661 3634 1569 3634 1630 3634 1661 3635 1572 3635 1569 3635 1659 3636 1569 3636 1660 3636 1660 3637 1566 3637 1641 3637 1662 3638 1663 3638 1664 3638 1665 3639 1664 3639 1663 3639 1662 3640 1664 3640 1666 3640 1667 3641 1666 3641 1664 3641 1667 3642 1664 3642 1665 3642 1668 3643 1669 3643 1663 3643 1670 3644 1663 3644 1669 3644 1662 3645 1668 3645 1663 3645 1670 3646 1665 3646 1663 3646 1668 3647 1671 3647 1669 3647 1672 3648 1669 3648 1671 3648 1670 3649 1669 3649 1672 3649 1668 3650 1673 3650 1671 3650 1674 3651 1671 3651 1673 3651 1672 3652 1671 3652 1674 3652 1668 3653 1675 3653 1673 3653 1676 3654 1673 3654 1675 3654 1674 3655 1673 3655 1676 3655 1677 3656 1678 3656 1675 3656 1679 3657 1675 3657 1678 3657 1668 3658 1677 3658 1675 3658 1676 3659 1675 3659 1679 3659 1677 3660 1680 3660 1678 3660 1681 3661 1678 3661 1680 3661 1679 3662 1678 3662 1681 3662 1677 3663 1682 3663 1680 3663 1683 3664 1680 3664 1682 3664 1681 3665 1680 3665 1683 3665 1684 3666 1685 3666 1682 3666 1686 3667 1682 3667 1685 3667 1687 3668 1688 3668 1682 3668 1684 3669 1682 3669 1688 3669 1677 3670 1687 3670 1682 3670 1683 3671 1682 3671 1686 3671 1684 3672 1689 3672 1685 3672 1690 3673 1685 3673 1689 3673 1686 3674 1685 3674 1690 3674 1684 3675 1691 3675 1689 3675 1692 3676 1689 3676 1691 3676 1690 3677 1689 3677 1692 3677 1684 3678 1693 3678 1691 3678 1694 3679 1691 3679 1693 3679 1692 3680 1691 3680 1694 3680 1695 3681 1696 3681 1693 3681 1697 3682 1693 3682 1696 3682 1684 3683 1695 3683 1693 3683 1694 3684 1693 3684 1697 3684 1695 3685 1698 3685 1696 3685 1699 3686 1696 3686 1698 3686 1697 3687 1696 3687 1699 3687 1695 3688 1700 3688 1698 3688 1701 3689 1698 3689 1700 3689 1699 3690 1698 3690 1701 3690 1695 3691 1702 3691 1700 3691 1703 3692 1700 3692 1702 3692 1701 3693 1700 3693 1703 3693 1704 3694 1705 3694 1702 3694 1706 3695 1702 3695 1705 3695 1695 3696 1704 3696 1702 3696 1703 3697 1702 3697 1706 3697 1704 3698 1707 3698 1705 3698 1708 3699 1705 3699 1707 3699 1706 3700 1705 3700 1708 3700 1704 3701 1709 3701 1707 3701 1710 3702 1707 3702 1709 3702 1708 3703 1707 3703 1710 3703 1704 3704 1711 3704 1709 3704 1712 3705 1709 3705 1711 3705 1710 3706 1709 3706 1712 3706 1713 3707 1714 3707 1711 3707 1715 3708 1711 3708 1714 3708 1704 3709 1713 3709 1711 3709 1712 3710 1711 3710 1715 3710 1716 3711 1717 3711 1714 3711 1718 3712 1714 3712 1717 3712 1713 3713 1716 3713 1714 3713 1715 3714 1714 3714 1718 3714 1716 3715 1719 3715 1717 3715 1720 3716 1717 3716 1719 3716 1718 3717 1717 3717 1720 3717 1716 3718 1721 3718 1719 3718 1722 3719 1719 3719 1721 3719 1720 3720 1719 3720 1722 3720 1723 3721 1724 3721 1721 3721 1725 3722 1721 3722 1724 3722 1726 3723 1723 3723 1721 3723 1716 3724 1726 3724 1721 3724 1722 3725 1721 3725 1725 3725 1727 3726 1728 3726 1724 3726 1729 3727 1724 3727 1728 3727 1727 3728 1724 3728 1723 3728 1725 3729 1724 3729 1729 3729 1727 3730 1730 3730 1728 3730 1731 3731 1728 3731 1730 3731 1729 3732 1728 3732 1731 3732 1727 3733 1732 3733 1730 3733 1733 3734 1730 3734 1732 3734 1731 3735 1730 3735 1733 3735 1727 3736 1734 3736 1732 3736 1735 3737 1732 3737 1734 3737 1733 3738 1732 3738 1735 3738 1662 3739 1736 3739 1734 3739 1737 3740 1734 3740 1736 3740 1727 3741 1662 3741 1734 3741 1735 3742 1734 3742 1737 3742 1662 3743 1666 3743 1736 3743 1738 3744 1736 3744 1666 3744 1737 3745 1736 3745 1738 3745 1738 3746 1666 3746 1667 3746 1739 3747 1740 3747 1741 3747 1742 3748 1741 3748 1740 3748 1739 3749 1741 3749 1743 3749 1744 3750 1743 3750 1741 3750 1744 3751 1741 3751 1742 3751 1727 3752 1745 3752 1740 3752 1746 3753 1740 3753 1745 3753 1739 3754 1727 3754 1740 3754 1746 3755 1742 3755 1740 3755 1727 3756 1723 3756 1745 3756 1747 3757 1745 3757 1723 3757 1746 3758 1745 3758 1747 3758 1748 3759 1749 3759 1723 3759 1750 3760 1723 3760 1749 3760 1726 3761 1748 3761 1723 3761 1747 3762 1723 3762 1750 3762 1751 3763 1752 3763 1749 3763 1753 3764 1749 3764 1752 3764 1748 3765 1751 3765 1749 3765 1750 3766 1749 3766 1753 3766 1754 3767 1755 3767 1752 3767 1756 3768 1752 3768 1755 3768 1754 3769 1752 3769 1751 3769 1753 3770 1752 3770 1756 3770 1757 3771 1758 3771 1755 3771 1759 3772 1755 3772 1758 3772 1754 3773 1757 3773 1755 3773 1756 3774 1755 3774 1759 3774 1760 3775 1761 3775 1758 3775 1762 3776 1758 3776 1761 3776 1760 3777 1758 3777 1757 3777 1759 3778 1758 3778 1762 3778 1739 3779 1743 3779 1761 3779 1763 3780 1761 3780 1743 3780 1764 3781 1761 3781 1760 3781 1764 3782 1739 3782 1761 3782 1762 3783 1761 3783 1763 3783 1763 3784 1743 3784 1744 3784 1765 3785 1751 3785 1748 3785 1766 3786 1754 3786 1751 3786 1766 3787 1751 3787 1765 3787 1767 3788 1748 3788 1726 3788 1767 3789 1765 3789 1748 3789 1768 3790 1726 3790 1716 3790 1767 3791 1726 3791 1768 3791 1713 3792 1769 3792 1716 3792 1770 3793 1716 3793 1769 3793 1768 3794 1716 3794 1770 3794 1713 3795 1771 3795 1769 3795 1772 3796 1769 3796 1771 3796 1770 3797 1769 3797 1772 3797 1760 3798 1773 3798 1771 3798 1774 3799 1771 3799 1773 3799 1713 3800 1760 3800 1771 3800 1772 3801 1771 3801 1774 3801 1760 3802 1775 3802 1773 3802 1776 3803 1773 3803 1775 3803 1774 3804 1773 3804 1776 3804 1760 3805 1757 3805 1775 3805 1777 3806 1775 3806 1757 3806 1776 3807 1775 3807 1777 3807 1778 3808 1757 3808 1754 3808 1777 3809 1757 3809 1778 3809 1778 3810 1754 3810 1766 3810 1779 3811 1780 3811 1781 3811 1782 3812 1781 3812 1780 3812 1783 3813 1781 3813 1784 3813 1785 3814 1784 3814 1781 3814 1783 3815 1779 3815 1781 3815 1785 3816 1781 3816 1782 3816 1786 3817 1787 3817 1780 3817 1788 3818 1780 3818 1787 3818 1779 3819 1786 3819 1780 3819 1788 3820 1782 3820 1780 3820 1789 3821 1790 3821 1787 3821 1791 3822 1787 3822 1790 3822 1789 3823 1787 3823 1786 3823 1788 3824 1787 3824 1791 3824 1792 3825 1793 3825 1790 3825 1794 3826 1790 3826 1793 3826 1789 3827 1792 3827 1790 3827 1791 3828 1790 3828 1794 3828 1792 3829 1795 3829 1793 3829 1796 3830 1793 3830 1795 3830 1794 3831 1793 3831 1796 3831 1684 3832 1797 3832 1795 3832 1798 3833 1795 3833 1797 3833 1792 3834 1684 3834 1795 3834 1796 3835 1795 3835 1798 3835 1684 3836 1799 3836 1797 3836 1800 3837 1797 3837 1799 3837 1798 3838 1797 3838 1800 3838 1684 3839 1688 3839 1799 3839 1801 3840 1799 3840 1688 3840 1800 3841 1799 3841 1801 3841 1802 3842 1784 3842 1688 3842 1803 3843 1688 3843 1784 3843 1687 3844 1802 3844 1688 3844 1801 3845 1688 3845 1803 3845 1802 3846 1783 3846 1784 3846 1803 3847 1784 3847 1785 3847 1804 3848 1805 3848 1806 3848 1807 3849 1806 3849 1805 3849 1804 3850 1806 3850 1808 3850 1809 3851 1808 3851 1806 3851 1809 3852 1806 3852 1807 3852 1789 3853 1810 3853 1805 3853 1811 3854 1805 3854 1810 3854 1804 3855 1789 3855 1805 3855 1811 3856 1807 3856 1805 3856 1789 3857 1786 3857 1810 3857 1812 3858 1810 3858 1786 3858 1811 3859 1810 3859 1812 3859 1813 3860 1786 3860 1779 3860 1812 3861 1786 3861 1813 3861 1814 3862 1779 3862 1783 3862 1813 3863 1779 3863 1814 3863 1815 3864 1783 3864 1802 3864 1814 3865 1783 3865 1815 3865 1816 3866 1802 3866 1687 3866 1815 3867 1802 3867 1816 3867 1817 3868 1687 3868 1677 3868 1816 3869 1687 3869 1817 3869 1804 3870 1808 3870 1677 3870 1818 3871 1677 3871 1808 3871 1668 3872 1804 3872 1677 3872 1817 3873 1677 3873 1818 3873 1818 3874 1808 3874 1809 3874 1819 3875 1820 3875 1821 3875 1822 3876 1821 3876 1820 3876 1819 3877 1821 3877 1823 3877 1824 3878 1823 3878 1821 3878 1824 3879 1821 3879 1822 3879 1764 3880 1825 3880 1820 3880 1826 3881 1820 3881 1825 3881 1819 3882 1764 3882 1820 3882 1826 3883 1822 3883 1820 3883 1764 3884 1827 3884 1825 3884 1828 3885 1825 3885 1827 3885 1826 3886 1825 3886 1828 3886 1764 3887 1829 3887 1827 3887 1830 3888 1827 3888 1829 3888 1828 3889 1827 3889 1830 3889 1760 3890 1831 3890 1829 3890 1832 3891 1829 3891 1831 3891 1764 3892 1760 3892 1829 3892 1830 3893 1829 3893 1832 3893 1833 3894 1834 3894 1831 3894 1835 3895 1831 3895 1834 3895 1760 3896 1833 3896 1831 3896 1832 3897 1831 3897 1835 3897 1833 3898 1836 3898 1834 3898 1837 3899 1834 3899 1836 3899 1835 3900 1834 3900 1837 3900 1833 3901 1838 3901 1836 3901 1839 3902 1836 3902 1838 3902 1837 3903 1836 3903 1839 3903 1840 3904 1841 3904 1838 3904 1842 3905 1838 3905 1841 3905 1833 3906 1840 3906 1838 3906 1839 3907 1838 3907 1842 3907 1840 3908 1843 3908 1841 3908 1844 3909 1841 3909 1843 3909 1842 3910 1841 3910 1844 3910 1840 3911 1845 3911 1843 3911 1846 3912 1843 3912 1845 3912 1844 3913 1843 3913 1846 3913 1840 3914 1847 3914 1845 3914 1848 3915 1845 3915 1847 3915 1846 3916 1845 3916 1848 3916 1849 3917 1850 3917 1847 3917 1851 3918 1847 3918 1850 3918 1840 3919 1852 3919 1847 3919 1849 3920 1847 3920 1852 3920 1848 3921 1847 3921 1851 3921 1819 3922 1853 3922 1850 3922 1854 3923 1850 3923 1853 3923 1849 3924 1819 3924 1850 3924 1851 3925 1850 3925 1854 3925 1819 3926 1823 3926 1853 3926 1855 3927 1853 3927 1823 3927 1854 3928 1853 3928 1855 3928 1855 3929 1823 3929 1824 3929 1856 3930 1857 3930 1858 3930 1859 3931 1858 3931 1857 3931 1856 3932 1858 3932 1860 3932 1861 3933 1860 3933 1858 3933 1861 3934 1858 3934 1859 3934 1862 3935 1863 3935 1857 3935 1864 3936 1857 3936 1863 3936 1856 3937 1862 3937 1857 3937 1864 3938 1859 3938 1857 3938 1862 3939 1865 3939 1863 3939 1866 3940 1863 3940 1865 3940 1864 3941 1863 3941 1866 3941 1867 3942 1868 3942 1865 3942 1869 3943 1865 3943 1868 3943 1867 3944 1865 3944 1862 3944 1866 3945 1865 3945 1869 3945 1870 3946 1871 3946 1868 3946 1872 3947 1868 3947 1871 3947 1867 3948 1870 3948 1868 3948 1869 3949 1868 3949 1872 3949 1870 3950 1873 3950 1871 3950 1874 3951 1871 3951 1873 3951 1872 3952 1871 3952 1874 3952 1870 3953 1875 3953 1873 3953 1876 3954 1873 3954 1875 3954 1874 3955 1873 3955 1876 3955 1870 3956 1877 3956 1875 3956 1878 3957 1875 3957 1877 3957 1876 3958 1875 3958 1878 3958 1879 3959 1860 3959 1877 3959 1880 3960 1877 3960 1860 3960 1881 3961 1879 3961 1877 3961 1870 3962 1881 3962 1877 3962 1878 3963 1877 3963 1880 3963 1879 3964 1856 3964 1860 3964 1880 3965 1860 3965 1861 3965 1882 3966 1883 3966 1884 3966 1885 3967 1884 3967 1883 3967 1882 3968 1884 3968 1886 3968 1887 3969 1886 3969 1884 3969 1887 3970 1884 3970 1885 3970 1882 3971 1888 3971 1883 3971 1889 3972 1883 3972 1888 3972 1889 3973 1885 3973 1883 3973 1882 3974 1890 3974 1888 3974 1891 3975 1888 3975 1890 3975 1889 3976 1888 3976 1891 3976 1892 3977 1893 3977 1890 3977 1894 3978 1890 3978 1893 3978 1882 3979 1892 3979 1890 3979 1891 3980 1890 3980 1894 3980 1892 3981 1895 3981 1893 3981 1896 3982 1893 3982 1895 3982 1894 3983 1893 3983 1896 3983 1897 3984 1898 3984 1895 3984 1899 3985 1895 3985 1898 3985 1892 3986 1897 3986 1895 3986 1896 3987 1895 3987 1899 3987 1897 3988 1900 3988 1898 3988 1901 3989 1898 3989 1900 3989 1899 3990 1898 3990 1901 3990 1902 3991 1903 3991 1900 3991 1904 3992 1900 3992 1903 3992 1897 3993 1902 3993 1900 3993 1901 3994 1900 3994 1904 3994 1905 3995 1886 3995 1903 3995 1906 3996 1903 3996 1886 3996 1907 3997 1905 3997 1903 3997 1908 3998 1907 3998 1903 3998 1902 3999 1908 3999 1903 3999 1904 4000 1903 4000 1906 4000 1905 4001 1909 4001 1886 4001 1882 4002 1886 4002 1909 4002 1906 4003 1886 4003 1887 4003 1862 4004 1910 4004 1911 4004 1912 4005 1911 4005 1910 4005 1862 4006 1911 4006 1913 4006 1914 4007 1913 4007 1911 4007 1914 4008 1911 4008 1912 4008 1915 4009 1916 4009 1910 4009 1917 4010 1910 4010 1916 4010 1862 4011 1915 4011 1910 4011 1917 4012 1912 4012 1910 4012 1915 4013 1918 4013 1916 4013 1919 4014 1916 4014 1918 4014 1917 4015 1916 4015 1919 4015 1920 4016 1921 4016 1918 4016 1922 4017 1918 4017 1921 4017 1920 4018 1918 4018 1915 4018 1919 4019 1918 4019 1922 4019 1920 4020 1923 4020 1921 4020 1924 4021 1921 4021 1923 4021 1922 4022 1921 4022 1924 4022 1925 4023 1926 4023 1923 4023 1927 4024 1923 4024 1926 4024 1925 4025 1923 4025 1928 4025 1920 4026 1928 4026 1923 4026 1924 4027 1923 4027 1927 4027 1929 4028 1930 4028 1926 4028 1931 4029 1926 4029 1930 4029 1925 4030 1929 4030 1926 4030 1927 4031 1926 4031 1931 4031 1882 4032 1932 4032 1930 4032 1933 4033 1930 4033 1932 4033 1882 4034 1930 4034 1929 4034 1931 4035 1930 4035 1933 4035 1862 4036 1913 4036 1932 4036 1934 4037 1932 4037 1913 4037 1867 4038 1862 4038 1932 4038 1882 4039 1867 4039 1932 4039 1933 4040 1932 4040 1934 4040 1934 4041 1913 4041 1914 4041 1935 4042 1936 4042 1928 4042 1937 4043 1928 4043 1936 4043 1938 4044 1925 4044 1928 4044 1920 4045 1935 4045 1928 4045 1938 4046 1928 4046 1937 4046 1939 4047 1940 4047 1936 4047 1941 4048 1936 4048 1940 4048 1935 4049 1939 4049 1936 4049 1941 4050 1937 4050 1936 4050 1939 4051 1942 4051 1940 4051 1943 4052 1940 4052 1942 4052 1941 4053 1940 4053 1943 4053 1944 4054 1945 4054 1942 4054 1946 4055 1942 4055 1945 4055 1947 4056 1944 4056 1942 4056 1939 4057 1947 4057 1942 4057 1943 4058 1942 4058 1946 4058 1944 4059 1948 4059 1945 4059 1949 4060 1945 4060 1948 4060 1946 4061 1945 4061 1949 4061 1892 4062 1950 4062 1948 4062 1951 4063 1948 4063 1950 4063 1944 4064 1892 4064 1948 4064 1949 4065 1948 4065 1951 4065 1892 4066 1952 4066 1950 4066 1953 4067 1950 4067 1952 4067 1951 4068 1950 4068 1953 4068 1892 4069 1929 4069 1952 4069 1954 4070 1952 4070 1929 4070 1953 4071 1952 4071 1954 4071 1955 4072 1929 4072 1925 4072 1882 4073 1929 4073 1892 4073 1954 4074 1929 4074 1955 4074 1955 4075 1925 4075 1938 4075 1551 4076 1956 4076 1957 4076 1958 4077 1957 4077 1956 4077 1551 4078 1957 4078 1959 4078 1960 4079 1959 4079 1957 4079 1960 4080 1957 4080 1958 4080 1551 4081 1961 4081 1956 4081 1962 4082 1956 4082 1961 4082 1962 4083 1958 4083 1956 4083 1551 4084 1963 4084 1961 4084 1964 4085 1961 4085 1963 4085 1962 4086 1961 4086 1964 4086 1551 4087 1965 4087 1963 4087 1966 4088 1963 4088 1965 4088 1964 4089 1963 4089 1966 4089 1551 4090 1967 4090 1965 4090 1968 4091 1965 4091 1967 4091 1966 4092 1965 4092 1968 4092 1630 4093 1969 4093 1967 4093 1970 4094 1967 4094 1969 4094 1551 4095 1630 4095 1967 4095 1968 4096 1967 4096 1970 4096 1971 4097 1972 4097 1969 4097 1973 4098 1969 4098 1972 4098 1630 4099 1971 4099 1969 4099 1970 4100 1969 4100 1973 4100 1971 4101 1974 4101 1972 4101 1975 4102 1972 4102 1974 4102 1973 4103 1972 4103 1975 4103 1971 4104 1976 4104 1974 4104 1977 4105 1974 4105 1976 4105 1975 4106 1974 4106 1977 4106 1971 4107 1978 4107 1976 4107 1979 4108 1976 4108 1978 4108 1977 4109 1976 4109 1979 4109 1971 4110 1980 4110 1978 4110 1981 4111 1978 4111 1980 4111 1979 4112 1978 4112 1981 4112 1971 4113 1982 4113 1980 4113 1983 4114 1980 4114 1982 4114 1981 4115 1980 4115 1983 4115 1984 4116 1985 4116 1982 4116 1986 4117 1982 4117 1985 4117 1971 4118 1984 4118 1982 4118 1983 4119 1982 4119 1986 4119 1984 4120 1987 4120 1985 4120 1988 4121 1985 4121 1987 4121 1986 4122 1985 4122 1988 4122 1984 4123 1989 4123 1987 4123 1990 4124 1987 4124 1989 4124 1988 4125 1987 4125 1990 4125 1991 4126 1992 4126 1989 4126 1993 4127 1989 4127 1992 4127 1991 4128 1989 4128 1984 4128 1990 4129 1989 4129 1993 4129 1991 4130 1994 4130 1992 4130 1995 4131 1992 4131 1994 4131 1993 4132 1992 4132 1995 4132 1991 4133 1996 4133 1994 4133 1997 4134 1994 4134 1996 4134 1995 4135 1994 4135 1997 4135 1991 4136 1959 4136 1996 4136 1998 4137 1996 4137 1959 4137 1997 4138 1996 4138 1998 4138 1991 4139 1551 4139 1959 4139 1998 4140 1959 4140 1960 4140 1882 4141 1999 4141 2000 4141 2001 4142 2000 4142 1999 4142 2002 4143 1882 4143 2000 4143 2001 4144 2002 4144 2000 4144 1882 4145 2003 4145 1999 4145 2004 4146 1999 4146 2003 4146 2004 4147 2001 4147 1999 4147 1882 4148 1909 4148 2003 4148 2005 4149 2003 4149 1909 4149 2004 4150 2003 4150 2005 4150 2006 4151 1909 4151 1905 4151 2005 4152 1909 4152 2006 4152 2007 4153 1905 4153 1907 4153 2008 4154 1905 4154 2007 4154 2006 4155 1905 4155 2008 4155 2007 4156 1907 4156 1908 4156 2009 4157 1908 4157 1902 4157 2007 4158 1908 4158 2009 4158 2010 4159 1902 4159 1897 4159 2009 4160 1902 4160 2010 4160 2011 4161 1897 4161 1892 4161 2010 4162 1897 4162 2011 4162 2012 4163 1892 4163 1944 4163 2011 4164 1892 4164 2012 4164 2013 4165 1944 4165 1947 4165 2012 4166 1944 4166 2013 4166 1939 4167 2014 4167 1947 4167 2015 4168 1947 4168 2014 4168 2013 4169 1947 4169 2015 4169 1939 4170 2016 4170 2014 4170 2017 4171 2014 4171 2016 4171 2015 4172 2014 4172 2017 4172 2018 4173 1984 4173 2016 4173 2019 4174 2016 4174 1984 4174 1939 4175 2018 4175 2016 4175 2017 4176 2016 4176 2019 4176 2020 4177 1984 4177 1971 4177 2018 4178 1991 4178 1984 4178 2019 4179 1984 4179 2020 4179 2021 4180 1971 4180 1630 4180 2020 4181 1971 4181 2021 4181 2022 4182 1630 4182 1633 4182 2023 4183 1630 4183 1551 4183 2024 4184 1638 4184 1630 4184 2025 4185 2024 4185 1630 4185 2026 4186 2025 4186 1630 4186 1650 4187 2026 4187 1630 4187 2027 4188 1661 4188 1630 4188 2028 4189 2027 4189 1630 4189 2029 4190 2028 4190 1630 4190 2030 4191 2029 4191 1630 4191 2031 4192 2030 4192 1630 4192 2023 4193 2031 4193 1630 4193 2021 4194 1630 4194 2022 4194 2032 4195 1852 4195 1633 4195 2033 4196 1633 4196 1852 4196 1544 4197 2032 4197 1633 4197 2034 4198 1544 4198 1633 4198 2035 4199 2034 4199 1633 4199 2036 4200 2035 4200 1633 4200 1625 4201 2036 4201 1633 4201 2022 4202 1633 4202 2033 4202 2037 4203 1852 4203 1840 4203 2032 4204 1849 4204 1852 4204 2033 4205 1852 4205 2037 4205 2038 4206 1840 4206 1833 4206 2037 4207 1840 4207 2038 4207 2039 4208 1833 4208 1760 4208 2038 4209 1833 4209 2039 4209 2040 4210 1760 4210 1713 4210 2039 4211 1760 4211 2040 4211 2041 4212 1713 4212 1704 4212 2040 4213 1713 4213 2041 4213 2042 4214 1704 4214 1695 4214 2041 4215 1704 4215 2042 4215 2043 4216 1695 4216 1684 4216 2042 4217 1695 4217 2043 4217 2044 4218 1684 4218 1792 4218 2043 4219 1684 4219 2044 4219 1789 4220 2045 4220 1792 4220 2046 4221 1792 4221 2045 4221 2044 4222 1792 4222 2046 4222 2047 4223 2048 4223 2045 4223 2049 4224 2045 4224 2048 4224 1789 4225 2047 4225 2045 4225 2046 4226 2045 4226 2049 4226 2050 4227 2051 4227 2048 4227 2052 4228 2048 4228 2051 4228 2047 4229 2050 4229 2048 4229 2049 4230 2048 4230 2052 4230 2053 4231 2054 4231 2051 4231 2055 4232 2051 4232 2054 4232 2050 4233 2053 4233 2051 4233 2052 4234 2051 4234 2055 4234 2056 4235 2057 4235 2054 4235 2058 4236 2054 4236 2057 4236 2053 4237 2056 4237 2054 4237 2055 4238 2054 4238 2058 4238 2059 4239 2057 4239 2056 4239 2058 4240 2057 4240 2059 4240 2060 4241 2056 4241 2053 4241 2059 4242 2056 4242 2060 4242 2061 4243 2053 4243 2050 4243 2060 4244 2053 4244 2061 4244 2062 4245 2050 4245 2047 4245 2061 4246 2050 4246 2062 4246 2063 4247 2047 4247 1789 4247 2062 4248 2047 4248 2063 4248 2064 4249 1789 4249 1804 4249 2063 4250 1789 4250 2064 4250 2065 4251 1804 4251 1668 4251 2064 4252 1804 4252 2065 4252 2066 4253 1668 4253 1662 4253 2065 4254 1668 4254 2066 4254 2067 4255 1662 4255 1727 4255 2066 4256 1662 4256 2067 4256 2068 4257 1727 4257 1739 4257 2067 4258 1727 4258 2068 4258 2069 4259 1739 4259 1764 4259 2068 4260 1739 4260 2069 4260 2070 4261 1764 4261 1819 4261 2069 4262 1764 4262 2070 4262 2071 4263 1819 4263 1849 4263 2070 4264 1819 4264 2071 4264 2072 4265 1849 4265 2032 4265 2071 4266 1849 4266 2072 4266 2073 4267 2032 4267 1544 4267 2072 4268 2032 4268 2073 4268 2074 4269 1544 4269 1551 4269 2075 4270 1596 4270 1544 4270 2076 4271 2075 4271 1544 4271 2077 4272 2076 4272 1544 4272 2078 4273 2077 4273 1544 4273 2079 4274 2078 4274 1544 4274 2034 4275 2079 4275 1544 4275 2080 4276 1544 4276 1584 4276 2081 4277 1561 4277 1544 4277 2082 4278 2081 4278 1544 4278 2080 4279 2082 4279 1544 4279 2073 4280 1544 4280 2074 4280 2083 4281 1551 4281 1991 4281 2084 4282 2023 4282 1551 4282 2085 4283 2084 4283 1551 4283 1548 4284 2085 4284 1551 4284 2074 4285 1551 4285 2083 4285 2086 4286 1991 4286 2018 4286 2083 4287 1991 4287 2086 4287 2087 4288 2088 4288 2018 4288 2089 4289 2018 4289 2088 4289 2087 4290 2018 4290 1939 4290 2086 4291 2018 4291 2089 4291 1920 4292 2090 4292 2088 4292 2091 4293 2088 4293 2090 4293 2087 4294 1920 4294 2088 4294 2089 4295 2088 4295 2091 4295 1920 4296 1915 4296 2090 4296 2092 4297 2090 4297 1915 4297 2091 4298 2090 4298 2092 4298 2093 4299 1915 4299 1862 4299 2092 4300 1915 4300 2093 4300 2094 4301 1862 4301 1856 4301 2093 4302 1862 4302 2094 4302 2095 4303 1856 4303 1879 4303 2094 4304 1856 4304 2095 4304 2096 4305 1879 4305 1881 4305 2095 4306 1879 4306 2096 4306 1870 4307 2097 4307 1881 4307 2098 4308 1881 4308 2097 4308 2096 4309 1881 4309 2098 4309 1870 4310 2099 4310 2097 4310 2100 4311 2097 4311 2099 4311 2098 4312 2097 4312 2100 4312 1870 4313 2101 4313 2099 4313 2102 4314 2099 4314 2101 4314 2103 4315 2099 4315 2102 4315 2100 4316 2099 4316 2103 4316 1870 4317 2104 4317 2101 4317 2102 4318 2101 4318 2104 4318 1870 4319 2105 4319 2104 4319 2106 4320 2104 4320 2105 4320 2102 4321 2104 4321 2106 4321 1870 4322 2107 4322 2105 4322 2108 4323 2105 4323 2107 4323 2106 4324 2105 4324 2108 4324 1870 4325 2109 4325 2107 4325 2110 4326 2107 4326 2109 4326 2108 4327 2107 4327 2110 4327 2111 4328 2109 4328 1870 4328 2112 4329 2109 4329 2111 4329 2110 4330 2109 4330 2112 4330 2111 4331 1870 4331 1867 4331 2113 4332 1867 4332 1882 4332 2111 4333 1867 4333 2113 4333 2114 4334 1882 4334 2002 4334 2113 4335 1882 4335 2114 4335 2115 4336 2002 4336 2001 4336 2114 4337 2002 4337 2115 4337 2116 4338 1624 4338 1623 4338 2117 4339 1620 4339 1624 4339 2117 4340 1624 4340 2118 4340 2116 4341 2118 4341 1624 4341 2116 4342 1623 4342 1595 4342 2119 4343 1595 4343 1596 4343 2116 4344 1595 4344 2119 4344 2120 4345 1596 4345 2075 4345 2119 4346 1596 4346 2120 4346 2121 4347 2075 4347 2076 4347 2120 4348 2075 4348 2121 4348 2122 4349 2076 4349 2077 4349 2121 4350 2076 4350 2122 4350 2123 4351 2077 4351 2078 4351 2122 4352 2077 4352 2123 4352 2124 4353 2078 4353 2079 4353 2123 4354 2078 4354 2124 4354 2125 4355 2079 4355 2034 4355 2126 4356 2079 4356 2125 4356 2124 4357 2079 4357 2126 4357 2125 4358 2034 4358 2035 4358 2127 4359 2035 4359 2036 4359 2125 4360 2035 4360 2127 4360 2128 4361 2036 4361 1625 4361 2127 4362 2036 4362 2128 4362 2129 4363 1625 4363 1628 4363 2128 4364 1625 4364 2129 4364 2130 4365 1628 4365 1629 4365 2129 4366 1628 4366 2130 4366 2131 4367 1629 4367 1620 4367 2130 4368 1629 4368 2131 4368 2131 4369 1620 4369 2117 4369 2132 4370 1611 4370 1606 4370 2132 4371 1609 4371 1611 4371 2133 4372 1606 4372 1639 4372 2133 4373 2132 4373 1606 4373 2134 4374 1639 4374 1638 4374 2133 4375 1639 4375 2134 4375 2135 4376 1638 4376 2024 4376 2134 4377 1638 4377 2135 4377 2136 4378 2024 4378 2025 4378 2135 4379 2024 4379 2136 4379 2137 4380 2025 4380 2026 4380 2136 4381 2025 4381 2137 4381 1650 4382 2138 4382 2026 4382 2139 4383 2026 4383 2138 4383 2137 4384 2026 4384 2139 4384 2140 4385 2141 4385 2138 4385 2142 4386 2138 4386 2141 4386 1650 4387 2140 4387 2138 4387 2143 4388 2138 4388 2142 4388 2139 4389 2138 4389 2143 4389 2144 4390 2145 4390 2141 4390 2142 4391 2141 4391 2145 4391 2146 4392 2144 4392 2141 4392 2140 4393 2146 4393 2141 4393 2144 4394 2147 4394 2145 4394 2148 4395 2145 4395 2147 4395 2142 4396 2145 4396 2148 4396 2149 4397 1584 4397 2147 4397 2150 4398 2147 4398 1584 4398 2144 4399 2149 4399 2147 4399 2148 4400 2147 4400 2150 4400 2151 4401 1584 4401 1612 4401 2149 4402 2080 4402 1584 4402 2150 4403 1584 4403 2151 4403 2152 4404 1612 4404 1613 4404 2151 4405 1612 4405 2152 4405 2153 4406 1613 4406 1614 4406 2152 4407 1613 4407 2153 4407 2154 4408 1614 4408 1609 4408 2153 4409 1614 4409 2154 4409 2155 4410 1609 4410 2132 4410 2154 4411 1609 4411 2155 4411 2156 4412 1649 4412 1648 4412 2157 4413 1645 4413 1649 4413 2157 4414 1649 4414 2158 4414 2156 4415 2158 4415 1649 4415 2156 4416 1648 4416 1560 4416 2159 4417 1560 4417 1562 4417 2156 4418 1560 4418 2159 4418 2160 4419 1562 4419 1561 4419 2159 4420 1562 4420 2160 4420 2161 4421 1561 4421 2081 4421 2160 4422 1561 4422 2161 4422 2162 4423 2081 4423 2082 4423 2161 4424 2081 4424 2162 4424 2163 4425 2082 4425 2080 4425 2162 4426 2082 4426 2163 4426 2164 4427 2080 4427 2149 4427 2163 4428 2080 4428 2164 4428 2165 4429 2149 4429 2144 4429 2166 4430 2149 4430 2165 4430 2164 4431 2149 4431 2166 4431 2165 4432 2144 4432 2146 4432 2167 4433 2146 4433 2140 4433 2165 4434 2146 4434 2167 4434 2168 4435 2140 4435 1650 4435 2167 4436 2140 4436 2168 4436 2169 4437 1650 4437 1653 4437 2168 4438 1650 4438 2169 4438 2170 4439 1653 4439 1654 4439 2169 4440 1653 4440 2170 4440 2171 4441 1654 4441 1645 4441 2170 4442 1654 4442 2171 4442 2171 4443 1645 4443 2157 4443 2172 4444 1577 4444 1572 4444 2172 4445 1575 4445 1577 4445 2173 4446 1572 4446 1661 4446 2173 4447 2172 4447 1572 4447 2174 4448 1661 4448 2027 4448 2173 4449 1661 4449 2174 4449 2175 4450 2027 4450 2028 4450 2176 4451 2027 4451 2175 4451 2174 4452 2027 4452 2176 4452 2175 4453 2028 4453 2029 4453 2177 4454 2029 4454 2030 4454 2175 4455 2029 4455 2177 4455 2178 4456 2030 4456 2031 4456 2177 4457 2030 4457 2178 4457 2179 4458 2031 4458 2023 4458 2180 4459 2031 4459 2179 4459 2178 4460 2031 4460 2180 4460 2179 4461 2023 4461 2084 4461 2181 4462 2084 4462 2085 4462 2179 4463 2084 4463 2181 4463 2182 4464 2085 4464 1548 4464 2181 4465 2085 4465 2182 4465 2183 4466 1548 4466 1578 4466 2184 4467 1548 4467 2183 4467 2182 4468 1548 4468 2184 4468 2183 4469 1578 4469 1579 4469 2185 4470 1579 4470 1580 4470 2183 4471 1579 4471 2185 4471 2186 4472 1580 4472 1575 4472 2185 4473 1580 4473 2186 4473 2187 4474 1575 4474 2172 4474 2186 4475 1575 4475 2187 4475 2188 4476 1939 4476 1935 4476 2189 4477 2087 4477 1939 4477 2189 4478 1939 4478 2188 4478 2190 4479 1935 4479 1920 4479 2190 4480 2188 4480 1935 4480 2191 4481 1920 4481 2087 4481 2190 4482 1920 4482 2191 4482 2191 4483 2087 4483 2189 4483 2083 4484 1550 4484 1547 4484 2162 4485 1547 4485 1553 4485 2162 4486 2083 4486 1547 4486 2083 4487 1576 4487 1550 4487 2083 4488 1574 4488 1576 4488 1641 4489 1571 4489 1574 4489 1660 4490 1641 4490 1574 4490 2186 4491 1660 4491 1574 4491 2185 4492 1574 4492 2083 4492 2185 4493 2186 4493 1574 4493 1640 4494 1568 4494 1571 4494 1641 4495 1640 4495 1571 4495 1642 4496 1565 4496 1568 4496 1642 4497 1568 4497 1640 4497 1644 4498 1558 4498 1565 4498 1642 4499 1644 4499 1565 4499 2157 4500 1555 4500 1558 4500 2157 4501 1558 4501 1644 4501 2159 4502 1553 4502 1555 4502 2157 4503 2158 4503 1555 4503 2156 4504 1555 4504 2158 4504 2156 4505 2159 4505 1555 4505 2161 4506 2162 4506 1553 4506 2160 4507 2161 4507 1553 4507 2159 4508 2160 4508 1553 4508 2083 4509 1586 4509 1583 4509 2122 4510 1583 4510 1588 4510 2074 4511 2083 4511 1583 4511 2122 4512 2074 4512 1583 4512 2083 4513 1610 4513 1586 4513 2083 4514 1608 4514 1610 4514 1616 4515 1605 4515 1608 4515 1637 4516 1616 4516 1608 4516 2154 4517 1637 4517 1608 4517 2152 4518 1608 4518 2083 4518 2153 4519 2154 4519 1608 4519 2152 4520 2153 4520 1608 4520 1615 4521 1602 4521 1605 4521 1616 4522 1615 4522 1605 4522 1617 4523 1599 4523 1602 4523 1617 4524 1602 4524 1615 4524 1619 4525 1593 4525 1599 4525 1617 4526 1619 4526 1599 4526 2117 4527 1590 4527 1593 4527 2117 4528 1593 4528 1619 4528 2119 4529 1588 4529 1590 4529 2117 4530 2118 4530 1590 4530 2116 4531 1590 4531 2118 4531 2116 4532 2119 4532 1590 4532 2121 4533 2122 4533 1588 4533 2120 4534 2121 4534 1588 4534 2119 4535 2120 4535 1588 4535 2154 4536 1636 4536 1637 4536 2132 4537 1635 4537 1636 4537 2155 4538 2132 4538 1636 4538 2154 4539 2155 4539 1636 4539 2136 4540 1632 4540 1635 4540 2133 4541 1635 4541 2132 4541 2135 4542 2136 4542 1635 4542 2134 4543 2135 4543 1635 4543 2133 4544 2134 4544 1635 4544 2033 4545 1627 4545 1632 4545 2136 4546 2033 4546 1632 4546 2033 4547 1622 4547 1627 4547 2033 4548 1619 4548 1622 4548 2131 4549 1619 4549 2033 4549 2131 4550 2117 4550 1619 4550 2186 4551 1659 4551 1660 4551 2172 4552 1658 4552 1659 4552 2187 4553 2172 4553 1659 4553 2186 4554 2187 4554 1659 4554 2175 4555 1656 4555 1658 4555 2173 4556 1658 4556 2172 4556 2176 4557 2175 4557 1658 4557 2174 4558 2176 4558 1658 4558 2173 4559 2174 4559 1658 4559 2033 4560 1652 4560 1656 4560 2022 4561 2033 4561 1656 4561 2175 4562 2022 4562 1656 4562 2033 4563 1647 4563 1652 4563 2033 4564 1644 4564 1647 4564 2170 4565 1644 4565 2033 4565 2171 4566 2157 4566 1644 4566 2170 4567 2171 4567 1644 4567 2068 4568 1667 4568 1665 4568 2067 4569 1665 4569 1670 4569 2067 4570 2068 4570 1665 4570 2068 4571 1738 4571 1667 4571 2068 4572 1737 4572 1738 4572 2068 4573 1735 4573 1737 4573 2069 4574 1733 4574 1735 4574 2068 4575 2069 4575 1735 4575 1747 4576 1731 4576 1733 4576 2069 4577 1747 4577 1733 4577 1747 4578 1729 4578 1731 4578 1747 4579 1725 4579 1729 4579 1768 4580 1722 4580 1725 4580 1747 4581 1750 4581 1725 4581 1768 4582 1725 4582 1750 4582 2042 4583 1720 4583 1722 4583 2042 4584 1722 4584 1768 4584 2042 4585 1718 4585 1720 4585 2042 4586 1715 4586 1718 4586 2042 4587 1712 4587 1715 4587 2043 4588 1710 4588 1712 4588 2042 4589 2043 4589 1712 4589 2043 4590 1708 4590 1710 4590 2043 4591 1706 4591 1708 4591 2043 4592 1703 4592 1706 4592 2044 4593 1701 4593 1703 4593 2043 4594 2044 4594 1703 4594 2044 4595 1699 4595 1701 4595 2044 4596 1697 4596 1699 4596 2044 4597 1694 4597 1697 4597 1801 4598 1692 4598 1694 4598 2044 4599 1801 4599 1694 4599 1801 4600 1690 4600 1692 4600 1801 4601 1686 4601 1690 4601 2066 4602 1683 4602 1686 4602 1801 4603 1803 4603 1686 4603 1817 4604 1686 4604 1803 4604 2066 4605 1686 4605 1817 4605 2066 4606 1681 4606 1683 4606 2066 4607 1679 4607 1681 4607 2066 4608 1676 4608 1679 4608 2067 4609 1674 4609 1676 4609 2066 4610 2067 4610 1676 4610 2067 4611 1672 4611 1674 4611 2067 4612 1670 4612 1672 4612 2070 4613 1744 4613 1742 4613 2069 4614 1742 4614 1746 4614 2069 4615 2070 4615 1742 4615 2070 4616 1763 4616 1744 4616 2070 4617 1762 4617 1763 4617 1766 4618 1759 4618 1762 4618 1778 4619 1766 4619 1762 4619 2070 4620 1778 4620 1762 4620 1765 4621 1756 4621 1759 4621 1766 4622 1765 4622 1759 4622 1767 4623 1753 4623 1756 4623 1767 4624 1756 4624 1765 4624 1768 4625 1750 4625 1753 4625 1767 4626 1768 4626 1753 4626 2069 4627 1746 4627 1747 4627 2070 4628 1777 4628 1778 4628 2041 4629 1776 4629 1777 4629 2040 4630 1777 4630 2070 4630 2040 4631 2041 4631 1777 4631 2041 4632 1774 4632 1776 4632 2041 4633 1772 4633 1774 4633 2042 4634 1770 4634 1772 4634 2041 4635 2042 4635 1772 4635 2042 4636 1768 4636 1770 4636 1816 4637 1785 4637 1782 4637 1815 4638 1782 4638 1788 4638 1815 4639 1816 4639 1782 4639 1817 4640 1803 4640 1785 4640 1816 4641 1817 4641 1785 4641 2046 4642 1800 4642 1801 4642 2044 4643 2046 4643 1801 4643 2046 4644 1798 4644 1800 4644 2046 4645 1796 4645 1798 4645 2049 4646 1794 4646 1796 4646 2046 4647 2049 4647 1796 4647 2049 4648 1791 4648 1794 4648 1814 4649 1788 4649 1791 4649 1813 4650 1814 4650 1791 4650 2049 4651 1813 4651 1791 4651 1814 4652 1815 4652 1788 4652 2066 4653 1809 4653 1807 4653 2065 4654 1807 4654 1811 4654 2065 4655 2066 4655 1807 4655 2066 4656 1818 4656 1809 4656 2066 4657 1817 4657 1818 4657 2049 4658 1812 4658 1813 4658 2065 4659 1811 4659 1812 4659 2049 4660 2065 4660 1812 4660 2072 4661 1824 4661 1822 4661 2071 4662 1822 4662 1826 4662 2071 4663 2072 4663 1822 4663 2072 4664 1855 4664 1824 4664 2072 4665 1854 4665 1855 4665 2072 4666 1851 4666 1854 4666 2038 4667 1848 4667 1851 4667 2072 4668 2073 4668 1851 4668 2038 4669 1851 4669 2073 4669 2039 4670 1846 4670 1848 4670 2038 4671 2039 4671 1848 4671 2039 4672 1844 4672 1846 4672 2039 4673 1842 4673 1844 4673 2039 4674 1839 4674 1842 4674 2040 4675 1837 4675 1839 4675 2039 4676 2040 4676 1839 4676 2040 4677 1835 4677 1837 4677 2040 4678 1832 4678 1835 4678 2070 4679 1830 4679 1832 4679 2040 4680 2070 4680 1832 4680 2071 4681 1828 4681 1830 4681 2070 4682 2071 4682 1830 4682 2071 4683 1826 4683 1828 4683 2096 4684 1861 4684 1859 4684 2095 4685 1859 4685 1864 4685 2095 4686 2096 4686 1859 4686 2096 4687 1880 4687 1861 4687 2098 4688 1878 4688 1880 4688 2096 4689 2098 4689 1880 4689 2102 4690 1876 4690 1878 4690 2103 4691 2102 4691 1878 4691 2100 4692 2103 4692 1878 4692 2098 4693 2100 4693 1878 4693 2113 4694 1874 4694 1876 4694 2106 4695 2113 4695 1876 4695 2102 4696 2106 4696 1876 4696 2113 4697 1872 4697 1874 4697 2113 4698 1869 4698 1872 4698 2113 4699 1866 4699 1869 4699 2095 4700 1864 4700 1866 4700 2095 4701 1866 4701 2113 4701 2115 4702 1887 4702 1885 4702 2115 4703 1885 4703 1889 4703 2115 4704 1906 4704 1887 4704 2115 4705 1904 4705 1906 4705 2011 4706 1901 4706 1904 4706 2010 4707 1904 4707 2115 4707 2010 4708 2011 4708 1904 4708 2012 4709 1899 4709 1901 4709 2011 4710 2012 4710 1901 4710 2012 4711 1896 4711 1899 4711 2013 4712 1894 4712 1896 4712 2012 4713 2013 4713 1896 4713 2013 4714 1891 4714 1894 4714 2114 4715 1889 4715 1891 4715 2013 4716 2114 4716 1891 4716 2114 4717 2115 4717 1889 4717 2095 4718 1914 4718 1912 4718 2094 4719 1912 4719 1917 4719 2094 4720 2095 4720 1912 4720 2095 4721 1934 4721 1914 4721 2095 4722 1933 4722 1934 4722 1938 4723 1931 4723 1933 4723 1955 4724 1938 4724 1933 4724 2113 4725 1955 4725 1933 4725 2095 4726 2113 4726 1933 4726 1937 4727 1927 4727 1931 4727 1938 4728 1937 4728 1931 4728 2191 4729 1924 4729 1927 4729 2190 4730 1927 4730 1937 4730 2190 4731 2191 4731 1927 4731 2189 4732 1922 4732 1924 4732 2191 4733 2189 4733 1924 4733 2189 4734 1919 4734 1922 4734 2094 4735 1917 4735 1919 4735 2093 4736 2094 4736 1919 4736 2189 4737 2093 4737 1919 4737 2190 4738 1937 4738 1941 4738 2113 4739 1954 4739 1955 4739 2013 4740 1953 4740 1954 4740 2113 4741 2114 4741 1954 4741 2013 4742 1954 4742 2114 4742 2013 4743 1951 4743 1953 4743 2013 4744 1949 4744 1951 4744 2015 4745 1946 4745 1949 4745 2013 4746 2015 4746 1949 4746 2015 4747 1943 4747 1946 4747 2190 4748 1941 4748 1943 4748 2190 4749 1943 4749 2015 4749 2086 4750 1960 4750 1958 4750 2086 4751 1958 4751 1962 4751 2086 4752 1998 4752 1960 4752 2089 4753 1997 4753 1998 4753 2086 4754 2089 4754 1998 4754 2089 4755 1995 4755 1997 4755 2089 4756 1993 4756 1995 4756 2021 4757 1990 4757 1993 4757 2021 4758 1993 4758 2089 4758 2021 4759 1988 4759 1990 4759 2021 4760 1986 4760 1988 4760 2021 4761 1983 4761 1986 4761 2022 4762 1981 4762 1983 4762 2021 4763 2022 4763 1983 4763 2022 4764 1979 4764 1981 4764 2022 4765 1977 4765 1979 4765 2022 4766 1975 4766 1977 4766 2022 4767 1973 4767 1975 4767 2022 4768 1970 4768 1973 4768 2083 4769 1968 4769 1970 4769 2022 4770 2083 4770 1970 4770 2086 4771 1966 4771 1968 4771 2083 4772 2086 4772 1968 4772 2086 4773 1964 4773 1966 4773 2086 4774 1962 4774 1964 4774 2004 4775 2115 4775 2001 4775 2009 4776 2010 4776 2115 4776 2007 4777 2009 4777 2115 4777 2008 4778 2007 4778 2115 4778 2006 4779 2008 4779 2115 4779 2005 4780 2006 4780 2115 4780 2004 4781 2005 4781 2115 4781 2112 4782 2111 4782 2113 4782 2110 4783 2112 4783 2113 4783 2108 4784 2110 4784 2113 4784 2106 4785 2108 4785 2113 4785 2189 4786 2092 4786 2093 4786 2189 4787 2091 4787 2092 4787 2020 4788 2089 4788 2091 4788 2189 4789 2020 4789 2091 4789 2020 4790 2021 4790 2089 4790 2180 4791 2083 4791 2022 4791 2151 4792 2152 4792 2083 4792 2150 4793 2151 4793 2083 4793 2148 4794 2150 4794 2083 4794 2162 4795 2148 4795 2083 4795 2183 4796 2185 4796 2083 4796 2184 4797 2183 4797 2083 4797 2182 4798 2184 4798 2083 4798 2181 4799 2182 4799 2083 4799 2179 4800 2181 4800 2083 4800 2180 4801 2179 4801 2083 4801 2037 4802 2073 4802 2074 4802 2033 4803 2037 4803 2074 4803 2126 4804 2033 4804 2074 4804 2124 4805 2126 4805 2074 4805 2123 4806 2124 4806 2074 4806 2122 4807 2123 4807 2074 4807 2037 4808 2038 4808 2073 4808 2049 4809 2064 4809 2065 4809 2052 4810 2063 4810 2064 4810 2049 4811 2052 4811 2064 4811 2055 4812 2062 4812 2063 4812 2052 4813 2055 4813 2063 4813 2058 4814 2061 4814 2062 4814 2055 4815 2058 4815 2062 4815 2059 4816 2060 4816 2061 4816 2058 4817 2059 4817 2061 4817 2130 4818 2131 4818 2033 4818 2129 4819 2130 4819 2033 4819 2128 4820 2129 4820 2033 4820 2127 4821 2128 4821 2033 4821 2125 4822 2127 4822 2033 4822 2126 4823 2125 4823 2033 4823 2167 4824 2033 4824 2136 4824 2169 4825 2170 4825 2033 4825 2168 4826 2169 4826 2033 4826 2167 4827 2168 4827 2033 4827 2178 4828 2180 4828 2022 4828 2177 4829 2178 4829 2022 4829 2175 4830 2177 4830 2022 4830 2188 4831 2019 4831 2020 4831 2189 4832 2188 4832 2020 4832 2190 4833 2017 4833 2019 4833 2190 4834 2019 4834 2188 4834 2190 4835 2015 4835 2017 4835 2162 4836 2142 4836 2148 4836 2163 4837 2143 4837 2142 4837 2162 4838 2163 4838 2142 4838 2166 4839 2139 4839 2143 4839 2164 4840 2166 4840 2143 4840 2163 4841 2164 4841 2143 4841 2166 4842 2137 4842 2139 4842 2165 4843 2136 4843 2137 4843 2166 4844 2165 4844 2137 4844 2165 4845 2167 4845 2136 4845 2192 4846 2193 4846 2194 4846 2195 4847 2194 4847 2193 4847 2196 4848 2194 4848 2197 4848 2198 4849 2197 4849 2194 4849 2199 4850 2192 4850 2194 4850 2196 4851 2199 4851 2194 4851 2198 4852 2194 4852 2195 4852 2192 4853 2200 4853 2193 4853 2201 4854 2193 4854 2200 4854 2201 4855 2195 4855 2193 4855 2192 4856 2202 4856 2200 4856 2203 4857 2200 4857 2202 4857 2201 4858 2200 4858 2203 4858 2204 4859 2205 4859 2202 4859 2206 4860 2202 4860 2205 4860 2207 4861 2204 4861 2202 4861 2208 4862 2207 4862 2202 4862 2209 4863 2202 4863 2192 4863 2210 4864 2208 4864 2202 4864 2209 4865 2210 4865 2202 4865 2203 4866 2202 4866 2206 4866 2211 4867 2212 4867 2205 4867 2213 4868 2205 4868 2212 4868 2204 4869 2211 4869 2205 4869 2206 4870 2205 4870 2213 4870 2214 4871 2215 4871 2212 4871 2216 4872 2212 4872 2215 4872 2214 4873 2212 4873 2211 4873 2213 4874 2212 4874 2216 4874 2217 4875 2218 4875 2215 4875 2219 4876 2215 4876 2218 4876 2214 4877 2217 4877 2215 4877 2216 4878 2215 4878 2219 4878 2220 4879 2221 4879 2218 4879 2222 4880 2218 4880 2221 4880 2220 4881 2218 4881 2217 4881 2219 4882 2218 4882 2222 4882 2223 4883 2197 4883 2221 4883 2224 4884 2221 4884 2197 4884 2220 4885 2225 4885 2221 4885 2223 4886 2221 4886 2225 4886 2222 4887 2221 4887 2224 4887 2226 4888 2196 4888 2197 4888 2227 4889 2226 4889 2197 4889 2228 4890 2227 4890 2197 4890 2223 4891 2228 4891 2197 4891 2224 4892 2197 4892 2198 4892 2192 4893 2229 4893 2230 4893 2231 4894 2230 4894 2229 4894 2232 4895 2230 4895 2233 4895 2234 4896 2233 4896 2230 4896 2232 4897 2192 4897 2230 4897 2234 4898 2230 4898 2231 4898 2192 4899 2235 4899 2229 4899 2236 4900 2229 4900 2235 4900 2236 4901 2231 4901 2229 4901 2192 4902 2237 4902 2235 4902 2238 4903 2235 4903 2237 4903 2236 4904 2235 4904 2238 4904 2239 4905 2240 4905 2237 4905 2241 4906 2237 4906 2240 4906 2242 4907 2239 4907 2237 4907 2243 4908 2242 4908 2237 4908 2244 4909 2237 4909 2192 4909 2244 4910 2243 4910 2237 4910 2238 4911 2237 4911 2241 4911 2245 4912 2246 4912 2240 4912 2247 4913 2240 4913 2246 4913 2239 4914 2245 4914 2240 4914 2241 4915 2240 4915 2247 4915 2248 4916 2249 4916 2246 4916 2250 4917 2246 4917 2249 4917 2248 4918 2246 4918 2245 4918 2247 4919 2246 4919 2250 4919 2251 4920 2252 4920 2249 4920 2253 4921 2249 4921 2252 4921 2248 4922 2251 4922 2249 4922 2250 4923 2249 4923 2253 4923 2254 4924 2255 4924 2252 4924 2256 4925 2252 4925 2255 4925 2254 4926 2252 4926 2251 4926 2253 4927 2252 4927 2256 4927 2257 4928 2233 4928 2255 4928 2258 4929 2255 4929 2233 4929 2254 4930 2259 4930 2255 4930 2257 4931 2255 4931 2259 4931 2256 4932 2255 4932 2258 4932 2260 4933 2232 4933 2233 4933 2261 4934 2260 4934 2233 4934 2262 4935 2261 4935 2233 4935 2257 4936 2262 4936 2233 4936 2258 4937 2233 4937 2234 4937 2263 4938 2245 4938 2239 4938 2264 4939 2248 4939 2245 4939 2264 4940 2245 4940 2263 4940 2265 4941 2239 4941 2242 4941 2265 4942 2263 4942 2239 4942 2243 4943 2266 4943 2242 4943 2267 4944 2242 4944 2266 4944 2265 4945 2242 4945 2267 4945 2268 4946 2269 4946 2266 4946 2270 4947 2266 4947 2269 4947 2271 4948 2272 4948 2266 4948 2268 4949 2266 4949 2272 4949 2243 4950 2271 4950 2266 4950 2267 4951 2266 4951 2270 4951 2273 4952 2274 4952 2269 4952 2275 4953 2269 4953 2274 4953 2276 4954 2273 4954 2269 4954 2277 4955 2276 4955 2269 4955 2268 4956 2277 4956 2269 4956 2270 4957 2269 4957 2275 4957 2278 4958 2279 4958 2274 4958 2280 4959 2274 4959 2279 4959 2281 4960 2278 4960 2274 4960 2273 4961 2281 4961 2274 4961 2275 4962 2274 4962 2280 4962 2278 4963 2282 4963 2279 4963 2283 4964 2279 4964 2282 4964 2280 4965 2279 4965 2283 4965 2278 4966 2251 4966 2282 4966 2284 4967 2282 4967 2251 4967 2283 4968 2282 4968 2284 4968 2285 4969 2251 4969 2248 4969 2286 4970 2251 4970 2278 4970 2287 4971 2254 4971 2251 4971 2286 4972 2287 4972 2251 4972 2284 4973 2251 4973 2285 4973 2285 4974 2248 4974 2264 4974 2288 4975 2211 4975 2204 4975 2289 4976 2214 4976 2211 4976 2289 4977 2211 4977 2288 4977 2290 4978 2204 4978 2207 4978 2290 4979 2288 4979 2204 4979 2208 4980 2291 4980 2207 4980 2292 4981 2207 4981 2291 4981 2290 4982 2207 4982 2292 4982 2293 4983 2294 4983 2291 4983 2295 4984 2291 4984 2294 4984 2296 4985 2297 4985 2291 4985 2293 4986 2291 4986 2297 4986 2208 4987 2296 4987 2291 4987 2292 4988 2291 4988 2295 4988 2298 4989 2299 4989 2294 4989 2300 4990 2294 4990 2299 4990 2301 4991 2298 4991 2294 4991 2302 4992 2301 4992 2294 4992 2293 4993 2302 4993 2294 4993 2295 4994 2294 4994 2300 4994 2278 4995 2303 4995 2299 4995 2304 4996 2299 4996 2303 4996 2298 4997 2278 4997 2299 4997 2300 4998 2299 4998 2304 4998 2278 4999 2305 4999 2303 4999 2306 5000 2303 5000 2305 5000 2304 5001 2303 5001 2306 5001 2278 5002 2217 5002 2305 5002 2307 5003 2305 5003 2217 5003 2306 5004 2305 5004 2307 5004 2308 5005 2217 5005 2214 5005 2309 5006 2217 5006 2278 5006 2309 5007 2220 5007 2217 5007 2307 5008 2217 5008 2308 5008 2308 5009 2214 5009 2289 5009 2310 5010 2311 5010 2312 5010 2313 5011 2312 5011 2311 5011 2310 5012 2312 5012 2314 5012 2315 5013 2314 5013 2312 5013 2315 5014 2312 5014 2313 5014 2316 5015 2317 5015 2311 5015 2318 5016 2311 5016 2317 5016 2310 5017 2316 5017 2311 5017 2318 5018 2313 5018 2311 5018 2316 5019 2319 5019 2317 5019 2320 5020 2317 5020 2319 5020 2318 5021 2317 5021 2320 5021 2316 5022 2321 5022 2319 5022 2322 5023 2319 5023 2321 5023 2320 5024 2319 5024 2322 5024 2316 5025 2323 5025 2321 5025 2324 5026 2321 5026 2323 5026 2322 5027 2321 5027 2324 5027 2325 5028 2326 5028 2323 5028 2327 5029 2323 5029 2326 5029 2316 5030 2325 5030 2323 5030 2324 5031 2323 5031 2327 5031 2325 5032 2328 5032 2326 5032 2329 5033 2326 5033 2328 5033 2327 5034 2326 5034 2329 5034 2325 5035 2330 5035 2328 5035 2331 5036 2328 5036 2330 5036 2329 5037 2328 5037 2331 5037 2332 5038 2333 5038 2330 5038 2334 5039 2330 5039 2333 5039 2335 5040 2336 5040 2330 5040 2332 5041 2330 5041 2336 5041 2325 5042 2335 5042 2330 5042 2331 5043 2330 5043 2334 5043 2332 5044 2337 5044 2333 5044 2338 5045 2333 5045 2337 5045 2334 5046 2333 5046 2338 5046 2332 5047 2339 5047 2337 5047 2340 5048 2337 5048 2339 5048 2338 5049 2337 5049 2340 5049 2332 5050 2341 5050 2339 5050 2342 5051 2339 5051 2341 5051 2340 5052 2339 5052 2342 5052 2343 5053 2344 5053 2341 5053 2345 5054 2341 5054 2344 5054 2332 5055 2343 5055 2341 5055 2342 5056 2341 5056 2345 5056 2343 5057 2346 5057 2344 5057 2347 5058 2344 5058 2346 5058 2345 5059 2344 5059 2347 5059 2343 5060 2348 5060 2346 5060 2349 5061 2346 5061 2348 5061 2347 5062 2346 5062 2349 5062 2343 5063 2350 5063 2348 5063 2351 5064 2348 5064 2350 5064 2349 5065 2348 5065 2351 5065 2352 5066 2353 5066 2350 5066 2354 5067 2350 5067 2353 5067 2343 5068 2352 5068 2350 5068 2351 5069 2350 5069 2354 5069 2352 5070 2355 5070 2353 5070 2356 5071 2353 5071 2355 5071 2354 5072 2353 5072 2356 5072 2352 5073 2357 5073 2355 5073 2358 5074 2355 5074 2357 5074 2356 5075 2355 5075 2358 5075 2352 5076 2359 5076 2357 5076 2360 5077 2357 5077 2359 5077 2358 5078 2357 5078 2360 5078 2361 5079 2362 5079 2359 5079 2363 5080 2359 5080 2362 5080 2352 5081 2361 5081 2359 5081 2360 5082 2359 5082 2363 5082 2364 5083 2365 5083 2362 5083 2366 5084 2362 5084 2365 5084 2361 5085 2364 5085 2362 5085 2363 5086 2362 5086 2366 5086 2364 5087 2367 5087 2365 5087 2368 5088 2365 5088 2367 5088 2366 5089 2365 5089 2368 5089 2364 5090 2369 5090 2367 5090 2370 5091 2367 5091 2369 5091 2368 5092 2367 5092 2370 5092 2371 5093 2372 5093 2369 5093 2373 5094 2369 5094 2372 5094 2374 5095 2371 5095 2369 5095 2364 5096 2374 5096 2369 5096 2370 5097 2369 5097 2373 5097 2375 5098 2376 5098 2372 5098 2377 5099 2372 5099 2376 5099 2375 5100 2372 5100 2371 5100 2373 5101 2372 5101 2377 5101 2375 5102 2378 5102 2376 5102 2379 5103 2376 5103 2378 5103 2377 5104 2376 5104 2379 5104 2375 5105 2380 5105 2378 5105 2381 5106 2378 5106 2380 5106 2379 5107 2378 5107 2381 5107 2375 5108 2382 5108 2380 5108 2383 5109 2380 5109 2382 5109 2381 5110 2380 5110 2383 5110 2310 5111 2384 5111 2382 5111 2385 5112 2382 5112 2384 5112 2375 5113 2310 5113 2382 5113 2383 5114 2382 5114 2385 5114 2310 5115 2314 5115 2384 5115 2386 5116 2384 5116 2314 5116 2385 5117 2384 5117 2386 5117 2386 5118 2314 5118 2315 5118 2387 5119 2388 5119 2389 5119 2390 5120 2389 5120 2388 5120 2387 5121 2389 5121 2391 5121 2392 5122 2391 5122 2389 5122 2392 5123 2389 5123 2390 5123 2375 5124 2393 5124 2388 5124 2394 5125 2388 5125 2393 5125 2387 5126 2375 5126 2388 5126 2394 5127 2390 5127 2388 5127 2375 5128 2371 5128 2393 5128 2395 5129 2393 5129 2371 5129 2394 5130 2393 5130 2395 5130 2396 5131 2397 5131 2371 5131 2398 5132 2371 5132 2397 5132 2374 5133 2396 5133 2371 5133 2395 5134 2371 5134 2398 5134 2399 5135 2400 5135 2397 5135 2401 5136 2397 5136 2400 5136 2396 5137 2399 5137 2397 5137 2398 5138 2397 5138 2401 5138 2402 5139 2403 5139 2400 5139 2404 5140 2400 5140 2403 5140 2402 5141 2400 5141 2399 5141 2401 5142 2400 5142 2404 5142 2405 5143 2406 5143 2403 5143 2407 5144 2403 5144 2406 5144 2402 5145 2405 5145 2403 5145 2404 5146 2403 5146 2407 5146 2408 5147 2409 5147 2406 5147 2410 5148 2406 5148 2409 5148 2408 5149 2406 5149 2405 5149 2407 5150 2406 5150 2410 5150 2387 5151 2391 5151 2409 5151 2411 5152 2409 5152 2391 5152 2412 5153 2409 5153 2408 5153 2412 5154 2387 5154 2409 5154 2410 5155 2409 5155 2411 5155 2411 5156 2391 5156 2392 5156 2413 5157 2399 5157 2396 5157 2414 5158 2402 5158 2399 5158 2414 5159 2399 5159 2413 5159 2415 5160 2396 5160 2374 5160 2415 5161 2413 5161 2396 5161 2416 5162 2374 5162 2364 5162 2415 5163 2374 5163 2416 5163 2361 5164 2417 5164 2364 5164 2418 5165 2364 5165 2417 5165 2416 5166 2364 5166 2418 5166 2361 5167 2419 5167 2417 5167 2420 5168 2417 5168 2419 5168 2418 5169 2417 5169 2420 5169 2408 5170 2421 5170 2419 5170 2422 5171 2419 5171 2421 5171 2361 5172 2408 5172 2419 5172 2420 5173 2419 5173 2422 5173 2408 5174 2423 5174 2421 5174 2424 5175 2421 5175 2423 5175 2422 5176 2421 5176 2424 5176 2408 5177 2405 5177 2423 5177 2425 5178 2423 5178 2405 5178 2424 5179 2423 5179 2425 5179 2426 5180 2405 5180 2402 5180 2425 5181 2405 5181 2426 5181 2426 5182 2402 5182 2414 5182 2427 5183 2428 5183 2429 5183 2430 5184 2429 5184 2428 5184 2431 5185 2429 5185 2432 5185 2433 5186 2432 5186 2429 5186 2431 5187 2427 5187 2429 5187 2433 5188 2429 5188 2430 5188 2434 5189 2435 5189 2428 5189 2436 5190 2428 5190 2435 5190 2427 5191 2434 5191 2428 5191 2436 5192 2430 5192 2428 5192 2437 5193 2438 5193 2435 5193 2439 5194 2435 5194 2438 5194 2437 5195 2435 5195 2434 5195 2436 5196 2435 5196 2439 5196 2440 5197 2441 5197 2438 5197 2442 5198 2438 5198 2441 5198 2437 5199 2440 5199 2438 5199 2439 5200 2438 5200 2442 5200 2440 5201 2443 5201 2441 5201 2444 5202 2441 5202 2443 5202 2442 5203 2441 5203 2444 5203 2332 5204 2445 5204 2443 5204 2446 5205 2443 5205 2445 5205 2440 5206 2332 5206 2443 5206 2444 5207 2443 5207 2446 5207 2332 5208 2447 5208 2445 5208 2448 5209 2445 5209 2447 5209 2446 5210 2445 5210 2448 5210 2332 5211 2336 5211 2447 5211 2449 5212 2447 5212 2336 5212 2448 5213 2447 5213 2449 5213 2450 5214 2432 5214 2336 5214 2451 5215 2336 5215 2432 5215 2335 5216 2450 5216 2336 5216 2449 5217 2336 5217 2451 5217 2450 5218 2431 5218 2432 5218 2451 5219 2432 5219 2433 5219 2452 5220 2453 5220 2454 5220 2455 5221 2454 5221 2453 5221 2452 5222 2454 5222 2456 5222 2457 5223 2456 5223 2454 5223 2457 5224 2454 5224 2455 5224 2437 5225 2458 5225 2453 5225 2459 5226 2453 5226 2458 5226 2452 5227 2437 5227 2453 5227 2459 5228 2455 5228 2453 5228 2437 5229 2434 5229 2458 5229 2460 5230 2458 5230 2434 5230 2459 5231 2458 5231 2460 5231 2461 5232 2434 5232 2427 5232 2460 5233 2434 5233 2461 5233 2462 5234 2427 5234 2431 5234 2461 5235 2427 5235 2462 5235 2463 5236 2431 5236 2450 5236 2462 5237 2431 5237 2463 5237 2464 5238 2450 5238 2335 5238 2463 5239 2450 5239 2464 5239 2465 5240 2335 5240 2325 5240 2464 5241 2335 5241 2465 5241 2452 5242 2456 5242 2325 5242 2466 5243 2325 5243 2456 5243 2316 5244 2452 5244 2325 5244 2465 5245 2325 5245 2466 5245 2466 5246 2456 5246 2457 5246 2467 5247 2468 5247 2469 5247 2470 5248 2469 5248 2468 5248 2467 5249 2469 5249 2471 5249 2472 5250 2471 5250 2469 5250 2472 5251 2469 5251 2470 5251 2412 5252 2473 5252 2468 5252 2474 5253 2468 5253 2473 5253 2467 5254 2412 5254 2468 5254 2474 5255 2470 5255 2468 5255 2412 5256 2475 5256 2473 5256 2476 5257 2473 5257 2475 5257 2474 5258 2473 5258 2476 5258 2412 5259 2477 5259 2475 5259 2478 5260 2475 5260 2477 5260 2476 5261 2475 5261 2478 5261 2408 5262 2479 5262 2477 5262 2480 5263 2477 5263 2479 5263 2412 5264 2408 5264 2477 5264 2478 5265 2477 5265 2480 5265 2481 5266 2482 5266 2479 5266 2483 5267 2479 5267 2482 5267 2408 5268 2481 5268 2479 5268 2480 5269 2479 5269 2483 5269 2481 5270 2484 5270 2482 5270 2485 5271 2482 5271 2484 5271 2483 5272 2482 5272 2485 5272 2481 5273 2486 5273 2484 5273 2487 5274 2484 5274 2486 5274 2485 5275 2484 5275 2487 5275 2488 5276 2489 5276 2486 5276 2490 5277 2486 5277 2489 5277 2481 5278 2488 5278 2486 5278 2487 5279 2486 5279 2490 5279 2488 5280 2491 5280 2489 5280 2492 5281 2489 5281 2491 5281 2490 5282 2489 5282 2492 5282 2488 5283 2493 5283 2491 5283 2494 5284 2491 5284 2493 5284 2492 5285 2491 5285 2494 5285 2488 5286 2495 5286 2493 5286 2496 5287 2493 5287 2495 5287 2494 5288 2493 5288 2496 5288 2497 5289 2498 5289 2495 5289 2499 5290 2495 5290 2498 5290 2488 5291 2500 5291 2495 5291 2497 5292 2495 5292 2500 5292 2496 5293 2495 5293 2499 5293 2467 5294 2501 5294 2498 5294 2502 5295 2498 5295 2501 5295 2497 5296 2467 5296 2498 5296 2499 5297 2498 5297 2502 5297 2467 5298 2471 5298 2501 5298 2503 5299 2501 5299 2471 5299 2502 5300 2501 5300 2503 5300 2503 5301 2471 5301 2472 5301 2504 5302 2505 5302 2506 5302 2507 5303 2506 5303 2505 5303 2504 5304 2506 5304 2508 5304 2509 5305 2508 5305 2506 5305 2509 5306 2506 5306 2507 5306 2510 5307 2511 5307 2505 5307 2512 5308 2505 5308 2511 5308 2504 5309 2510 5309 2505 5309 2512 5310 2507 5310 2505 5310 2510 5311 2513 5311 2511 5311 2514 5312 2511 5312 2513 5312 2512 5313 2511 5313 2514 5313 2515 5314 2516 5314 2513 5314 2517 5315 2513 5315 2516 5315 2515 5316 2513 5316 2510 5316 2514 5317 2513 5317 2517 5317 2518 5318 2519 5318 2516 5318 2520 5319 2516 5319 2519 5319 2515 5320 2518 5320 2516 5320 2517 5321 2516 5321 2520 5321 2518 5322 2521 5322 2519 5322 2522 5323 2519 5323 2521 5323 2520 5324 2519 5324 2522 5324 2518 5325 2523 5325 2521 5325 2524 5326 2521 5326 2523 5326 2522 5327 2521 5327 2524 5327 2518 5328 2525 5328 2523 5328 2526 5329 2523 5329 2525 5329 2524 5330 2523 5330 2526 5330 2527 5331 2508 5331 2525 5331 2528 5332 2525 5332 2508 5332 2529 5333 2527 5333 2525 5333 2518 5334 2529 5334 2525 5334 2526 5335 2525 5335 2528 5335 2527 5336 2504 5336 2508 5336 2528 5337 2508 5337 2509 5337 2530 5338 2531 5338 2532 5338 2533 5339 2532 5339 2531 5339 2530 5340 2532 5340 2534 5340 2535 5341 2534 5341 2532 5341 2535 5342 2532 5342 2533 5342 2530 5343 2536 5343 2531 5343 2537 5344 2531 5344 2536 5344 2537 5345 2533 5345 2531 5345 2530 5346 2538 5346 2536 5346 2539 5347 2536 5347 2538 5347 2537 5348 2536 5348 2539 5348 2540 5349 2541 5349 2538 5349 2542 5350 2538 5350 2541 5350 2530 5351 2540 5351 2538 5351 2539 5352 2538 5352 2542 5352 2540 5353 2543 5353 2541 5353 2544 5354 2541 5354 2543 5354 2542 5355 2541 5355 2544 5355 2545 5356 2546 5356 2543 5356 2547 5357 2543 5357 2546 5357 2540 5358 2545 5358 2543 5358 2544 5359 2543 5359 2547 5359 2545 5360 2548 5360 2546 5360 2549 5361 2546 5361 2548 5361 2547 5362 2546 5362 2549 5362 2550 5363 2551 5363 2548 5363 2552 5364 2548 5364 2551 5364 2545 5365 2550 5365 2548 5365 2549 5366 2548 5366 2552 5366 2553 5367 2534 5367 2551 5367 2554 5368 2551 5368 2534 5368 2555 5369 2553 5369 2551 5369 2556 5370 2555 5370 2551 5370 2550 5371 2556 5371 2551 5371 2552 5372 2551 5372 2554 5372 2553 5373 2557 5373 2534 5373 2530 5374 2534 5374 2557 5374 2554 5375 2534 5375 2535 5375 2510 5376 2558 5376 2559 5376 2560 5377 2559 5377 2558 5377 2510 5378 2559 5378 2561 5378 2562 5379 2561 5379 2559 5379 2562 5380 2559 5380 2560 5380 2563 5381 2564 5381 2558 5381 2565 5382 2558 5382 2564 5382 2510 5383 2563 5383 2558 5383 2565 5384 2560 5384 2558 5384 2563 5385 2566 5385 2564 5385 2567 5386 2564 5386 2566 5386 2565 5387 2564 5387 2567 5387 2568 5388 2569 5388 2566 5388 2570 5389 2566 5389 2569 5389 2568 5390 2566 5390 2563 5390 2567 5391 2566 5391 2570 5391 2568 5392 2571 5392 2569 5392 2572 5393 2569 5393 2571 5393 2570 5394 2569 5394 2572 5394 2573 5395 2574 5395 2571 5395 2575 5396 2571 5396 2574 5396 2573 5397 2571 5397 2576 5397 2568 5398 2576 5398 2571 5398 2572 5399 2571 5399 2575 5399 2577 5400 2578 5400 2574 5400 2579 5401 2574 5401 2578 5401 2573 5402 2577 5402 2574 5402 2575 5403 2574 5403 2579 5403 2530 5404 2580 5404 2578 5404 2581 5405 2578 5405 2580 5405 2530 5406 2578 5406 2577 5406 2579 5407 2578 5407 2581 5407 2510 5408 2561 5408 2580 5408 2582 5409 2580 5409 2561 5409 2515 5410 2510 5410 2580 5410 2530 5411 2515 5411 2580 5411 2581 5412 2580 5412 2582 5412 2582 5413 2561 5413 2562 5413 2583 5414 2584 5414 2576 5414 2585 5415 2576 5415 2584 5415 2586 5416 2573 5416 2576 5416 2568 5417 2583 5417 2576 5417 2586 5418 2576 5418 2585 5418 2587 5419 2588 5419 2584 5419 2589 5420 2584 5420 2588 5420 2583 5421 2587 5421 2584 5421 2589 5422 2585 5422 2584 5422 2587 5423 2590 5423 2588 5423 2591 5424 2588 5424 2590 5424 2589 5425 2588 5425 2591 5425 2592 5426 2593 5426 2590 5426 2594 5427 2590 5427 2593 5427 2595 5428 2592 5428 2590 5428 2587 5429 2595 5429 2590 5429 2591 5430 2590 5430 2594 5430 2592 5431 2596 5431 2593 5431 2597 5432 2593 5432 2596 5432 2594 5433 2593 5433 2597 5433 2540 5434 2598 5434 2596 5434 2599 5435 2596 5435 2598 5435 2592 5436 2540 5436 2596 5436 2597 5437 2596 5437 2599 5437 2540 5438 2600 5438 2598 5438 2601 5439 2598 5439 2600 5439 2599 5440 2598 5440 2601 5440 2540 5441 2577 5441 2600 5441 2602 5442 2600 5442 2577 5442 2601 5443 2600 5443 2602 5443 2603 5444 2577 5444 2573 5444 2530 5445 2577 5445 2540 5445 2602 5446 2577 5446 2603 5446 2603 5447 2573 5447 2586 5447 2199 5448 2604 5448 2605 5448 2606 5449 2605 5449 2604 5449 2199 5450 2605 5450 2607 5450 2608 5451 2607 5451 2605 5451 2608 5452 2605 5452 2606 5452 2199 5453 2609 5453 2604 5453 2610 5454 2604 5454 2609 5454 2610 5455 2606 5455 2604 5455 2199 5456 2611 5456 2609 5456 2612 5457 2609 5457 2611 5457 2610 5458 2609 5458 2612 5458 2199 5459 2613 5459 2611 5459 2614 5460 2611 5460 2613 5460 2612 5461 2611 5461 2614 5461 2199 5462 2615 5462 2613 5462 2616 5463 2613 5463 2615 5463 2614 5464 2613 5464 2616 5464 2278 5465 2617 5465 2615 5465 2618 5466 2615 5466 2617 5466 2199 5467 2278 5467 2615 5467 2616 5468 2615 5468 2618 5468 2619 5469 2620 5469 2617 5469 2621 5470 2617 5470 2620 5470 2278 5471 2619 5471 2617 5471 2618 5472 2617 5472 2621 5472 2619 5473 2622 5473 2620 5473 2623 5474 2620 5474 2622 5474 2621 5475 2620 5475 2623 5475 2619 5476 2624 5476 2622 5476 2625 5477 2622 5477 2624 5477 2623 5478 2622 5478 2625 5478 2619 5479 2626 5479 2624 5479 2627 5480 2624 5480 2626 5480 2625 5481 2624 5481 2627 5481 2619 5482 2628 5482 2626 5482 2629 5483 2626 5483 2628 5483 2627 5484 2626 5484 2629 5484 2619 5485 2630 5485 2628 5485 2631 5486 2628 5486 2630 5486 2629 5487 2628 5487 2631 5487 2632 5488 2633 5488 2630 5488 2634 5489 2630 5489 2633 5489 2619 5490 2632 5490 2630 5490 2631 5491 2630 5491 2634 5491 2632 5492 2635 5492 2633 5492 2636 5493 2633 5493 2635 5493 2634 5494 2633 5494 2636 5494 2632 5495 2637 5495 2635 5495 2638 5496 2635 5496 2637 5496 2636 5497 2635 5497 2638 5497 2639 5498 2640 5498 2637 5498 2641 5499 2637 5499 2640 5499 2639 5500 2637 5500 2632 5500 2638 5501 2637 5501 2641 5501 2639 5502 2642 5502 2640 5502 2643 5503 2640 5503 2642 5503 2641 5504 2640 5504 2643 5504 2639 5505 2644 5505 2642 5505 2645 5506 2642 5506 2644 5506 2643 5507 2642 5507 2645 5507 2639 5508 2607 5508 2644 5508 2646 5509 2644 5509 2607 5509 2645 5510 2644 5510 2646 5510 2639 5511 2199 5511 2607 5511 2646 5512 2607 5512 2608 5512 2530 5513 2647 5513 2648 5513 2649 5514 2648 5514 2647 5514 2650 5515 2530 5515 2648 5515 2649 5516 2650 5516 2648 5516 2530 5517 2651 5517 2647 5517 2652 5518 2647 5518 2651 5518 2652 5519 2649 5519 2647 5519 2530 5520 2557 5520 2651 5520 2653 5521 2651 5521 2557 5521 2652 5522 2651 5522 2653 5522 2654 5523 2557 5523 2553 5523 2653 5524 2557 5524 2654 5524 2655 5525 2553 5525 2555 5525 2656 5526 2553 5526 2655 5526 2654 5527 2553 5527 2656 5527 2655 5528 2555 5528 2556 5528 2657 5529 2556 5529 2550 5529 2655 5530 2556 5530 2657 5530 2658 5531 2550 5531 2545 5531 2657 5532 2550 5532 2658 5532 2659 5533 2545 5533 2540 5533 2658 5534 2545 5534 2659 5534 2660 5535 2540 5535 2592 5535 2659 5536 2540 5536 2660 5536 2661 5537 2592 5537 2595 5537 2660 5538 2592 5538 2661 5538 2587 5539 2662 5539 2595 5539 2663 5540 2595 5540 2662 5540 2661 5541 2595 5541 2663 5541 2587 5542 2664 5542 2662 5542 2665 5543 2662 5543 2664 5543 2663 5544 2662 5544 2665 5544 2666 5545 2632 5545 2664 5545 2667 5546 2664 5546 2632 5546 2587 5547 2666 5547 2664 5547 2665 5548 2664 5548 2667 5548 2668 5549 2632 5549 2619 5549 2666 5550 2639 5550 2632 5550 2667 5551 2632 5551 2668 5551 2669 5552 2619 5552 2278 5552 2668 5553 2619 5553 2669 5553 2670 5554 2278 5554 2281 5554 2671 5555 2278 5555 2199 5555 2672 5556 2286 5556 2278 5556 2673 5557 2672 5557 2278 5557 2674 5558 2673 5558 2278 5558 2298 5559 2674 5559 2278 5559 2675 5560 2309 5560 2278 5560 2676 5561 2675 5561 2278 5561 2677 5562 2676 5562 2278 5562 2678 5563 2677 5563 2278 5563 2679 5564 2678 5564 2278 5564 2671 5565 2679 5565 2278 5565 2669 5566 2278 5566 2670 5566 2680 5567 2500 5567 2281 5567 2681 5568 2281 5568 2500 5568 2192 5569 2680 5569 2281 5569 2682 5570 2192 5570 2281 5570 2683 5571 2682 5571 2281 5571 2684 5572 2683 5572 2281 5572 2273 5573 2684 5573 2281 5573 2670 5574 2281 5574 2681 5574 2685 5575 2500 5575 2488 5575 2680 5576 2497 5576 2500 5576 2681 5577 2500 5577 2685 5577 2686 5578 2488 5578 2481 5578 2685 5579 2488 5579 2686 5579 2687 5580 2481 5580 2408 5580 2686 5581 2481 5581 2687 5581 2688 5582 2408 5582 2361 5582 2687 5583 2408 5583 2688 5583 2689 5584 2361 5584 2352 5584 2688 5585 2361 5585 2689 5585 2690 5586 2352 5586 2343 5586 2689 5587 2352 5587 2690 5587 2691 5588 2343 5588 2332 5588 2690 5589 2343 5589 2691 5589 2692 5590 2332 5590 2440 5590 2691 5591 2332 5591 2692 5591 2437 5592 2693 5592 2440 5592 2694 5593 2440 5593 2693 5593 2692 5594 2440 5594 2694 5594 2695 5595 2696 5595 2693 5595 2697 5596 2693 5596 2696 5596 2437 5597 2695 5597 2693 5597 2694 5598 2693 5598 2697 5598 2698 5599 2699 5599 2696 5599 2700 5600 2696 5600 2699 5600 2695 5601 2698 5601 2696 5601 2697 5602 2696 5602 2700 5602 2701 5603 2702 5603 2699 5603 2703 5604 2699 5604 2702 5604 2698 5605 2701 5605 2699 5605 2700 5606 2699 5606 2703 5606 2704 5607 2705 5607 2702 5607 2706 5608 2702 5608 2705 5608 2701 5609 2704 5609 2702 5609 2703 5610 2702 5610 2706 5610 2707 5611 2705 5611 2704 5611 2706 5612 2705 5612 2707 5612 2708 5613 2704 5613 2701 5613 2707 5614 2704 5614 2708 5614 2709 5615 2701 5615 2698 5615 2708 5616 2701 5616 2709 5616 2710 5617 2698 5617 2695 5617 2709 5618 2698 5618 2710 5618 2711 5619 2695 5619 2437 5619 2710 5620 2695 5620 2711 5620 2712 5621 2437 5621 2452 5621 2711 5622 2437 5622 2712 5622 2713 5623 2452 5623 2316 5623 2712 5624 2452 5624 2713 5624 2714 5625 2316 5625 2310 5625 2713 5626 2316 5626 2714 5626 2715 5627 2310 5627 2375 5627 2714 5628 2310 5628 2715 5628 2716 5629 2375 5629 2387 5629 2715 5630 2375 5630 2716 5630 2717 5631 2387 5631 2412 5631 2716 5632 2387 5632 2717 5632 2718 5633 2412 5633 2467 5633 2717 5634 2412 5634 2718 5634 2719 5635 2467 5635 2497 5635 2718 5636 2467 5636 2719 5636 2720 5637 2497 5637 2680 5637 2719 5638 2497 5638 2720 5638 2721 5639 2680 5639 2192 5639 2720 5640 2680 5640 2721 5640 2722 5641 2192 5641 2199 5641 2723 5642 2244 5642 2192 5642 2724 5643 2723 5643 2192 5643 2725 5644 2724 5644 2192 5644 2726 5645 2725 5645 2192 5645 2727 5646 2726 5646 2192 5646 2682 5647 2727 5647 2192 5647 2728 5648 2192 5648 2232 5648 2729 5649 2209 5649 2192 5649 2730 5650 2729 5650 2192 5650 2728 5651 2730 5651 2192 5651 2721 5652 2192 5652 2722 5652 2731 5653 2199 5653 2639 5653 2732 5654 2671 5654 2199 5654 2733 5655 2732 5655 2199 5655 2196 5656 2733 5656 2199 5656 2722 5657 2199 5657 2731 5657 2734 5658 2639 5658 2666 5658 2731 5659 2639 5659 2734 5659 2735 5660 2736 5660 2666 5660 2737 5661 2666 5661 2736 5661 2735 5662 2666 5662 2587 5662 2734 5663 2666 5663 2737 5663 2568 5664 2738 5664 2736 5664 2739 5665 2736 5665 2738 5665 2735 5666 2568 5666 2736 5666 2737 5667 2736 5667 2739 5667 2568 5668 2563 5668 2738 5668 2740 5669 2738 5669 2563 5669 2739 5670 2738 5670 2740 5670 2741 5671 2563 5671 2510 5671 2740 5672 2563 5672 2741 5672 2742 5673 2510 5673 2504 5673 2741 5674 2510 5674 2742 5674 2743 5675 2504 5675 2527 5675 2742 5676 2504 5676 2743 5676 2744 5677 2527 5677 2529 5677 2743 5678 2527 5678 2744 5678 2518 5679 2745 5679 2529 5679 2746 5680 2529 5680 2745 5680 2744 5681 2529 5681 2746 5681 2518 5682 2747 5682 2745 5682 2748 5683 2745 5683 2747 5683 2746 5684 2745 5684 2748 5684 2518 5685 2749 5685 2747 5685 2750 5686 2747 5686 2749 5686 2751 5687 2747 5687 2750 5687 2748 5688 2747 5688 2751 5688 2518 5689 2752 5689 2749 5689 2750 5690 2749 5690 2752 5690 2518 5691 2753 5691 2752 5691 2754 5692 2752 5692 2753 5692 2750 5693 2752 5693 2754 5693 2518 5694 2755 5694 2753 5694 2756 5695 2753 5695 2755 5695 2754 5696 2753 5696 2756 5696 2518 5697 2757 5697 2755 5697 2758 5698 2755 5698 2757 5698 2756 5699 2755 5699 2758 5699 2759 5700 2757 5700 2518 5700 2760 5701 2757 5701 2759 5701 2758 5702 2757 5702 2760 5702 2759 5703 2518 5703 2515 5703 2761 5704 2515 5704 2530 5704 2759 5705 2515 5705 2761 5705 2762 5706 2530 5706 2650 5706 2761 5707 2530 5707 2762 5707 2763 5708 2650 5708 2649 5708 2762 5709 2650 5709 2763 5709 2764 5710 2272 5710 2271 5710 2765 5711 2268 5711 2272 5711 2765 5712 2272 5712 2766 5712 2764 5713 2766 5713 2272 5713 2764 5714 2271 5714 2243 5714 2767 5715 2243 5715 2244 5715 2764 5716 2243 5716 2767 5716 2768 5717 2244 5717 2723 5717 2767 5718 2244 5718 2768 5718 2769 5719 2723 5719 2724 5719 2768 5720 2723 5720 2769 5720 2770 5721 2724 5721 2725 5721 2769 5722 2724 5722 2770 5722 2771 5723 2725 5723 2726 5723 2770 5724 2725 5724 2771 5724 2772 5725 2726 5725 2727 5725 2771 5726 2726 5726 2772 5726 2773 5727 2727 5727 2682 5727 2774 5728 2727 5728 2773 5728 2772 5729 2727 5729 2774 5729 2773 5730 2682 5730 2683 5730 2775 5731 2683 5731 2684 5731 2773 5732 2683 5732 2775 5732 2776 5733 2684 5733 2273 5733 2775 5734 2684 5734 2776 5734 2777 5735 2273 5735 2276 5735 2776 5736 2273 5736 2777 5736 2778 5737 2276 5737 2277 5737 2777 5738 2276 5738 2778 5738 2779 5739 2277 5739 2268 5739 2778 5740 2277 5740 2779 5740 2779 5741 2268 5741 2765 5741 2780 5742 2259 5742 2254 5742 2780 5743 2257 5743 2259 5743 2781 5744 2254 5744 2287 5744 2781 5745 2780 5745 2254 5745 2782 5746 2287 5746 2286 5746 2781 5747 2287 5747 2782 5747 2783 5748 2286 5748 2672 5748 2782 5749 2286 5749 2783 5749 2784 5750 2672 5750 2673 5750 2783 5751 2672 5751 2784 5751 2785 5752 2673 5752 2674 5752 2784 5753 2673 5753 2785 5753 2298 5754 2786 5754 2674 5754 2787 5755 2674 5755 2786 5755 2785 5756 2674 5756 2787 5756 2788 5757 2789 5757 2786 5757 2790 5758 2786 5758 2789 5758 2298 5759 2788 5759 2786 5759 2791 5760 2786 5760 2790 5760 2787 5761 2786 5761 2791 5761 2792 5762 2793 5762 2789 5762 2790 5763 2789 5763 2793 5763 2794 5764 2792 5764 2789 5764 2788 5765 2794 5765 2789 5765 2792 5766 2795 5766 2793 5766 2796 5767 2793 5767 2795 5767 2790 5768 2793 5768 2796 5768 2797 5769 2232 5769 2795 5769 2798 5770 2795 5770 2232 5770 2792 5771 2797 5771 2795 5771 2796 5772 2795 5772 2798 5772 2799 5773 2232 5773 2260 5773 2797 5774 2728 5774 2232 5774 2798 5775 2232 5775 2799 5775 2800 5776 2260 5776 2261 5776 2799 5777 2260 5777 2800 5777 2801 5778 2261 5778 2262 5778 2800 5779 2261 5779 2801 5779 2802 5780 2262 5780 2257 5780 2801 5781 2262 5781 2802 5781 2803 5782 2257 5782 2780 5782 2802 5783 2257 5783 2803 5783 2804 5784 2297 5784 2296 5784 2805 5785 2293 5785 2297 5785 2805 5786 2297 5786 2806 5786 2804 5787 2806 5787 2297 5787 2804 5788 2296 5788 2208 5788 2807 5789 2208 5789 2210 5789 2804 5790 2208 5790 2807 5790 2808 5791 2210 5791 2209 5791 2807 5792 2210 5792 2808 5792 2809 5793 2209 5793 2729 5793 2808 5794 2209 5794 2809 5794 2810 5795 2729 5795 2730 5795 2809 5796 2729 5796 2810 5796 2811 5797 2730 5797 2728 5797 2810 5798 2730 5798 2811 5798 2812 5799 2728 5799 2797 5799 2811 5800 2728 5800 2812 5800 2813 5801 2797 5801 2792 5801 2814 5802 2797 5802 2813 5802 2812 5803 2797 5803 2814 5803 2813 5804 2792 5804 2794 5804 2815 5805 2794 5805 2788 5805 2813 5806 2794 5806 2815 5806 2816 5807 2788 5807 2298 5807 2815 5808 2788 5808 2816 5808 2817 5809 2298 5809 2301 5809 2816 5810 2298 5810 2817 5810 2818 5811 2301 5811 2302 5811 2817 5812 2301 5812 2818 5812 2819 5813 2302 5813 2293 5813 2818 5814 2302 5814 2819 5814 2819 5815 2293 5815 2805 5815 2820 5816 2225 5816 2220 5816 2820 5817 2223 5817 2225 5817 2821 5818 2220 5818 2309 5818 2821 5819 2820 5819 2220 5819 2822 5820 2309 5820 2675 5820 2821 5821 2309 5821 2822 5821 2823 5822 2675 5822 2676 5822 2824 5823 2675 5823 2823 5823 2822 5824 2675 5824 2824 5824 2823 5825 2676 5825 2677 5825 2825 5826 2677 5826 2678 5826 2823 5827 2677 5827 2825 5827 2826 5828 2678 5828 2679 5828 2825 5829 2678 5829 2826 5829 2827 5830 2679 5830 2671 5830 2828 5831 2679 5831 2827 5831 2826 5832 2679 5832 2828 5832 2827 5833 2671 5833 2732 5833 2829 5834 2732 5834 2733 5834 2827 5835 2732 5835 2829 5835 2830 5836 2733 5836 2196 5836 2829 5837 2733 5837 2830 5837 2831 5838 2196 5838 2226 5838 2832 5839 2196 5839 2831 5839 2830 5840 2196 5840 2832 5840 2831 5841 2226 5841 2227 5841 2833 5842 2227 5842 2228 5842 2831 5843 2227 5843 2833 5843 2834 5844 2228 5844 2223 5844 2833 5845 2228 5845 2834 5845 2835 5846 2223 5846 2820 5846 2834 5847 2223 5847 2835 5847 2836 5848 2587 5848 2583 5848 2837 5849 2735 5849 2587 5849 2837 5850 2587 5850 2836 5850 2838 5851 2583 5851 2568 5851 2838 5852 2836 5852 2583 5852 2839 5853 2568 5853 2735 5853 2838 5854 2568 5854 2839 5854 2839 5855 2735 5855 2837 5855 2731 5856 2198 5856 2195 5856 2810 5857 2195 5857 2201 5857 2810 5858 2731 5858 2195 5858 2731 5859 2224 5859 2198 5859 2731 5860 2222 5860 2224 5860 2289 5861 2219 5861 2222 5861 2308 5862 2289 5862 2222 5862 2834 5863 2308 5863 2222 5863 2833 5864 2222 5864 2731 5864 2833 5865 2834 5865 2222 5865 2288 5866 2216 5866 2219 5866 2289 5867 2288 5867 2219 5867 2290 5868 2213 5868 2216 5868 2290 5869 2216 5869 2288 5869 2292 5870 2206 5870 2213 5870 2290 5871 2292 5871 2213 5871 2805 5872 2203 5872 2206 5872 2805 5873 2206 5873 2292 5873 2807 5874 2201 5874 2203 5874 2805 5875 2806 5875 2203 5875 2804 5876 2203 5876 2806 5876 2804 5877 2807 5877 2203 5877 2809 5878 2810 5878 2201 5878 2808 5879 2809 5879 2201 5879 2807 5880 2808 5880 2201 5880 2731 5881 2234 5881 2231 5881 2770 5882 2231 5882 2236 5882 2722 5883 2731 5883 2231 5883 2770 5884 2722 5884 2231 5884 2731 5885 2258 5885 2234 5885 2731 5886 2256 5886 2258 5886 2264 5887 2253 5887 2256 5887 2285 5888 2264 5888 2256 5888 2802 5889 2285 5889 2256 5889 2800 5890 2256 5890 2731 5890 2801 5891 2802 5891 2256 5891 2800 5892 2801 5892 2256 5892 2263 5893 2250 5893 2253 5893 2264 5894 2263 5894 2253 5894 2265 5895 2247 5895 2250 5895 2265 5896 2250 5896 2263 5896 2267 5897 2241 5897 2247 5897 2265 5898 2267 5898 2247 5898 2765 5899 2238 5899 2241 5899 2765 5900 2241 5900 2267 5900 2767 5901 2236 5901 2238 5901 2765 5902 2766 5902 2238 5902 2764 5903 2238 5903 2766 5903 2764 5904 2767 5904 2238 5904 2769 5905 2770 5905 2236 5905 2768 5906 2769 5906 2236 5906 2767 5907 2768 5907 2236 5907 2802 5908 2284 5908 2285 5908 2780 5909 2283 5909 2284 5909 2803 5910 2780 5910 2284 5910 2802 5911 2803 5911 2284 5911 2784 5912 2280 5912 2283 5912 2781 5913 2283 5913 2780 5913 2783 5914 2784 5914 2283 5914 2782 5915 2783 5915 2283 5915 2781 5916 2782 5916 2283 5916 2681 5917 2275 5917 2280 5917 2784 5918 2681 5918 2280 5918 2681 5919 2270 5919 2275 5919 2681 5920 2267 5920 2270 5920 2779 5921 2267 5921 2681 5921 2779 5922 2765 5922 2267 5922 2834 5923 2307 5923 2308 5923 2820 5924 2306 5924 2307 5924 2835 5925 2820 5925 2307 5925 2834 5926 2835 5926 2307 5926 2823 5927 2304 5927 2306 5927 2821 5928 2306 5928 2820 5928 2824 5929 2823 5929 2306 5929 2822 5930 2824 5930 2306 5930 2821 5931 2822 5931 2306 5931 2681 5932 2300 5932 2304 5932 2670 5933 2681 5933 2304 5933 2823 5934 2670 5934 2304 5934 2681 5935 2295 5935 2300 5935 2681 5936 2292 5936 2295 5936 2818 5937 2292 5937 2681 5937 2819 5938 2805 5938 2292 5938 2818 5939 2819 5939 2292 5939 2716 5940 2315 5940 2313 5940 2715 5941 2313 5941 2318 5941 2715 5942 2716 5942 2313 5942 2716 5943 2386 5943 2315 5943 2716 5944 2385 5944 2386 5944 2716 5945 2383 5945 2385 5945 2717 5946 2381 5946 2383 5946 2716 5947 2717 5947 2383 5947 2395 5948 2379 5948 2381 5948 2717 5949 2395 5949 2381 5949 2395 5950 2377 5950 2379 5950 2395 5951 2373 5951 2377 5951 2416 5952 2370 5952 2373 5952 2395 5953 2398 5953 2373 5953 2416 5954 2373 5954 2398 5954 2690 5955 2368 5955 2370 5955 2690 5956 2370 5956 2416 5956 2690 5957 2366 5957 2368 5957 2690 5958 2363 5958 2366 5958 2690 5959 2360 5959 2363 5959 2691 5960 2358 5960 2360 5960 2690 5961 2691 5961 2360 5961 2691 5962 2356 5962 2358 5962 2691 5963 2354 5963 2356 5963 2691 5964 2351 5964 2354 5964 2692 5965 2349 5965 2351 5965 2691 5966 2692 5966 2351 5966 2692 5967 2347 5967 2349 5967 2692 5968 2345 5968 2347 5968 2692 5969 2342 5969 2345 5969 2449 5970 2340 5970 2342 5970 2692 5971 2449 5971 2342 5971 2449 5972 2338 5972 2340 5972 2449 5973 2334 5973 2338 5973 2714 5974 2331 5974 2334 5974 2449 5975 2451 5975 2334 5975 2465 5976 2334 5976 2451 5976 2714 5977 2334 5977 2465 5977 2714 5978 2329 5978 2331 5978 2714 5979 2327 5979 2329 5979 2714 5980 2324 5980 2327 5980 2715 5981 2322 5981 2324 5981 2714 5982 2715 5982 2324 5982 2715 5983 2320 5983 2322 5983 2715 5984 2318 5984 2320 5984 2718 5985 2392 5985 2390 5985 2717 5986 2390 5986 2394 5986 2717 5987 2718 5987 2390 5987 2718 5988 2411 5988 2392 5988 2718 5989 2410 5989 2411 5989 2414 5990 2407 5990 2410 5990 2426 5991 2414 5991 2410 5991 2718 5992 2426 5992 2410 5992 2413 5993 2404 5993 2407 5993 2414 5994 2413 5994 2407 5994 2415 5995 2401 5995 2404 5995 2415 5996 2404 5996 2413 5996 2416 5997 2398 5997 2401 5997 2415 5998 2416 5998 2401 5998 2717 5999 2394 5999 2395 5999 2718 6000 2425 6000 2426 6000 2689 6001 2424 6001 2425 6001 2688 6002 2425 6002 2718 6002 2688 6003 2689 6003 2425 6003 2689 6004 2422 6004 2424 6004 2689 6005 2420 6005 2422 6005 2690 6006 2418 6006 2420 6006 2689 6007 2690 6007 2420 6007 2690 6008 2416 6008 2418 6008 2464 6009 2433 6009 2430 6009 2463 6010 2430 6010 2436 6010 2463 6011 2464 6011 2430 6011 2465 6012 2451 6012 2433 6012 2464 6013 2465 6013 2433 6013 2694 6014 2448 6014 2449 6014 2692 6015 2694 6015 2449 6015 2694 6016 2446 6016 2448 6016 2694 6017 2444 6017 2446 6017 2697 6018 2442 6018 2444 6018 2694 6019 2697 6019 2444 6019 2697 6020 2439 6020 2442 6020 2462 6021 2436 6021 2439 6021 2461 6022 2462 6022 2439 6022 2697 6023 2461 6023 2439 6023 2462 6024 2463 6024 2436 6024 2714 6025 2457 6025 2455 6025 2713 6026 2455 6026 2459 6026 2713 6027 2714 6027 2455 6027 2714 6028 2466 6028 2457 6028 2714 6029 2465 6029 2466 6029 2697 6030 2460 6030 2461 6030 2713 6031 2459 6031 2460 6031 2697 6032 2713 6032 2460 6032 2720 6033 2472 6033 2470 6033 2719 6034 2470 6034 2474 6034 2719 6035 2720 6035 2470 6035 2720 6036 2503 6036 2472 6036 2720 6037 2502 6037 2503 6037 2720 6038 2499 6038 2502 6038 2686 6039 2496 6039 2499 6039 2720 6040 2721 6040 2499 6040 2686 6041 2499 6041 2721 6041 2687 6042 2494 6042 2496 6042 2686 6043 2687 6043 2496 6043 2687 6044 2492 6044 2494 6044 2687 6045 2490 6045 2492 6045 2687 6046 2487 6046 2490 6046 2688 6047 2485 6047 2487 6047 2687 6048 2688 6048 2487 6048 2688 6049 2483 6049 2485 6049 2688 6050 2480 6050 2483 6050 2718 6051 2478 6051 2480 6051 2688 6052 2718 6052 2480 6052 2719 6053 2476 6053 2478 6053 2718 6054 2719 6054 2478 6054 2719 6055 2474 6055 2476 6055 2744 6056 2509 6056 2507 6056 2743 6057 2507 6057 2512 6057 2743 6058 2744 6058 2507 6058 2744 6059 2528 6059 2509 6059 2746 6060 2526 6060 2528 6060 2744 6061 2746 6061 2528 6061 2750 6062 2524 6062 2526 6062 2751 6063 2750 6063 2526 6063 2748 6064 2751 6064 2526 6064 2746 6065 2748 6065 2526 6065 2761 6066 2522 6066 2524 6066 2754 6067 2761 6067 2524 6067 2750 6068 2754 6068 2524 6068 2761 6069 2520 6069 2522 6069 2761 6070 2517 6070 2520 6070 2761 6071 2514 6071 2517 6071 2743 6072 2512 6072 2514 6072 2743 6073 2514 6073 2761 6073 2763 6074 2535 6074 2533 6074 2763 6075 2533 6075 2537 6075 2763 6076 2554 6076 2535 6076 2763 6077 2552 6077 2554 6077 2659 6078 2549 6078 2552 6078 2658 6079 2552 6079 2763 6079 2658 6080 2659 6080 2552 6080 2660 6081 2547 6081 2549 6081 2659 6082 2660 6082 2549 6082 2660 6083 2544 6083 2547 6083 2661 6084 2542 6084 2544 6084 2660 6085 2661 6085 2544 6085 2661 6086 2539 6086 2542 6086 2762 6087 2537 6087 2539 6087 2661 6088 2762 6088 2539 6088 2762 6089 2763 6089 2537 6089 2743 6090 2562 6090 2560 6090 2742 6091 2560 6091 2565 6091 2742 6092 2743 6092 2560 6092 2743 6093 2582 6093 2562 6093 2743 6094 2581 6094 2582 6094 2586 6095 2579 6095 2581 6095 2603 6096 2586 6096 2581 6096 2761 6097 2603 6097 2581 6097 2743 6098 2761 6098 2581 6098 2585 6099 2575 6099 2579 6099 2586 6100 2585 6100 2579 6100 2839 6101 2572 6101 2575 6101 2838 6102 2575 6102 2585 6102 2838 6103 2839 6103 2575 6103 2837 6104 2570 6104 2572 6104 2839 6105 2837 6105 2572 6105 2837 6106 2567 6106 2570 6106 2742 6107 2565 6107 2567 6107 2741 6108 2742 6108 2567 6108 2837 6109 2741 6109 2567 6109 2838 6110 2585 6110 2589 6110 2761 6111 2602 6111 2603 6111 2661 6112 2601 6112 2602 6112 2761 6113 2762 6113 2602 6113 2661 6114 2602 6114 2762 6114 2661 6115 2599 6115 2601 6115 2661 6116 2597 6116 2599 6116 2663 6117 2594 6117 2597 6117 2661 6118 2663 6118 2597 6118 2663 6119 2591 6119 2594 6119 2838 6120 2589 6120 2591 6120 2838 6121 2591 6121 2663 6121 2734 6122 2608 6122 2606 6122 2734 6123 2606 6123 2610 6123 2734 6124 2646 6124 2608 6124 2737 6125 2645 6125 2646 6125 2734 6126 2737 6126 2646 6126 2737 6127 2643 6127 2645 6127 2737 6128 2641 6128 2643 6128 2669 6129 2638 6129 2641 6129 2669 6130 2641 6130 2737 6130 2669 6131 2636 6131 2638 6131 2669 6132 2634 6132 2636 6132 2669 6133 2631 6133 2634 6133 2670 6134 2629 6134 2631 6134 2669 6135 2670 6135 2631 6135 2670 6136 2627 6136 2629 6136 2670 6137 2625 6137 2627 6137 2670 6138 2623 6138 2625 6138 2670 6139 2621 6139 2623 6139 2670 6140 2618 6140 2621 6140 2731 6141 2616 6141 2618 6141 2670 6142 2731 6142 2618 6142 2734 6143 2614 6143 2616 6143 2731 6144 2734 6144 2616 6144 2734 6145 2612 6145 2614 6145 2734 6146 2610 6146 2612 6146 2652 6147 2763 6147 2649 6147 2657 6148 2658 6148 2763 6148 2655 6149 2657 6149 2763 6149 2656 6150 2655 6150 2763 6150 2654 6151 2656 6151 2763 6151 2653 6152 2654 6152 2763 6152 2652 6153 2653 6153 2763 6153 2760 6154 2759 6154 2761 6154 2758 6155 2760 6155 2761 6155 2756 6156 2758 6156 2761 6156 2754 6157 2756 6157 2761 6157 2837 6158 2740 6158 2741 6158 2837 6159 2739 6159 2740 6159 2668 6160 2737 6160 2739 6160 2837 6161 2668 6161 2739 6161 2668 6162 2669 6162 2737 6162 2828 6163 2731 6163 2670 6163 2799 6164 2800 6164 2731 6164 2798 6165 2799 6165 2731 6165 2796 6166 2798 6166 2731 6166 2810 6167 2796 6167 2731 6167 2831 6168 2833 6168 2731 6168 2832 6169 2831 6169 2731 6169 2830 6170 2832 6170 2731 6170 2829 6171 2830 6171 2731 6171 2827 6172 2829 6172 2731 6172 2828 6173 2827 6173 2731 6173 2685 6174 2721 6174 2722 6174 2681 6175 2685 6175 2722 6175 2774 6176 2681 6176 2722 6176 2772 6177 2774 6177 2722 6177 2771 6178 2772 6178 2722 6178 2770 6179 2771 6179 2722 6179 2685 6180 2686 6180 2721 6180 2697 6181 2712 6181 2713 6181 2700 6182 2711 6182 2712 6182 2697 6183 2700 6183 2712 6183 2703 6184 2710 6184 2711 6184 2700 6185 2703 6185 2711 6185 2706 6186 2709 6186 2710 6186 2703 6187 2706 6187 2710 6187 2707 6188 2708 6188 2709 6188 2706 6189 2707 6189 2709 6189 2778 6190 2779 6190 2681 6190 2777 6191 2778 6191 2681 6191 2776 6192 2777 6192 2681 6192 2775 6193 2776 6193 2681 6193 2773 6194 2775 6194 2681 6194 2774 6195 2773 6195 2681 6195 2815 6196 2681 6196 2784 6196 2817 6197 2818 6197 2681 6197 2816 6198 2817 6198 2681 6198 2815 6199 2816 6199 2681 6199 2826 6200 2828 6200 2670 6200 2825 6201 2826 6201 2670 6201 2823 6202 2825 6202 2670 6202 2836 6203 2667 6203 2668 6203 2837 6204 2836 6204 2668 6204 2838 6205 2665 6205 2667 6205 2838 6206 2667 6206 2836 6206 2838 6207 2663 6207 2665 6207 2810 6208 2790 6208 2796 6208 2811 6209 2791 6209 2790 6209 2810 6210 2811 6210 2790 6210 2814 6211 2787 6211 2791 6211 2812 6212 2814 6212 2791 6212 2811 6213 2812 6213 2791 6213 2814 6214 2785 6214 2787 6214 2813 6215 2784 6215 2785 6215 2814 6216 2813 6216 2785 6216 2813 6217 2815 6217 2784 6217 2840 6218 2841 6218 2842 6218 2843 6219 2842 6219 2841 6219 2844 6220 2842 6220 2845 6220 2846 6221 2845 6221 2842 6221 2847 6222 2840 6222 2842 6222 2844 6223 2847 6223 2842 6223 2846 6224 2842 6224 2843 6224 2840 6225 2848 6225 2841 6225 2849 6226 2841 6226 2848 6226 2849 6227 2843 6227 2841 6227 2840 6228 2850 6228 2848 6228 2851 6229 2848 6229 2850 6229 2849 6230 2848 6230 2851 6230 2852 6231 2853 6231 2850 6231 2854 6232 2850 6232 2853 6232 2855 6233 2852 6233 2850 6233 2856 6234 2855 6234 2850 6234 2857 6235 2850 6235 2840 6235 2858 6236 2856 6236 2850 6236 2857 6237 2858 6237 2850 6237 2851 6238 2850 6238 2854 6238 2859 6239 2860 6239 2853 6239 2861 6240 2853 6240 2860 6240 2852 6241 2859 6241 2853 6241 2854 6242 2853 6242 2861 6242 2862 6243 2863 6243 2860 6243 2864 6244 2860 6244 2863 6244 2862 6245 2860 6245 2859 6245 2861 6246 2860 6246 2864 6246 2865 6247 2866 6247 2863 6247 2867 6248 2863 6248 2866 6248 2862 6249 2865 6249 2863 6249 2864 6250 2863 6250 2867 6250 2868 6251 2869 6251 2866 6251 2870 6252 2866 6252 2869 6252 2868 6253 2866 6253 2865 6253 2867 6254 2866 6254 2870 6254 2871 6255 2845 6255 2869 6255 2872 6256 2869 6256 2845 6256 2868 6257 2873 6257 2869 6257 2871 6258 2869 6258 2873 6258 2870 6259 2869 6259 2872 6259 2874 6260 2844 6260 2845 6260 2875 6261 2874 6261 2845 6261 2876 6262 2875 6262 2845 6262 2871 6263 2876 6263 2845 6263 2872 6264 2845 6264 2846 6264 2840 6265 2877 6265 2878 6265 2879 6266 2878 6266 2877 6266 2880 6267 2878 6267 2881 6267 2882 6268 2881 6268 2878 6268 2880 6269 2840 6269 2878 6269 2882 6270 2878 6270 2879 6270 2840 6271 2883 6271 2877 6271 2884 6272 2877 6272 2883 6272 2884 6273 2879 6273 2877 6273 2840 6274 2885 6274 2883 6274 2886 6275 2883 6275 2885 6275 2884 6276 2883 6276 2886 6276 2887 6277 2888 6277 2885 6277 2889 6278 2885 6278 2888 6278 2890 6279 2887 6279 2885 6279 2891 6280 2890 6280 2885 6280 2892 6281 2885 6281 2840 6281 2892 6282 2891 6282 2885 6282 2886 6283 2885 6283 2889 6283 2893 6284 2894 6284 2888 6284 2895 6285 2888 6285 2894 6285 2887 6286 2893 6286 2888 6286 2889 6287 2888 6287 2895 6287 2896 6288 2897 6288 2894 6288 2898 6289 2894 6289 2897 6289 2896 6290 2894 6290 2893 6290 2895 6291 2894 6291 2898 6291 2899 6292 2900 6292 2897 6292 2901 6293 2897 6293 2900 6293 2896 6294 2899 6294 2897 6294 2898 6295 2897 6295 2901 6295 2902 6296 2903 6296 2900 6296 2904 6297 2900 6297 2903 6297 2902 6298 2900 6298 2899 6298 2901 6299 2900 6299 2904 6299 2905 6300 2881 6300 2903 6300 2906 6301 2903 6301 2881 6301 2902 6302 2907 6302 2903 6302 2905 6303 2903 6303 2907 6303 2904 6304 2903 6304 2906 6304 2908 6305 2880 6305 2881 6305 2909 6306 2908 6306 2881 6306 2910 6307 2909 6307 2881 6307 2905 6308 2910 6308 2881 6308 2906 6309 2881 6309 2882 6309 2911 6310 2893 6310 2887 6310 2912 6311 2896 6311 2893 6311 2912 6312 2893 6312 2911 6312 2913 6313 2887 6313 2890 6313 2913 6314 2911 6314 2887 6314 2891 6315 2914 6315 2890 6315 2915 6316 2890 6316 2914 6316 2913 6317 2890 6317 2915 6317 2916 6318 2917 6318 2914 6318 2918 6319 2914 6319 2917 6319 2919 6320 2920 6320 2914 6320 2916 6321 2914 6321 2920 6321 2891 6322 2919 6322 2914 6322 2915 6323 2914 6323 2918 6323 2921 6324 2922 6324 2917 6324 2923 6325 2917 6325 2922 6325 2924 6326 2921 6326 2917 6326 2925 6327 2924 6327 2917 6327 2916 6328 2925 6328 2917 6328 2918 6329 2917 6329 2923 6329 2926 6330 2927 6330 2922 6330 2928 6331 2922 6331 2927 6331 2929 6332 2926 6332 2922 6332 2921 6333 2929 6333 2922 6333 2923 6334 2922 6334 2928 6334 2926 6335 2930 6335 2927 6335 2931 6336 2927 6336 2930 6336 2928 6337 2927 6337 2931 6337 2926 6338 2899 6338 2930 6338 2932 6339 2930 6339 2899 6339 2931 6340 2930 6340 2932 6340 2933 6341 2899 6341 2896 6341 2934 6342 2899 6342 2926 6342 2935 6343 2902 6343 2899 6343 2934 6344 2935 6344 2899 6344 2932 6345 2899 6345 2933 6345 2933 6346 2896 6346 2912 6346 2936 6347 2859 6347 2852 6347 2937 6348 2862 6348 2859 6348 2937 6349 2859 6349 2936 6349 2938 6350 2852 6350 2855 6350 2938 6351 2936 6351 2852 6351 2856 6352 2939 6352 2855 6352 2940 6353 2855 6353 2939 6353 2938 6354 2855 6354 2940 6354 2941 6355 2942 6355 2939 6355 2943 6356 2939 6356 2942 6356 2944 6357 2945 6357 2939 6357 2941 6358 2939 6358 2945 6358 2856 6359 2944 6359 2939 6359 2940 6360 2939 6360 2943 6360 2946 6361 2947 6361 2942 6361 2948 6362 2942 6362 2947 6362 2949 6363 2946 6363 2942 6363 2950 6364 2949 6364 2942 6364 2941 6365 2950 6365 2942 6365 2943 6366 2942 6366 2948 6366 2926 6367 2951 6367 2947 6367 2952 6368 2947 6368 2951 6368 2946 6369 2926 6369 2947 6369 2948 6370 2947 6370 2952 6370 2926 6371 2953 6371 2951 6371 2954 6372 2951 6372 2953 6372 2952 6373 2951 6373 2954 6373 2926 6374 2865 6374 2953 6374 2955 6375 2953 6375 2865 6375 2954 6376 2953 6376 2955 6376 2956 6377 2865 6377 2862 6377 2957 6378 2865 6378 2926 6378 2957 6379 2868 6379 2865 6379 2955 6380 2865 6380 2956 6380 2956 6381 2862 6381 2937 6381 2958 6382 2959 6382 2960 6382 2961 6383 2960 6383 2959 6383 2958 6384 2960 6384 2962 6384 2963 6385 2962 6385 2960 6385 2963 6386 2960 6386 2961 6386 2964 6387 2965 6387 2959 6387 2966 6388 2959 6388 2965 6388 2958 6389 2964 6389 2959 6389 2966 6390 2961 6390 2959 6390 2964 6391 2967 6391 2965 6391 2968 6392 2965 6392 2967 6392 2966 6393 2965 6393 2968 6393 2964 6394 2969 6394 2967 6394 2970 6395 2967 6395 2969 6395 2968 6396 2967 6396 2970 6396 2964 6397 2971 6397 2969 6397 2972 6398 2969 6398 2971 6398 2970 6399 2969 6399 2972 6399 2973 6400 2974 6400 2971 6400 2975 6401 2971 6401 2974 6401 2964 6402 2973 6402 2971 6402 2972 6403 2971 6403 2975 6403 2973 6404 2976 6404 2974 6404 2977 6405 2974 6405 2976 6405 2975 6406 2974 6406 2977 6406 2973 6407 2978 6407 2976 6407 2979 6408 2976 6408 2978 6408 2977 6409 2976 6409 2979 6409 2980 6410 2981 6410 2978 6410 2982 6411 2978 6411 2981 6411 2983 6412 2984 6412 2978 6412 2980 6413 2978 6413 2984 6413 2973 6414 2983 6414 2978 6414 2979 6415 2978 6415 2982 6415 2980 6416 2985 6416 2981 6416 2986 6417 2981 6417 2985 6417 2982 6418 2981 6418 2986 6418 2980 6419 2987 6419 2985 6419 2988 6420 2985 6420 2987 6420 2986 6421 2985 6421 2988 6421 2980 6422 2989 6422 2987 6422 2990 6423 2987 6423 2989 6423 2988 6424 2987 6424 2990 6424 2991 6425 2992 6425 2989 6425 2993 6426 2989 6426 2992 6426 2980 6427 2991 6427 2989 6427 2990 6428 2989 6428 2993 6428 2991 6429 2994 6429 2992 6429 2995 6430 2992 6430 2994 6430 2993 6431 2992 6431 2995 6431 2991 6432 2996 6432 2994 6432 2997 6433 2994 6433 2996 6433 2995 6434 2994 6434 2997 6434 2991 6435 2998 6435 2996 6435 2999 6436 2996 6436 2998 6436 2997 6437 2996 6437 2999 6437 3000 6438 3001 6438 2998 6438 3002 6439 2998 6439 3001 6439 2991 6440 3000 6440 2998 6440 2999 6441 2998 6441 3002 6441 3000 6442 3003 6442 3001 6442 3004 6443 3001 6443 3003 6443 3002 6444 3001 6444 3004 6444 3000 6445 3005 6445 3003 6445 3006 6446 3003 6446 3005 6446 3004 6447 3003 6447 3006 6447 3000 6448 3007 6448 3005 6448 3008 6449 3005 6449 3007 6449 3006 6450 3005 6450 3008 6450 3009 6451 3010 6451 3007 6451 3011 6452 3007 6452 3010 6452 3000 6453 3009 6453 3007 6453 3008 6454 3007 6454 3011 6454 3012 6455 3013 6455 3010 6455 3014 6456 3010 6456 3013 6456 3009 6457 3012 6457 3010 6457 3011 6458 3010 6458 3014 6458 3012 6459 3015 6459 3013 6459 3016 6460 3013 6460 3015 6460 3014 6461 3013 6461 3016 6461 3012 6462 3017 6462 3015 6462 3018 6463 3015 6463 3017 6463 3016 6464 3015 6464 3018 6464 3019 6465 3020 6465 3017 6465 3021 6466 3017 6466 3020 6466 3022 6467 3019 6467 3017 6467 3012 6468 3022 6468 3017 6468 3018 6469 3017 6469 3021 6469 3023 6470 3024 6470 3020 6470 3025 6471 3020 6471 3024 6471 3023 6472 3020 6472 3019 6472 3021 6473 3020 6473 3025 6473 3023 6474 3026 6474 3024 6474 3027 6475 3024 6475 3026 6475 3025 6476 3024 6476 3027 6476 3023 6477 3028 6477 3026 6477 3029 6478 3026 6478 3028 6478 3027 6479 3026 6479 3029 6479 3023 6480 3030 6480 3028 6480 3031 6481 3028 6481 3030 6481 3029 6482 3028 6482 3031 6482 2958 6483 3032 6483 3030 6483 3033 6484 3030 6484 3032 6484 3023 6485 2958 6485 3030 6485 3031 6486 3030 6486 3033 6486 2958 6487 2962 6487 3032 6487 3034 6488 3032 6488 2962 6488 3033 6489 3032 6489 3034 6489 3034 6490 2962 6490 2963 6490 3035 6491 3036 6491 3037 6491 3038 6492 3037 6492 3036 6492 3035 6493 3037 6493 3039 6493 3040 6494 3039 6494 3037 6494 3040 6495 3037 6495 3038 6495 3023 6496 3041 6496 3036 6496 3042 6497 3036 6497 3041 6497 3035 6498 3023 6498 3036 6498 3042 6499 3038 6499 3036 6499 3023 6500 3019 6500 3041 6500 3043 6501 3041 6501 3019 6501 3042 6502 3041 6502 3043 6502 3044 6503 3045 6503 3019 6503 3046 6504 3019 6504 3045 6504 3022 6505 3044 6505 3019 6505 3043 6506 3019 6506 3046 6506 3047 6507 3048 6507 3045 6507 3049 6508 3045 6508 3048 6508 3044 6509 3047 6509 3045 6509 3046 6510 3045 6510 3049 6510 3050 6511 3051 6511 3048 6511 3052 6512 3048 6512 3051 6512 3050 6513 3048 6513 3047 6513 3049 6514 3048 6514 3052 6514 3053 6515 3054 6515 3051 6515 3055 6516 3051 6516 3054 6516 3050 6517 3053 6517 3051 6517 3052 6518 3051 6518 3055 6518 3056 6519 3057 6519 3054 6519 3058 6520 3054 6520 3057 6520 3056 6521 3054 6521 3053 6521 3055 6522 3054 6522 3058 6522 3035 6523 3039 6523 3057 6523 3059 6524 3057 6524 3039 6524 3060 6525 3057 6525 3056 6525 3060 6526 3035 6526 3057 6526 3058 6527 3057 6527 3059 6527 3059 6528 3039 6528 3040 6528 3061 6529 3047 6529 3044 6529 3062 6530 3050 6530 3047 6530 3062 6531 3047 6531 3061 6531 3063 6532 3044 6532 3022 6532 3063 6533 3061 6533 3044 6533 3064 6534 3022 6534 3012 6534 3063 6535 3022 6535 3064 6535 3009 6536 3065 6536 3012 6536 3066 6537 3012 6537 3065 6537 3064 6538 3012 6538 3066 6538 3009 6539 3067 6539 3065 6539 3068 6540 3065 6540 3067 6540 3066 6541 3065 6541 3068 6541 3056 6542 3069 6542 3067 6542 3070 6543 3067 6543 3069 6543 3009 6544 3056 6544 3067 6544 3068 6545 3067 6545 3070 6545 3056 6546 3071 6546 3069 6546 3072 6547 3069 6547 3071 6547 3070 6548 3069 6548 3072 6548 3056 6549 3053 6549 3071 6549 3073 6550 3071 6550 3053 6550 3072 6551 3071 6551 3073 6551 3074 6552 3053 6552 3050 6552 3073 6553 3053 6553 3074 6553 3074 6554 3050 6554 3062 6554 3075 6555 3076 6555 3077 6555 3078 6556 3077 6556 3076 6556 3079 6557 3077 6557 3080 6557 3081 6558 3080 6558 3077 6558 3079 6559 3075 6559 3077 6559 3081 6560 3077 6560 3078 6560 3082 6561 3083 6561 3076 6561 3084 6562 3076 6562 3083 6562 3075 6563 3082 6563 3076 6563 3084 6564 3078 6564 3076 6564 3085 6565 3086 6565 3083 6565 3087 6566 3083 6566 3086 6566 3085 6567 3083 6567 3082 6567 3084 6568 3083 6568 3087 6568 3088 6569 3089 6569 3086 6569 3090 6570 3086 6570 3089 6570 3085 6571 3088 6571 3086 6571 3087 6572 3086 6572 3090 6572 3088 6573 3091 6573 3089 6573 3092 6574 3089 6574 3091 6574 3090 6575 3089 6575 3092 6575 2980 6576 3093 6576 3091 6576 3094 6577 3091 6577 3093 6577 3088 6578 2980 6578 3091 6578 3092 6579 3091 6579 3094 6579 2980 6580 3095 6580 3093 6580 3096 6581 3093 6581 3095 6581 3094 6582 3093 6582 3096 6582 2980 6583 2984 6583 3095 6583 3097 6584 3095 6584 2984 6584 3096 6585 3095 6585 3097 6585 3098 6586 3080 6586 2984 6586 3099 6587 2984 6587 3080 6587 2983 6588 3098 6588 2984 6588 3097 6589 2984 6589 3099 6589 3098 6590 3079 6590 3080 6590 3099 6591 3080 6591 3081 6591 3100 6592 3101 6592 3102 6592 3103 6593 3102 6593 3101 6593 3100 6594 3102 6594 3104 6594 3105 6595 3104 6595 3102 6595 3105 6596 3102 6596 3103 6596 3085 6597 3106 6597 3101 6597 3107 6598 3101 6598 3106 6598 3100 6599 3085 6599 3101 6599 3107 6600 3103 6600 3101 6600 3085 6601 3082 6601 3106 6601 3108 6602 3106 6602 3082 6602 3107 6603 3106 6603 3108 6603 3109 6604 3082 6604 3075 6604 3108 6605 3082 6605 3109 6605 3110 6606 3075 6606 3079 6606 3109 6607 3075 6607 3110 6607 3111 6608 3079 6608 3098 6608 3110 6609 3079 6609 3111 6609 3112 6610 3098 6610 2983 6610 3111 6611 3098 6611 3112 6611 3113 6612 2983 6612 2973 6612 3112 6613 2983 6613 3113 6613 3100 6614 3104 6614 2973 6614 3114 6615 2973 6615 3104 6615 2964 6616 3100 6616 2973 6616 3113 6617 2973 6617 3114 6617 3114 6618 3104 6618 3105 6618 3115 6619 3116 6619 3117 6619 3118 6620 3117 6620 3116 6620 3115 6621 3117 6621 3119 6621 3120 6622 3119 6622 3117 6622 3120 6623 3117 6623 3118 6623 3060 6624 3121 6624 3116 6624 3122 6625 3116 6625 3121 6625 3115 6626 3060 6626 3116 6626 3122 6627 3118 6627 3116 6627 3060 6628 3123 6628 3121 6628 3124 6629 3121 6629 3123 6629 3122 6630 3121 6630 3124 6630 3060 6631 3125 6631 3123 6631 3126 6632 3123 6632 3125 6632 3124 6633 3123 6633 3126 6633 3056 6634 3127 6634 3125 6634 3128 6635 3125 6635 3127 6635 3060 6636 3056 6636 3125 6636 3126 6637 3125 6637 3128 6637 3129 6638 3130 6638 3127 6638 3131 6639 3127 6639 3130 6639 3056 6640 3129 6640 3127 6640 3128 6641 3127 6641 3131 6641 3129 6642 3132 6642 3130 6642 3133 6643 3130 6643 3132 6643 3131 6644 3130 6644 3133 6644 3129 6645 3134 6645 3132 6645 3135 6646 3132 6646 3134 6646 3133 6647 3132 6647 3135 6647 3136 6648 3137 6648 3134 6648 3138 6649 3134 6649 3137 6649 3129 6650 3136 6650 3134 6650 3135 6651 3134 6651 3138 6651 3136 6652 3139 6652 3137 6652 3140 6653 3137 6653 3139 6653 3138 6654 3137 6654 3140 6654 3136 6655 3141 6655 3139 6655 3142 6656 3139 6656 3141 6656 3140 6657 3139 6657 3142 6657 3136 6658 3143 6658 3141 6658 3144 6659 3141 6659 3143 6659 3142 6660 3141 6660 3144 6660 3145 6661 3146 6661 3143 6661 3147 6662 3143 6662 3146 6662 3136 6663 3148 6663 3143 6663 3145 6664 3143 6664 3148 6664 3144 6665 3143 6665 3147 6665 3115 6666 3149 6666 3146 6666 3150 6667 3146 6667 3149 6667 3145 6668 3115 6668 3146 6668 3147 6669 3146 6669 3150 6669 3115 6670 3119 6670 3149 6670 3151 6671 3149 6671 3119 6671 3150 6672 3149 6672 3151 6672 3151 6673 3119 6673 3120 6673 3152 6674 3153 6674 3154 6674 3155 6675 3154 6675 3153 6675 3152 6676 3154 6676 3156 6676 3157 6677 3156 6677 3154 6677 3157 6678 3154 6678 3155 6678 3158 6679 3159 6679 3153 6679 3160 6680 3153 6680 3159 6680 3152 6681 3158 6681 3153 6681 3160 6682 3155 6682 3153 6682 3158 6683 3161 6683 3159 6683 3162 6684 3159 6684 3161 6684 3160 6685 3159 6685 3162 6685 3163 6686 3164 6686 3161 6686 3165 6687 3161 6687 3164 6687 3163 6688 3161 6688 3158 6688 3162 6689 3161 6689 3165 6689 3166 6690 3167 6690 3164 6690 3168 6691 3164 6691 3167 6691 3163 6692 3166 6692 3164 6692 3165 6693 3164 6693 3168 6693 3166 6694 3169 6694 3167 6694 3170 6695 3167 6695 3169 6695 3168 6696 3167 6696 3170 6696 3166 6697 3171 6697 3169 6697 3172 6698 3169 6698 3171 6698 3170 6699 3169 6699 3172 6699 3166 6700 3173 6700 3171 6700 3174 6701 3171 6701 3173 6701 3172 6702 3171 6702 3174 6702 3175 6703 3156 6703 3173 6703 3176 6704 3173 6704 3156 6704 3177 6705 3175 6705 3173 6705 3166 6706 3177 6706 3173 6706 3174 6707 3173 6707 3176 6707 3175 6708 3152 6708 3156 6708 3176 6709 3156 6709 3157 6709 3178 6710 3179 6710 3180 6710 3181 6711 3180 6711 3179 6711 3178 6712 3180 6712 3182 6712 3183 6713 3182 6713 3180 6713 3183 6714 3180 6714 3181 6714 3178 6715 3184 6715 3179 6715 3185 6716 3179 6716 3184 6716 3185 6717 3181 6717 3179 6717 3178 6718 3186 6718 3184 6718 3187 6719 3184 6719 3186 6719 3185 6720 3184 6720 3187 6720 3188 6721 3189 6721 3186 6721 3190 6722 3186 6722 3189 6722 3178 6723 3188 6723 3186 6723 3187 6724 3186 6724 3190 6724 3188 6725 3191 6725 3189 6725 3192 6726 3189 6726 3191 6726 3190 6727 3189 6727 3192 6727 3193 6728 3194 6728 3191 6728 3195 6729 3191 6729 3194 6729 3188 6730 3193 6730 3191 6730 3192 6731 3191 6731 3195 6731 3193 6732 3196 6732 3194 6732 3197 6733 3194 6733 3196 6733 3195 6734 3194 6734 3197 6734 3198 6735 3199 6735 3196 6735 3200 6736 3196 6736 3199 6736 3193 6737 3198 6737 3196 6737 3197 6738 3196 6738 3200 6738 3201 6739 3182 6739 3199 6739 3202 6740 3199 6740 3182 6740 3203 6741 3201 6741 3199 6741 3204 6742 3203 6742 3199 6742 3198 6743 3204 6743 3199 6743 3200 6744 3199 6744 3202 6744 3201 6745 3205 6745 3182 6745 3178 6746 3182 6746 3205 6746 3202 6747 3182 6747 3183 6747 3158 6748 3206 6748 3207 6748 3208 6749 3207 6749 3206 6749 3158 6750 3207 6750 3209 6750 3210 6751 3209 6751 3207 6751 3210 6752 3207 6752 3208 6752 3211 6753 3212 6753 3206 6753 3213 6754 3206 6754 3212 6754 3158 6755 3211 6755 3206 6755 3213 6756 3208 6756 3206 6756 3211 6757 3214 6757 3212 6757 3215 6758 3212 6758 3214 6758 3213 6759 3212 6759 3215 6759 3216 6760 3217 6760 3214 6760 3218 6761 3214 6761 3217 6761 3216 6762 3214 6762 3211 6762 3215 6763 3214 6763 3218 6763 3216 6764 3219 6764 3217 6764 3220 6765 3217 6765 3219 6765 3218 6766 3217 6766 3220 6766 3221 6767 3222 6767 3219 6767 3223 6768 3219 6768 3222 6768 3221 6769 3219 6769 3224 6769 3216 6770 3224 6770 3219 6770 3220 6771 3219 6771 3223 6771 3225 6772 3226 6772 3222 6772 3227 6773 3222 6773 3226 6773 3221 6774 3225 6774 3222 6774 3223 6775 3222 6775 3227 6775 3178 6776 3228 6776 3226 6776 3229 6777 3226 6777 3228 6777 3178 6778 3226 6778 3225 6778 3227 6779 3226 6779 3229 6779 3158 6780 3209 6780 3228 6780 3230 6781 3228 6781 3209 6781 3163 6782 3158 6782 3228 6782 3178 6783 3163 6783 3228 6783 3229 6784 3228 6784 3230 6784 3230 6785 3209 6785 3210 6785 3231 6786 3232 6786 3224 6786 3233 6787 3224 6787 3232 6787 3234 6788 3221 6788 3224 6788 3216 6789 3231 6789 3224 6789 3234 6790 3224 6790 3233 6790 3235 6791 3236 6791 3232 6791 3237 6792 3232 6792 3236 6792 3231 6793 3235 6793 3232 6793 3237 6794 3233 6794 3232 6794 3235 6795 3238 6795 3236 6795 3239 6796 3236 6796 3238 6796 3237 6797 3236 6797 3239 6797 3240 6798 3241 6798 3238 6798 3242 6799 3238 6799 3241 6799 3243 6800 3240 6800 3238 6800 3235 6801 3243 6801 3238 6801 3239 6802 3238 6802 3242 6802 3240 6803 3244 6803 3241 6803 3245 6804 3241 6804 3244 6804 3242 6805 3241 6805 3245 6805 3188 6806 3246 6806 3244 6806 3247 6807 3244 6807 3246 6807 3240 6808 3188 6808 3244 6808 3245 6809 3244 6809 3247 6809 3188 6810 3248 6810 3246 6810 3249 6811 3246 6811 3248 6811 3247 6812 3246 6812 3249 6812 3188 6813 3225 6813 3248 6813 3250 6814 3248 6814 3225 6814 3249 6815 3248 6815 3250 6815 3251 6816 3225 6816 3221 6816 3178 6817 3225 6817 3188 6817 3250 6818 3225 6818 3251 6818 3251 6819 3221 6819 3234 6819 2847 6820 3252 6820 3253 6820 3254 6821 3253 6821 3252 6821 2847 6822 3253 6822 3255 6822 3256 6823 3255 6823 3253 6823 3256 6824 3253 6824 3254 6824 2847 6825 3257 6825 3252 6825 3258 6826 3252 6826 3257 6826 3258 6827 3254 6827 3252 6827 2847 6828 3259 6828 3257 6828 3260 6829 3257 6829 3259 6829 3258 6830 3257 6830 3260 6830 2847 6831 3261 6831 3259 6831 3262 6832 3259 6832 3261 6832 3260 6833 3259 6833 3262 6833 2847 6834 3263 6834 3261 6834 3264 6835 3261 6835 3263 6835 3262 6836 3261 6836 3264 6836 2926 6837 3265 6837 3263 6837 3266 6838 3263 6838 3265 6838 2847 6839 2926 6839 3263 6839 3264 6840 3263 6840 3266 6840 3267 6841 3268 6841 3265 6841 3269 6842 3265 6842 3268 6842 2926 6843 3267 6843 3265 6843 3266 6844 3265 6844 3269 6844 3267 6845 3270 6845 3268 6845 3271 6846 3268 6846 3270 6846 3269 6847 3268 6847 3271 6847 3267 6848 3272 6848 3270 6848 3273 6849 3270 6849 3272 6849 3271 6850 3270 6850 3273 6850 3267 6851 3274 6851 3272 6851 3275 6852 3272 6852 3274 6852 3273 6853 3272 6853 3275 6853 3267 6854 3276 6854 3274 6854 3277 6855 3274 6855 3276 6855 3275 6856 3274 6856 3277 6856 3267 6857 3278 6857 3276 6857 3279 6858 3276 6858 3278 6858 3277 6859 3276 6859 3279 6859 3280 6860 3281 6860 3278 6860 3282 6861 3278 6861 3281 6861 3267 6862 3280 6862 3278 6862 3279 6863 3278 6863 3282 6863 3280 6864 3283 6864 3281 6864 3284 6865 3281 6865 3283 6865 3282 6866 3281 6866 3284 6866 3280 6867 3285 6867 3283 6867 3286 6868 3283 6868 3285 6868 3284 6869 3283 6869 3286 6869 3287 6870 3288 6870 3285 6870 3289 6871 3285 6871 3288 6871 3287 6872 3285 6872 3280 6872 3286 6873 3285 6873 3289 6873 3287 6874 3290 6874 3288 6874 3291 6875 3288 6875 3290 6875 3289 6876 3288 6876 3291 6876 3287 6877 3292 6877 3290 6877 3293 6878 3290 6878 3292 6878 3291 6879 3290 6879 3293 6879 3287 6880 3255 6880 3292 6880 3294 6881 3292 6881 3255 6881 3293 6882 3292 6882 3294 6882 3287 6883 2847 6883 3255 6883 3294 6884 3255 6884 3256 6884 3178 6885 3295 6885 3296 6885 3297 6886 3296 6886 3295 6886 3298 6887 3178 6887 3296 6887 3297 6888 3298 6888 3296 6888 3178 6889 3299 6889 3295 6889 3300 6890 3295 6890 3299 6890 3300 6891 3297 6891 3295 6891 3178 6892 3205 6892 3299 6892 3301 6893 3299 6893 3205 6893 3300 6894 3299 6894 3301 6894 3302 6895 3205 6895 3201 6895 3301 6896 3205 6896 3302 6896 3303 6897 3201 6897 3203 6897 3304 6898 3201 6898 3303 6898 3302 6899 3201 6899 3304 6899 3303 6900 3203 6900 3204 6900 3305 6901 3204 6901 3198 6901 3303 6902 3204 6902 3305 6902 3306 6903 3198 6903 3193 6903 3305 6904 3198 6904 3306 6904 3307 6905 3193 6905 3188 6905 3306 6906 3193 6906 3307 6906 3308 6907 3188 6907 3240 6907 3307 6908 3188 6908 3308 6908 3309 6909 3240 6909 3243 6909 3308 6910 3240 6910 3309 6910 3235 6911 3310 6911 3243 6911 3311 6912 3243 6912 3310 6912 3309 6913 3243 6913 3311 6913 3235 6914 3312 6914 3310 6914 3313 6915 3310 6915 3312 6915 3311 6916 3310 6916 3313 6916 3314 6917 3280 6917 3312 6917 3315 6918 3312 6918 3280 6918 3235 6919 3314 6919 3312 6919 3313 6920 3312 6920 3315 6920 3316 6921 3280 6921 3267 6921 3314 6922 3287 6922 3280 6922 3315 6923 3280 6923 3316 6923 3317 6924 3267 6924 2926 6924 3316 6925 3267 6925 3317 6925 3318 6926 2926 6926 2929 6926 3319 6927 2926 6927 2847 6927 3320 6928 2934 6928 2926 6928 3321 6929 3320 6929 2926 6929 3322 6930 3321 6930 2926 6930 2946 6931 3322 6931 2926 6931 3323 6932 2957 6932 2926 6932 3324 6933 3323 6933 2926 6933 3325 6934 3324 6934 2926 6934 3326 6935 3325 6935 2926 6935 3327 6936 3326 6936 2926 6936 3319 6937 3327 6937 2926 6937 3317 6938 2926 6938 3318 6938 3328 6939 3148 6939 2929 6939 3329 6940 2929 6940 3148 6940 2840 6941 3328 6941 2929 6941 3330 6942 2840 6942 2929 6942 3331 6943 3330 6943 2929 6943 3332 6944 3331 6944 2929 6944 2921 6945 3332 6945 2929 6945 3318 6946 2929 6946 3329 6946 3333 6947 3148 6947 3136 6947 3328 6948 3145 6948 3148 6948 3329 6949 3148 6949 3333 6949 3334 6950 3136 6950 3129 6950 3333 6951 3136 6951 3334 6951 3335 6952 3129 6952 3056 6952 3334 6953 3129 6953 3335 6953 3336 6954 3056 6954 3009 6954 3335 6955 3056 6955 3336 6955 3337 6956 3009 6956 3000 6956 3336 6957 3009 6957 3337 6957 3338 6958 3000 6958 2991 6958 3337 6959 3000 6959 3338 6959 3339 6960 2991 6960 2980 6960 3338 6961 2991 6961 3339 6961 3340 6962 2980 6962 3088 6962 3339 6963 2980 6963 3340 6963 3085 6964 3341 6964 3088 6964 3342 6965 3088 6965 3341 6965 3340 6966 3088 6966 3342 6966 3343 6967 3344 6967 3341 6967 3345 6968 3341 6968 3344 6968 3085 6969 3343 6969 3341 6969 3342 6970 3341 6970 3345 6970 3346 6971 3347 6971 3344 6971 3348 6972 3344 6972 3347 6972 3343 6973 3346 6973 3344 6973 3345 6974 3344 6974 3348 6974 3349 6975 3350 6975 3347 6975 3351 6976 3347 6976 3350 6976 3346 6977 3349 6977 3347 6977 3348 6978 3347 6978 3351 6978 3352 6979 3353 6979 3350 6979 3354 6980 3350 6980 3353 6980 3349 6981 3352 6981 3350 6981 3351 6982 3350 6982 3354 6982 3355 6983 3353 6983 3352 6983 3354 6984 3353 6984 3355 6984 3356 6985 3352 6985 3349 6985 3355 6986 3352 6986 3356 6986 3357 6987 3349 6987 3346 6987 3356 6988 3349 6988 3357 6988 3358 6989 3346 6989 3343 6989 3357 6990 3346 6990 3358 6990 3359 6991 3343 6991 3085 6991 3358 6992 3343 6992 3359 6992 3360 6993 3085 6993 3100 6993 3359 6994 3085 6994 3360 6994 3361 6995 3100 6995 2964 6995 3360 6996 3100 6996 3361 6996 3362 6997 2964 6997 2958 6997 3361 6998 2964 6998 3362 6998 3363 6999 2958 6999 3023 6999 3362 7000 2958 7000 3363 7000 3364 7001 3023 7001 3035 7001 3363 7002 3023 7002 3364 7002 3365 7003 3035 7003 3060 7003 3364 7004 3035 7004 3365 7004 3366 7005 3060 7005 3115 7005 3365 7006 3060 7006 3366 7006 3367 7007 3115 7007 3145 7007 3366 7008 3115 7008 3367 7008 3368 7009 3145 7009 3328 7009 3367 7010 3145 7010 3368 7010 3369 7011 3328 7011 2840 7011 3368 7012 3328 7012 3369 7012 3370 7013 2840 7013 2847 7013 3371 7014 2892 7014 2840 7014 3372 7015 3371 7015 2840 7015 3373 7016 3372 7016 2840 7016 3374 7017 3373 7017 2840 7017 3375 7018 3374 7018 2840 7018 3330 7019 3375 7019 2840 7019 3376 7020 2840 7020 2880 7020 3377 7021 2857 7021 2840 7021 3378 7022 3377 7022 2840 7022 3376 7023 3378 7023 2840 7023 3369 7024 2840 7024 3370 7024 3379 7025 2847 7025 3287 7025 3380 7026 3319 7026 2847 7026 3381 7027 3380 7027 2847 7027 2844 7028 3381 7028 2847 7028 3370 7029 2847 7029 3379 7029 3382 7030 3287 7030 3314 7030 3379 7031 3287 7031 3382 7031 3383 7032 3384 7032 3314 7032 3385 7033 3314 7033 3384 7033 3383 7034 3314 7034 3235 7034 3382 7035 3314 7035 3385 7035 3216 7036 3386 7036 3384 7036 3387 7037 3384 7037 3386 7037 3383 7038 3216 7038 3384 7038 3385 7039 3384 7039 3387 7039 3216 7040 3211 7040 3386 7040 3388 7041 3386 7041 3211 7041 3387 7042 3386 7042 3388 7042 3389 7043 3211 7043 3158 7043 3388 7044 3211 7044 3389 7044 3390 7045 3158 7045 3152 7045 3389 7046 3158 7046 3390 7046 3391 7047 3152 7047 3175 7047 3390 7048 3152 7048 3391 7048 3392 7049 3175 7049 3177 7049 3391 7050 3175 7050 3392 7050 3166 7051 3393 7051 3177 7051 3394 7052 3177 7052 3393 7052 3392 7053 3177 7053 3394 7053 3166 7054 3395 7054 3393 7054 3396 7055 3393 7055 3395 7055 3394 7056 3393 7056 3396 7056 3166 7057 3397 7057 3395 7057 3398 7058 3395 7058 3397 7058 3399 7059 3395 7059 3398 7059 3396 7060 3395 7060 3399 7060 3166 7061 3400 7061 3397 7061 3398 7062 3397 7062 3400 7062 3166 7063 3401 7063 3400 7063 3402 7064 3400 7064 3401 7064 3398 7065 3400 7065 3402 7065 3166 7066 3403 7066 3401 7066 3404 7067 3401 7067 3403 7067 3402 7068 3401 7068 3404 7068 3166 7069 3405 7069 3403 7069 3406 7070 3403 7070 3405 7070 3404 7071 3403 7071 3406 7071 3407 7072 3405 7072 3166 7072 3408 7073 3405 7073 3407 7073 3406 7074 3405 7074 3408 7074 3407 7075 3166 7075 3163 7075 3409 7076 3163 7076 3178 7076 3407 7077 3163 7077 3409 7077 3410 7078 3178 7078 3298 7078 3409 7079 3178 7079 3410 7079 3411 7080 3298 7080 3297 7080 3410 7081 3298 7081 3411 7081 3412 7082 2920 7082 2919 7082 3413 7083 2916 7083 2920 7083 3413 7084 2920 7084 3414 7084 3412 7085 3414 7085 2920 7085 3412 7086 2919 7086 2891 7086 3415 7087 2891 7087 2892 7087 3412 7088 2891 7088 3415 7088 3416 7089 2892 7089 3371 7089 3415 7090 2892 7090 3416 7090 3417 7091 3371 7091 3372 7091 3416 7092 3371 7092 3417 7092 3418 7093 3372 7093 3373 7093 3417 7094 3372 7094 3418 7094 3419 7095 3373 7095 3374 7095 3418 7096 3373 7096 3419 7096 3420 7097 3374 7097 3375 7097 3419 7098 3374 7098 3420 7098 3421 7099 3375 7099 3330 7099 3422 7100 3375 7100 3421 7100 3420 7101 3375 7101 3422 7101 3421 7102 3330 7102 3331 7102 3423 7103 3331 7103 3332 7103 3421 7104 3331 7104 3423 7104 3424 7105 3332 7105 2921 7105 3423 7106 3332 7106 3424 7106 3425 7107 2921 7107 2924 7107 3424 7108 2921 7108 3425 7108 3426 7109 2924 7109 2925 7109 3425 7110 2924 7110 3426 7110 3427 7111 2925 7111 2916 7111 3426 7112 2925 7112 3427 7112 3427 7113 2916 7113 3413 7113 3428 7114 2907 7114 2902 7114 3428 7115 2905 7115 2907 7115 3429 7116 2902 7116 2935 7116 3429 7117 3428 7117 2902 7117 3430 7118 2935 7118 2934 7118 3429 7119 2935 7119 3430 7119 3431 7120 2934 7120 3320 7120 3430 7121 2934 7121 3431 7121 3432 7122 3320 7122 3321 7122 3431 7123 3320 7123 3432 7123 3433 7124 3321 7124 3322 7124 3432 7125 3321 7125 3433 7125 2946 7126 3434 7126 3322 7126 3435 7127 3322 7127 3434 7127 3433 7128 3322 7128 3435 7128 3436 7129 3437 7129 3434 7129 3438 7130 3434 7130 3437 7130 2946 7131 3436 7131 3434 7131 3439 7132 3434 7132 3438 7132 3435 7133 3434 7133 3439 7133 3440 7134 3441 7134 3437 7134 3438 7135 3437 7135 3441 7135 3442 7136 3440 7136 3437 7136 3436 7137 3442 7137 3437 7137 3440 7138 3443 7138 3441 7138 3444 7139 3441 7139 3443 7139 3438 7140 3441 7140 3444 7140 3445 7141 2880 7141 3443 7141 3446 7142 3443 7142 2880 7142 3440 7143 3445 7143 3443 7143 3444 7144 3443 7144 3446 7144 3447 7145 2880 7145 2908 7145 3445 7146 3376 7146 2880 7146 3446 7147 2880 7147 3447 7147 3448 7148 2908 7148 2909 7148 3447 7149 2908 7149 3448 7149 3449 7150 2909 7150 2910 7150 3448 7151 2909 7151 3449 7151 3450 7152 2910 7152 2905 7152 3449 7153 2910 7153 3450 7153 3451 7154 2905 7154 3428 7154 3450 7155 2905 7155 3451 7155 3452 7156 2945 7156 2944 7156 3453 7157 2941 7157 2945 7157 3453 7158 2945 7158 3454 7158 3452 7159 3454 7159 2945 7159 3452 7160 2944 7160 2856 7160 3455 7161 2856 7161 2858 7161 3452 7162 2856 7162 3455 7162 3456 7163 2858 7163 2857 7163 3455 7164 2858 7164 3456 7164 3457 7165 2857 7165 3377 7165 3456 7166 2857 7166 3457 7166 3458 7167 3377 7167 3378 7167 3457 7168 3377 7168 3458 7168 3459 7169 3378 7169 3376 7169 3458 7170 3378 7170 3459 7170 3460 7171 3376 7171 3445 7171 3459 7172 3376 7172 3460 7172 3461 7173 3445 7173 3440 7173 3462 7174 3445 7174 3461 7174 3460 7175 3445 7175 3462 7175 3461 7176 3440 7176 3442 7176 3463 7177 3442 7177 3436 7177 3461 7178 3442 7178 3463 7178 3464 7179 3436 7179 2946 7179 3463 7180 3436 7180 3464 7180 3465 7181 2946 7181 2949 7181 3464 7182 2946 7182 3465 7182 3466 7183 2949 7183 2950 7183 3465 7184 2949 7184 3466 7184 3467 7185 2950 7185 2941 7185 3466 7186 2950 7186 3467 7186 3467 7187 2941 7187 3453 7187 3468 7188 2873 7188 2868 7188 3468 7189 2871 7189 2873 7189 3469 7190 2868 7190 2957 7190 3469 7191 3468 7191 2868 7191 3470 7192 2957 7192 3323 7192 3469 7193 2957 7193 3470 7193 3471 7194 3323 7194 3324 7194 3472 7195 3323 7195 3471 7195 3470 7196 3323 7196 3472 7196 3471 7197 3324 7197 3325 7197 3473 7198 3325 7198 3326 7198 3471 7199 3325 7199 3473 7199 3474 7200 3326 7200 3327 7200 3473 7201 3326 7201 3474 7201 3475 7202 3327 7202 3319 7202 3476 7203 3327 7203 3475 7203 3474 7204 3327 7204 3476 7204 3475 7205 3319 7205 3380 7205 3477 7206 3380 7206 3381 7206 3475 7207 3380 7207 3477 7207 3478 7208 3381 7208 2844 7208 3477 7209 3381 7209 3478 7209 3479 7210 2844 7210 2874 7210 3480 7211 2844 7211 3479 7211 3478 7212 2844 7212 3480 7212 3479 7213 2874 7213 2875 7213 3481 7214 2875 7214 2876 7214 3479 7215 2875 7215 3481 7215 3482 7216 2876 7216 2871 7216 3481 7217 2876 7217 3482 7217 3483 7218 2871 7218 3468 7218 3482 7219 2871 7219 3483 7219 3484 7220 3235 7220 3231 7220 3485 7221 3383 7221 3235 7221 3485 7222 3235 7222 3484 7222 3486 7223 3231 7223 3216 7223 3486 7224 3484 7224 3231 7224 3487 7225 3216 7225 3383 7225 3486 7226 3216 7226 3487 7226 3487 7227 3383 7227 3485 7227 3379 7228 2846 7228 2843 7228 3458 7229 2843 7229 2849 7229 3458 7230 3379 7230 2843 7230 3379 7231 2872 7231 2846 7231 3379 7232 2870 7232 2872 7232 2937 7233 2867 7233 2870 7233 2956 7234 2937 7234 2870 7234 3482 7235 2956 7235 2870 7235 3481 7236 2870 7236 3379 7236 3481 7237 3482 7237 2870 7237 2936 7238 2864 7238 2867 7238 2937 7239 2936 7239 2867 7239 2938 7240 2861 7240 2864 7240 2938 7241 2864 7241 2936 7241 2940 7242 2854 7242 2861 7242 2938 7243 2940 7243 2861 7243 3453 7244 2851 7244 2854 7244 3453 7245 2854 7245 2940 7245 3455 7246 2849 7246 2851 7246 3453 7247 3454 7247 2851 7247 3452 7248 2851 7248 3454 7248 3452 7249 3455 7249 2851 7249 3457 7250 3458 7250 2849 7250 3456 7251 3457 7251 2849 7251 3455 7252 3456 7252 2849 7252 3379 7253 2882 7253 2879 7253 3418 7254 2879 7254 2884 7254 3370 7255 3379 7255 2879 7255 3418 7256 3370 7256 2879 7256 3379 7257 2906 7257 2882 7257 3379 7258 2904 7258 2906 7258 2912 7259 2901 7259 2904 7259 2933 7260 2912 7260 2904 7260 3450 7261 2933 7261 2904 7261 3448 7262 2904 7262 3379 7262 3449 7263 3450 7263 2904 7263 3448 7264 3449 7264 2904 7264 2911 7265 2898 7265 2901 7265 2912 7266 2911 7266 2901 7266 2913 7267 2895 7267 2898 7267 2913 7268 2898 7268 2911 7268 2915 7269 2889 7269 2895 7269 2913 7270 2915 7270 2895 7270 3413 7271 2886 7271 2889 7271 3413 7272 2889 7272 2915 7272 3415 7273 2884 7273 2886 7273 3413 7274 3414 7274 2886 7274 3412 7275 2886 7275 3414 7275 3412 7276 3415 7276 2886 7276 3417 7277 3418 7277 2884 7277 3416 7278 3417 7278 2884 7278 3415 7279 3416 7279 2884 7279 3450 7280 2932 7280 2933 7280 3428 7281 2931 7281 2932 7281 3451 7282 3428 7282 2932 7282 3450 7283 3451 7283 2932 7283 3432 7284 2928 7284 2931 7284 3429 7285 2931 7285 3428 7285 3431 7286 3432 7286 2931 7286 3430 7287 3431 7287 2931 7287 3429 7288 3430 7288 2931 7288 3329 7289 2923 7289 2928 7289 3432 7290 3329 7290 2928 7290 3329 7291 2918 7291 2923 7291 3329 7292 2915 7292 2918 7292 3427 7293 2915 7293 3329 7293 3427 7294 3413 7294 2915 7294 3482 7295 2955 7295 2956 7295 3468 7296 2954 7296 2955 7296 3483 7297 3468 7297 2955 7297 3482 7298 3483 7298 2955 7298 3471 7299 2952 7299 2954 7299 3469 7300 2954 7300 3468 7300 3472 7301 3471 7301 2954 7301 3470 7302 3472 7302 2954 7302 3469 7303 3470 7303 2954 7303 3329 7304 2948 7304 2952 7304 3318 7305 3329 7305 2952 7305 3471 7306 3318 7306 2952 7306 3329 7307 2943 7307 2948 7307 3329 7308 2940 7308 2943 7308 3466 7309 2940 7309 3329 7309 3467 7310 3453 7310 2940 7310 3466 7311 3467 7311 2940 7311 3364 7312 2963 7312 2961 7312 3363 7313 2961 7313 2966 7313 3363 7314 3364 7314 2961 7314 3364 7315 3034 7315 2963 7315 3364 7316 3033 7316 3034 7316 3364 7317 3031 7317 3033 7317 3365 7318 3029 7318 3031 7318 3364 7319 3365 7319 3031 7319 3043 7320 3027 7320 3029 7320 3365 7321 3043 7321 3029 7321 3043 7322 3025 7322 3027 7322 3043 7323 3021 7323 3025 7323 3064 7324 3018 7324 3021 7324 3043 7325 3046 7325 3021 7325 3064 7326 3021 7326 3046 7326 3338 7327 3016 7327 3018 7327 3338 7328 3018 7328 3064 7328 3338 7329 3014 7329 3016 7329 3338 7330 3011 7330 3014 7330 3338 7331 3008 7331 3011 7331 3339 7332 3006 7332 3008 7332 3338 7333 3339 7333 3008 7333 3339 7334 3004 7334 3006 7334 3339 7335 3002 7335 3004 7335 3339 7336 2999 7336 3002 7336 3340 7337 2997 7337 2999 7337 3339 7338 3340 7338 2999 7338 3340 7339 2995 7339 2997 7339 3340 7340 2993 7340 2995 7340 3340 7341 2990 7341 2993 7341 3097 7342 2988 7342 2990 7342 3340 7343 3097 7343 2990 7343 3097 7344 2986 7344 2988 7344 3097 7345 2982 7345 2986 7345 3362 7346 2979 7346 2982 7346 3097 7347 3099 7347 2982 7347 3113 7348 2982 7348 3099 7348 3362 7349 2982 7349 3113 7349 3362 7350 2977 7350 2979 7350 3362 7351 2975 7351 2977 7351 3362 7352 2972 7352 2975 7352 3363 7353 2970 7353 2972 7353 3362 7354 3363 7354 2972 7354 3363 7355 2968 7355 2970 7355 3363 7356 2966 7356 2968 7356 3366 7357 3040 7357 3038 7357 3365 7358 3038 7358 3042 7358 3365 7359 3366 7359 3038 7359 3366 7360 3059 7360 3040 7360 3366 7361 3058 7361 3059 7361 3062 7362 3055 7362 3058 7362 3074 7363 3062 7363 3058 7363 3366 7364 3074 7364 3058 7364 3061 7365 3052 7365 3055 7365 3062 7366 3061 7366 3055 7366 3063 7367 3049 7367 3052 7367 3063 7368 3052 7368 3061 7368 3064 7369 3046 7369 3049 7369 3063 7370 3064 7370 3049 7370 3365 7371 3042 7371 3043 7371 3366 7372 3073 7372 3074 7372 3337 7373 3072 7373 3073 7373 3336 7374 3073 7374 3366 7374 3336 7375 3337 7375 3073 7375 3337 7376 3070 7376 3072 7376 3337 7377 3068 7377 3070 7377 3338 7378 3066 7378 3068 7378 3337 7379 3338 7379 3068 7379 3338 7380 3064 7380 3066 7380 3112 7381 3081 7381 3078 7381 3111 7382 3078 7382 3084 7382 3111 7383 3112 7383 3078 7383 3113 7384 3099 7384 3081 7384 3112 7385 3113 7385 3081 7385 3342 7386 3096 7386 3097 7386 3340 7387 3342 7387 3097 7387 3342 7388 3094 7388 3096 7388 3342 7389 3092 7389 3094 7389 3345 7390 3090 7390 3092 7390 3342 7391 3345 7391 3092 7391 3345 7392 3087 7392 3090 7392 3110 7393 3084 7393 3087 7393 3109 7394 3110 7394 3087 7394 3345 7395 3109 7395 3087 7395 3110 7396 3111 7396 3084 7396 3362 7397 3105 7397 3103 7397 3361 7398 3103 7398 3107 7398 3361 7399 3362 7399 3103 7399 3362 7400 3114 7400 3105 7400 3362 7401 3113 7401 3114 7401 3345 7402 3108 7402 3109 7402 3361 7403 3107 7403 3108 7403 3345 7404 3361 7404 3108 7404 3368 7405 3120 7405 3118 7405 3367 7406 3118 7406 3122 7406 3367 7407 3368 7407 3118 7407 3368 7408 3151 7408 3120 7408 3368 7409 3150 7409 3151 7409 3368 7410 3147 7410 3150 7410 3334 7411 3144 7411 3147 7411 3368 7412 3369 7412 3147 7412 3334 7413 3147 7413 3369 7413 3335 7414 3142 7414 3144 7414 3334 7415 3335 7415 3144 7415 3335 7416 3140 7416 3142 7416 3335 7417 3138 7417 3140 7417 3335 7418 3135 7418 3138 7418 3336 7419 3133 7419 3135 7419 3335 7420 3336 7420 3135 7420 3336 7421 3131 7421 3133 7421 3336 7422 3128 7422 3131 7422 3366 7423 3126 7423 3128 7423 3336 7424 3366 7424 3128 7424 3367 7425 3124 7425 3126 7425 3366 7426 3367 7426 3126 7426 3367 7427 3122 7427 3124 7427 3392 7428 3157 7428 3155 7428 3391 7429 3155 7429 3160 7429 3391 7430 3392 7430 3155 7430 3392 7431 3176 7431 3157 7431 3394 7432 3174 7432 3176 7432 3392 7433 3394 7433 3176 7433 3398 7434 3172 7434 3174 7434 3399 7435 3398 7435 3174 7435 3396 7436 3399 7436 3174 7436 3394 7437 3396 7437 3174 7437 3409 7438 3170 7438 3172 7438 3402 7439 3409 7439 3172 7439 3398 7440 3402 7440 3172 7440 3409 7441 3168 7441 3170 7441 3409 7442 3165 7442 3168 7442 3409 7443 3162 7443 3165 7443 3391 7444 3160 7444 3162 7444 3391 7445 3162 7445 3409 7445 3411 7446 3183 7446 3181 7446 3411 7447 3181 7447 3185 7447 3411 7448 3202 7448 3183 7448 3411 7449 3200 7449 3202 7449 3307 7450 3197 7450 3200 7450 3306 7451 3200 7451 3411 7451 3306 7452 3307 7452 3200 7452 3308 7453 3195 7453 3197 7453 3307 7454 3308 7454 3197 7454 3308 7455 3192 7455 3195 7455 3309 7456 3190 7456 3192 7456 3308 7457 3309 7457 3192 7457 3309 7458 3187 7458 3190 7458 3410 7459 3185 7459 3187 7459 3309 7460 3410 7460 3187 7460 3410 7461 3411 7461 3185 7461 3391 7462 3210 7462 3208 7462 3390 7463 3208 7463 3213 7463 3390 7464 3391 7464 3208 7464 3391 7465 3230 7465 3210 7465 3391 7466 3229 7466 3230 7466 3234 7467 3227 7467 3229 7467 3251 7468 3234 7468 3229 7468 3409 7469 3251 7469 3229 7469 3391 7470 3409 7470 3229 7470 3233 7471 3223 7471 3227 7471 3234 7472 3233 7472 3227 7472 3487 7473 3220 7473 3223 7473 3486 7474 3223 7474 3233 7474 3486 7475 3487 7475 3223 7475 3485 7476 3218 7476 3220 7476 3487 7477 3485 7477 3220 7477 3485 7478 3215 7478 3218 7478 3390 7479 3213 7479 3215 7479 3389 7480 3390 7480 3215 7480 3485 7481 3389 7481 3215 7481 3486 7482 3233 7482 3237 7482 3409 7483 3250 7483 3251 7483 3309 7484 3249 7484 3250 7484 3409 7485 3410 7485 3250 7485 3309 7486 3250 7486 3410 7486 3309 7487 3247 7487 3249 7487 3309 7488 3245 7488 3247 7488 3311 7489 3242 7489 3245 7489 3309 7490 3311 7490 3245 7490 3311 7491 3239 7491 3242 7491 3486 7492 3237 7492 3239 7492 3486 7493 3239 7493 3311 7493 3382 7494 3256 7494 3254 7494 3382 7495 3254 7495 3258 7495 3382 7496 3294 7496 3256 7496 3385 7497 3293 7497 3294 7497 3382 7498 3385 7498 3294 7498 3385 7499 3291 7499 3293 7499 3385 7500 3289 7500 3291 7500 3317 7501 3286 7501 3289 7501 3317 7502 3289 7502 3385 7502 3317 7503 3284 7503 3286 7503 3317 7504 3282 7504 3284 7504 3317 7505 3279 7505 3282 7505 3318 7506 3277 7506 3279 7506 3317 7507 3318 7507 3279 7507 3318 7508 3275 7508 3277 7508 3318 7509 3273 7509 3275 7509 3318 7510 3271 7510 3273 7510 3318 7511 3269 7511 3271 7511 3318 7512 3266 7512 3269 7512 3379 7513 3264 7513 3266 7513 3318 7514 3379 7514 3266 7514 3382 7515 3262 7515 3264 7515 3379 7516 3382 7516 3264 7516 3382 7517 3260 7517 3262 7517 3382 7518 3258 7518 3260 7518 3300 7519 3411 7519 3297 7519 3305 7520 3306 7520 3411 7520 3303 7521 3305 7521 3411 7521 3304 7522 3303 7522 3411 7522 3302 7523 3304 7523 3411 7523 3301 7524 3302 7524 3411 7524 3300 7525 3301 7525 3411 7525 3408 7526 3407 7526 3409 7526 3406 7527 3408 7527 3409 7527 3404 7528 3406 7528 3409 7528 3402 7529 3404 7529 3409 7529 3485 7530 3388 7530 3389 7530 3485 7531 3387 7531 3388 7531 3316 7532 3385 7532 3387 7532 3485 7533 3316 7533 3387 7533 3316 7534 3317 7534 3385 7534 3476 7535 3379 7535 3318 7535 3447 7536 3448 7536 3379 7536 3446 7537 3447 7537 3379 7537 3444 7538 3446 7538 3379 7538 3458 7539 3444 7539 3379 7539 3479 7540 3481 7540 3379 7540 3480 7541 3479 7541 3379 7541 3478 7542 3480 7542 3379 7542 3477 7543 3478 7543 3379 7543 3475 7544 3477 7544 3379 7544 3476 7545 3475 7545 3379 7545 3333 7546 3369 7546 3370 7546 3329 7547 3333 7547 3370 7547 3422 7548 3329 7548 3370 7548 3420 7549 3422 7549 3370 7549 3419 7550 3420 7550 3370 7550 3418 7551 3419 7551 3370 7551 3333 7552 3334 7552 3369 7552 3345 7553 3360 7553 3361 7553 3348 7554 3359 7554 3360 7554 3345 7555 3348 7555 3360 7555 3351 7556 3358 7556 3359 7556 3348 7557 3351 7557 3359 7557 3354 7558 3357 7558 3358 7558 3351 7559 3354 7559 3358 7559 3355 7560 3356 7560 3357 7560 3354 7561 3355 7561 3357 7561 3426 7562 3427 7562 3329 7562 3425 7563 3426 7563 3329 7563 3424 7564 3425 7564 3329 7564 3423 7565 3424 7565 3329 7565 3421 7566 3423 7566 3329 7566 3422 7567 3421 7567 3329 7567 3463 7568 3329 7568 3432 7568 3465 7569 3466 7569 3329 7569 3464 7570 3465 7570 3329 7570 3463 7571 3464 7571 3329 7571 3474 7572 3476 7572 3318 7572 3473 7573 3474 7573 3318 7573 3471 7574 3473 7574 3318 7574 3484 7575 3315 7575 3316 7575 3485 7576 3484 7576 3316 7576 3486 7577 3313 7577 3315 7577 3486 7578 3315 7578 3484 7578 3486 7579 3311 7579 3313 7579 3458 7580 3438 7580 3444 7580 3459 7581 3439 7581 3438 7581 3458 7582 3459 7582 3438 7582 3462 7583 3435 7583 3439 7583 3460 7584 3462 7584 3439 7584 3459 7585 3460 7585 3439 7585 3462 7586 3433 7586 3435 7586 3461 7587 3432 7587 3433 7587 3462 7588 3461 7588 3433 7588 3461 7589 3463 7589 3432 7589 3488 7590 3489 7590 3490 7590 3491 7591 3490 7591 3489 7591 3492 7592 3490 7592 3493 7592 3494 7593 3493 7593 3490 7593 3492 7594 3488 7594 3490 7594 3494 7595 3490 7595 3491 7595 3495 7596 3496 7596 3489 7596 3497 7597 3489 7597 3496 7597 3488 7598 3495 7598 3489 7598 3497 7599 3491 7599 3489 7599 3498 7600 3499 7600 3496 7600 3500 7601 3496 7601 3499 7601 3495 7602 3498 7602 3496 7602 3497 7603 3496 7603 3500 7603 3501 7604 3502 7604 3499 7604 3503 7605 3499 7605 3502 7605 3504 7606 3499 7606 3498 7606 3505 7607 3499 7607 3504 7607 3505 7608 3501 7608 3499 7608 3500 7609 3499 7609 3503 7609 3501 7610 3506 7610 3502 7610 3507 7611 3502 7611 3506 7611 3503 7612 3502 7612 3507 7612 3508 7613 3509 7613 3506 7613 3510 7614 3506 7614 3509 7614 3501 7615 3508 7615 3506 7615 3507 7616 3506 7616 3510 7616 3508 7617 3511 7617 3509 7617 3512 7618 3509 7618 3511 7618 3510 7619 3509 7619 3512 7619 3508 7620 3513 7620 3511 7620 3514 7621 3511 7621 3513 7621 3512 7622 3511 7622 3514 7622 3508 7623 3515 7623 3513 7623 3516 7624 3513 7624 3515 7624 3514 7625 3513 7625 3516 7625 3508 7626 3517 7626 3515 7626 3518 7627 3515 7627 3517 7627 3516 7628 3515 7628 3518 7628 3519 7629 3520 7629 3517 7629 3521 7630 3517 7630 3520 7630 3519 7631 3517 7631 3522 7631 3508 7632 3522 7632 3517 7632 3518 7633 3517 7633 3521 7633 3523 7634 3524 7634 3520 7634 3525 7635 3520 7635 3524 7635 3519 7636 3523 7636 3520 7636 3521 7637 3520 7637 3525 7637 3526 7638 3493 7638 3524 7638 3527 7639 3524 7639 3493 7639 3523 7640 3526 7640 3524 7640 3525 7641 3524 7641 3527 7641 3526 7642 3492 7642 3493 7642 3527 7643 3493 7643 3494 7643 3528 7644 3529 7644 3530 7644 3531 7645 3530 7645 3529 7645 3532 7646 3530 7646 3533 7646 3534 7647 3533 7647 3530 7647 3528 7648 3530 7648 3532 7648 3534 7649 3530 7649 3531 7649 3535 7650 3536 7650 3529 7650 3537 7651 3529 7651 3536 7651 3538 7652 3529 7652 3528 7652 3538 7653 3535 7653 3529 7653 3537 7654 3531 7654 3529 7654 3535 7655 3539 7655 3536 7655 3540 7656 3536 7656 3539 7656 3537 7657 3536 7657 3540 7657 3541 7658 3542 7658 3539 7658 3543 7659 3539 7659 3542 7659 3535 7660 3541 7660 3539 7660 3540 7661 3539 7661 3543 7661 3544 7662 3545 7662 3542 7662 3546 7663 3542 7663 3545 7663 3541 7664 3544 7664 3542 7664 3543 7665 3542 7665 3546 7665 3547 7666 3548 7666 3545 7666 3549 7667 3545 7667 3548 7667 3550 7668 3547 7668 3545 7668 3551 7669 3550 7669 3545 7669 3552 7670 3551 7670 3545 7670 3553 7671 3552 7671 3545 7671 3544 7672 3553 7672 3545 7672 3546 7673 3545 7673 3549 7673 3554 7674 3555 7674 3548 7674 3556 7675 3548 7675 3555 7675 3547 7676 3554 7676 3548 7676 3549 7677 3548 7677 3556 7677 3557 7678 3558 7678 3555 7678 3559 7679 3555 7679 3558 7679 3560 7680 3557 7680 3555 7680 3554 7681 3560 7681 3555 7681 3556 7682 3555 7682 3559 7682 3561 7683 3562 7683 3558 7683 3563 7684 3558 7684 3562 7684 3557 7685 3561 7685 3558 7685 3559 7686 3558 7686 3563 7686 3564 7687 3565 7687 3562 7687 3566 7688 3562 7688 3565 7688 3561 7689 3564 7689 3562 7689 3563 7690 3562 7690 3566 7690 3567 7691 3568 7691 3565 7691 3569 7692 3565 7692 3568 7692 3564 7693 3567 7693 3565 7693 3566 7694 3565 7694 3569 7694 3570 7695 3571 7695 3568 7695 3572 7696 3568 7696 3571 7696 3567 7697 3570 7697 3568 7697 3569 7698 3568 7698 3572 7698 3573 7699 3533 7699 3571 7699 3574 7700 3571 7700 3533 7700 3570 7701 3573 7701 3571 7701 3572 7702 3571 7702 3574 7702 3573 7703 3532 7703 3533 7703 3574 7704 3533 7704 3534 7704 3575 7705 3532 7705 3573 7705 3528 7706 3532 7706 3576 7706 3577 7707 3576 7707 3532 7707 3577 7708 3532 7708 3575 7708 3578 7709 3573 7709 3570 7709 3578 7710 3575 7710 3573 7710 3579 7711 3570 7711 3567 7711 3578 7712 3570 7712 3579 7712 3580 7713 3567 7713 3564 7713 3579 7714 3567 7714 3580 7714 3581 7715 3564 7715 3561 7715 3580 7716 3564 7716 3581 7716 3582 7717 3561 7717 3557 7717 3581 7718 3561 7718 3582 7718 3583 7719 3557 7719 3560 7719 3582 7720 3557 7720 3583 7720 3584 7721 3585 7721 3560 7721 3586 7722 3560 7722 3585 7722 3587 7723 3584 7723 3560 7723 3554 7724 3587 7724 3560 7724 3583 7725 3560 7725 3586 7725 3584 7726 3588 7726 3585 7726 3589 7727 3585 7727 3588 7727 3586 7728 3585 7728 3589 7728 3528 7729 3590 7729 3588 7729 3591 7730 3588 7730 3590 7730 3584 7731 3528 7731 3588 7731 3589 7732 3588 7732 3591 7732 3528 7733 3592 7733 3590 7733 3593 7734 3590 7734 3592 7734 3591 7735 3590 7735 3593 7735 3528 7736 3594 7736 3592 7736 3595 7737 3592 7737 3594 7737 3593 7738 3592 7738 3595 7738 3528 7739 3576 7739 3594 7739 3596 7740 3594 7740 3576 7740 3595 7741 3594 7741 3596 7741 3596 7742 3576 7742 3577 7742 3508 7743 3597 7743 3522 7743 3598 7744 3522 7744 3597 7744 3599 7745 3519 7745 3522 7745 3599 7746 3522 7746 3598 7746 3600 7747 3601 7747 3597 7747 3602 7748 3597 7748 3601 7748 3603 7749 3600 7749 3597 7749 3508 7750 3603 7750 3597 7750 3602 7751 3598 7751 3597 7751 3600 7752 3604 7752 3601 7752 3605 7753 3601 7753 3604 7753 3602 7754 3601 7754 3605 7754 3600 7755 3606 7755 3604 7755 3607 7756 3604 7756 3606 7756 3605 7757 3604 7757 3607 7757 3608 7758 3609 7758 3606 7758 3610 7759 3606 7759 3609 7759 3600 7760 3608 7760 3606 7760 3607 7761 3606 7761 3610 7761 3611 7762 3612 7762 3609 7762 3613 7763 3609 7763 3612 7763 3614 7764 3611 7764 3609 7764 3615 7765 3614 7765 3609 7765 3616 7766 3615 7766 3609 7766 3617 7767 3616 7767 3609 7767 3608 7768 3617 7768 3609 7768 3610 7769 3609 7769 3613 7769 3504 7770 3498 7770 3612 7770 3618 7771 3612 7771 3498 7771 3611 7772 3504 7772 3612 7772 3613 7773 3612 7773 3618 7773 3619 7774 3498 7774 3495 7774 3618 7775 3498 7775 3619 7775 3620 7776 3495 7776 3488 7776 3619 7777 3495 7777 3620 7777 3621 7778 3488 7778 3492 7778 3620 7779 3488 7779 3621 7779 3622 7780 3492 7780 3526 7780 3621 7781 3492 7781 3622 7781 3623 7782 3526 7782 3523 7782 3622 7783 3526 7783 3623 7783 3624 7784 3523 7784 3519 7784 3623 7785 3523 7785 3624 7785 3624 7786 3519 7786 3599 7786 3625 7787 3626 7787 3627 7787 3628 7788 3627 7788 3626 7788 3629 7789 3625 7789 3627 7789 3629 7790 3627 7790 3628 7790 3630 7791 3631 7791 3626 7791 3632 7792 3626 7792 3631 7792 3633 7793 3630 7793 3626 7793 3625 7794 3633 7794 3626 7794 3632 7795 3628 7795 3626 7795 3634 7796 3635 7796 3631 7796 3636 7797 3631 7797 3635 7797 3630 7798 3634 7798 3631 7798 3632 7799 3631 7799 3636 7799 3505 7800 3504 7800 3635 7800 3637 7801 3635 7801 3504 7801 3638 7802 3505 7802 3635 7802 3639 7803 3638 7803 3635 7803 3634 7804 3639 7804 3635 7804 3636 7805 3635 7805 3637 7805 3640 7806 3504 7806 3611 7806 3637 7807 3504 7807 3640 7807 3641 7808 3611 7808 3614 7808 3640 7809 3611 7809 3641 7809 3642 7810 3614 7810 3615 7810 3641 7811 3614 7811 3642 7811 3643 7812 3615 7812 3616 7812 3642 7813 3615 7813 3643 7813 3644 7814 3616 7814 3617 7814 3643 7815 3616 7815 3644 7815 3645 7816 3617 7816 3608 7816 3644 7817 3617 7817 3645 7817 3646 7818 3608 7818 3600 7818 3645 7819 3608 7819 3646 7819 3647 7820 3600 7820 3603 7820 3646 7821 3600 7821 3647 7821 3648 7822 3649 7822 3603 7822 3650 7823 3603 7823 3649 7823 3651 7824 3648 7824 3603 7824 3508 7825 3651 7825 3603 7825 3647 7826 3603 7826 3650 7826 3652 7827 3653 7827 3649 7827 3654 7828 3649 7828 3653 7828 3648 7829 3652 7829 3649 7829 3650 7830 3649 7830 3654 7830 3655 7831 3653 7831 3652 7831 3654 7832 3653 7832 3655 7832 3656 7833 3652 7833 3648 7833 3655 7834 3652 7834 3656 7834 3657 7835 3648 7835 3651 7835 3656 7836 3648 7836 3657 7836 3658 7837 3528 7837 3651 7837 3659 7838 3651 7838 3528 7838 3508 7839 3658 7839 3651 7839 3657 7840 3651 7840 3659 7840 3660 7841 3528 7841 3584 7841 3658 7842 3538 7842 3528 7842 3659 7843 3528 7843 3660 7843 3661 7844 3584 7844 3587 7844 3660 7845 3584 7845 3661 7845 3554 7846 3662 7846 3587 7846 3663 7847 3587 7847 3662 7847 3661 7848 3587 7848 3663 7848 3554 7849 3664 7849 3662 7849 3665 7850 3662 7850 3664 7850 3663 7851 3662 7851 3665 7851 3554 7852 3666 7852 3664 7852 3667 7853 3664 7853 3666 7853 3665 7854 3664 7854 3667 7854 3668 7855 3669 7855 3666 7855 3670 7856 3666 7856 3669 7856 3554 7857 3668 7857 3666 7857 3667 7858 3666 7858 3670 7858 3671 7859 3672 7859 3669 7859 3673 7860 3669 7860 3672 7860 3668 7861 3671 7861 3669 7861 3670 7862 3669 7862 3673 7862 3674 7863 3675 7863 3672 7863 3676 7864 3672 7864 3675 7864 3671 7865 3674 7865 3672 7865 3673 7866 3672 7866 3676 7866 3674 7867 3677 7867 3675 7867 3678 7868 3675 7868 3677 7868 3676 7869 3675 7869 3678 7869 3674 7870 3679 7870 3677 7870 3680 7871 3677 7871 3679 7871 3678 7872 3677 7872 3680 7872 3681 7873 3679 7873 3674 7873 3680 7874 3679 7874 3681 7874 3671 7875 3682 7875 3674 7875 3683 7876 3674 7876 3682 7876 3681 7877 3674 7877 3683 7877 3684 7878 3682 7878 3671 7878 3683 7879 3682 7879 3684 7879 3685 7880 3671 7880 3668 7880 3684 7881 3671 7881 3685 7881 3686 7882 3668 7882 3554 7882 3685 7883 3668 7883 3686 7883 3687 7884 3554 7884 3547 7884 3686 7885 3554 7885 3687 7885 3688 7886 3547 7886 3550 7886 3687 7887 3547 7887 3688 7887 3689 7888 3550 7888 3551 7888 3688 7889 3550 7889 3689 7889 3690 7890 3551 7890 3552 7890 3689 7891 3551 7891 3690 7891 3691 7892 3552 7892 3553 7892 3690 7893 3552 7893 3691 7893 3692 7894 3553 7894 3544 7894 3691 7895 3553 7895 3692 7895 3693 7896 3544 7896 3541 7896 3692 7897 3544 7897 3693 7897 3694 7898 3541 7898 3535 7898 3693 7899 3541 7899 3694 7899 3695 7900 3535 7900 3538 7900 3694 7901 3535 7901 3695 7901 3696 7902 3697 7902 3538 7902 3698 7903 3538 7903 3697 7903 3658 7904 3696 7904 3538 7904 3695 7905 3538 7905 3698 7905 3699 7906 3700 7906 3697 7906 3701 7907 3697 7907 3700 7907 3696 7908 3699 7908 3697 7908 3698 7909 3697 7909 3701 7909 3702 7910 3700 7910 3699 7910 3701 7911 3700 7911 3702 7911 3703 7912 3699 7912 3696 7912 3702 7913 3699 7913 3703 7913 3704 7914 3696 7914 3658 7914 3703 7915 3696 7915 3704 7915 3705 7916 3658 7916 3508 7916 3704 7917 3658 7917 3705 7917 3706 7918 3508 7918 3501 7918 3705 7919 3508 7919 3706 7919 3707 7920 3501 7920 3505 7920 3706 7921 3501 7921 3707 7921 3708 7922 3505 7922 3638 7922 3707 7923 3505 7923 3708 7923 3709 7924 3638 7924 3639 7924 3708 7925 3638 7925 3709 7925 3710 7926 3639 7926 3634 7926 3709 7927 3639 7927 3710 7927 3711 7928 3634 7928 3630 7928 3710 7929 3634 7929 3711 7929 3712 7930 3630 7930 3633 7930 3711 7931 3630 7931 3712 7931 3625 7932 3713 7932 3633 7932 3714 7933 3633 7933 3713 7933 3712 7934 3633 7934 3714 7934 3625 7935 3715 7935 3713 7935 3716 7936 3713 7936 3715 7936 3714 7937 3713 7937 3716 7937 3625 7938 3717 7938 3715 7938 3718 7939 3715 7939 3717 7939 3716 7940 3715 7940 3718 7940 3719 7941 3717 7941 3625 7941 3718 7942 3717 7942 3719 7942 3719 7943 3625 7943 3629 7943 3623 7944 3494 7944 3491 7944 3622 7945 3491 7945 3497 7945 3622 7946 3623 7946 3491 7946 3624 7947 3527 7947 3494 7947 3623 7948 3624 7948 3494 7948 3599 7949 3525 7949 3527 7949 3624 7950 3599 7950 3527 7950 3598 7951 3521 7951 3525 7951 3599 7952 3598 7952 3525 7952 3650 7953 3518 7953 3521 7953 3650 7954 3521 7954 3598 7954 3706 7955 3516 7955 3518 7955 3650 7956 3706 7956 3518 7956 3706 7957 3514 7957 3516 7957 3706 7958 3512 7958 3514 7958 3707 7959 3510 7959 3512 7959 3706 7960 3707 7960 3512 7960 3707 7961 3507 7961 3510 7961 3708 7962 3503 7962 3507 7962 3707 7963 3708 7963 3507 7963 3620 7964 3500 7964 3503 7964 3619 7965 3620 7965 3503 7965 3708 7966 3619 7966 3503 7966 3621 7967 3497 7967 3500 7967 3620 7968 3621 7968 3500 7968 3621 7969 3622 7969 3497 7969 3578 7970 3534 7970 3531 7970 3698 7971 3531 7971 3537 7971 3578 7972 3531 7972 3575 7972 3698 7973 3575 7973 3531 7973 3579 7974 3574 7974 3534 7974 3578 7975 3579 7975 3534 7975 3580 7976 3572 7976 3574 7976 3579 7977 3580 7977 3574 7977 3581 7978 3569 7978 3572 7978 3580 7979 3581 7979 3572 7979 3582 7980 3566 7980 3569 7980 3581 7981 3582 7981 3569 7981 3583 7982 3563 7982 3566 7982 3582 7983 3583 7983 3566 7983 3586 7984 3559 7984 3563 7984 3583 7985 3586 7985 3563 7985 3688 7986 3556 7986 3559 7986 3663 7987 3559 7987 3586 7987 3667 7988 3688 7988 3559 7988 3665 7989 3667 7989 3559 7989 3663 7990 3665 7990 3559 7990 3691 7991 3549 7991 3556 7991 3690 7992 3691 7992 3556 7992 3689 7993 3690 7993 3556 7993 3688 7994 3689 7994 3556 7994 3693 7995 3546 7995 3549 7995 3692 7996 3693 7996 3549 7996 3691 7997 3692 7997 3549 7997 3695 7998 3543 7998 3546 7998 3694 7999 3695 7999 3546 7999 3693 8000 3694 8000 3546 8000 3698 8001 3540 8001 3543 8001 3695 8002 3698 8002 3543 8002 3698 8003 3537 8003 3540 8003 3698 8004 3577 8004 3575 8004 3660 8005 3596 8005 3577 8005 3660 8006 3577 8006 3698 8006 3660 8007 3595 8007 3596 8007 3660 8008 3593 8008 3595 8008 3661 8009 3591 8009 3593 8009 3660 8010 3661 8010 3593 8010 3661 8011 3589 8011 3591 8011 3663 8012 3586 8012 3589 8012 3661 8013 3663 8013 3589 8013 3650 8014 3598 8014 3602 8014 3641 8015 3618 8015 3619 8015 3640 8016 3619 8016 3708 8016 3640 8017 3641 8017 3619 8017 3645 8018 3613 8018 3618 8018 3644 8019 3645 8019 3618 8019 3643 8020 3644 8020 3618 8020 3642 8021 3643 8021 3618 8021 3641 8022 3642 8022 3618 8022 3647 8023 3610 8023 3613 8023 3646 8024 3647 8024 3613 8024 3645 8025 3646 8025 3613 8025 3647 8026 3607 8026 3610 8026 3650 8027 3605 8027 3607 8027 3647 8028 3650 8028 3607 8028 3650 8029 3602 8029 3605 8029 3716 8030 3629 8030 3628 8030 3714 8031 3716 8031 3628 8031 3632 8032 3714 8032 3628 8032 3718 8033 3719 8033 3629 8033 3716 8034 3718 8034 3629 8034 3632 8035 3712 8035 3714 8035 3636 8036 3711 8036 3712 8036 3632 8037 3636 8037 3712 8037 3640 8038 3710 8038 3711 8038 3636 8039 3640 8039 3711 8039 3640 8040 3709 8040 3710 8040 3640 8041 3708 8041 3709 8041 3659 8042 3705 8042 3706 8042 3659 8043 3706 8043 3650 8043 3650 8044 3657 8044 3659 8044 3705 8045 3660 8045 3698 8045 3659 8046 3660 8046 3705 8046 3702 8047 3703 8047 3704 8047 3701 8048 3702 8048 3704 8048 3698 8049 3701 8049 3704 8049 3698 8050 3704 8050 3705 8050 3686 8051 3687 8051 3688 8051 3670 8052 3686 8052 3688 8052 3667 8053 3670 8053 3688 8053 3673 8054 3685 8054 3686 8054 3670 8055 3673 8055 3686 8055 3676 8056 3684 8056 3685 8056 3673 8057 3676 8057 3685 8057 3678 8058 3683 8058 3684 8058 3676 8059 3678 8059 3684 8059 3680 8060 3681 8060 3683 8060 3678 8061 3680 8061 3683 8061 3655 8062 3656 8062 3657 8062 3654 8063 3655 8063 3657 8063 3650 8064 3654 8064 3657 8064 3636 8065 3637 8065 3640 8065 3720 8066 3721 8066 3722 8066 3723 8067 3722 8067 3721 8067 3724 8068 3722 8068 3725 8068 3726 8069 3725 8069 3722 8069 3724 8070 3720 8070 3722 8070 3726 8071 3722 8071 3723 8071 3727 8072 3728 8072 3721 8072 3729 8073 3721 8073 3728 8073 3720 8074 3727 8074 3721 8074 3729 8075 3723 8075 3721 8075 3730 8076 3731 8076 3728 8076 3732 8077 3728 8077 3731 8077 3727 8078 3730 8078 3728 8078 3729 8079 3728 8079 3732 8079 3733 8080 3734 8080 3731 8080 3735 8081 3731 8081 3734 8081 3736 8082 3731 8082 3730 8082 3737 8083 3731 8083 3736 8083 3737 8084 3733 8084 3731 8084 3732 8085 3731 8085 3735 8085 3733 8086 3738 8086 3734 8086 3739 8087 3734 8087 3738 8087 3735 8088 3734 8088 3739 8088 3740 8089 3741 8089 3738 8089 3742 8090 3738 8090 3741 8090 3733 8091 3740 8091 3738 8091 3739 8092 3738 8092 3742 8092 3740 8093 3743 8093 3741 8093 3744 8094 3741 8094 3743 8094 3742 8095 3741 8095 3744 8095 3740 8096 3745 8096 3743 8096 3746 8097 3743 8097 3745 8097 3744 8098 3743 8098 3746 8098 3740 8099 3747 8099 3745 8099 3748 8100 3745 8100 3747 8100 3746 8101 3745 8101 3748 8101 3740 8102 3749 8102 3747 8102 3750 8103 3747 8103 3749 8103 3748 8104 3747 8104 3750 8104 3751 8105 3752 8105 3749 8105 3753 8106 3749 8106 3752 8106 3751 8107 3749 8107 3754 8107 3740 8108 3754 8108 3749 8108 3750 8109 3749 8109 3753 8109 3755 8110 3756 8110 3752 8110 3757 8111 3752 8111 3756 8111 3751 8112 3755 8112 3752 8112 3753 8113 3752 8113 3757 8113 3758 8114 3725 8114 3756 8114 3759 8115 3756 8115 3725 8115 3755 8116 3758 8116 3756 8116 3757 8117 3756 8117 3759 8117 3758 8118 3724 8118 3725 8118 3759 8119 3725 8119 3726 8119 3760 8120 3761 8120 3762 8120 3763 8121 3762 8121 3761 8121 3764 8122 3762 8122 3765 8122 3766 8123 3765 8123 3762 8123 3760 8124 3762 8124 3764 8124 3766 8125 3762 8125 3763 8125 3767 8126 3768 8126 3761 8126 3769 8127 3761 8127 3768 8127 3770 8128 3761 8128 3760 8128 3770 8129 3767 8129 3761 8129 3769 8130 3763 8130 3761 8130 3767 8131 3771 8131 3768 8131 3772 8132 3768 8132 3771 8132 3769 8133 3768 8133 3772 8133 3773 8134 3774 8134 3771 8134 3775 8135 3771 8135 3774 8135 3767 8136 3773 8136 3771 8136 3772 8137 3771 8137 3775 8137 3776 8138 3777 8138 3774 8138 3778 8139 3774 8139 3777 8139 3773 8140 3776 8140 3774 8140 3775 8141 3774 8141 3778 8141 3779 8142 3780 8142 3777 8142 3781 8143 3777 8143 3780 8143 3782 8144 3779 8144 3777 8144 3783 8145 3782 8145 3777 8145 3784 8146 3783 8146 3777 8146 3785 8147 3784 8147 3777 8147 3776 8148 3785 8148 3777 8148 3778 8149 3777 8149 3781 8149 3786 8150 3787 8150 3780 8150 3788 8151 3780 8151 3787 8151 3779 8152 3786 8152 3780 8152 3781 8153 3780 8153 3788 8153 3789 8154 3790 8154 3787 8154 3791 8155 3787 8155 3790 8155 3792 8156 3789 8156 3787 8156 3786 8157 3792 8157 3787 8157 3788 8158 3787 8158 3791 8158 3793 8159 3794 8159 3790 8159 3795 8160 3790 8160 3794 8160 3789 8161 3793 8161 3790 8161 3791 8162 3790 8162 3795 8162 3796 8163 3797 8163 3794 8163 3798 8164 3794 8164 3797 8164 3793 8165 3796 8165 3794 8165 3795 8166 3794 8166 3798 8166 3799 8167 3800 8167 3797 8167 3801 8168 3797 8168 3800 8168 3796 8169 3799 8169 3797 8169 3798 8170 3797 8170 3801 8170 3802 8171 3803 8171 3800 8171 3804 8172 3800 8172 3803 8172 3799 8173 3802 8173 3800 8173 3801 8174 3800 8174 3804 8174 3805 8175 3765 8175 3803 8175 3806 8176 3803 8176 3765 8176 3802 8177 3805 8177 3803 8177 3804 8178 3803 8178 3806 8178 3805 8179 3764 8179 3765 8179 3806 8180 3765 8180 3766 8180 3807 8181 3764 8181 3805 8181 3760 8182 3764 8182 3808 8182 3809 8183 3808 8183 3764 8183 3809 8184 3764 8184 3807 8184 3810 8185 3805 8185 3802 8185 3810 8186 3807 8186 3805 8186 3811 8187 3802 8187 3799 8187 3810 8188 3802 8188 3811 8188 3812 8189 3799 8189 3796 8189 3811 8190 3799 8190 3812 8190 3813 8191 3796 8191 3793 8191 3812 8192 3796 8192 3813 8192 3814 8193 3793 8193 3789 8193 3813 8194 3793 8194 3814 8194 3815 8195 3789 8195 3792 8195 3814 8196 3789 8196 3815 8196 3816 8197 3817 8197 3792 8197 3818 8198 3792 8198 3817 8198 3819 8199 3816 8199 3792 8199 3786 8200 3819 8200 3792 8200 3815 8201 3792 8201 3818 8201 3816 8202 3820 8202 3817 8202 3821 8203 3817 8203 3820 8203 3818 8204 3817 8204 3821 8204 3760 8205 3822 8205 3820 8205 3823 8206 3820 8206 3822 8206 3816 8207 3760 8207 3820 8207 3821 8208 3820 8208 3823 8208 3760 8209 3824 8209 3822 8209 3825 8210 3822 8210 3824 8210 3823 8211 3822 8211 3825 8211 3760 8212 3826 8212 3824 8212 3827 8213 3824 8213 3826 8213 3825 8214 3824 8214 3827 8214 3760 8215 3808 8215 3826 8215 3828 8216 3826 8216 3808 8216 3827 8217 3826 8217 3828 8217 3828 8218 3808 8218 3809 8218 3740 8219 3829 8219 3754 8219 3830 8220 3754 8220 3829 8220 3831 8221 3751 8221 3754 8221 3831 8222 3754 8222 3830 8222 3832 8223 3833 8223 3829 8223 3834 8224 3829 8224 3833 8224 3835 8225 3832 8225 3829 8225 3740 8226 3835 8226 3829 8226 3834 8227 3830 8227 3829 8227 3832 8228 3836 8228 3833 8228 3837 8229 3833 8229 3836 8229 3834 8230 3833 8230 3837 8230 3832 8231 3838 8231 3836 8231 3839 8232 3836 8232 3838 8232 3837 8233 3836 8233 3839 8233 3840 8234 3841 8234 3838 8234 3842 8235 3838 8235 3841 8235 3832 8236 3840 8236 3838 8236 3839 8237 3838 8237 3842 8237 3843 8238 3844 8238 3841 8238 3845 8239 3841 8239 3844 8239 3846 8240 3843 8240 3841 8240 3847 8241 3846 8241 3841 8241 3848 8242 3847 8242 3841 8242 3849 8243 3848 8243 3841 8243 3840 8244 3849 8244 3841 8244 3842 8245 3841 8245 3845 8245 3736 8246 3730 8246 3844 8246 3850 8247 3844 8247 3730 8247 3843 8248 3736 8248 3844 8248 3845 8249 3844 8249 3850 8249 3851 8250 3730 8250 3727 8250 3850 8251 3730 8251 3851 8251 3852 8252 3727 8252 3720 8252 3851 8253 3727 8253 3852 8253 3853 8254 3720 8254 3724 8254 3852 8255 3720 8255 3853 8255 3854 8256 3724 8256 3758 8256 3853 8257 3724 8257 3854 8257 3855 8258 3758 8258 3755 8258 3854 8259 3758 8259 3855 8259 3856 8260 3755 8260 3751 8260 3855 8261 3755 8261 3856 8261 3856 8262 3751 8262 3831 8262 3857 8263 3858 8263 3859 8263 3860 8264 3859 8264 3858 8264 3861 8265 3857 8265 3859 8265 3861 8266 3859 8266 3860 8266 3862 8267 3863 8267 3858 8267 3864 8268 3858 8268 3863 8268 3865 8269 3862 8269 3858 8269 3857 8270 3865 8270 3858 8270 3864 8271 3860 8271 3858 8271 3866 8272 3867 8272 3863 8272 3868 8273 3863 8273 3867 8273 3862 8274 3866 8274 3863 8274 3864 8275 3863 8275 3868 8275 3737 8276 3736 8276 3867 8276 3869 8277 3867 8277 3736 8277 3870 8278 3737 8278 3867 8278 3871 8279 3870 8279 3867 8279 3866 8280 3871 8280 3867 8280 3868 8281 3867 8281 3869 8281 3872 8282 3736 8282 3843 8282 3869 8283 3736 8283 3872 8283 3873 8284 3843 8284 3846 8284 3872 8285 3843 8285 3873 8285 3874 8286 3846 8286 3847 8286 3873 8287 3846 8287 3874 8287 3875 8288 3847 8288 3848 8288 3874 8289 3847 8289 3875 8289 3876 8290 3848 8290 3849 8290 3875 8291 3848 8291 3876 8291 3877 8292 3849 8292 3840 8292 3876 8293 3849 8293 3877 8293 3878 8294 3840 8294 3832 8294 3877 8295 3840 8295 3878 8295 3879 8296 3832 8296 3835 8296 3878 8297 3832 8297 3879 8297 3880 8298 3881 8298 3835 8298 3882 8299 3835 8299 3881 8299 3883 8300 3880 8300 3835 8300 3740 8301 3883 8301 3835 8301 3879 8302 3835 8302 3882 8302 3884 8303 3885 8303 3881 8303 3886 8304 3881 8304 3885 8304 3880 8305 3884 8305 3881 8305 3882 8306 3881 8306 3886 8306 3887 8307 3885 8307 3884 8307 3886 8308 3885 8308 3887 8308 3888 8309 3884 8309 3880 8309 3887 8310 3884 8310 3888 8310 3889 8311 3880 8311 3883 8311 3888 8312 3880 8312 3889 8312 3890 8313 3760 8313 3883 8313 3891 8314 3883 8314 3760 8314 3740 8315 3890 8315 3883 8315 3889 8316 3883 8316 3891 8316 3892 8317 3760 8317 3816 8317 3890 8318 3770 8318 3760 8318 3891 8319 3760 8319 3892 8319 3893 8320 3816 8320 3819 8320 3892 8321 3816 8321 3893 8321 3786 8322 3894 8322 3819 8322 3895 8323 3819 8323 3894 8323 3893 8324 3819 8324 3895 8324 3786 8325 3896 8325 3894 8325 3897 8326 3894 8326 3896 8326 3895 8327 3894 8327 3897 8327 3786 8328 3898 8328 3896 8328 3899 8329 3896 8329 3898 8329 3897 8330 3896 8330 3899 8330 3900 8331 3901 8331 3898 8331 3902 8332 3898 8332 3901 8332 3786 8333 3900 8333 3898 8333 3899 8334 3898 8334 3902 8334 3903 8335 3904 8335 3901 8335 3905 8336 3901 8336 3904 8336 3900 8337 3903 8337 3901 8337 3902 8338 3901 8338 3905 8338 3906 8339 3907 8339 3904 8339 3908 8340 3904 8340 3907 8340 3903 8341 3906 8341 3904 8341 3905 8342 3904 8342 3908 8342 3906 8343 3909 8343 3907 8343 3910 8344 3907 8344 3909 8344 3908 8345 3907 8345 3910 8345 3906 8346 3911 8346 3909 8346 3912 8347 3909 8347 3911 8347 3910 8348 3909 8348 3912 8348 3913 8349 3911 8349 3906 8349 3912 8350 3911 8350 3913 8350 3903 8351 3914 8351 3906 8351 3915 8352 3906 8352 3914 8352 3913 8353 3906 8353 3915 8353 3916 8354 3914 8354 3903 8354 3915 8355 3914 8355 3916 8355 3917 8356 3903 8356 3900 8356 3916 8357 3903 8357 3917 8357 3918 8358 3900 8358 3786 8358 3917 8359 3900 8359 3918 8359 3919 8360 3786 8360 3779 8360 3918 8361 3786 8361 3919 8361 3920 8362 3779 8362 3782 8362 3919 8363 3779 8363 3920 8363 3921 8364 3782 8364 3783 8364 3920 8365 3782 8365 3921 8365 3922 8366 3783 8366 3784 8366 3921 8367 3783 8367 3922 8367 3923 8368 3784 8368 3785 8368 3922 8369 3784 8369 3923 8369 3924 8370 3785 8370 3776 8370 3923 8371 3785 8371 3924 8371 3925 8372 3776 8372 3773 8372 3924 8373 3776 8373 3925 8373 3926 8374 3773 8374 3767 8374 3925 8375 3773 8375 3926 8375 3927 8376 3767 8376 3770 8376 3926 8377 3767 8377 3927 8377 3928 8378 3929 8378 3770 8378 3930 8379 3770 8379 3929 8379 3890 8380 3928 8380 3770 8380 3927 8381 3770 8381 3930 8381 3931 8382 3932 8382 3929 8382 3933 8383 3929 8383 3932 8383 3928 8384 3931 8384 3929 8384 3930 8385 3929 8385 3933 8385 3934 8386 3932 8386 3931 8386 3933 8387 3932 8387 3934 8387 3935 8388 3931 8388 3928 8388 3934 8389 3931 8389 3935 8389 3936 8390 3928 8390 3890 8390 3935 8391 3928 8391 3936 8391 3937 8392 3890 8392 3740 8392 3936 8393 3890 8393 3937 8393 3938 8394 3740 8394 3733 8394 3937 8395 3740 8395 3938 8395 3939 8396 3733 8396 3737 8396 3938 8397 3733 8397 3939 8397 3940 8398 3737 8398 3870 8398 3939 8399 3737 8399 3940 8399 3941 8400 3870 8400 3871 8400 3940 8401 3870 8401 3941 8401 3942 8402 3871 8402 3866 8402 3941 8403 3871 8403 3942 8403 3943 8404 3866 8404 3862 8404 3942 8405 3866 8405 3943 8405 3944 8406 3862 8406 3865 8406 3943 8407 3862 8407 3944 8407 3857 8408 3945 8408 3865 8408 3946 8409 3865 8409 3945 8409 3944 8410 3865 8410 3946 8410 3857 8411 3947 8411 3945 8411 3948 8412 3945 8412 3947 8412 3946 8413 3945 8413 3948 8413 3857 8414 3949 8414 3947 8414 3950 8415 3947 8415 3949 8415 3948 8416 3947 8416 3950 8416 3951 8417 3949 8417 3857 8417 3950 8418 3949 8418 3951 8418 3951 8419 3857 8419 3861 8419 3855 8420 3726 8420 3723 8420 3854 8421 3723 8421 3729 8421 3854 8422 3855 8422 3723 8422 3856 8423 3759 8423 3726 8423 3855 8424 3856 8424 3726 8424 3831 8425 3757 8425 3759 8425 3856 8426 3831 8426 3759 8426 3830 8427 3753 8427 3757 8427 3831 8428 3830 8428 3757 8428 3882 8429 3750 8429 3753 8429 3882 8430 3753 8430 3830 8430 3938 8431 3748 8431 3750 8431 3882 8432 3938 8432 3750 8432 3938 8433 3746 8433 3748 8433 3938 8434 3744 8434 3746 8434 3939 8435 3742 8435 3744 8435 3938 8436 3939 8436 3744 8436 3939 8437 3739 8437 3742 8437 3940 8438 3735 8438 3739 8438 3939 8439 3940 8439 3739 8439 3852 8440 3732 8440 3735 8440 3851 8441 3852 8441 3735 8441 3940 8442 3851 8442 3735 8442 3853 8443 3729 8443 3732 8443 3852 8444 3853 8444 3732 8444 3853 8445 3854 8445 3729 8445 3810 8446 3766 8446 3763 8446 3930 8447 3763 8447 3769 8447 3810 8448 3763 8448 3807 8448 3930 8449 3807 8449 3763 8449 3811 8450 3806 8450 3766 8450 3810 8451 3811 8451 3766 8451 3812 8452 3804 8452 3806 8452 3811 8453 3812 8453 3806 8453 3813 8454 3801 8454 3804 8454 3812 8455 3813 8455 3804 8455 3814 8456 3798 8456 3801 8456 3813 8457 3814 8457 3801 8457 3815 8458 3795 8458 3798 8458 3814 8459 3815 8459 3798 8459 3818 8460 3791 8460 3795 8460 3815 8461 3818 8461 3795 8461 3920 8462 3788 8462 3791 8462 3895 8463 3791 8463 3818 8463 3899 8464 3920 8464 3791 8464 3897 8465 3899 8465 3791 8465 3895 8466 3897 8466 3791 8466 3923 8467 3781 8467 3788 8467 3922 8468 3923 8468 3788 8468 3921 8469 3922 8469 3788 8469 3920 8470 3921 8470 3788 8470 3925 8471 3778 8471 3781 8471 3924 8472 3925 8472 3781 8472 3923 8473 3924 8473 3781 8473 3927 8474 3775 8474 3778 8474 3926 8475 3927 8475 3778 8475 3925 8476 3926 8476 3778 8476 3930 8477 3772 8477 3775 8477 3927 8478 3930 8478 3775 8478 3930 8479 3769 8479 3772 8479 3930 8480 3809 8480 3807 8480 3892 8481 3828 8481 3809 8481 3892 8482 3809 8482 3930 8482 3892 8483 3827 8483 3828 8483 3892 8484 3825 8484 3827 8484 3893 8485 3823 8485 3825 8485 3892 8486 3893 8486 3825 8486 3893 8487 3821 8487 3823 8487 3895 8488 3818 8488 3821 8488 3893 8489 3895 8489 3821 8489 3882 8490 3830 8490 3834 8490 3873 8491 3850 8491 3851 8491 3872 8492 3851 8492 3940 8492 3872 8493 3873 8493 3851 8493 3877 8494 3845 8494 3850 8494 3876 8495 3877 8495 3850 8495 3875 8496 3876 8496 3850 8496 3874 8497 3875 8497 3850 8497 3873 8498 3874 8498 3850 8498 3879 8499 3842 8499 3845 8499 3878 8500 3879 8500 3845 8500 3877 8501 3878 8501 3845 8501 3879 8502 3839 8502 3842 8502 3882 8503 3837 8503 3839 8503 3879 8504 3882 8504 3839 8504 3882 8505 3834 8505 3837 8505 3948 8506 3861 8506 3860 8506 3946 8507 3948 8507 3860 8507 3864 8508 3946 8508 3860 8508 3950 8509 3951 8509 3861 8509 3948 8510 3950 8510 3861 8510 3864 8511 3944 8511 3946 8511 3868 8512 3943 8512 3944 8512 3864 8513 3868 8513 3944 8513 3872 8514 3942 8514 3943 8514 3868 8515 3872 8515 3943 8515 3872 8516 3941 8516 3942 8516 3872 8517 3940 8517 3941 8517 3891 8518 3937 8518 3938 8518 3891 8519 3938 8519 3882 8519 3882 8520 3889 8520 3891 8520 3937 8521 3892 8521 3930 8521 3891 8522 3892 8522 3937 8522 3934 8523 3935 8523 3936 8523 3933 8524 3934 8524 3936 8524 3930 8525 3933 8525 3936 8525 3930 8526 3936 8526 3937 8526 3918 8527 3919 8527 3920 8527 3902 8528 3918 8528 3920 8528 3899 8529 3902 8529 3920 8529 3905 8530 3917 8530 3918 8530 3902 8531 3905 8531 3918 8531 3908 8532 3916 8532 3917 8532 3905 8533 3908 8533 3917 8533 3910 8534 3915 8534 3916 8534 3908 8535 3910 8535 3916 8535 3912 8536 3913 8536 3915 8536 3910 8537 3912 8537 3915 8537 3887 8538 3888 8538 3889 8538 3886 8539 3887 8539 3889 8539 3882 8540 3886 8540 3889 8540 3868 8541 3869 8541 3872 8541 3952 8542 3953 8542 3954 8542 3955 8543 3954 8543 3953 8543 3952 8544 3954 8544 3956 8544 3957 8545 3956 8545 3954 8545 3957 8546 3954 8546 3955 8546 3958 8547 3959 8547 3953 8547 3960 8548 3953 8548 3959 8548 3958 8549 3953 8549 3952 8549 3960 8550 3955 8550 3953 8550 3958 8551 3961 8551 3959 8551 3962 8552 3959 8552 3961 8552 3960 8553 3959 8553 3962 8553 3963 8554 3964 8554 3961 8554 3965 8555 3961 8555 3964 8555 3958 8556 3963 8556 3961 8556 3962 8557 3961 8557 3965 8557 3963 8558 3966 8558 3964 8558 3967 8559 3964 8559 3966 8559 3965 8560 3964 8560 3967 8560 3963 8561 3968 8561 3966 8561 3969 8562 3966 8562 3968 8562 3967 8563 3966 8563 3969 8563 3952 8564 3956 8564 3968 8564 3970 8565 3968 8565 3956 8565 3971 8566 3972 8566 3968 8566 3973 8567 3968 8567 3972 8567 3974 8568 3971 8568 3968 8568 3975 8569 3974 8569 3968 8569 3976 8570 3968 8570 3973 8570 3977 8571 3975 8571 3968 8571 3978 8572 3977 8572 3968 8572 3963 8573 3978 8573 3968 8573 3976 8574 3952 8574 3968 8574 3969 8575 3968 8575 3970 8575 3970 8576 3956 8576 3957 8576 3979 8577 3980 8577 3981 8577 3982 8578 3981 8578 3980 8578 3979 8579 3981 8579 3983 8579 3984 8580 3983 8580 3981 8580 3984 8581 3981 8581 3982 8581 3979 8582 3985 8582 3980 8582 3986 8583 3980 8583 3985 8583 3986 8584 3982 8584 3980 8584 3987 8585 3988 8585 3985 8585 3989 8586 3985 8586 3988 8586 3990 8587 3987 8587 3985 8587 3979 8588 3990 8588 3985 8588 3986 8589 3985 8589 3989 8589 3987 8590 3991 8590 3988 8590 3992 8591 3988 8591 3991 8591 3989 8592 3988 8592 3992 8592 3993 8593 3994 8593 3991 8593 3995 8594 3991 8594 3994 8594 3987 8595 3993 8595 3991 8595 3992 8596 3991 8596 3995 8596 3996 8597 3997 8597 3994 8597 3998 8598 3994 8598 3997 8598 3999 8599 3996 8599 3994 8599 3993 8600 3999 8600 3994 8600 3995 8601 3994 8601 3998 8601 4000 8602 3983 8602 3997 8602 4001 8603 3997 8603 3983 8603 4000 8604 3997 8604 3996 8604 3998 8605 3997 8605 4001 8605 4000 8606 3979 8606 3983 8606 4001 8607 3983 8607 3984 8607 4002 8608 4003 8608 4004 8608 4005 8609 4004 8609 4003 8609 4006 8610 4004 8610 4007 8610 4008 8611 4007 8611 4004 8611 4009 8612 4002 8612 4004 8612 4009 8613 4004 8613 4006 8613 4008 8614 4004 8614 4005 8614 4002 8615 4010 8615 4003 8615 4011 8616 4003 8616 4010 8616 4011 8617 4005 8617 4003 8617 4002 8618 4012 8618 4010 8618 4013 8619 4010 8619 4012 8619 4011 8620 4010 8620 4013 8620 4002 8621 4014 8621 4012 8621 4015 8622 4012 8622 4014 8622 4013 8623 4012 8623 4015 8623 4002 8624 4016 8624 4014 8624 4017 8625 4014 8625 4016 8625 4015 8626 4014 8626 4017 8626 4018 8627 4019 8627 4016 8627 4020 8628 4016 8628 4019 8628 4021 8629 4018 8629 4016 8629 4002 8630 4021 8630 4016 8630 4017 8631 4016 8631 4020 8631 4022 8632 4023 8632 4019 8632 4024 8633 4019 8633 4023 8633 4018 8634 4022 8634 4019 8634 4020 8635 4019 8635 4024 8635 4022 8636 4025 8636 4023 8636 4026 8637 4023 8637 4025 8637 4024 8638 4023 8638 4026 8638 4027 8639 4028 8639 4025 8639 4029 8640 4025 8640 4028 8640 4030 8641 4025 8641 4022 8641 4030 8642 4031 8642 4025 8642 4027 8643 4025 8643 4031 8643 4026 8644 4025 8644 4029 8644 4027 8645 4032 8645 4028 8645 4033 8646 4028 8646 4032 8646 4029 8647 4028 8647 4033 8647 4006 8648 4034 8648 4032 8648 4035 8649 4032 8649 4034 8649 4027 8650 4006 8650 4032 8650 4033 8651 4032 8651 4035 8651 4006 8652 4036 8652 4034 8652 4037 8653 4034 8653 4036 8653 4035 8654 4034 8654 4037 8654 4006 8655 4038 8655 4036 8655 4039 8656 4036 8656 4038 8656 4037 8657 4036 8657 4039 8657 4006 8658 4040 8658 4038 8658 4041 8659 4038 8659 4040 8659 4039 8660 4038 8660 4041 8660 4006 8661 4007 8661 4040 8661 4042 8662 4040 8662 4007 8662 4041 8663 4040 8663 4042 8663 4042 8664 4007 8664 4008 8664 4043 8665 4044 8665 4045 8665 4046 8666 4045 8666 4044 8666 4043 8667 4045 8667 4047 8667 4048 8668 4047 8668 4045 8668 4048 8669 4045 8669 4046 8669 4049 8670 4050 8670 4044 8670 4051 8671 4044 8671 4050 8671 4049 8672 4044 8672 4043 8672 4051 8673 4046 8673 4044 8673 4052 8674 4053 8674 4050 8674 4054 8675 4050 8675 4053 8675 4049 8676 4052 8676 4050 8676 4051 8677 4050 8677 4054 8677 4052 8678 4055 8678 4053 8678 4056 8679 4053 8679 4055 8679 4054 8680 4053 8680 4056 8680 4052 8681 4057 8681 4055 8681 4058 8682 4055 8682 4057 8682 4056 8683 4055 8683 4058 8683 4052 8684 4059 8684 4057 8684 4060 8685 4057 8685 4059 8685 4058 8686 4057 8686 4060 8686 4052 8687 4061 8687 4059 8687 4062 8688 4059 8688 4061 8688 4060 8689 4059 8689 4062 8689 4052 8690 4063 8690 4061 8690 4064 8691 4061 8691 4063 8691 4062 8692 4061 8692 4064 8692 4065 8693 4066 8693 4063 8693 4067 8694 4063 8694 4066 8694 4052 8695 4065 8695 4063 8695 4064 8696 4063 8696 4067 8696 4065 8697 4068 8697 4066 8697 4069 8698 4066 8698 4068 8698 4067 8699 4066 8699 4069 8699 4065 8700 4070 8700 4068 8700 4071 8701 4068 8701 4070 8701 4069 8702 4068 8702 4071 8702 4043 8703 4072 8703 4070 8703 4073 8704 4070 8704 4072 8704 4065 8705 4043 8705 4070 8705 4071 8706 4070 8706 4073 8706 4043 8707 4074 8707 4072 8707 4075 8708 4072 8708 4074 8708 4073 8709 4072 8709 4075 8709 4043 8710 4076 8710 4074 8710 4077 8711 4074 8711 4076 8711 4075 8712 4074 8712 4077 8712 4043 8713 4047 8713 4076 8713 4078 8714 4076 8714 4047 8714 4077 8715 4076 8715 4078 8715 4078 8716 4047 8716 4048 8716 4079 8717 4080 8717 4081 8717 4082 8718 4081 8718 4080 8718 4079 8719 4081 8719 4083 8719 4084 8720 4083 8720 4081 8720 4084 8721 4081 8721 4082 8721 4079 8722 4085 8722 4080 8722 4086 8723 4080 8723 4085 8723 4086 8724 4082 8724 4080 8724 4079 8725 4087 8725 4085 8725 4088 8726 4085 8726 4087 8726 4086 8727 4085 8727 4088 8727 4079 8728 4089 8728 4087 8728 4090 8729 4087 8729 4089 8729 4088 8730 4087 8730 4090 8730 4091 8731 4092 8731 4089 8731 4093 8732 4089 8732 4092 8732 4094 8733 4091 8733 4089 8733 4095 8734 4094 8734 4089 8734 4095 8735 4089 8735 4079 8735 4090 8736 4089 8736 4093 8736 4096 8737 4097 8737 4092 8737 4098 8738 4092 8738 4097 8738 4091 8739 4096 8739 4092 8739 4093 8740 4092 8740 4098 8740 4099 8741 4100 8741 4097 8741 4101 8742 4097 8742 4100 8742 4096 8743 4099 8743 4097 8743 4098 8744 4097 8744 4101 8744 4102 8745 4103 8745 4100 8745 4104 8746 4100 8746 4103 8746 4099 8747 4102 8747 4100 8747 4101 8748 4100 8748 4104 8748 4105 8749 4106 8749 4103 8749 4107 8750 4103 8750 4106 8750 4105 8751 4103 8751 4102 8751 4104 8752 4103 8752 4107 8752 4108 8753 4109 8753 4106 8753 4110 8754 4106 8754 4109 8754 4105 8755 4108 8755 4106 8755 4107 8756 4106 8756 4110 8756 4111 8757 4112 8757 4109 8757 4113 8758 4109 8758 4112 8758 4108 8759 4111 8759 4109 8759 4110 8760 4109 8760 4113 8760 4114 8761 4115 8761 4112 8761 4116 8762 4112 8762 4115 8762 4111 8763 4114 8763 4112 8763 4113 8764 4112 8764 4116 8764 4117 8765 4118 8765 4115 8765 4119 8766 4115 8766 4118 8766 4120 8767 4115 8767 4114 8767 4120 8768 4117 8768 4115 8768 4116 8769 4115 8769 4119 8769 4117 8770 4121 8770 4118 8770 4122 8771 4118 8771 4121 8771 4119 8772 4118 8772 4122 8772 4117 8773 4083 8773 4121 8773 4123 8774 4121 8774 4083 8774 4122 8775 4121 8775 4123 8775 4117 8776 4079 8776 4083 8776 4123 8777 4083 8777 4084 8777 4124 8778 4102 8778 4099 8778 4125 8779 4105 8779 4102 8779 4125 8780 4102 8780 4124 8780 4126 8781 4099 8781 4096 8781 4126 8782 4124 8782 4099 8782 4127 8783 4096 8783 4091 8783 4126 8784 4096 8784 4127 8784 4128 8785 4091 8785 4094 8785 4127 8786 4091 8786 4128 8786 4129 8787 4130 8787 4094 8787 4131 8788 4094 8788 4130 8788 4095 8789 4129 8789 4094 8789 4128 8790 4094 8790 4131 8790 4129 8791 4132 8791 4130 8791 4133 8792 4130 8792 4132 8792 4131 8793 4130 8793 4133 8793 4134 8794 4135 8794 4132 8794 4136 8795 4132 8795 4135 8795 4129 8796 4134 8796 4132 8796 4133 8797 4132 8797 4136 8797 4134 8798 4137 8798 4135 8798 4138 8799 4135 8799 4137 8799 4136 8800 4135 8800 4138 8800 4134 8801 4139 8801 4137 8801 4140 8802 4137 8802 4139 8802 4138 8803 4137 8803 4140 8803 4134 8804 4141 8804 4139 8804 4142 8805 4139 8805 4141 8805 4140 8806 4139 8806 4142 8806 4134 8807 4143 8807 4141 8807 4144 8808 4141 8808 4143 8808 4142 8809 4141 8809 4144 8809 4134 8810 4114 8810 4143 8810 4145 8811 4143 8811 4114 8811 4144 8812 4143 8812 4145 8812 4146 8813 4114 8813 4111 8813 4134 8814 4120 8814 4114 8814 4145 8815 4114 8815 4146 8815 4147 8816 4111 8816 4108 8816 4146 8817 4111 8817 4147 8817 4148 8818 4108 8818 4105 8818 4147 8819 4108 8819 4148 8819 4148 8820 4105 8820 4125 8820 4149 8821 4150 8821 4151 8821 4152 8822 4151 8822 4150 8822 4153 8823 4151 8823 4154 8823 4155 8824 4154 8824 4151 8824 4156 8825 4149 8825 4151 8825 4153 8826 4156 8826 4151 8826 4155 8827 4151 8827 4152 8827 4149 8828 4157 8828 4150 8828 4158 8829 4150 8829 4157 8829 4158 8830 4152 8830 4150 8830 4149 8831 4159 8831 4157 8831 4160 8832 4157 8832 4159 8832 4158 8833 4157 8833 4160 8833 4149 8834 4161 8834 4159 8834 4162 8835 4159 8835 4161 8835 4160 8836 4159 8836 4162 8836 4149 8837 4163 8837 4161 8837 4164 8838 4161 8838 4163 8838 4162 8839 4161 8839 4164 8839 4165 8840 4166 8840 4163 8840 4167 8841 4163 8841 4166 8841 4168 8842 4163 8842 4149 8842 4168 8843 4165 8843 4163 8843 4164 8844 4163 8844 4167 8844 4169 8845 4170 8845 4166 8845 4171 8846 4166 8846 4170 8846 4165 8847 4169 8847 4166 8847 4167 8848 4166 8848 4171 8848 4169 8849 4172 8849 4170 8849 4173 8850 4170 8850 4172 8850 4171 8851 4170 8851 4173 8851 4174 8852 4175 8852 4172 8852 4176 8853 4172 8853 4175 8853 4177 8854 4178 8854 4172 8854 4174 8855 4172 8855 4178 8855 4169 8856 4177 8856 4172 8856 4173 8857 4172 8857 4176 8857 4174 8858 4179 8858 4175 8858 4180 8859 4175 8859 4179 8859 4176 8860 4175 8860 4180 8860 4153 8861 4181 8861 4179 8861 4182 8862 4179 8862 4181 8862 4174 8863 4153 8863 4179 8863 4180 8864 4179 8864 4182 8864 4153 8865 4183 8865 4181 8865 4184 8866 4181 8866 4183 8866 4182 8867 4181 8867 4184 8867 4153 8868 4185 8868 4183 8868 4186 8869 4183 8869 4185 8869 4184 8870 4183 8870 4186 8870 4153 8871 4187 8871 4185 8871 4188 8872 4185 8872 4187 8872 4186 8873 4185 8873 4188 8873 4153 8874 4154 8874 4187 8874 4189 8875 4187 8875 4154 8875 4188 8876 4187 8876 4189 8876 4189 8877 4154 8877 4155 8877 4190 8878 4191 8878 4192 8878 4193 8879 4192 8879 4191 8879 4190 8880 4192 8880 4194 8880 4195 8881 4194 8881 4192 8881 4195 8882 4192 8882 4193 8882 4196 8883 4197 8883 4191 8883 4198 8884 4191 8884 4197 8884 4196 8885 4191 8885 4190 8885 4198 8886 4193 8886 4191 8886 4199 8887 4200 8887 4197 8887 4201 8888 4197 8888 4200 8888 4196 8889 4199 8889 4197 8889 4198 8890 4197 8890 4201 8890 4199 8891 4202 8891 4200 8891 4203 8892 4200 8892 4202 8892 4201 8893 4200 8893 4203 8893 4199 8894 4204 8894 4202 8894 4205 8895 4202 8895 4204 8895 4203 8896 4202 8896 4205 8896 4199 8897 4206 8897 4204 8897 4207 8898 4204 8898 4206 8898 4205 8899 4204 8899 4207 8899 4199 8900 4208 8900 4206 8900 4209 8901 4206 8901 4208 8901 4207 8902 4206 8902 4209 8902 4199 8903 4210 8903 4208 8903 4211 8904 4208 8904 4210 8904 4209 8905 4208 8905 4211 8905 4212 8906 4213 8906 4210 8906 4214 8907 4210 8907 4213 8907 4199 8908 4212 8908 4210 8908 4211 8909 4210 8909 4214 8909 4212 8910 4215 8910 4213 8910 4216 8911 4213 8911 4215 8911 4214 8912 4213 8912 4216 8912 4212 8913 4217 8913 4215 8913 4218 8914 4215 8914 4217 8914 4216 8915 4215 8915 4218 8915 4190 8916 4219 8916 4217 8916 4220 8917 4217 8917 4219 8917 4212 8918 4190 8918 4217 8918 4218 8919 4217 8919 4220 8919 4190 8920 4221 8920 4219 8920 4222 8921 4219 8921 4221 8921 4220 8922 4219 8922 4222 8922 4190 8923 4223 8923 4221 8923 4224 8924 4221 8924 4223 8924 4222 8925 4221 8925 4224 8925 4190 8926 4194 8926 4223 8926 4225 8927 4223 8927 4194 8927 4224 8928 4223 8928 4225 8928 4225 8929 4194 8929 4195 8929 4226 8930 4227 8930 4228 8930 4229 8931 4228 8931 4227 8931 4226 8932 4228 8932 4230 8932 4231 8933 4230 8933 4228 8933 4231 8934 4228 8934 4229 8934 4226 8935 4232 8935 4227 8935 4233 8936 4227 8936 4232 8936 4233 8937 4229 8937 4227 8937 4226 8938 4234 8938 4232 8938 4235 8939 4232 8939 4234 8939 4233 8940 4232 8940 4235 8940 4226 8941 4236 8941 4234 8941 4237 8942 4234 8942 4236 8942 4235 8943 4234 8943 4237 8943 4238 8944 4239 8944 4236 8944 4240 8945 4236 8945 4239 8945 4241 8946 4238 8946 4236 8946 4242 8947 4241 8947 4236 8947 4242 8948 4236 8948 4226 8948 4237 8949 4236 8949 4240 8949 4243 8950 4244 8950 4239 8950 4245 8951 4239 8951 4244 8951 4238 8952 4243 8952 4239 8952 4240 8953 4239 8953 4245 8953 4246 8954 4247 8954 4244 8954 4248 8955 4244 8955 4247 8955 4243 8956 4246 8956 4244 8956 4245 8957 4244 8957 4248 8957 4249 8958 4250 8958 4247 8958 4251 8959 4247 8959 4250 8959 4246 8960 4249 8960 4247 8960 4248 8961 4247 8961 4251 8961 4252 8962 4253 8962 4250 8962 4254 8963 4250 8963 4253 8963 4252 8964 4250 8964 4249 8964 4251 8965 4250 8965 4254 8965 4255 8966 4256 8966 4253 8966 4257 8967 4253 8967 4256 8967 4252 8968 4255 8968 4253 8968 4254 8969 4253 8969 4257 8969 4258 8970 4259 8970 4256 8970 4260 8971 4256 8971 4259 8971 4255 8972 4258 8972 4256 8972 4257 8973 4256 8973 4260 8973 4261 8974 4262 8974 4259 8974 4263 8975 4259 8975 4262 8975 4258 8976 4261 8976 4259 8976 4260 8977 4259 8977 4263 8977 4264 8978 4265 8978 4262 8978 4266 8979 4262 8979 4265 8979 4267 8980 4262 8980 4261 8980 4267 8981 4264 8981 4262 8981 4263 8982 4262 8982 4266 8982 4264 8983 4268 8983 4265 8983 4269 8984 4265 8984 4268 8984 4266 8985 4265 8985 4269 8985 4264 8986 4230 8986 4268 8986 4270 8987 4268 8987 4230 8987 4269 8988 4268 8988 4270 8988 4264 8989 4226 8989 4230 8989 4270 8990 4230 8990 4231 8990 4271 8991 4249 8991 4246 8991 4272 8992 4252 8992 4249 8992 4272 8993 4249 8993 4271 8993 4273 8994 4246 8994 4243 8994 4273 8995 4271 8995 4246 8995 4274 8996 4243 8996 4238 8996 4273 8997 4243 8997 4274 8997 4275 8998 4238 8998 4241 8998 4274 8999 4238 8999 4275 8999 4276 9000 4277 9000 4241 9000 4278 9001 4241 9001 4277 9001 4242 9002 4276 9002 4241 9002 4275 9003 4241 9003 4278 9003 4276 9004 4279 9004 4277 9004 4280 9005 4277 9005 4279 9005 4278 9006 4277 9006 4280 9006 4281 9007 4282 9007 4279 9007 4283 9008 4279 9008 4282 9008 4276 9009 4281 9009 4279 9009 4280 9010 4279 9010 4283 9010 4281 9011 4284 9011 4282 9011 4285 9012 4282 9012 4284 9012 4283 9013 4282 9013 4285 9013 4281 9014 4286 9014 4284 9014 4287 9015 4284 9015 4286 9015 4285 9016 4284 9016 4287 9016 4281 9017 4288 9017 4286 9017 4289 9018 4286 9018 4288 9018 4287 9019 4286 9019 4289 9019 4281 9020 4290 9020 4288 9020 4291 9021 4288 9021 4290 9021 4289 9022 4288 9022 4291 9022 4281 9023 4261 9023 4290 9023 4292 9024 4290 9024 4261 9024 4291 9025 4290 9025 4292 9025 4293 9026 4261 9026 4258 9026 4281 9027 4267 9027 4261 9027 4292 9028 4261 9028 4293 9028 4294 9029 4258 9029 4255 9029 4293 9030 4258 9030 4294 9030 4295 9031 4255 9031 4252 9031 4294 9032 4255 9032 4295 9032 4295 9033 4252 9033 4272 9033 4296 9034 4297 9034 4298 9034 4299 9035 4298 9035 4297 9035 4296 9036 4298 9036 4300 9036 4301 9037 4300 9037 4298 9037 4301 9038 4298 9038 4299 9038 4296 9039 4302 9039 4297 9039 4303 9040 4297 9040 4302 9040 4303 9041 4299 9041 4297 9041 4296 9042 4304 9042 4302 9042 4305 9043 4302 9043 4304 9043 4303 9044 4302 9044 4305 9044 4306 9045 4307 9045 4304 9045 4308 9046 4304 9046 4307 9046 4306 9047 4304 9047 4296 9047 4305 9048 4304 9048 4308 9048 4309 9049 4310 9049 4307 9049 4311 9050 4307 9050 4310 9050 4306 9051 4309 9051 4307 9051 4308 9052 4307 9052 4311 9052 4309 9053 4312 9053 4310 9053 4313 9054 4310 9054 4312 9054 4311 9055 4310 9055 4313 9055 4309 9056 4314 9056 4312 9056 4315 9057 4312 9057 4314 9057 4313 9058 4312 9058 4315 9058 4309 9059 4316 9059 4314 9059 4317 9060 4314 9060 4316 9060 4315 9061 4314 9061 4317 9061 4296 9062 4300 9062 4316 9062 4318 9063 4316 9063 4300 9063 4296 9064 4316 9064 4319 9064 4309 9065 4319 9065 4316 9065 4317 9066 4316 9066 4318 9066 4318 9067 4300 9067 4301 9067 4320 9068 4321 9068 4322 9068 4323 9069 4322 9069 4321 9069 4320 9070 4322 9070 4324 9070 4325 9071 4324 9071 4322 9071 4325 9072 4322 9072 4323 9072 4156 9073 4326 9073 4321 9073 4327 9074 4321 9074 4326 9074 4320 9075 4156 9075 4321 9075 4327 9076 4323 9076 4321 9076 4156 9077 4328 9077 4326 9077 4329 9078 4326 9078 4328 9078 4327 9079 4326 9079 4329 9079 4156 9080 4330 9080 4328 9080 4331 9081 4328 9081 4330 9081 4329 9082 4328 9082 4331 9082 4156 9083 4332 9083 4330 9083 4333 9084 4330 9084 4332 9084 4331 9085 4330 9085 4333 9085 4334 9086 4335 9086 4332 9086 4336 9087 4332 9087 4335 9087 4153 9088 4332 9088 4156 9088 4337 9089 4334 9089 4332 9089 4153 9090 4337 9090 4332 9090 4333 9091 4332 9091 4336 9091 4338 9092 4339 9092 4335 9092 4340 9093 4335 9093 4339 9093 4341 9094 4338 9094 4335 9094 4334 9095 4341 9095 4335 9095 4336 9096 4335 9096 4340 9096 4342 9097 4343 9097 4339 9097 4344 9098 4339 9098 4343 9098 4338 9099 4342 9099 4339 9099 4340 9100 4339 9100 4344 9100 4342 9101 4345 9101 4343 9101 4346 9102 4343 9102 4345 9102 4344 9103 4343 9103 4346 9103 4342 9104 4347 9104 4345 9104 4348 9105 4345 9105 4347 9105 4346 9106 4345 9106 4348 9106 4349 9107 4350 9107 4347 9107 4351 9108 4347 9108 4350 9108 4342 9109 4349 9109 4347 9109 4348 9110 4347 9110 4351 9110 4349 9111 4352 9111 4350 9111 4353 9112 4350 9112 4352 9112 4351 9113 4350 9113 4353 9113 4349 9114 4354 9114 4352 9114 4355 9115 4352 9115 4354 9115 4353 9116 4352 9116 4355 9116 4356 9117 4357 9117 4354 9117 4358 9118 4354 9118 4357 9118 4349 9119 4356 9119 4354 9119 4355 9120 4354 9120 4358 9120 4359 9121 4360 9121 4357 9121 4361 9122 4357 9122 4360 9122 4362 9123 4357 9123 4356 9123 4362 9124 4359 9124 4357 9124 4358 9125 4357 9125 4361 9125 4359 9126 4363 9126 4360 9126 4364 9127 4360 9127 4363 9127 4361 9128 4360 9128 4364 9128 4359 9129 4324 9129 4363 9129 4365 9130 4363 9130 4324 9130 4364 9131 4363 9131 4365 9131 4359 9132 4320 9132 4324 9132 4365 9133 4324 9133 4325 9133 4366 9134 4367 9134 4368 9134 4369 9135 4368 9135 4367 9135 4370 9136 4368 9136 4371 9136 4372 9137 4371 9137 4368 9137 4370 9138 4366 9138 4368 9138 4372 9139 4368 9139 4369 9139 4366 9140 4373 9140 4367 9140 4374 9141 4367 9141 4373 9141 4374 9142 4369 9142 4367 9142 4375 9143 4376 9143 4373 9143 4377 9144 4373 9144 4376 9144 4366 9145 4375 9145 4373 9145 4374 9146 4373 9146 4377 9146 4375 9147 4378 9147 4376 9147 4379 9148 4376 9148 4378 9148 4377 9149 4376 9149 4379 9149 4375 9150 4380 9150 4378 9150 4381 9151 4378 9151 4380 9151 4379 9152 4378 9152 4381 9152 4382 9153 4383 9153 4380 9153 4384 9154 4380 9154 4383 9154 4382 9155 4380 9155 4375 9155 4381 9156 4380 9156 4384 9156 4382 9157 4385 9157 4383 9157 4386 9158 4383 9158 4385 9158 4384 9159 4383 9159 4386 9159 4382 9160 4387 9160 4385 9160 4388 9161 4385 9161 4387 9161 4386 9162 4385 9162 4388 9162 4389 9163 4390 9163 4387 9163 4391 9164 4387 9164 4390 9164 4382 9165 4389 9165 4387 9165 4388 9166 4387 9166 4391 9166 4389 9167 4392 9167 4390 9167 4393 9168 4390 9168 4392 9168 4391 9169 4390 9169 4393 9169 4009 9170 4394 9170 4392 9170 4395 9171 4392 9171 4394 9171 4389 9172 4009 9172 4392 9172 4393 9173 4392 9173 4395 9173 4009 9174 4396 9174 4394 9174 4397 9175 4394 9175 4396 9175 4395 9176 4394 9176 4397 9176 4009 9177 4398 9177 4396 9177 4399 9178 4396 9178 4398 9178 4397 9179 4396 9179 4399 9179 4009 9180 4400 9180 4398 9180 4401 9181 4398 9181 4400 9181 4399 9182 4398 9182 4401 9182 4402 9183 4403 9183 4400 9183 4404 9184 4400 9184 4403 9184 4405 9185 4402 9185 4400 9185 4006 9186 4405 9186 4400 9186 4009 9187 4006 9187 4400 9187 4401 9188 4400 9188 4404 9188 4406 9189 4407 9189 4403 9189 4408 9190 4403 9190 4407 9190 4409 9191 4406 9191 4403 9191 4402 9192 4409 9192 4403 9192 4404 9193 4403 9193 4408 9193 4370 9194 4371 9194 4407 9194 4410 9195 4407 9195 4371 9195 4406 9196 4370 9196 4407 9196 4408 9197 4407 9197 4410 9197 4410 9198 4371 9198 4372 9198 4309 9199 4411 9199 4319 9199 4412 9200 4319 9200 4411 9200 4413 9201 4296 9201 4319 9201 4413 9202 4319 9202 4412 9202 4414 9203 4415 9203 4411 9203 4416 9204 4411 9204 4415 9204 4417 9205 4414 9205 4411 9205 4309 9206 4417 9206 4411 9206 4416 9207 4412 9207 4411 9207 4414 9208 4296 9208 4415 9208 4418 9209 4415 9209 4296 9209 4416 9210 4415 9210 4418 9210 4306 9211 4296 9211 4414 9211 4418 9212 4296 9212 4413 9212 4362 9213 4419 9213 4420 9213 4421 9214 4420 9214 4419 9214 4362 9215 4420 9215 4422 9215 4423 9216 4422 9216 4420 9216 4423 9217 4420 9217 4421 9217 4362 9218 4424 9218 4419 9218 4425 9219 4419 9219 4424 9219 4425 9220 4421 9220 4419 9220 4426 9221 4427 9221 4424 9221 4428 9222 4424 9222 4427 9222 4362 9223 4426 9223 4424 9223 4425 9224 4424 9224 4428 9224 4429 9225 4430 9225 4427 9225 4431 9226 4427 9226 4430 9226 4426 9227 4429 9227 4427 9227 4428 9228 4427 9228 4431 9228 4432 9229 4433 9229 4430 9229 4434 9230 4430 9230 4433 9230 4432 9231 4430 9231 4429 9231 4431 9232 4430 9232 4434 9232 4432 9233 4435 9233 4433 9233 4436 9234 4433 9234 4435 9234 4434 9235 4433 9235 4436 9235 4362 9236 4422 9236 4435 9236 4437 9237 4435 9237 4422 9237 4432 9238 4438 9238 4435 9238 4439 9239 4435 9239 4438 9239 4439 9240 4362 9240 4435 9240 4436 9241 4435 9241 4437 9241 4437 9242 4422 9242 4423 9242 4440 9243 4441 9243 4442 9243 4443 9244 4442 9244 4441 9244 4444 9245 4442 9245 4445 9245 4446 9246 4445 9246 4442 9246 4444 9247 4440 9247 4442 9247 4446 9248 4442 9248 4443 9248 4440 9249 4447 9249 4441 9249 4448 9250 4441 9250 4447 9250 4448 9251 4443 9251 4441 9251 4449 9252 4450 9252 4447 9252 4451 9253 4447 9253 4450 9253 4452 9254 4449 9254 4447 9254 4447 9255 4440 9255 4453 9255 4448 9256 4447 9256 4451 9256 4449 9257 4454 9257 4450 9257 4455 9258 4450 9258 4454 9258 4451 9259 4450 9259 4455 9259 4456 9260 4457 9260 4454 9260 4458 9261 4454 9261 4457 9261 4456 9262 4454 9262 4449 9262 4455 9263 4454 9263 4458 9263 4456 9264 4459 9264 4457 9264 4460 9265 4457 9265 4459 9265 4458 9266 4457 9266 4460 9266 4444 9267 4445 9267 4459 9267 4461 9268 4459 9268 4445 9268 4459 9269 4456 9269 4462 9269 4463 9270 4444 9270 4459 9270 4460 9271 4459 9271 4461 9271 4461 9272 4445 9272 4446 9272 4417 9273 4464 9273 4465 9273 4466 9274 4465 9274 4464 9274 4417 9275 4465 9275 4467 9275 4468 9276 4467 9276 4465 9276 4468 9277 4465 9277 4466 9277 4417 9278 4469 9278 4464 9278 4470 9279 4464 9279 4469 9279 4470 9280 4466 9280 4464 9280 4471 9281 4472 9281 4469 9281 4473 9282 4469 9282 4472 9282 4178 9283 4471 9283 4469 9283 4417 9284 4178 9284 4469 9284 4470 9285 4469 9285 4473 9285 4474 9286 4475 9286 4472 9286 4476 9287 4472 9287 4475 9287 4471 9288 4474 9288 4472 9288 4473 9289 4472 9289 4476 9289 4477 9290 4478 9290 4475 9290 4479 9291 4475 9291 4478 9291 4477 9292 4475 9292 4474 9292 4476 9293 4475 9293 4479 9293 4168 9294 4149 9294 4478 9294 4480 9295 4478 9295 4149 9295 4477 9296 4168 9296 4478 9296 4479 9297 4478 9297 4480 9297 4417 9298 4467 9298 4149 9298 4481 9299 4149 9299 4467 9299 4156 9300 4417 9300 4149 9300 4480 9301 4149 9301 4481 9301 4481 9302 4467 9302 4468 9302 4482 9303 4474 9303 4471 9303 4483 9304 4477 9304 4474 9304 4483 9305 4474 9305 4482 9305 4484 9306 4471 9306 4178 9306 4484 9307 4482 9307 4471 9307 4485 9308 4178 9308 4177 9308 4174 9309 4178 9309 4417 9309 4484 9310 4178 9310 4485 9310 4486 9311 4177 9311 4169 9311 4485 9312 4177 9312 4486 9312 4487 9313 4169 9313 4165 9313 4486 9314 4169 9314 4487 9314 4488 9315 4165 9315 4168 9315 4487 9316 4165 9316 4488 9316 4489 9317 4168 9317 4477 9317 4488 9318 4168 9318 4489 9318 4489 9319 4477 9319 4483 9319 4490 9320 4022 9320 4018 9320 4491 9321 4030 9321 4022 9321 4491 9322 4022 9322 4490 9322 4492 9323 4018 9323 4021 9323 4492 9324 4490 9324 4018 9324 4493 9325 4494 9325 4021 9325 4495 9326 4021 9326 4494 9326 4002 9327 4493 9327 4021 9327 4492 9328 4021 9328 4495 9328 4496 9329 4497 9329 4494 9329 4498 9330 4494 9330 4497 9330 4493 9331 4496 9331 4494 9331 4495 9332 4494 9332 4498 9332 4499 9333 4500 9333 4497 9333 4501 9334 4497 9334 4500 9334 4499 9335 4497 9335 4496 9335 4498 9336 4497 9336 4501 9336 4502 9337 4031 9337 4500 9337 4503 9338 4500 9338 4031 9338 4499 9339 4502 9339 4500 9339 4501 9340 4500 9340 4503 9340 4504 9341 4031 9341 4030 9341 4306 9342 4031 9342 4502 9342 4306 9343 4027 9343 4031 9343 4503 9344 4031 9344 4504 9344 4504 9345 4030 9345 4491 9345 4505 9346 3972 9346 3971 9346 4506 9347 3973 9347 3972 9347 4506 9348 3972 9348 4505 9348 4507 9349 3971 9349 3974 9349 4507 9350 4505 9350 3971 9350 3975 9351 4508 9351 3974 9351 4509 9352 3974 9352 4508 9352 4507 9353 3974 9353 4509 9353 4510 9354 4511 9354 4508 9354 4512 9355 4508 9355 4511 9355 3975 9356 4510 9356 4508 9356 4509 9357 4508 9357 4512 9357 4513 9358 4514 9358 4511 9358 4515 9359 4511 9359 4514 9359 4513 9360 4511 9360 4510 9360 4512 9361 4511 9361 4515 9361 4513 9362 4516 9362 4514 9362 4517 9363 4514 9363 4516 9363 4515 9364 4514 9364 4517 9364 3976 9365 3973 9365 4516 9365 4518 9366 4516 9366 3973 9366 4519 9367 4516 9367 4513 9367 4519 9368 3976 9368 4516 9368 4517 9369 4516 9369 4518 9369 4518 9370 3973 9370 4506 9370 4520 9371 4521 9371 4522 9371 4523 9372 4522 9372 4521 9372 4524 9373 4522 9373 4525 9373 4526 9374 4525 9374 4522 9374 4524 9375 4520 9375 4522 9375 4526 9376 4522 9376 4523 9376 4520 9377 4527 9377 4521 9377 4528 9378 4521 9378 4527 9378 4528 9379 4523 9379 4521 9379 4529 9380 4530 9380 4527 9380 4531 9381 4527 9381 4530 9381 4527 9382 4520 9382 3978 9382 4532 9383 4529 9383 4527 9383 4528 9384 4527 9384 4531 9384 4529 9385 4533 9385 4530 9385 4534 9386 4530 9386 4533 9386 4531 9387 4530 9387 4534 9387 4535 9388 4536 9388 4533 9388 4537 9389 4533 9389 4536 9389 4535 9390 4533 9390 4529 9390 4534 9391 4533 9391 4537 9391 4535 9392 4538 9392 4536 9392 4539 9393 4536 9393 4538 9393 4537 9394 4536 9394 4539 9394 4524 9395 4525 9395 4538 9395 4540 9396 4538 9396 4525 9396 4541 9397 4524 9397 4538 9397 4538 9398 4535 9398 4542 9398 4539 9399 4538 9399 4540 9399 4540 9400 4525 9400 4526 9400 4543 9401 4496 9401 4493 9401 4544 9402 4499 9402 4496 9402 4544 9403 4496 9403 4543 9403 4545 9404 4493 9404 4002 9404 4545 9405 4543 9405 4493 9405 4306 9406 4546 9406 4002 9406 4547 9407 4002 9407 4546 9407 4009 9408 4306 9408 4002 9408 4545 9409 4002 9409 4547 9409 4306 9410 4548 9410 4546 9410 4549 9411 4546 9411 4548 9411 4547 9412 4546 9412 4549 9412 4306 9413 4550 9413 4548 9413 4551 9414 4548 9414 4550 9414 4549 9415 4548 9415 4551 9415 4306 9416 4502 9416 4550 9416 4552 9417 4550 9417 4502 9417 4551 9418 4550 9418 4552 9418 4553 9419 4502 9419 4499 9419 4552 9420 4502 9420 4553 9420 4553 9421 4499 9421 4544 9421 4554 9422 4449 9422 4452 9422 4555 9423 4456 9423 4449 9423 4555 9424 4449 9424 4554 9424 4453 9425 4556 9425 4452 9425 4557 9426 4452 9426 4556 9426 4453 9427 4452 9427 4447 9427 4557 9428 4554 9428 4452 9428 4362 9429 4356 9429 4556 9429 4558 9430 4556 9430 4356 9430 4362 9431 4556 9431 4453 9431 4557 9432 4556 9432 4558 9432 4559 9433 4560 9433 4356 9433 4561 9434 4356 9434 4560 9434 4349 9435 4559 9435 4356 9435 4558 9436 4356 9436 4561 9436 4559 9437 4562 9437 4560 9437 4563 9438 4560 9438 4562 9438 4561 9439 4560 9439 4563 9439 4559 9440 4564 9440 4562 9440 4565 9441 4562 9441 4564 9441 4563 9442 4562 9442 4565 9442 4566 9443 4567 9443 4564 9443 4568 9444 4564 9444 4567 9444 4559 9445 4566 9445 4564 9445 4565 9446 4564 9446 4568 9446 4566 9447 4462 9447 4567 9447 4569 9448 4567 9448 4462 9448 4568 9449 4567 9449 4569 9449 4462 9450 4463 9450 4459 9450 4570 9451 4462 9451 4456 9451 4571 9452 4463 9452 4462 9452 4566 9453 4571 9453 4462 9453 4569 9454 4462 9454 4570 9454 4570 9455 4456 9455 4555 9455 4572 9456 4429 9456 4426 9456 4573 9457 4432 9457 4429 9457 4573 9458 4429 9458 4572 9458 4362 9459 4574 9459 4426 9459 4575 9460 4426 9460 4574 9460 4575 9461 4572 9461 4426 9461 4362 9462 4453 9462 4574 9462 4576 9463 4574 9463 4453 9463 4575 9464 4574 9464 4576 9464 4577 9465 4453 9465 4440 9465 4576 9466 4453 9466 4577 9466 4578 9467 4440 9467 4444 9467 4577 9468 4440 9468 4578 9468 4579 9469 4444 9469 4463 9469 4578 9470 4444 9470 4579 9470 4580 9471 4463 9471 4571 9471 4579 9472 4463 9472 4580 9472 4566 9473 4438 9473 4571 9473 4581 9474 4571 9474 4438 9474 4580 9475 4571 9475 4581 9475 4582 9476 4438 9476 4432 9476 4566 9477 4439 9477 4438 9477 4581 9478 4438 9478 4582 9478 4582 9479 4432 9479 4573 9479 4583 9480 4510 9480 3975 9480 4584 9481 4513 9481 4510 9481 4584 9482 4510 9482 4583 9482 4585 9483 3975 9483 3977 9483 4585 9484 4583 9484 3975 9484 4586 9485 3977 9485 3978 9485 4585 9486 3977 9486 4586 9486 3978 9487 4532 9487 4527 9487 4587 9488 3978 9488 4520 9488 4588 9489 4532 9489 3978 9489 3963 9490 4588 9490 3978 9490 4586 9491 3978 9491 4587 9491 4589 9492 4520 9492 4524 9492 4587 9493 4520 9493 4589 9493 4590 9494 4524 9494 4541 9494 4589 9495 4524 9495 4590 9495 4542 9496 4591 9496 4541 9496 4592 9497 4541 9497 4591 9497 4542 9498 4541 9498 4538 9498 4590 9499 4541 9499 4592 9499 4593 9500 4594 9500 4591 9500 4595 9501 4591 9501 4594 9501 4593 9502 4591 9502 4542 9502 4592 9503 4591 9503 4595 9503 4519 9504 4513 9504 4594 9504 4596 9505 4594 9505 4513 9505 4593 9506 4519 9506 4594 9506 4595 9507 4594 9507 4596 9507 4596 9508 4513 9508 4584 9508 4597 9509 4529 9509 4532 9509 4598 9510 4535 9510 4529 9510 4598 9511 4529 9511 4597 9511 4599 9512 4532 9512 4588 9512 4599 9513 4597 9513 4532 9513 3963 9514 4600 9514 4588 9514 4601 9515 4588 9515 4600 9515 4599 9516 4588 9516 4601 9516 4593 9517 4602 9517 4600 9517 4603 9518 4600 9518 4602 9518 4604 9519 4593 9519 4600 9519 3963 9520 4604 9520 4600 9520 4601 9521 4600 9521 4603 9521 4593 9522 4605 9522 4602 9522 4606 9523 4602 9523 4605 9523 4603 9524 4602 9524 4606 9524 4593 9525 4607 9525 4605 9525 4608 9526 4605 9526 4607 9526 4606 9527 4605 9527 4608 9527 4593 9528 4609 9528 4607 9528 4610 9529 4607 9529 4609 9529 4608 9530 4607 9530 4610 9530 4593 9531 4542 9531 4609 9531 4611 9532 4609 9532 4542 9532 4610 9533 4609 9533 4611 9533 4612 9534 4542 9534 4535 9534 4611 9535 4542 9535 4612 9535 4612 9536 4535 9536 4598 9536 4613 9537 3952 9537 3976 9537 4614 9538 3958 9538 3952 9538 4614 9539 3952 9539 4613 9539 4615 9540 3976 9540 4519 9540 4613 9541 3976 9541 4615 9541 4593 9542 4616 9542 4519 9542 4617 9543 4519 9543 4616 9543 4615 9544 4519 9544 4617 9544 4382 9545 4375 9545 4616 9545 4618 9546 4616 9546 4375 9546 4593 9547 4382 9547 4616 9547 4617 9548 4616 9548 4618 9548 4619 9549 4375 9549 4366 9549 4618 9550 4375 9550 4619 9550 4620 9551 4366 9551 4370 9551 4620 9552 4619 9552 4366 9552 4621 9553 4370 9553 4406 9553 4620 9554 4370 9554 4621 9554 4622 9555 4406 9555 4409 9555 4621 9556 4406 9556 4622 9556 4623 9557 4409 9557 4402 9557 4622 9558 4409 9558 4623 9558 4624 9559 4402 9559 4405 9559 4623 9560 4402 9560 4624 9560 4625 9561 4405 9561 4006 9561 4624 9562 4405 9562 4625 9562 4626 9563 4006 9563 4027 9563 4625 9564 4006 9564 4626 9564 4049 9565 4043 9565 4027 9565 4627 9566 4027 9566 4043 9566 4414 9567 4049 9567 4027 9567 4306 9568 4414 9568 4027 9568 4626 9569 4027 9569 4627 9569 4628 9570 4043 9570 4065 9570 4627 9571 4043 9571 4628 9571 4629 9572 4630 9572 4065 9572 4631 9573 4065 9573 4630 9573 4052 9574 4629 9574 4065 9574 4628 9575 4065 9575 4631 9575 4632 9576 4633 9576 4630 9576 4634 9577 4630 9577 4633 9577 4629 9578 4632 9578 4630 9578 4631 9579 4630 9579 4634 9579 4635 9580 4636 9580 4633 9580 4637 9581 4633 9581 4636 9581 4632 9582 4635 9582 4633 9582 4634 9583 4633 9583 4637 9583 4638 9584 4636 9584 4635 9584 4637 9585 4636 9585 4638 9585 4639 9586 4635 9586 4632 9586 4638 9587 4635 9587 4639 9587 4640 9588 4632 9588 4629 9588 4639 9589 4632 9589 4640 9589 4641 9590 4629 9590 4052 9590 4640 9591 4629 9591 4641 9591 4642 9592 4052 9592 4049 9592 4641 9593 4052 9593 4642 9593 4643 9594 4049 9594 4414 9594 4642 9595 4049 9595 4643 9595 4644 9596 4414 9596 4417 9596 4643 9597 4414 9597 4644 9597 4645 9598 4417 9598 4156 9598 4309 9599 4174 9599 4417 9599 4644 9600 4417 9600 4645 9600 4646 9601 4156 9601 4320 9601 4645 9602 4156 9602 4646 9602 4647 9603 4320 9603 4359 9603 4646 9604 4320 9604 4647 9604 4648 9605 4359 9605 4362 9605 4647 9606 4359 9606 4648 9606 4649 9607 4362 9607 4439 9607 4648 9608 4362 9608 4649 9608 4566 9609 4650 9609 4439 9609 4651 9610 4439 9610 4650 9610 4649 9611 4439 9611 4651 9611 4652 9612 4653 9612 4650 9612 4654 9613 4650 9613 4653 9613 4566 9614 4652 9614 4650 9614 4651 9615 4650 9615 4654 9615 4655 9616 4656 9616 4653 9616 4657 9617 4653 9617 4656 9617 4652 9618 4655 9618 4653 9618 4654 9619 4653 9619 4657 9619 4658 9620 4659 9620 4656 9620 4660 9621 4656 9621 4659 9621 4655 9622 4658 9622 4656 9622 4657 9623 4656 9623 4660 9623 4661 9624 4226 9624 4659 9624 4662 9625 4659 9625 4226 9625 4658 9626 4661 9626 4659 9626 4660 9627 4659 9627 4662 9627 4663 9628 4226 9628 4264 9628 4664 9629 4242 9629 4226 9629 4665 9630 4664 9630 4226 9630 4661 9631 4665 9631 4226 9631 4662 9632 4226 9632 4663 9632 4267 9633 4666 9633 4264 9633 4667 9634 4264 9634 4666 9634 4663 9635 4264 9635 4667 9635 4668 9636 4669 9636 4666 9636 4670 9637 4666 9637 4669 9637 4267 9638 4668 9638 4666 9638 4667 9639 4666 9639 4670 9639 4671 9640 4672 9640 4669 9640 4673 9641 4669 9641 4672 9641 4668 9642 4671 9642 4669 9642 4670 9643 4669 9643 4673 9643 4674 9644 4675 9644 4672 9644 4676 9645 4672 9645 4675 9645 4671 9646 4674 9646 4672 9646 4673 9647 4672 9647 4676 9647 4677 9648 4675 9648 4674 9648 4676 9649 4675 9649 4677 9649 4678 9650 4674 9650 4671 9650 4677 9651 4674 9651 4678 9651 4679 9652 4671 9652 4668 9652 4678 9653 4671 9653 4679 9653 4680 9654 4668 9654 4267 9654 4679 9655 4668 9655 4680 9655 4681 9656 4267 9656 4281 9656 4680 9657 4267 9657 4681 9657 4682 9658 4281 9658 4276 9658 4681 9659 4281 9659 4682 9659 4242 9660 4683 9660 4276 9660 4684 9661 4276 9661 4683 9661 4682 9662 4276 9662 4684 9662 4242 9663 4685 9663 4683 9663 4686 9664 4683 9664 4685 9664 4684 9665 4683 9665 4686 9665 4242 9666 4687 9666 4685 9666 4688 9667 4685 9667 4687 9667 4686 9668 4685 9668 4688 9668 4689 9669 4687 9669 4242 9669 4688 9670 4687 9670 4689 9670 4690 9671 4242 9671 4664 9671 4689 9672 4242 9672 4690 9672 4665 9673 4691 9673 4664 9673 4692 9674 4664 9674 4691 9674 4690 9675 4664 9675 4692 9675 4693 9676 4691 9676 4665 9676 4692 9677 4691 9677 4693 9677 4694 9678 4665 9678 4661 9678 4693 9679 4665 9679 4694 9679 4695 9680 4661 9680 4658 9680 4694 9681 4661 9681 4695 9681 4696 9682 4658 9682 4655 9682 4695 9683 4658 9683 4696 9683 4697 9684 4655 9684 4652 9684 4696 9685 4655 9685 4697 9685 4698 9686 4652 9686 4566 9686 4697 9687 4652 9687 4698 9687 4699 9688 4566 9688 4559 9688 4698 9689 4566 9689 4699 9689 4700 9690 4559 9690 4349 9690 4699 9691 4559 9691 4700 9691 4701 9692 4349 9692 4342 9692 4700 9693 4349 9693 4701 9693 4702 9694 4342 9694 4338 9694 4701 9695 4342 9695 4702 9695 4703 9696 4338 9696 4341 9696 4702 9697 4338 9697 4703 9697 4704 9698 4341 9698 4334 9698 4703 9699 4341 9699 4704 9699 4705 9700 4334 9700 4337 9700 4704 9701 4334 9701 4705 9701 4706 9702 4337 9702 4153 9702 4705 9703 4337 9703 4706 9703 4707 9704 4153 9704 4174 9704 4706 9705 4153 9705 4707 9705 4196 9706 4190 9706 4174 9706 4708 9707 4174 9707 4190 9707 4309 9708 4196 9708 4174 9708 4707 9709 4174 9709 4708 9709 4709 9710 4190 9710 4212 9710 4708 9711 4190 9711 4709 9711 4710 9712 4711 9712 4212 9712 4712 9713 4212 9713 4711 9713 4199 9714 4710 9714 4212 9714 4709 9715 4212 9715 4712 9715 4713 9716 4714 9716 4711 9716 4715 9717 4711 9717 4714 9717 4710 9718 4713 9718 4711 9718 4712 9719 4711 9719 4715 9719 4716 9720 4717 9720 4714 9720 4718 9721 4714 9721 4717 9721 4713 9722 4716 9722 4714 9722 4715 9723 4714 9723 4718 9723 4719 9724 4717 9724 4716 9724 4718 9725 4717 9725 4719 9725 4720 9726 4716 9726 4713 9726 4719 9727 4716 9727 4720 9727 4721 9728 4713 9728 4710 9728 4720 9729 4713 9729 4721 9729 4722 9730 4710 9730 4199 9730 4721 9731 4710 9731 4722 9731 4723 9732 4199 9732 4196 9732 4722 9733 4199 9733 4723 9733 4724 9734 4196 9734 4309 9734 4723 9735 4196 9735 4724 9735 4725 9736 4309 9736 4306 9736 4724 9737 4309 9737 4725 9737 4726 9738 4306 9738 4009 9738 4725 9739 4306 9739 4726 9739 4727 9740 4009 9740 4389 9740 4726 9741 4009 9741 4727 9741 4728 9742 4389 9742 4382 9742 4727 9743 4389 9743 4728 9743 4729 9744 4382 9744 4593 9744 4728 9745 4382 9745 4729 9745 4730 9746 4593 9746 4604 9746 4729 9747 4593 9747 4730 9747 4000 9748 4731 9748 4604 9748 4732 9749 4604 9749 4731 9749 3963 9750 4000 9750 4604 9750 4730 9751 4604 9751 4732 9751 4000 9752 3996 9752 4731 9752 4733 9753 4731 9753 3996 9753 4732 9754 4731 9754 4733 9754 4734 9755 4735 9755 3996 9755 4736 9756 3996 9756 4735 9756 3999 9757 4734 9757 3996 9757 4733 9758 3996 9758 4736 9758 4737 9759 4738 9759 4735 9759 4739 9760 4735 9760 4738 9760 4734 9761 4737 9761 4735 9761 4736 9762 4735 9762 4739 9762 4740 9763 4079 9763 4738 9763 4741 9764 4738 9764 4079 9764 4737 9765 4740 9765 4738 9765 4739 9766 4738 9766 4741 9766 4742 9767 4079 9767 4117 9767 4743 9768 4095 9768 4079 9768 4744 9769 4743 9769 4079 9769 4740 9770 4744 9770 4079 9770 4741 9771 4079 9771 4742 9771 4120 9772 4745 9772 4117 9772 4746 9773 4117 9773 4745 9773 4742 9774 4117 9774 4746 9774 4747 9775 4748 9775 4745 9775 4749 9776 4745 9776 4748 9776 4120 9777 4747 9777 4745 9777 4746 9778 4745 9778 4749 9778 4750 9779 4751 9779 4748 9779 4752 9780 4748 9780 4751 9780 4747 9781 4750 9781 4748 9781 4749 9782 4748 9782 4752 9782 4753 9783 4754 9783 4751 9783 4755 9784 4751 9784 4754 9784 4750 9785 4753 9785 4751 9785 4752 9786 4751 9786 4755 9786 4756 9787 4754 9787 4753 9787 4755 9788 4754 9788 4756 9788 4757 9789 4753 9789 4750 9789 4756 9790 4753 9790 4757 9790 4758 9791 4750 9791 4747 9791 4757 9792 4750 9792 4758 9792 4759 9793 4747 9793 4120 9793 4758 9794 4747 9794 4759 9794 4760 9795 4120 9795 4134 9795 4759 9796 4120 9796 4760 9796 4761 9797 4134 9797 4129 9797 4760 9798 4134 9798 4761 9798 4095 9799 4762 9799 4129 9799 4763 9800 4129 9800 4762 9800 4761 9801 4129 9801 4763 9801 4095 9802 4764 9802 4762 9802 4765 9803 4762 9803 4764 9803 4763 9804 4762 9804 4765 9804 4095 9805 4766 9805 4764 9805 4767 9806 4764 9806 4766 9806 4765 9807 4764 9807 4767 9807 4768 9808 4766 9808 4095 9808 4767 9809 4766 9809 4768 9809 4769 9810 4095 9810 4743 9810 4768 9811 4095 9811 4769 9811 4744 9812 4770 9812 4743 9812 4771 9813 4743 9813 4770 9813 4769 9814 4743 9814 4771 9814 4772 9815 4770 9815 4744 9815 4771 9816 4770 9816 4772 9816 4773 9817 4744 9817 4740 9817 4772 9818 4744 9818 4773 9818 4774 9819 4740 9819 4737 9819 4773 9820 4740 9820 4774 9820 4775 9821 4737 9821 4734 9821 4774 9822 4737 9822 4775 9822 4776 9823 4734 9823 3999 9823 4775 9824 4734 9824 4776 9824 4777 9825 3999 9825 3993 9825 4776 9826 3999 9826 4777 9826 4778 9827 3993 9827 3987 9827 4777 9828 3993 9828 4778 9828 4779 9829 3987 9829 3990 9829 4778 9830 3987 9830 4779 9830 4780 9831 3990 9831 3979 9831 4779 9832 3990 9832 4780 9832 4781 9833 3979 9833 4000 9833 4780 9834 3979 9834 4781 9834 4782 9835 4000 9835 3963 9835 4781 9836 4000 9836 4782 9836 4783 9837 3963 9837 3958 9837 4782 9838 3963 9838 4783 9838 4783 9839 3958 9839 4614 9839 4615 9840 3957 9840 3955 9840 4614 9841 3955 9841 3960 9841 4613 9842 4615 9842 3955 9842 4614 9843 4613 9843 3955 9843 4615 9844 3970 9844 3957 9844 4617 9845 3969 9845 3970 9845 4615 9846 4617 9846 3970 9846 4649 9847 3967 9847 3969 9847 4617 9848 4618 9848 3969 9848 4649 9849 3969 9849 4618 9849 4783 9850 3965 9850 3967 9850 4649 9851 4783 9851 3967 9851 4614 9852 3962 9852 3965 9852 4783 9853 4614 9853 3965 9853 4614 9854 3960 9854 3962 9854 4781 9855 3984 9855 3982 9855 4781 9856 3982 9856 3986 9856 4782 9857 4001 9857 3984 9857 4781 9858 4782 9858 3984 9858 4782 9859 3998 9859 4001 9859 4782 9860 3995 9860 3998 9860 4780 9861 3992 9861 3995 9861 4585 9862 3995 9862 4583 9862 4782 9863 4583 9863 3995 9863 4586 9864 4587 9864 3995 9864 4779 9865 3995 9865 4587 9865 4585 9866 4586 9866 3995 9866 4779 9867 4780 9867 3995 9867 4780 9868 3989 9868 3992 9868 4780 9869 3986 9869 3989 9869 4780 9870 4781 9870 3986 9870 4623 9871 4008 9871 4005 9871 4623 9872 4005 9872 4011 9872 4623 9873 4042 9873 4008 9873 4623 9874 4041 9874 4042 9874 4623 9875 4039 9875 4041 9875 4077 9876 4037 9876 4039 9876 4075 9877 4077 9877 4039 9877 4624 9878 4075 9878 4039 9878 4623 9879 4624 9879 4039 9879 4078 9880 4035 9880 4037 9880 4077 9881 4078 9881 4037 9881 4048 9882 4033 9882 4035 9882 4078 9883 4048 9883 4035 9883 4046 9884 4029 9884 4033 9884 4048 9885 4046 9885 4033 9885 4051 9886 4026 9886 4029 9886 4051 9887 4029 9887 4046 9887 4054 9888 4024 9888 4026 9888 4051 9889 4054 9889 4026 9889 4056 9890 4020 9890 4024 9890 4054 9891 4056 9891 4024 9891 4058 9892 4017 9892 4020 9892 4056 9893 4058 9893 4020 9893 4643 9894 4015 9894 4017 9894 4639 9895 4017 9895 4058 9895 4642 9896 4643 9896 4017 9896 4641 9897 4642 9897 4017 9897 4640 9898 4641 9898 4017 9898 4639 9899 4640 9899 4017 9899 4644 9900 4013 9900 4015 9900 4643 9901 4644 9901 4015 9901 4623 9902 4011 9902 4013 9902 4623 9903 4013 9903 4644 9903 4638 9904 4073 9904 4075 9904 4624 9905 4638 9905 4075 9905 4638 9906 4071 9906 4073 9906 4639 9907 4069 9907 4071 9907 4638 9908 4639 9908 4071 9908 4639 9909 4067 9909 4069 9909 4639 9910 4064 9910 4067 9910 4639 9911 4062 9911 4064 9911 4639 9912 4060 9912 4062 9912 4639 9913 4058 9913 4060 9913 4755 9914 4084 9914 4082 9914 4694 9915 4082 9915 4086 9915 4694 9916 4755 9916 4082 9916 4755 9917 4123 9917 4084 9917 4755 9918 4122 9918 4123 9918 4756 9919 4119 9919 4122 9919 4755 9920 4756 9920 4122 9920 4756 9921 4116 9921 4119 9921 4756 9922 4113 9922 4116 9922 4756 9923 4110 9923 4113 9923 4756 9924 4107 9924 4110 9924 4694 9925 4104 9925 4107 9925 4694 9926 4107 9926 4756 9926 4694 9927 4101 9927 4104 9927 4694 9928 4098 9928 4101 9928 4694 9929 4093 9929 4098 9929 4694 9930 4090 9930 4093 9930 4694 9931 4088 9931 4090 9931 4694 9932 4086 9932 4088 9932 4757 9933 4125 9933 4124 9933 4769 9934 4124 9934 4126 9934 4757 9935 4124 9935 4769 9935 4757 9936 4148 9936 4125 9936 4758 9937 4147 9937 4148 9937 4757 9938 4758 9938 4148 9938 4758 9939 4146 9939 4147 9939 4758 9940 4145 9940 4146 9940 4758 9941 4144 9941 4145 9941 4758 9942 4142 9942 4144 9942 4758 9943 4140 9943 4142 9943 4768 9944 4138 9944 4140 9944 4758 9945 4768 9945 4140 9945 4768 9946 4136 9946 4138 9946 4768 9947 4133 9947 4136 9947 4769 9948 4131 9948 4133 9948 4768 9949 4769 9949 4133 9949 4769 9950 4128 9950 4131 9950 4769 9951 4127 9951 4128 9951 4769 9952 4126 9952 4127 9952 4704 9953 4155 9953 4152 9953 4704 9954 4152 9954 4158 9954 4704 9955 4189 9955 4155 9955 4704 9956 4188 9956 4189 9956 4704 9957 4186 9957 4188 9957 4224 9958 4184 9958 4186 9958 4222 9959 4224 9959 4186 9959 4705 9960 4222 9960 4186 9960 4704 9961 4705 9961 4186 9961 4225 9962 4182 9962 4184 9962 4224 9963 4225 9963 4184 9963 4195 9964 4180 9964 4182 9964 4225 9965 4195 9965 4182 9965 4193 9966 4176 9966 4180 9966 4195 9967 4193 9967 4180 9967 4198 9968 4173 9968 4176 9968 4198 9969 4176 9969 4193 9969 4201 9970 4171 9970 4173 9970 4198 9971 4201 9971 4173 9971 4203 9972 4167 9972 4171 9972 4201 9973 4203 9973 4171 9973 4205 9974 4164 9974 4167 9974 4203 9975 4205 9975 4167 9975 4724 9976 4162 9976 4164 9976 4720 9977 4164 9977 4205 9977 4723 9978 4724 9978 4164 9978 4722 9979 4723 9979 4164 9979 4721 9980 4722 9980 4164 9980 4720 9981 4721 9981 4164 9981 4725 9982 4160 9982 4162 9982 4724 9983 4725 9983 4162 9983 4704 9984 4158 9984 4160 9984 4704 9985 4160 9985 4725 9985 4719 9986 4220 9986 4222 9986 4705 9987 4719 9987 4222 9987 4719 9988 4218 9988 4220 9988 4720 9989 4216 9989 4218 9989 4719 9990 4720 9990 4218 9990 4720 9991 4214 9991 4216 9991 4720 9992 4211 9992 4214 9992 4720 9993 4209 9993 4211 9993 4720 9994 4207 9994 4209 9994 4720 9995 4205 9995 4207 9995 4676 9996 4231 9996 4229 9996 4460 9997 4229 9997 4233 9997 4460 9998 4461 9998 4229 9998 4676 9999 4229 9999 4461 9999 4676 10000 4270 10000 4231 10000 4676 10001 4269 10001 4270 10001 4677 10002 4266 10002 4269 10002 4676 10003 4677 10003 4269 10003 4677 10004 4263 10004 4266 10004 4677 10005 4260 10005 4263 10005 4677 10006 4257 10006 4260 10006 4677 10007 4254 10007 4257 10007 4773 10008 4251 10008 4254 10008 4677 10009 4773 10009 4254 10009 4773 10010 4248 10010 4251 10010 4773 10011 4245 10011 4248 10011 4773 10012 4240 10012 4245 10012 4773 10013 4237 10013 4240 10013 4773 10014 4235 10014 4237 10014 4458 10015 4233 10015 4235 10015 4487 10016 4458 10016 4235 10016 4551 10017 4487 10017 4235 10017 4551 10018 4235 10018 4537 10018 4773 10019 4537 10019 4235 10019 4458 10020 4460 10020 4233 10020 4678 10021 4272 10021 4271 10021 4690 10022 4271 10022 4273 10022 4678 10023 4271 10023 4690 10023 4678 10024 4295 10024 4272 10024 4679 10025 4294 10025 4295 10025 4678 10026 4679 10026 4295 10026 4679 10027 4293 10027 4294 10027 4679 10028 4292 10028 4293 10028 4679 10029 4291 10029 4292 10029 4679 10030 4289 10030 4291 10030 4679 10031 4287 10031 4289 10031 4689 10032 4285 10032 4287 10032 4679 10033 4689 10033 4287 10033 4689 10034 4283 10034 4285 10034 4689 10035 4280 10035 4283 10035 4690 10036 4278 10036 4280 10036 4689 10037 4690 10037 4280 10037 4690 10038 4275 10038 4278 10038 4690 10039 4274 10039 4275 10039 4690 10040 4273 10040 4274 10040 4701 10041 4301 10041 4299 10041 4730 10042 4299 10042 4303 10042 4730 10043 4732 10043 4299 10043 4700 10044 4299 10044 4732 10044 4700 10045 4701 10045 4299 10045 4701 10046 4318 10046 4301 10046 4701 10047 4317 10047 4318 10047 4701 10048 4315 10048 4317 10048 4702 10049 4313 10049 4315 10049 4701 10050 4702 10050 4315 10050 4730 10051 4311 10051 4313 10051 4729 10052 4730 10052 4313 10052 4702 10053 4729 10053 4313 10053 4730 10054 4308 10054 4311 10054 4730 10055 4305 10055 4308 10055 4730 10056 4303 10056 4305 10056 4578 10057 4325 10057 4323 10057 4369 10058 4323 10058 4327 10058 4595 10059 4323 10059 4369 10059 4577 10060 4578 10060 4323 10060 4595 10061 4577 10061 4323 10061 4579 10062 4365 10062 4325 10062 4578 10063 4579 10063 4325 10063 4660 10064 4364 10064 4365 10064 4660 10065 4365 10065 4579 10065 4660 10066 4361 10066 4364 10066 4662 10067 4358 10067 4361 10067 4660 10068 4662 10068 4361 10068 4662 10069 4355 10069 4358 10069 4663 10070 4353 10070 4355 10070 4662 10071 4663 10071 4355 10071 4663 10072 4351 10072 4353 10072 4663 10073 4348 10073 4351 10073 4395 10074 4346 10074 4348 10074 4393 10075 4395 10075 4348 10075 4663 10076 4393 10076 4348 10076 4397 10077 4344 10077 4346 10077 4395 10078 4397 10078 4346 10078 4399 10079 4340 10079 4344 10079 4397 10080 4399 10080 4344 10080 4401 10081 4336 10081 4340 10081 4399 10082 4401 10082 4340 10082 4404 10083 4333 10083 4336 10083 4401 10084 4404 10084 4336 10084 4408 10085 4331 10085 4333 10085 4404 10086 4408 10086 4333 10086 4410 10087 4329 10087 4331 10087 4408 10088 4410 10088 4331 10088 4372 10089 4327 10089 4329 10089 4410 10090 4372 10090 4329 10090 4372 10091 4369 10091 4327 10091 4592 10092 4369 10092 4374 10092 4592 10093 4595 10093 4369 10093 4774 10094 4391 10094 4393 10094 4663 10095 4774 10095 4393 10095 4775 10096 4388 10096 4391 10096 4774 10097 4775 10097 4391 10097 4775 10098 4386 10098 4388 10098 4775 10099 4384 10099 4386 10099 4775 10100 4381 10100 4384 10100 4776 10101 4379 10101 4381 10101 4775 10102 4776 10102 4381 10102 4776 10103 4377 10103 4379 10103 4590 10104 4374 10104 4377 10104 4777 10105 4590 10105 4377 10105 4776 10106 4777 10106 4377 10106 4590 10107 4592 10107 4374 10107 4693 10108 4413 10108 4412 10108 4693 10109 4412 10109 4416 10109 4772 10110 4418 10110 4413 10110 4771 10111 4772 10111 4413 10111 4693 10112 4771 10112 4413 10112 4772 10113 4416 10113 4418 10113 4692 10114 4416 10114 4772 10114 4692 10115 4693 10115 4416 10115 4657 10116 4423 10116 4421 10116 4466 10117 4421 10117 4425 10117 4783 10118 4421 10118 4466 10118 4654 10119 4421 10119 4783 10119 4654 10120 4657 10120 4421 10120 4657 10121 4437 10121 4423 10121 4657 10122 4436 10122 4437 10122 4657 10123 4434 10123 4436 10123 4480 10124 4431 10124 4434 10124 4479 10125 4480 10125 4434 10125 4572 10126 4479 10126 4434 10126 4657 10127 4572 10127 4434 10127 4481 10128 4428 10128 4431 10128 4480 10129 4481 10129 4431 10129 4468 10130 4425 10130 4428 10130 4481 10131 4468 10131 4428 10131 4468 10132 4466 10132 4425 10132 4676 10133 4446 10133 4443 10133 4482 10134 4443 10134 4448 10134 4774 10135 4443 10135 4482 10135 4673 10136 4443 10136 4774 10136 4673 10137 4676 10137 4443 10137 4676 10138 4461 10138 4446 10138 4488 10139 4455 10139 4458 10139 4487 10140 4488 10140 4458 10140 4489 10141 4451 10141 4455 10141 4488 10142 4489 10142 4455 10142 4483 10143 4448 10143 4451 10143 4489 10144 4483 10144 4451 10144 4483 10145 4482 10145 4448 10145 4490 10146 4466 10146 4470 10146 4783 10147 4466 10147 4490 10147 4503 10148 4476 10148 4479 10148 4501 10149 4503 10149 4479 10149 4572 10150 4501 10150 4479 10150 4504 10151 4473 10151 4476 10151 4503 10152 4504 10152 4476 10152 4491 10153 4470 10153 4473 10153 4504 10154 4491 10154 4473 10154 4491 10155 4490 10155 4470 10155 4543 10156 4482 10156 4484 10156 4774 10157 4482 10157 4543 10157 4552 10158 4486 10158 4487 10158 4551 10159 4552 10159 4487 10159 4553 10160 4485 10160 4486 10160 4552 10161 4553 10161 4486 10161 4544 10162 4484 10162 4485 10162 4553 10163 4544 10163 4485 10163 4544 10164 4543 10164 4484 10164 4505 10165 4490 10165 4492 10165 4783 10166 4490 10166 4505 10166 4517 10167 4498 10167 4501 10167 4515 10168 4517 10168 4501 10168 4572 10169 4515 10169 4501 10169 4518 10170 4495 10170 4498 10170 4517 10171 4518 10171 4498 10171 4506 10172 4492 10172 4495 10172 4518 10173 4506 10173 4495 10173 4506 10174 4505 10174 4492 10174 4783 10175 4505 10175 4507 10175 4782 10176 4512 10176 4515 10176 4782 10177 4515 10177 4572 10177 4782 10178 4509 10178 4512 10178 4783 10179 4507 10179 4509 10179 4782 10180 4783 10180 4509 10180 4545 10181 4526 10181 4523 10181 4774 10182 4523 10182 4528 10182 4545 10183 4523 10183 4543 10183 4774 10184 4543 10184 4523 10184 4547 10185 4540 10185 4526 10185 4545 10186 4547 10186 4526 10186 4549 10187 4539 10187 4540 10187 4547 10188 4549 10188 4540 10188 4551 10189 4537 10189 4539 10189 4549 10190 4551 10190 4539 10190 4774 10191 4534 10191 4537 10191 4773 10192 4774 10192 4537 10192 4774 10193 4531 10193 4534 10193 4774 10194 4528 10194 4531 10194 4697 10195 4555 10195 4554 10195 4597 10196 4554 10196 4557 10196 4739 10197 4554 10197 4597 10197 4697 10198 4554 10198 4739 10198 4698 10199 4570 10199 4555 10199 4697 10200 4698 10200 4555 10200 4698 10201 4569 10201 4570 10201 4698 10202 4568 10202 4569 10202 4698 10203 4565 10203 4568 10203 4610 10204 4563 10204 4565 10204 4608 10205 4610 10205 4565 10205 4698 10206 4608 10206 4565 10206 4611 10207 4561 10207 4563 10207 4610 10208 4611 10208 4563 10208 4612 10209 4558 10209 4561 10209 4611 10210 4612 10210 4561 10210 4598 10211 4557 10211 4558 10211 4612 10212 4598 10212 4558 10212 4598 10213 4597 10213 4557 10213 4657 10214 4573 10214 4572 10214 4583 10215 4572 10215 4575 10215 4782 10216 4572 10216 4583 10216 4657 10217 4582 10217 4573 10217 4657 10218 4581 10218 4582 10218 4660 10219 4580 10219 4581 10219 4657 10220 4660 10220 4581 10220 4660 10221 4579 10221 4580 10221 4596 10222 4576 10222 4577 10222 4595 10223 4596 10223 4577 10223 4584 10224 4575 10224 4576 10224 4596 10225 4584 10225 4576 10225 4584 10226 4583 10226 4575 10226 4778 10227 4589 10227 4590 10227 4777 10228 4778 10228 4590 10228 4779 10229 4587 10229 4589 10229 4778 10230 4779 10230 4589 10230 4739 10231 4597 10231 4599 10231 4736 10232 4606 10232 4608 10232 4733 10233 4736 10233 4608 10233 4698 10234 4733 10234 4608 10234 4736 10235 4603 10235 4606 10235 4736 10236 4601 10236 4603 10236 4739 10237 4599 10237 4601 10237 4736 10238 4739 10238 4601 10238 4649 10239 4618 10239 4619 10239 4648 10240 4649 10240 4619 10240 4620 10241 4648 10241 4619 10241 4651 10242 4654 10242 4783 10242 4649 10243 4651 10243 4783 10243 4663 10244 4673 10244 4774 10244 4692 10245 4772 10245 4773 10245 4690 10246 4692 10246 4773 10246 4677 10247 4690 10247 4773 10247 4694 10248 4769 10248 4771 10248 4693 10249 4694 10249 4771 10249 4756 10250 4757 10250 4769 10250 4694 10251 4756 10251 4769 10251 4758 10252 4767 10252 4768 10252 4759 10253 4765 10253 4767 10253 4758 10254 4759 10254 4767 10254 4761 10255 4763 10255 4765 10255 4760 10256 4761 10256 4765 10256 4759 10257 4760 10257 4765 10257 4695 10258 4752 10258 4755 10258 4694 10259 4695 10259 4755 10259 4742 10260 4749 10260 4752 10260 4695 10261 4742 10261 4752 10261 4742 10262 4746 10262 4749 10262 4695 10263 4741 10263 4742 10263 4696 10264 4739 10264 4741 10264 4695 10265 4696 10265 4741 10265 4696 10266 4697 10266 4739 10266 4699 10267 4732 10267 4733 10267 4698 10268 4699 10268 4733 10268 4699 10269 4700 10269 4732 10269 4702 10270 4728 10270 4729 10270 4703 10271 4727 10271 4728 10271 4702 10272 4703 10272 4728 10272 4725 10273 4726 10273 4727 10273 4703 10274 4725 10274 4727 10274 4703 10275 4704 10275 4725 10275 4705 10276 4718 10276 4719 10276 4706 10277 4715 10277 4718 10277 4705 10278 4706 10278 4718 10278 4707 10279 4712 10279 4715 10279 4706 10280 4707 10280 4715 10280 4708 10281 4709 10281 4712 10281 4707 10282 4708 10282 4712 10282 4677 10283 4678 10283 4690 10283 4679 10284 4688 10284 4689 10284 4680 10285 4686 10285 4688 10285 4679 10286 4680 10286 4688 10286 4682 10287 4684 10287 4686 10287 4681 10288 4682 10288 4686 10288 4680 10289 4681 10289 4686 10289 4663 10290 4670 10290 4673 10290 4663 10291 4667 10291 4670 10291 4621 10292 4647 10292 4648 10292 4620 10293 4621 10293 4648 10293 4622 10294 4646 10294 4647 10294 4621 10295 4622 10295 4647 10295 4644 10296 4645 10296 4646 10296 4622 10297 4644 10297 4646 10297 4622 10298 4623 10298 4644 10298 4624 10299 4637 10299 4638 10299 4625 10300 4634 10300 4637 10300 4624 10301 4625 10301 4637 10301 4626 10302 4631 10302 4634 10302 4625 10303 4626 10303 4634 10303 4627 10304 4628 10304 4631 10304 4626 10305 4627 10305 4631 10305 4784 10306 4785 10306 4786 10306 4787 10307 4786 10307 4785 10307 4788 10308 4786 10308 4789 10308 4790 10309 4789 10309 4786 10309 4788 10310 4784 10310 4786 10310 4790 10311 4786 10311 4787 10311 4784 10312 4791 10312 4785 10312 4792 10313 4785 10313 4791 10313 4792 10314 4787 10314 4785 10314 4784 10315 4793 10315 4791 10315 4794 10316 4791 10316 4793 10316 4792 10317 4791 10317 4794 10317 4784 10318 4795 10318 4793 10318 4796 10319 4793 10319 4795 10319 4794 10320 4793 10320 4796 10320 4784 10321 4797 10321 4795 10321 4798 10322 4795 10322 4797 10322 4796 10323 4795 10323 4798 10323 4784 10324 4799 10324 4797 10324 4800 10325 4797 10325 4799 10325 4798 10326 4797 10326 4800 10326 4784 10327 4801 10327 4799 10327 4802 10328 4799 10328 4801 10328 4800 10329 4799 10329 4802 10329 4784 10330 4803 10330 4801 10330 4804 10331 4801 10331 4803 10331 4802 10332 4801 10332 4804 10332 4784 10333 4805 10333 4803 10333 4806 10334 4803 10334 4805 10334 4804 10335 4803 10335 4806 10335 4807 10336 4808 10336 4805 10336 4809 10337 4805 10337 4808 10337 4784 10338 4807 10338 4805 10338 4806 10339 4805 10339 4809 10339 4810 10340 4811 10340 4808 10340 4812 10341 4808 10341 4811 10341 4807 10342 4810 10342 4808 10342 4809 10343 4808 10343 4812 10343 4810 10344 4813 10344 4811 10344 4814 10345 4811 10345 4813 10345 4812 10346 4811 10346 4814 10346 4810 10347 4815 10347 4813 10347 4816 10348 4813 10348 4815 10348 4814 10349 4813 10349 4816 10349 4810 10350 4817 10350 4815 10350 4818 10351 4815 10351 4817 10351 4816 10352 4815 10352 4818 10352 4819 10353 4820 10353 4817 10353 4821 10354 4817 10354 4820 10354 4810 10355 4819 10355 4817 10355 4818 10356 4817 10356 4821 10356 4822 10357 4823 10357 4820 10357 4824 10358 4820 10358 4823 10358 4819 10359 4822 10359 4820 10359 4821 10360 4820 10360 4824 10360 4825 10361 4826 10361 4823 10361 4827 10362 4823 10362 4826 10362 4822 10363 4825 10363 4823 10363 4824 10364 4823 10364 4827 10364 4828 10365 4829 10365 4826 10365 4830 10366 4826 10366 4829 10366 4825 10367 4828 10367 4826 10367 4827 10368 4826 10368 4830 10368 4828 10369 4831 10369 4829 10369 4832 10370 4829 10370 4831 10370 4830 10371 4829 10371 4832 10371 4833 10372 4834 10372 4831 10372 4835 10373 4831 10373 4834 10373 4833 10374 4831 10374 4828 10374 4832 10375 4831 10375 4835 10375 4833 10376 4836 10376 4834 10376 4837 10377 4834 10377 4836 10377 4835 10378 4834 10378 4837 10378 4838 10379 4839 10379 4836 10379 4840 10380 4836 10380 4839 10380 4833 10381 4838 10381 4836 10381 4837 10382 4836 10382 4840 10382 4838 10383 4841 10383 4839 10383 4842 10384 4839 10384 4841 10384 4840 10385 4839 10385 4842 10385 4838 10386 4843 10386 4841 10386 4844 10387 4841 10387 4843 10387 4842 10388 4841 10388 4844 10388 4845 10389 4846 10389 4843 10389 4847 10390 4843 10390 4846 10390 4848 10391 4845 10391 4843 10391 4838 10392 4848 10392 4843 10392 4844 10393 4843 10393 4847 10393 4849 10394 4850 10394 4846 10394 4851 10395 4846 10395 4850 10395 4845 10396 4849 10396 4846 10396 4847 10397 4846 10397 4851 10397 4852 10398 4853 10398 4850 10398 4854 10399 4850 10399 4853 10399 4849 10400 4852 10400 4850 10400 4851 10401 4850 10401 4854 10401 4855 10402 4856 10402 4853 10402 4857 10403 4853 10403 4856 10403 4852 10404 4855 10404 4853 10404 4854 10405 4853 10405 4857 10405 4858 10406 4859 10406 4856 10406 4860 10407 4856 10407 4859 10407 4855 10408 4858 10408 4856 10408 4857 10409 4856 10409 4860 10409 4861 10410 4862 10410 4859 10410 4863 10411 4859 10411 4862 10411 4858 10412 4864 10412 4859 10412 4865 10413 4859 10413 4864 10413 4865 10414 4861 10414 4859 10414 4860 10415 4859 10415 4863 10415 4866 10416 4789 10416 4862 10416 4867 10417 4862 10417 4789 10417 4868 10418 4862 10418 4861 10418 4868 10419 4866 10419 4862 10419 4863 10420 4862 10420 4867 10420 4866 10421 4788 10421 4789 10421 4867 10422 4789 10422 4790 10422 4869 10423 4870 10423 4871 10423 4872 10424 4871 10424 4870 10424 4873 10425 4871 10425 4874 10425 4875 10426 4874 10426 4871 10426 4873 10427 4869 10427 4871 10427 4875 10428 4871 10428 4872 10428 4876 10429 4877 10429 4870 10429 4878 10430 4870 10430 4877 10430 4879 10431 4876 10431 4870 10431 4869 10432 4879 10432 4870 10432 4878 10433 4872 10433 4870 10433 4880 10434 4881 10434 4877 10434 4882 10435 4877 10435 4881 10435 4883 10436 4880 10436 4877 10436 4876 10437 4883 10437 4877 10437 4878 10438 4877 10438 4882 10438 4880 10439 4884 10439 4881 10439 4885 10440 4881 10440 4884 10440 4882 10441 4881 10441 4885 10441 4880 10442 4886 10442 4884 10442 4887 10443 4884 10443 4886 10443 4885 10444 4884 10444 4887 10444 4880 10445 4888 10445 4886 10445 4889 10446 4886 10446 4888 10446 4887 10447 4886 10447 4889 10447 4880 10448 4890 10448 4888 10448 4891 10449 4888 10449 4890 10449 4889 10450 4888 10450 4891 10450 4880 10451 4892 10451 4890 10451 4893 10452 4890 10452 4892 10452 4891 10453 4890 10453 4893 10453 4894 10454 4895 10454 4892 10454 4896 10455 4892 10455 4895 10455 4897 10456 4892 10456 4880 10456 4898 10457 4899 10457 4892 10457 4894 10458 4892 10458 4899 10458 4897 10459 4898 10459 4892 10459 4893 10460 4892 10460 4896 10460 4894 10461 4900 10461 4895 10461 4901 10462 4895 10462 4900 10462 4896 10463 4895 10463 4901 10463 4902 10464 4903 10464 4900 10464 4904 10465 4900 10465 4903 10465 4894 10466 4902 10466 4900 10466 4901 10467 4900 10467 4904 10467 4902 10468 4905 10468 4903 10468 4906 10469 4903 10469 4905 10469 4904 10470 4903 10470 4906 10470 4902 10471 4907 10471 4905 10471 4908 10472 4905 10472 4907 10472 4906 10473 4905 10473 4908 10473 4902 10474 4909 10474 4907 10474 4910 10475 4907 10475 4909 10475 4908 10476 4907 10476 4910 10476 4902 10477 4911 10477 4909 10477 4912 10478 4909 10478 4911 10478 4910 10479 4909 10479 4912 10479 4902 10480 4913 10480 4911 10480 4914 10481 4911 10481 4913 10481 4912 10482 4911 10482 4914 10482 4915 10483 4916 10483 4913 10483 4917 10484 4913 10484 4916 10484 4902 10485 4915 10485 4913 10485 4914 10486 4913 10486 4917 10486 4918 10487 4864 10487 4916 10487 4919 10488 4916 10488 4864 10488 4915 10489 4918 10489 4916 10489 4917 10490 4916 10490 4919 10490 4920 10491 4864 10491 4858 10491 4918 10492 4865 10492 4864 10492 4919 10493 4864 10493 4920 10493 4921 10494 4858 10494 4855 10494 4920 10495 4858 10495 4921 10495 4922 10496 4855 10496 4852 10496 4921 10497 4855 10497 4922 10497 4923 10498 4852 10498 4849 10498 4922 10499 4852 10499 4923 10499 4924 10500 4849 10500 4845 10500 4923 10501 4849 10501 4924 10501 4925 10502 4845 10502 4848 10502 4924 10503 4845 10503 4925 10503 4926 10504 4927 10504 4848 10504 4928 10505 4848 10505 4927 10505 4838 10506 4926 10506 4848 10506 4925 10507 4848 10507 4928 10507 4929 10508 4930 10508 4927 10508 4931 10509 4927 10509 4930 10509 4926 10510 4929 10510 4927 10510 4928 10511 4927 10511 4931 10511 4929 10512 4932 10512 4930 10512 4933 10513 4930 10513 4932 10513 4931 10514 4930 10514 4933 10514 4929 10515 4934 10515 4932 10515 4935 10516 4932 10516 4934 10516 4933 10517 4932 10517 4935 10517 4936 10518 4937 10518 4934 10518 4938 10519 4934 10519 4937 10519 4929 10520 4936 10520 4934 10520 4935 10521 4934 10521 4938 10521 4936 10522 4939 10522 4937 10522 4940 10523 4937 10523 4939 10523 4938 10524 4937 10524 4940 10524 4873 10525 4874 10525 4939 10525 4941 10526 4939 10526 4874 10526 4936 10527 4873 10527 4939 10527 4940 10528 4939 10528 4941 10528 4941 10529 4874 10529 4875 10529 4942 10530 4943 10530 4944 10530 4945 10531 4944 10531 4943 10531 4946 10532 4944 10532 4947 10532 4948 10533 4947 10533 4944 10533 4946 10534 4942 10534 4944 10534 4948 10535 4944 10535 4945 10535 4949 10536 4950 10536 4943 10536 4951 10537 4943 10537 4950 10537 4942 10538 4949 10538 4943 10538 4951 10539 4945 10539 4943 10539 4949 10540 4952 10540 4950 10540 4953 10541 4950 10541 4952 10541 4951 10542 4950 10542 4953 10542 4954 10543 4955 10543 4952 10543 4956 10544 4952 10544 4955 10544 4949 10545 4954 10545 4952 10545 4953 10546 4952 10546 4956 10546 4954 10547 4957 10547 4955 10547 4958 10548 4955 10548 4957 10548 4956 10549 4955 10549 4958 10549 4959 10550 4960 10550 4957 10550 4961 10551 4957 10551 4960 10551 4954 10552 4959 10552 4957 10552 4958 10553 4957 10553 4961 10553 4959 10554 4962 10554 4960 10554 4963 10555 4960 10555 4962 10555 4961 10556 4960 10556 4963 10556 4959 10557 4964 10557 4962 10557 4965 10558 4962 10558 4964 10558 4963 10559 4962 10559 4965 10559 4966 10560 4967 10560 4964 10560 4968 10561 4964 10561 4967 10561 4969 10562 4966 10562 4964 10562 4959 10563 4969 10563 4964 10563 4965 10564 4964 10564 4968 10564 4970 10565 4971 10565 4967 10565 4972 10566 4967 10566 4971 10566 4966 10567 4970 10567 4967 10567 4968 10568 4967 10568 4972 10568 4973 10569 4974 10569 4971 10569 4975 10570 4971 10570 4974 10570 4970 10571 4973 10571 4971 10571 4972 10572 4971 10572 4975 10572 4976 10573 4977 10573 4974 10573 4978 10574 4974 10574 4977 10574 4973 10575 4976 10575 4974 10575 4975 10576 4974 10576 4978 10576 4979 10577 4980 10577 4977 10577 4981 10578 4977 10578 4980 10578 4976 10579 4979 10579 4977 10579 4978 10580 4977 10580 4981 10580 4982 10581 4983 10581 4980 10581 4984 10582 4980 10582 4983 10582 4979 10583 4985 10583 4980 10583 4986 10584 4980 10584 4985 10584 4986 10585 4982 10585 4980 10585 4981 10586 4980 10586 4984 10586 4987 10587 4988 10587 4983 10587 4989 10588 4983 10588 4988 10588 4990 10589 4987 10589 4983 10589 4982 10590 4990 10590 4983 10590 4984 10591 4983 10591 4989 10591 4991 10592 4992 10592 4988 10592 4993 10593 4988 10593 4992 10593 4987 10594 4991 10594 4988 10594 4989 10595 4988 10595 4993 10595 4994 10596 4995 10596 4992 10596 4996 10597 4992 10597 4995 10597 4991 10598 4994 10598 4992 10598 4993 10599 4992 10599 4996 10599 4994 10600 4997 10600 4995 10600 4998 10601 4995 10601 4997 10601 4996 10602 4995 10602 4998 10602 4994 10603 4999 10603 4997 10603 5000 10604 4997 10604 4999 10604 4998 10605 4997 10605 5000 10605 4994 10606 5001 10606 4999 10606 5002 10607 4999 10607 5001 10607 5000 10608 4999 10608 5002 10608 4994 10609 5003 10609 5001 10609 5004 10610 5001 10610 5003 10610 5002 10611 5001 10611 5004 10611 4994 10612 5005 10612 5003 10612 5006 10613 5003 10613 5005 10613 5004 10614 5003 10614 5006 10614 4994 10615 5007 10615 5005 10615 5008 10616 5005 10616 5007 10616 5006 10617 5005 10617 5008 10617 4994 10618 5009 10618 5007 10618 5010 10619 5007 10619 5009 10619 5008 10620 5007 10620 5010 10620 4994 10621 5011 10621 5009 10621 5012 10622 5009 10622 5011 10622 5010 10623 5009 10623 5012 10623 5013 10624 5014 10624 5011 10624 5015 10625 5011 10625 5014 10625 4994 10626 5013 10626 5011 10626 5012 10627 5011 10627 5015 10627 5016 10628 5017 10628 5014 10628 5018 10629 5014 10629 5017 10629 5013 10630 5016 10630 5014 10630 5015 10631 5014 10631 5018 10631 5016 10632 5019 10632 5017 10632 5020 10633 5017 10633 5019 10633 5018 10634 5017 10634 5020 10634 5016 10635 5021 10635 5019 10635 5022 10636 5019 10636 5021 10636 5020 10637 5019 10637 5022 10637 5016 10638 5023 10638 5021 10638 5024 10639 5021 10639 5023 10639 5022 10640 5021 10640 5024 10640 5025 10641 4947 10641 5023 10641 5026 10642 5023 10642 4947 10642 5016 10643 5025 10643 5023 10643 5024 10644 5023 10644 5026 10644 5025 10645 4946 10645 4947 10645 5026 10646 4947 10646 4948 10646 5027 10647 5028 10647 5029 10647 5030 10648 5029 10648 5028 10648 5031 10649 5029 10649 5032 10649 5033 10650 5032 10650 5029 10650 5031 10651 5027 10651 5029 10651 5033 10652 5029 10652 5030 10652 5034 10653 4985 10653 5028 10653 5035 10654 5028 10654 4985 10654 5027 10655 5034 10655 5028 10655 5035 10656 5030 10656 5028 10656 5036 10657 4985 10657 4979 10657 5034 10658 4986 10658 4985 10658 5035 10659 4985 10659 5036 10659 5037 10660 4979 10660 4976 10660 5036 10661 4979 10661 5037 10661 5038 10662 4976 10662 4973 10662 5037 10663 4976 10663 5038 10663 5039 10664 4973 10664 4970 10664 5038 10665 4973 10665 5039 10665 5040 10666 4970 10666 4966 10666 5039 10667 4970 10667 5040 10667 5041 10668 4966 10668 4969 10668 5040 10669 4966 10669 5041 10669 5042 10670 5043 10670 4969 10670 5044 10671 4969 10671 5043 10671 4959 10672 5042 10672 4969 10672 5041 10673 4969 10673 5044 10673 5045 10674 5046 10674 5043 10674 5047 10675 5043 10675 5046 10675 5042 10676 5045 10676 5043 10676 5044 10677 5043 10677 5047 10677 5045 10678 5048 10678 5046 10678 5049 10679 5046 10679 5048 10679 5047 10680 5046 10680 5049 10680 5045 10681 5050 10681 5048 10681 5051 10682 5048 10682 5050 10682 5049 10683 5048 10683 5051 10683 5052 10684 5053 10684 5050 10684 5054 10685 5050 10685 5053 10685 5045 10686 5052 10686 5050 10686 5051 10687 5050 10687 5054 10687 5052 10688 5055 10688 5053 10688 5056 10689 5053 10689 5055 10689 5054 10690 5053 10690 5056 10690 5057 10691 5058 10691 5055 10691 5059 10692 5055 10692 5058 10692 5057 10693 5055 10693 5052 10693 5056 10694 5055 10694 5059 10694 5057 10695 5060 10695 5058 10695 5061 10696 5058 10696 5060 10696 5059 10697 5058 10697 5061 10697 5062 10698 5063 10698 5060 10698 5064 10699 5060 10699 5063 10699 5057 10700 5062 10700 5060 10700 5061 10701 5060 10701 5064 10701 5065 10702 5066 10702 5063 10702 5067 10703 5063 10703 5066 10703 5068 10704 5065 10704 5063 10704 5062 10705 5068 10705 5063 10705 5064 10706 5063 10706 5067 10706 5069 10707 5070 10707 5066 10707 5071 10708 5066 10708 5070 10708 5072 10709 5066 10709 5065 10709 5072 10710 5069 10710 5066 10710 5067 10711 5066 10711 5071 10711 5069 10712 5073 10712 5070 10712 5074 10713 5070 10713 5073 10713 5071 10714 5070 10714 5074 10714 5069 10715 5075 10715 5073 10715 5076 10716 5073 10716 5075 10716 5074 10717 5073 10717 5076 10717 5069 10718 5077 10718 5075 10718 5078 10719 5075 10719 5077 10719 5076 10720 5075 10720 5078 10720 5069 10721 5079 10721 5077 10721 5080 10722 5077 10722 5079 10722 5078 10723 5077 10723 5080 10723 5069 10724 5081 10724 5079 10724 5082 10725 5079 10725 5081 10725 5080 10726 5079 10726 5082 10726 5083 10727 5084 10727 5081 10727 5085 10728 5081 10728 5084 10728 5086 10729 5087 10729 5081 10729 5083 10730 5081 10730 5087 10730 5088 10731 5086 10731 5081 10731 5069 10732 5088 10732 5081 10732 5082 10733 5081 10733 5085 10733 5083 10734 5089 10734 5084 10734 5090 10735 5084 10735 5089 10735 5085 10736 5084 10736 5090 10736 5031 10737 5091 10737 5089 10737 5092 10738 5089 10738 5091 10738 5083 10739 5031 10739 5089 10739 5090 10740 5089 10740 5092 10740 5031 10741 5093 10741 5091 10741 5094 10742 5091 10742 5093 10742 5092 10743 5091 10743 5094 10743 5031 10744 5095 10744 5093 10744 5096 10745 5093 10745 5095 10745 5094 10746 5093 10746 5096 10746 5031 10747 5097 10747 5095 10747 5098 10748 5095 10748 5097 10748 5096 10749 5095 10749 5098 10749 5031 10750 5032 10750 5097 10750 5099 10751 5097 10751 5032 10751 5098 10752 5097 10752 5099 10752 5099 10753 5032 10753 5033 10753 5100 10754 4880 10754 4883 10754 5101 10755 4897 10755 4880 10755 5101 10756 4880 10756 5100 10756 5102 10757 5103 10757 4883 10757 5104 10758 4883 10758 5103 10758 5102 10759 4883 10759 4876 10759 5104 10760 5100 10760 4883 10760 5102 10761 5105 10761 5103 10761 5106 10762 5103 10762 5105 10762 5104 10763 5103 10763 5106 10763 5102 10764 5107 10764 5105 10764 5108 10765 5105 10765 5107 10765 5106 10766 5105 10766 5108 10766 5109 10767 5110 10767 5107 10767 5111 10768 5107 10768 5110 10768 5112 10769 5109 10769 5107 10769 5102 10770 5112 10770 5107 10770 5108 10771 5107 10771 5111 10771 5113 10772 5114 10772 5110 10772 5115 10773 5110 10773 5114 10773 5109 10774 5113 10774 5110 10774 5111 10775 5110 10775 5115 10775 5116 10776 5117 10776 5114 10776 5118 10777 5114 10777 5117 10777 5113 10778 5116 10778 5114 10778 5115 10779 5114 10779 5118 10779 5119 10780 5120 10780 5117 10780 5121 10781 5117 10781 5120 10781 5116 10782 5119 10782 5117 10782 5118 10783 5117 10783 5121 10783 5122 10784 5123 10784 5120 10784 5124 10785 5120 10785 5123 10785 5122 10786 5120 10786 5119 10786 5121 10787 5120 10787 5124 10787 5125 10788 5126 10788 5123 10788 5127 10789 5123 10789 5126 10789 5122 10790 5125 10790 5123 10790 5124 10791 5123 10791 5127 10791 5128 10792 5129 10792 5126 10792 5130 10793 5126 10793 5129 10793 5125 10794 5128 10794 5126 10794 5127 10795 5126 10795 5130 10795 5131 10796 5132 10796 5129 10796 5133 10797 5129 10797 5132 10797 5128 10798 5131 10798 5129 10798 5130 10799 5129 10799 5133 10799 4894 10800 4899 10800 5132 10800 5134 10801 5132 10801 4899 10801 5135 10802 5132 10802 5131 10802 5136 10803 4894 10803 5132 10803 5137 10804 5136 10804 5132 10804 5138 10805 5137 10805 5132 10805 5135 10806 5138 10806 5132 10806 5133 10807 5132 10807 5134 10807 5139 10808 4899 10808 4898 10808 5134 10809 4899 10809 5139 10809 5140 10810 4898 10810 4897 10810 5139 10811 4898 10811 5140 10811 5140 10812 4897 10812 5101 10812 5141 10813 5142 10813 5143 10813 5144 10814 5143 10814 5142 10814 5145 10815 5143 10815 5146 10815 5147 10816 5146 10816 5143 10816 5145 10817 5141 10817 5143 10817 5147 10818 5143 10818 5144 10818 5148 10819 5149 10819 5142 10819 5150 10820 5142 10820 5149 10820 5151 10821 5148 10821 5142 10821 5141 10822 5151 10822 5142 10822 5150 10823 5144 10823 5142 10823 5102 10824 5152 10824 5149 10824 5153 10825 5149 10825 5152 10825 5102 10826 5149 10826 5148 10826 5150 10827 5149 10827 5153 10827 5102 10828 4876 10828 5152 10828 5154 10829 5152 10829 4876 10829 5153 10830 5152 10830 5154 10830 5155 10831 4876 10831 4879 10831 5154 10832 4876 10832 5155 10832 5156 10833 4879 10833 4869 10833 5155 10834 4879 10834 5156 10834 5157 10835 4869 10835 4873 10835 5156 10836 4869 10836 5157 10836 5158 10837 4873 10837 4936 10837 5157 10838 4873 10838 5158 10838 5159 10839 4936 10839 4929 10839 5158 10840 4936 10840 5159 10840 5160 10841 4929 10841 4926 10841 5159 10842 4929 10842 5160 10842 5161 10843 5162 10843 4926 10843 5163 10844 4926 10844 5162 10844 4838 10845 5161 10845 4926 10845 5160 10846 4926 10846 5163 10846 5164 10847 5165 10847 5162 10847 5166 10848 5162 10848 5165 10848 5161 10849 5164 10849 5162 10849 5163 10850 5162 10850 5166 10850 5167 10851 5168 10851 5165 10851 5169 10852 5165 10852 5168 10852 5170 10853 5165 10853 5164 10853 5171 10854 5167 10854 5165 10854 5170 10855 5171 10855 5165 10855 5166 10856 5165 10856 5169 10856 5167 10857 5172 10857 5168 10857 5173 10858 5168 10858 5172 10858 5169 10859 5168 10859 5173 10859 5174 10860 5146 10860 5172 10860 5175 10861 5172 10861 5146 10861 5167 10862 5174 10862 5172 10862 5173 10863 5172 10863 5175 10863 5176 10864 5145 10864 5146 10864 5177 10865 5176 10865 5146 10865 5178 10866 5177 10866 5146 10866 5174 10867 5178 10867 5146 10867 5175 10868 5146 10868 5147 10868 5179 10869 5052 10869 5045 10869 5180 10870 5057 10870 5052 10870 5180 10871 5052 10871 5179 10871 5181 10872 5045 10872 5042 10872 5181 10873 5179 10873 5045 10873 5182 10874 5183 10874 5042 10874 5184 10875 5042 10875 5183 10875 4959 10876 5182 10876 5042 10876 5181 10877 5042 10877 5184 10877 5185 10878 5186 10878 5183 10878 5187 10879 5183 10879 5186 10879 5182 10880 5185 10880 5183 10880 5184 10881 5183 10881 5187 10881 5188 10882 5189 10882 5186 10882 5190 10883 5186 10883 5189 10883 5191 10884 5186 10884 5185 10884 5192 10885 5186 10885 5191 10885 5192 10886 5188 10886 5186 10886 5187 10887 5186 10887 5190 10887 5188 10888 5193 10888 5189 10888 5194 10889 5189 10889 5193 10889 5190 10890 5189 10890 5194 10890 5195 10891 5196 10891 5193 10891 5197 10892 5193 10892 5196 10892 5188 10893 5195 10893 5193 10893 5194 10894 5193 10894 5197 10894 5198 10895 5199 10895 5196 10895 5200 10896 5196 10896 5199 10896 5201 10897 5198 10897 5196 10897 5202 10898 5201 10898 5196 10898 5203 10899 5202 10899 5196 10899 5195 10900 5203 10900 5196 10900 5197 10901 5196 10901 5200 10901 5204 10902 5205 10902 5199 10902 5206 10903 5199 10903 5205 10903 5198 10904 5204 10904 5199 10904 5200 10905 5199 10905 5206 10905 5207 10906 5208 10906 5205 10906 5209 10907 5205 10907 5208 10907 5210 10908 5205 10908 5204 10908 5210 10909 5207 10909 5205 10909 5206 10910 5205 10910 5209 10910 5211 10911 5212 10911 5208 10911 5213 10912 5208 10912 5212 10912 5211 10913 5208 10913 5207 10913 5209 10914 5208 10914 5213 10914 5211 10915 5065 10915 5212 10915 5214 10916 5212 10916 5065 10916 5213 10917 5212 10917 5214 10917 5215 10918 5065 10918 5068 10918 5211 10919 5072 10919 5065 10919 5214 10920 5065 10920 5215 10920 5216 10921 5068 10921 5062 10921 5215 10922 5068 10922 5216 10922 5217 10923 5062 10923 5057 10923 5216 10924 5062 10924 5217 10924 5217 10925 5057 10925 5180 10925 5218 10926 5219 10926 5220 10926 5221 10927 5220 10927 5219 10927 5222 10928 5220 10928 5223 10928 5224 10929 5223 10929 5220 10929 5222 10930 5218 10930 5220 10930 5224 10931 5220 10931 5221 10931 5225 10932 5226 10932 5219 10932 5227 10933 5219 10933 5226 10933 5218 10934 5225 10934 5219 10934 5227 10935 5221 10935 5219 10935 5228 10936 5229 10936 5226 10936 5230 10937 5226 10937 5229 10937 5225 10938 5228 10938 5226 10938 5227 10939 5226 10939 5230 10939 5231 10940 5232 10940 5229 10940 5233 10941 5229 10941 5232 10941 5228 10942 5231 10942 5229 10942 5230 10943 5229 10943 5233 10943 5083 10944 5087 10944 5232 10944 5234 10945 5232 10945 5087 10945 5235 10946 5232 10946 5231 10946 5236 10947 5232 10947 5235 10947 5237 10948 5083 10948 5232 10948 5238 10949 5237 10949 5232 10949 5236 10950 5238 10950 5232 10950 5233 10951 5232 10951 5234 10951 5239 10952 5087 10952 5086 10952 5234 10953 5087 10953 5239 10953 5240 10954 5086 10954 5088 10954 5239 10955 5086 10955 5240 10955 5241 10956 5088 10956 5069 10956 5240 10957 5088 10957 5241 10957 5242 10958 5069 10958 5072 10958 5241 10959 5069 10959 5242 10959 5211 10960 5243 10960 5072 10960 5244 10961 5072 10961 5243 10961 5242 10962 5072 10962 5244 10962 5211 10963 5245 10963 5243 10963 5246 10964 5243 10964 5245 10964 5244 10965 5243 10965 5246 10965 5211 10966 5247 10966 5245 10966 5248 10967 5245 10967 5247 10967 5246 10968 5245 10968 5248 10968 5249 10969 5250 10969 5247 10969 5251 10970 5247 10970 5250 10970 5252 10971 5249 10971 5247 10971 5211 10972 5252 10972 5247 10972 5248 10973 5247 10973 5251 10973 5253 10974 5254 10974 5250 10974 5255 10975 5250 10975 5254 10975 5249 10976 5253 10976 5250 10976 5251 10977 5250 10977 5255 10977 5256 10978 5223 10978 5254 10978 5257 10979 5254 10979 5223 10979 5253 10980 5256 10980 5254 10980 5255 10981 5254 10981 5257 10981 5256 10982 5222 10982 5223 10982 5257 10983 5223 10983 5224 10983 5258 10984 5119 10984 5116 10984 5259 10985 5122 10985 5119 10985 5259 10986 5119 10986 5258 10986 5260 10987 5116 10987 5113 10987 5260 10988 5258 10988 5116 10988 5261 10989 5113 10989 5109 10989 5260 10990 5113 10990 5261 10990 5262 10991 5109 10991 5112 10991 5261 10992 5109 10992 5262 10992 5263 10993 5264 10993 5112 10993 5265 10994 5112 10994 5264 10994 5263 10995 5112 10995 5102 10995 5262 10996 5112 10996 5265 10996 5263 10997 5266 10997 5264 10997 5267 10998 5264 10998 5266 10998 5265 10999 5264 10999 5267 10999 5268 11000 5269 11000 5266 11000 5270 11001 5266 11001 5269 11001 5263 11002 5268 11002 5266 11002 5267 11003 5266 11003 5270 11003 5268 11004 5271 11004 5269 11004 5272 11005 5269 11005 5271 11005 5270 11006 5269 11006 5272 11006 5268 11007 5273 11007 5271 11007 5274 11008 5271 11008 5273 11008 5272 11009 5271 11009 5274 11009 5268 11010 5275 11010 5273 11010 5276 11011 5273 11011 5275 11011 5274 11012 5273 11012 5276 11012 5268 11013 5277 11013 5275 11013 5278 11014 5275 11014 5277 11014 5276 11015 5275 11015 5278 11015 5268 11016 5131 11016 5277 11016 5279 11017 5277 11017 5131 11017 5278 11018 5277 11018 5279 11018 5280 11019 5131 11019 5128 11019 5268 11020 4807 11020 5131 11020 5281 11021 5131 11021 4807 11021 5281 11022 5135 11022 5131 11022 5279 11023 5131 11023 5280 11023 5282 11024 5128 11024 5125 11024 5280 11025 5128 11025 5282 11025 5283 11026 5125 11026 5122 11026 5282 11027 5125 11027 5283 11027 5283 11028 5122 11028 5259 11028 5284 11029 4828 11029 4825 11029 5285 11030 4833 11030 4828 11030 5285 11031 4828 11031 5284 11031 5286 11032 4825 11032 4822 11032 5286 11033 5284 11033 4825 11033 5287 11034 4822 11034 4819 11034 5286 11035 4822 11035 5287 11035 5288 11036 4819 11036 4810 11036 5287 11037 4819 11037 5288 11037 5289 11038 4810 11038 4807 11038 5288 11039 4810 11039 5289 11039 5268 11040 5290 11040 4807 11040 5291 11041 4807 11041 5290 11041 5292 11042 5281 11042 4807 11042 4784 11043 5292 11043 4807 11043 5289 11044 4807 11044 5291 11044 5268 11045 5293 11045 5290 11045 5294 11046 5290 11046 5293 11046 5291 11047 5290 11047 5294 11047 5295 11048 5296 11048 5293 11048 5297 11049 5293 11049 5296 11049 5295 11050 5293 11050 5268 11050 5294 11051 5293 11051 5297 11051 5298 11052 5299 11052 5296 11052 5300 11053 5296 11053 5299 11053 5301 11054 5298 11054 5296 11054 5302 11055 5301 11055 5296 11055 5295 11056 5302 11056 5296 11056 5297 11057 5296 11057 5300 11057 5303 11058 5304 11058 5299 11058 5305 11059 5299 11059 5304 11059 5306 11060 5303 11060 5299 11060 5298 11061 5306 11061 5299 11061 5300 11062 5299 11062 5305 11062 5170 11063 5307 11063 5304 11063 5308 11064 5304 11064 5307 11064 5303 11065 5170 11065 5304 11065 5305 11066 5304 11066 5308 11066 5170 11067 5164 11067 5307 11067 5309 11068 5307 11068 5164 11068 5308 11069 5307 11069 5309 11069 5310 11070 5164 11070 5161 11070 5309 11071 5164 11071 5310 11071 5311 11072 5161 11072 4838 11072 5310 11073 5161 11073 5311 11073 5312 11074 4838 11074 4833 11074 5311 11075 4838 11075 5312 11075 5312 11076 4833 11076 5285 11076 5313 11077 5314 11077 5315 11077 5316 11078 5315 11078 5314 11078 5313 11079 5315 11079 5317 11079 5318 11080 5317 11080 5315 11080 5318 11081 5315 11081 5316 11081 5313 11082 5319 11082 5314 11082 5320 11083 5314 11083 5319 11083 5320 11084 5316 11084 5314 11084 5313 11085 5321 11085 5319 11085 5322 11086 5319 11086 5321 11086 5320 11087 5319 11087 5322 11087 5313 11088 5231 11088 5321 11088 5323 11089 5321 11089 5231 11089 5322 11090 5321 11090 5323 11090 5324 11091 5231 11091 5228 11091 5313 11092 5013 11092 5231 11092 5325 11093 5231 11093 5013 11093 5325 11094 5235 11094 5231 11094 5323 11095 5231 11095 5324 11095 5326 11096 5228 11096 5225 11096 5324 11097 5228 11097 5326 11097 5327 11098 5225 11098 5218 11098 5326 11099 5225 11099 5327 11099 5328 11100 5218 11100 5222 11100 5327 11101 5218 11101 5328 11101 5329 11102 5222 11102 5256 11102 5328 11103 5222 11103 5329 11103 5330 11104 5256 11104 5253 11104 5329 11105 5256 11105 5330 11105 5331 11106 5253 11106 5249 11106 5330 11107 5253 11107 5331 11107 5332 11108 5249 11108 5252 11108 5331 11109 5249 11109 5332 11109 5333 11110 5334 11110 5252 11110 5335 11111 5252 11111 5334 11111 5211 11112 5333 11112 5252 11112 5332 11113 5252 11113 5335 11113 5333 11114 5336 11114 5334 11114 5337 11115 5334 11115 5336 11115 5335 11116 5334 11116 5337 11116 5313 11117 5317 11117 5336 11117 5338 11118 5336 11118 5317 11118 5333 11119 5313 11119 5336 11119 5337 11120 5336 11120 5338 11120 5338 11121 5317 11121 5318 11121 5339 11122 5340 11122 5341 11122 5342 11123 5341 11123 5340 11123 5343 11124 5341 11124 5344 11124 5345 11125 5344 11125 5341 11125 5346 11126 5339 11126 5341 11126 5347 11127 5346 11127 5341 11127 5343 11128 5347 11128 5341 11128 5345 11129 5341 11129 5342 11129 5348 11130 5349 11130 5340 11130 5350 11131 5340 11131 5349 11131 5351 11132 5348 11132 5340 11132 5339 11133 5351 11133 5340 11133 5350 11134 5342 11134 5340 11134 5191 11135 5352 11135 5349 11135 5353 11136 5349 11136 5352 11136 5348 11137 5191 11137 5349 11137 5350 11138 5349 11138 5353 11138 5191 11139 5185 11139 5352 11139 5354 11140 5352 11140 5185 11140 5353 11141 5352 11141 5354 11141 5355 11142 5185 11142 5182 11142 5354 11143 5185 11143 5355 11143 5356 11144 5182 11144 4959 11144 5355 11145 5182 11145 5356 11145 5357 11146 4959 11146 4954 11146 5356 11147 4959 11147 5357 11147 5358 11148 4954 11148 4949 11148 5357 11149 4954 11149 5358 11149 5359 11150 4949 11150 4942 11150 5358 11151 4949 11151 5359 11151 5360 11152 4942 11152 4946 11152 5359 11153 4942 11153 5360 11153 5361 11154 4946 11154 5025 11154 5360 11155 4946 11155 5361 11155 5362 11156 5025 11156 5016 11156 5361 11157 5025 11157 5362 11157 5363 11158 5016 11158 5013 11158 5362 11159 5016 11159 5363 11159 5313 11160 5364 11160 5013 11160 5365 11161 5013 11161 5364 11161 5366 11162 5325 11162 5013 11162 4994 11163 5366 11163 5013 11163 5363 11164 5013 11164 5365 11164 5313 11165 5344 11165 5364 11165 5367 11166 5364 11166 5344 11166 5365 11167 5364 11167 5367 11167 5313 11168 5343 11168 5344 11168 5367 11169 5344 11169 5345 11169 5368 11170 5369 11170 5370 11170 5371 11171 5370 11171 5369 11171 5368 11172 5370 11172 5372 11172 5373 11173 5372 11173 5370 11173 5373 11174 5370 11174 5374 11174 5371 11175 5374 11175 5370 11175 5375 11176 5376 11176 5369 11176 5371 11177 5369 11177 5376 11177 5368 11178 5377 11178 5369 11178 5375 11179 5369 11179 5377 11179 5378 11180 5379 11180 5376 11180 5380 11181 5376 11181 5379 11181 5381 11182 5376 11182 5375 11182 5381 11183 5378 11183 5376 11183 5371 11184 5376 11184 5380 11184 5382 11185 5383 11185 5379 11185 5384 11186 5379 11186 5383 11186 5378 11187 5382 11187 5379 11187 5380 11188 5379 11188 5384 11188 5385 11189 5386 11189 5383 11189 5387 11190 5383 11190 5386 11190 5388 11191 5385 11191 5383 11191 5389 11192 5388 11192 5383 11192 5390 11193 5389 11193 5383 11193 5382 11194 5390 11194 5383 11194 5391 11195 5383 11195 5387 11195 5384 11196 5383 11196 5391 11196 5392 11197 5393 11197 5386 11197 5387 11198 5386 11198 5393 11198 5385 11199 5392 11199 5386 11199 5394 11200 5395 11200 5393 11200 5396 11201 5393 11201 5395 11201 5392 11202 5394 11202 5393 11202 5387 11203 5393 11203 5396 11203 5397 11204 5398 11204 5395 11204 5399 11205 5395 11205 5398 11205 5394 11206 5397 11206 5395 11206 5396 11207 5395 11207 5399 11207 5397 11208 5400 11208 5398 11208 5401 11209 5398 11209 5400 11209 5402 11210 5398 11210 5401 11210 5399 11211 5398 11211 5402 11211 5403 11212 5404 11212 5400 11212 5401 11213 5400 11213 5404 11213 5405 11214 5400 11214 5397 11214 5403 11215 5400 11215 5405 11215 5406 11216 5407 11216 5404 11216 5408 11217 5404 11217 5407 11217 5409 11218 5404 11218 5403 11218 5409 11219 5406 11219 5404 11219 5401 11220 5404 11220 5408 11220 5410 11221 5411 11221 5407 11221 5412 11222 5407 11222 5411 11222 5406 11223 5410 11223 5407 11223 5408 11224 5407 11224 5412 11224 5413 11225 5414 11225 5411 11225 5415 11226 5411 11226 5414 11226 5416 11227 5413 11227 5411 11227 5417 11228 5416 11228 5411 11228 5418 11229 5417 11229 5411 11229 5410 11230 5418 11230 5411 11230 5419 11231 5411 11231 5415 11231 5412 11232 5411 11232 5419 11232 5420 11233 5421 11233 5414 11233 5415 11234 5414 11234 5421 11234 5413 11235 5420 11235 5414 11235 5422 11236 5372 11236 5421 11236 5423 11237 5421 11237 5372 11237 5420 11238 5422 11238 5421 11238 5415 11239 5421 11239 5423 11239 5422 11240 5368 11240 5372 11240 5423 11241 5372 11241 5373 11241 5424 11242 5148 11242 5151 11242 5425 11243 5102 11243 5148 11243 5425 11244 5148 11244 5424 11244 5426 11245 5427 11245 5151 11245 5428 11246 5151 11246 5427 11246 5141 11247 5426 11247 5151 11247 5428 11248 5424 11248 5151 11248 5426 11249 5429 11249 5427 11249 5430 11250 5427 11250 5429 11250 5428 11251 5427 11251 5430 11251 5426 11252 5431 11252 5429 11252 5432 11253 5429 11253 5431 11253 5430 11254 5429 11254 5432 11254 5433 11255 5434 11255 5431 11255 5435 11256 5431 11256 5434 11256 5426 11257 5433 11257 5431 11257 5432 11258 5431 11258 5435 11258 5433 11259 5436 11259 5434 11259 5437 11260 5434 11260 5436 11260 5435 11261 5434 11261 5437 11261 5438 11262 5439 11262 5436 11262 5440 11263 5436 11263 5439 11263 5438 11264 5436 11264 5433 11264 5437 11265 5436 11265 5440 11265 5438 11266 5441 11266 5439 11266 5442 11267 5439 11267 5441 11267 5440 11268 5439 11268 5442 11268 5438 11269 5443 11269 5441 11269 5444 11270 5441 11270 5443 11270 5442 11271 5441 11271 5444 11271 5438 11272 5445 11272 5443 11272 5446 11273 5443 11273 5445 11273 5444 11274 5443 11274 5446 11274 5447 11275 5448 11275 5445 11275 5449 11276 5445 11276 5448 11276 5447 11277 5445 11277 5438 11277 5446 11278 5445 11278 5449 11278 5447 11279 5450 11279 5448 11279 5451 11280 5448 11280 5450 11280 5449 11281 5448 11281 5451 11281 5447 11282 5102 11282 5450 11282 5452 11283 5450 11283 5102 11283 5451 11284 5450 11284 5452 11284 5447 11285 5263 11285 5102 11285 5452 11286 5102 11286 5425 11286 5453 11287 5454 11287 5455 11287 5456 11288 5455 11288 5454 11288 5457 11289 5455 11289 5458 11289 5459 11290 5458 11290 5455 11290 5457 11291 5453 11291 5455 11291 5459 11292 5455 11292 5456 11292 5453 11293 5460 11293 5454 11293 5461 11294 5454 11294 5460 11294 5461 11295 5456 11295 5454 11295 5462 11296 5463 11296 5460 11296 5464 11297 5460 11297 5463 11297 5453 11298 5462 11298 5460 11298 5461 11299 5460 11299 5464 11299 5462 11300 5465 11300 5463 11300 5466 11301 5463 11301 5465 11301 5464 11302 5463 11302 5466 11302 5295 11303 5467 11303 5465 11303 5468 11304 5465 11304 5467 11304 5462 11305 5295 11305 5465 11305 5466 11306 5465 11306 5468 11306 5295 11307 5469 11307 5467 11307 5470 11308 5467 11308 5469 11308 5468 11309 5467 11309 5470 11309 5295 11310 5268 11310 5469 11310 5471 11311 5469 11311 5268 11311 5470 11312 5469 11312 5471 11312 5472 11313 5268 11313 5263 11313 5471 11314 5268 11314 5472 11314 5473 11315 5474 11315 5263 11315 5475 11316 5263 11316 5474 11316 5447 11317 5473 11317 5263 11317 5472 11318 5263 11318 5475 11318 5476 11319 5477 11319 5474 11319 5478 11320 5474 11320 5477 11320 5473 11321 5476 11321 5474 11321 5475 11322 5474 11322 5478 11322 5476 11323 5479 11323 5477 11323 5480 11324 5477 11324 5479 11324 5478 11325 5477 11325 5480 11325 5476 11326 5481 11326 5479 11326 5482 11327 5479 11327 5481 11327 5480 11328 5479 11328 5482 11328 5457 11329 5458 11329 5481 11329 5483 11330 5481 11330 5458 11330 5476 11331 5457 11331 5481 11331 5482 11332 5481 11332 5483 11332 5483 11333 5458 11333 5459 11333 5484 11334 5433 11334 5426 11334 5485 11335 5438 11335 5433 11335 5485 11336 5433 11336 5484 11336 5486 11337 5426 11337 5141 11337 5486 11338 5484 11338 5426 11338 5487 11339 5141 11339 5145 11339 5486 11340 5141 11340 5487 11340 5488 11341 5145 11341 5176 11341 5487 11342 5145 11342 5488 11342 5489 11343 5176 11343 5177 11343 5488 11344 5176 11344 5489 11344 5490 11345 5177 11345 5178 11345 5491 11346 5177 11346 5490 11346 5489 11347 5177 11347 5491 11347 5490 11348 5178 11348 5174 11348 5492 11349 5174 11349 5167 11349 5490 11350 5174 11350 5492 11350 5493 11351 5167 11351 5171 11351 5492 11352 5167 11352 5493 11352 5494 11353 5495 11353 5171 11353 5496 11354 5171 11354 5495 11354 5170 11355 5494 11355 5171 11355 5493 11356 5171 11356 5496 11356 5405 11357 5397 11357 5495 11357 5497 11358 5495 11358 5397 11358 5494 11359 5405 11359 5495 11359 5496 11360 5495 11360 5497 11360 5498 11361 5499 11361 5397 11361 5500 11362 5397 11362 5499 11362 5501 11363 5498 11363 5397 11363 5502 11364 5501 11364 5397 11364 5503 11365 5502 11365 5397 11365 5394 11366 5503 11366 5397 11366 5497 11367 5397 11367 5500 11367 5375 11368 5504 11368 5499 11368 5505 11369 5499 11369 5504 11369 5498 11370 5375 11370 5499 11370 5506 11371 5499 11371 5505 11371 5500 11372 5499 11372 5506 11372 5375 11373 5377 11373 5504 11373 5505 11374 5504 11374 5377 11374 5507 11375 5508 11375 5377 11375 5509 11376 5377 11376 5508 11376 5368 11377 5507 11377 5377 11377 5505 11378 5377 11378 5509 11378 5192 11379 5191 11379 5508 11379 5510 11380 5508 11380 5191 11380 5507 11381 5192 11381 5508 11381 5509 11382 5508 11382 5510 11382 5511 11383 5191 11383 5348 11383 5510 11384 5191 11384 5511 11384 5512 11385 5348 11385 5351 11385 5511 11386 5348 11386 5512 11386 5339 11387 5513 11387 5351 11387 5514 11388 5351 11388 5513 11388 5512 11389 5351 11389 5514 11389 5515 11390 5513 11390 5339 11390 5516 11391 5513 11391 5515 11391 5514 11392 5513 11392 5516 11392 5515 11393 5339 11393 5346 11393 5517 11394 5346 11394 5347 11394 5515 11395 5346 11395 5517 11395 5518 11396 5347 11396 5343 11396 5517 11397 5347 11397 5518 11397 5519 11398 5520 11398 5343 11398 5521 11399 5343 11399 5520 11399 5522 11400 5519 11400 5343 11400 5523 11401 5522 11401 5343 11401 5313 11402 5523 11402 5343 11402 5518 11403 5343 11403 5521 11403 5524 11404 5525 11404 5520 11404 5526 11405 5520 11405 5525 11405 5527 11406 5524 11406 5520 11406 5519 11407 5527 11407 5520 11407 5521 11408 5520 11408 5526 11408 5528 11409 5529 11409 5525 11409 5530 11410 5525 11410 5529 11410 5531 11411 5528 11411 5525 11411 5524 11412 5531 11412 5525 11412 5526 11413 5525 11413 5530 11413 5532 11414 5533 11414 5529 11414 5534 11415 5529 11415 5533 11415 5535 11416 5529 11416 5528 11416 5535 11417 5536 11417 5529 11417 5532 11418 5529 11418 5536 11418 5530 11419 5529 11419 5534 11419 5532 11420 5537 11420 5533 11420 5538 11421 5533 11421 5537 11421 5534 11422 5533 11422 5538 11422 5532 11423 5539 11423 5537 11423 5540 11424 5537 11424 5539 11424 5538 11425 5537 11425 5540 11425 5532 11426 5541 11426 5539 11426 5542 11427 5539 11427 5541 11427 5540 11428 5539 11428 5542 11428 5532 11429 5543 11429 5541 11429 5544 11430 5541 11430 5543 11430 5542 11431 5541 11431 5544 11431 5545 11432 5546 11432 5543 11432 5547 11433 5543 11433 5546 11433 5548 11434 5545 11434 5543 11434 5532 11435 5548 11435 5543 11435 5549 11436 5543 11436 5547 11436 5544 11437 5543 11437 5549 11437 5550 11438 5551 11438 5546 11438 5547 11439 5546 11439 5551 11439 5545 11440 5550 11440 5546 11440 5552 11441 5553 11441 5551 11441 5554 11442 5551 11442 5553 11442 5550 11443 5552 11443 5551 11443 5547 11444 5551 11444 5554 11444 5555 11445 5556 11445 5553 11445 5557 11446 5553 11446 5556 11446 5552 11447 5555 11447 5553 11447 5554 11448 5553 11448 5557 11448 5558 11449 5559 11449 5556 11449 5560 11450 5556 11450 5559 11450 5555 11451 5558 11451 5556 11451 5557 11452 5556 11452 5560 11452 5561 11453 5562 11453 5559 11453 5563 11454 5559 11454 5562 11454 5558 11455 5561 11455 5559 11455 5560 11456 5559 11456 5563 11456 5564 11457 5565 11457 5562 11457 5566 11458 5562 11458 5565 11458 5561 11459 5564 11459 5562 11459 5563 11460 5562 11460 5566 11460 5567 11461 5565 11461 5564 11461 5568 11462 5565 11462 5567 11462 5566 11463 5565 11463 5568 11463 5567 11464 5564 11464 5561 11464 5569 11465 5561 11465 5558 11465 5567 11466 5561 11466 5569 11466 5570 11467 5558 11467 5555 11467 5569 11468 5558 11468 5570 11468 5571 11469 5555 11469 5552 11469 5570 11470 5555 11470 5571 11470 5572 11471 5552 11471 5550 11471 5571 11472 5552 11472 5572 11472 5573 11473 5550 11473 5545 11473 5572 11474 5550 11474 5573 11474 5574 11475 5545 11475 5548 11475 5575 11476 5545 11476 5574 11476 5573 11477 5545 11477 5575 11477 5576 11478 5577 11478 5548 11478 5574 11479 5548 11479 5577 11479 5532 11480 5576 11480 5548 11480 5578 11481 5579 11481 5577 11481 5580 11482 5577 11482 5579 11482 5576 11483 5578 11483 5577 11483 5574 11484 5577 11484 5580 11484 5578 11485 5581 11485 5579 11485 5582 11486 5579 11486 5581 11486 5580 11487 5579 11487 5582 11487 5578 11488 5583 11488 5581 11488 5584 11489 5581 11489 5583 11489 5582 11490 5581 11490 5584 11490 5578 11491 5585 11491 5583 11491 5586 11492 5583 11492 5585 11492 5584 11493 5583 11493 5586 11493 5587 11494 5588 11494 5585 11494 5589 11495 5585 11495 5588 11495 5590 11496 5587 11496 5585 11496 5591 11497 5590 11497 5585 11497 5592 11498 5591 11498 5585 11498 5593 11499 5592 11499 5585 11499 5578 11500 5593 11500 5585 11500 5586 11501 5585 11501 5589 11501 5594 11502 5595 11502 5588 11502 5596 11503 5588 11503 5595 11503 5597 11504 5594 11504 5588 11504 5587 11505 5597 11505 5588 11505 5589 11506 5588 11506 5596 11506 5210 11507 5204 11507 5595 11507 5598 11508 5595 11508 5204 11508 5599 11509 5210 11509 5595 11509 5600 11510 5599 11510 5595 11510 5594 11511 5600 11511 5595 11511 5596 11512 5595 11512 5598 11512 5601 11513 5204 11513 5198 11513 5598 11514 5204 11514 5601 11514 5602 11515 5198 11515 5201 11515 5601 11516 5198 11516 5602 11516 5603 11517 5201 11517 5202 11517 5602 11518 5201 11518 5603 11518 5604 11519 5202 11519 5203 11519 5605 11520 5202 11520 5604 11520 5603 11521 5202 11521 5605 11521 5604 11522 5203 11522 5195 11522 5606 11523 5195 11523 5188 11523 5604 11524 5195 11524 5606 11524 5607 11525 5188 11525 5192 11525 5606 11526 5188 11526 5607 11526 5608 11527 5192 11527 5507 11527 5607 11528 5192 11528 5608 11528 5609 11529 5507 11529 5368 11529 5608 11530 5507 11530 5609 11530 5610 11531 5611 11531 5368 11531 5612 11532 5368 11532 5611 11532 5613 11533 5610 11533 5368 11533 5614 11534 5613 11534 5368 11534 5615 11535 5614 11535 5368 11535 5422 11536 5615 11536 5368 11536 5609 11537 5368 11537 5612 11537 5403 11538 5616 11538 5611 11538 5617 11539 5611 11539 5616 11539 5610 11540 5403 11540 5611 11540 5618 11541 5611 11541 5617 11541 5612 11542 5611 11542 5618 11542 5403 11543 5405 11543 5616 11543 5617 11544 5616 11544 5405 11544 5619 11545 5405 11545 5494 11545 5617 11546 5405 11546 5619 11546 5620 11547 5494 11547 5170 11547 5619 11548 5494 11548 5620 11548 5621 11549 5170 11549 5303 11549 5620 11550 5170 11550 5621 11550 5622 11551 5303 11551 5306 11551 5621 11552 5303 11552 5622 11552 5298 11553 5623 11553 5306 11553 5624 11554 5306 11554 5623 11554 5622 11555 5306 11555 5624 11555 5625 11556 5623 11556 5298 11556 5626 11557 5623 11557 5625 11557 5624 11558 5623 11558 5626 11558 5625 11559 5298 11559 5301 11559 5627 11560 5301 11560 5302 11560 5625 11561 5301 11561 5627 11561 5628 11562 5302 11562 5295 11562 5627 11563 5302 11563 5628 11563 5629 11564 5295 11564 5462 11564 5628 11565 5295 11565 5629 11565 5630 11566 5462 11566 5453 11566 5629 11567 5462 11567 5630 11567 5631 11568 5453 11568 5457 11568 5630 11569 5453 11569 5631 11569 5476 11570 5632 11570 5457 11570 5633 11571 5457 11571 5632 11571 5631 11572 5457 11572 5633 11572 5476 11573 5634 11573 5632 11573 5635 11574 5632 11574 5634 11574 5633 11575 5632 11575 5635 11575 5476 11576 5636 11576 5634 11576 5637 11577 5634 11577 5636 11577 5635 11578 5634 11578 5637 11578 5476 11579 5638 11579 5636 11579 5639 11580 5636 11580 5638 11580 5637 11581 5636 11581 5639 11581 5476 11582 5640 11582 5638 11582 5641 11583 5638 11583 5640 11583 5639 11584 5638 11584 5641 11584 5642 11585 5643 11585 5640 11585 5644 11586 5640 11586 5643 11586 5645 11587 5642 11587 5640 11587 5476 11588 5645 11588 5640 11588 5646 11589 5640 11589 5644 11589 5641 11590 5640 11590 5646 11590 5647 11591 5648 11591 5643 11591 5644 11592 5643 11592 5648 11592 5642 11593 5647 11593 5643 11593 5649 11594 5650 11594 5648 11594 5651 11595 5648 11595 5650 11595 5647 11596 5649 11596 5648 11596 5644 11597 5648 11597 5651 11597 5652 11598 5653 11598 5650 11598 5654 11599 5650 11599 5653 11599 5649 11600 5652 11600 5650 11600 5651 11601 5650 11601 5654 11601 5655 11602 5656 11602 5653 11602 5657 11603 5653 11603 5656 11603 5652 11604 5655 11604 5653 11604 5654 11605 5653 11605 5657 11605 5658 11606 5659 11606 5656 11606 5660 11607 5656 11607 5659 11607 5655 11608 5658 11608 5656 11608 5657 11609 5656 11609 5660 11609 5661 11610 5662 11610 5659 11610 5663 11611 5659 11611 5662 11611 5658 11612 5661 11612 5659 11612 5660 11613 5659 11613 5663 11613 5664 11614 5662 11614 5661 11614 5665 11615 5662 11615 5664 11615 5663 11616 5662 11616 5665 11616 5664 11617 5661 11617 5658 11617 5666 11618 5658 11618 5655 11618 5664 11619 5658 11619 5666 11619 5667 11620 5655 11620 5652 11620 5666 11621 5655 11621 5667 11621 5668 11622 5652 11622 5649 11622 5667 11623 5652 11623 5668 11623 5669 11624 5649 11624 5647 11624 5668 11625 5649 11625 5669 11625 5670 11626 5647 11626 5642 11626 5669 11627 5647 11627 5670 11627 5671 11628 5642 11628 5645 11628 5672 11629 5642 11629 5671 11629 5670 11630 5642 11630 5672 11630 5673 11631 5674 11631 5645 11631 5671 11632 5645 11632 5674 11632 5673 11633 5645 11633 5476 11633 5447 11634 5675 11634 5674 11634 5676 11635 5674 11635 5675 11635 5673 11636 5447 11636 5674 11636 5671 11637 5674 11637 5676 11637 5447 11638 5677 11638 5675 11638 5678 11639 5675 11639 5677 11639 5676 11640 5675 11640 5678 11640 5447 11641 5679 11641 5677 11641 5680 11642 5677 11642 5679 11642 5678 11643 5677 11643 5680 11643 5447 11644 5438 11644 5679 11644 5681 11645 5679 11645 5438 11645 5680 11646 5679 11646 5681 11646 5681 11647 5438 11647 5485 11647 5682 11648 5528 11648 5531 11648 5683 11649 5535 11649 5528 11649 5683 11650 5528 11650 5682 11650 5684 11651 5531 11651 5524 11651 5684 11652 5682 11652 5531 11652 5685 11653 5524 11653 5527 11653 5684 11654 5524 11654 5685 11654 5686 11655 5527 11655 5519 11655 5685 11656 5527 11656 5686 11656 5687 11657 5519 11657 5522 11657 5686 11658 5519 11658 5687 11658 5688 11659 5522 11659 5523 11659 5687 11660 5522 11660 5688 11660 5689 11661 5523 11661 5313 11661 5688 11662 5523 11662 5689 11662 5690 11663 5313 11663 5333 11663 5689 11664 5313 11664 5690 11664 5691 11665 5692 11665 5333 11665 5693 11666 5333 11666 5692 11666 5578 11667 5333 11667 5211 11667 5691 11668 5333 11668 5578 11668 5690 11669 5333 11669 5693 11669 5532 11670 5694 11670 5692 11670 5695 11671 5692 11671 5694 11671 5691 11672 5532 11672 5692 11672 5693 11673 5692 11673 5695 11673 5532 11674 5696 11674 5694 11674 5697 11675 5694 11675 5696 11675 5695 11676 5694 11676 5697 11676 5532 11677 5536 11677 5696 11677 5698 11678 5696 11678 5536 11678 5697 11679 5696 11679 5698 11679 5699 11680 5536 11680 5535 11680 5698 11681 5536 11681 5699 11681 5699 11682 5535 11682 5683 11682 5700 11683 5207 11683 5210 11683 5701 11684 5211 11684 5207 11684 5701 11685 5207 11685 5700 11685 5702 11686 5210 11686 5599 11686 5702 11687 5700 11687 5210 11687 5703 11688 5599 11688 5600 11688 5702 11689 5599 11689 5703 11689 5704 11690 5600 11690 5594 11690 5703 11691 5600 11691 5704 11691 5705 11692 5594 11692 5597 11692 5704 11693 5594 11693 5705 11693 5706 11694 5597 11694 5587 11694 5705 11695 5597 11695 5706 11695 5707 11696 5587 11696 5590 11696 5706 11697 5587 11697 5707 11697 5708 11698 5590 11698 5591 11698 5707 11699 5590 11699 5708 11699 5709 11700 5591 11700 5592 11700 5708 11701 5591 11701 5709 11701 5710 11702 5592 11702 5593 11702 5709 11703 5592 11703 5710 11703 5578 11704 5711 11704 5593 11704 5712 11705 5593 11705 5711 11705 5710 11706 5593 11706 5712 11706 5578 11707 5713 11707 5711 11707 5714 11708 5711 11708 5713 11708 5712 11709 5711 11709 5714 11709 5578 11710 5211 11710 5713 11710 5715 11711 5713 11711 5211 11711 5714 11712 5713 11712 5715 11712 5715 11713 5211 11713 5701 11713 5716 11714 5476 11714 5473 11714 5716 11715 5673 11715 5476 11715 5717 11716 5473 11716 5447 11716 5718 11717 5716 11717 5473 11717 5718 11718 5473 11718 5717 11718 5717 11719 5447 11719 5673 11719 5719 11720 5673 11720 5716 11720 5717 11721 5673 11721 5719 11721 5720 11722 5403 11722 5610 11722 5721 11723 5403 11723 5722 11723 5723 11724 5722 11724 5403 11724 5721 11725 5409 11725 5403 11725 5723 11726 5403 11726 5724 11726 5720 11727 5724 11727 5403 11727 5720 11728 5610 11728 5613 11728 5725 11729 5722 11729 5613 11729 5723 11730 5613 11730 5722 11730 5726 11731 5727 11731 5613 11731 5728 11732 5613 11732 5727 11732 5614 11733 5726 11733 5613 11733 5728 11734 5725 11734 5613 11734 5729 11735 5613 11735 5723 11735 5720 11736 5613 11736 5729 11736 5725 11737 5721 11737 5722 11737 5730 11738 5375 11738 5498 11738 5731 11739 5375 11739 5732 11739 5733 11740 5732 11740 5375 11740 5731 11741 5381 11741 5375 11741 5733 11742 5375 11742 5730 11742 5734 11743 5498 11743 5501 11743 5734 11744 5730 11744 5498 11744 5735 11745 5732 11745 5501 11745 5733 11746 5501 11746 5732 11746 5736 11747 5737 11747 5501 11747 5735 11748 5501 11748 5737 11748 5738 11749 5736 11749 5501 11749 5502 11750 5738 11750 5501 11750 5739 11751 5501 11751 5733 11751 5734 11752 5501 11752 5739 11752 5735 11753 5731 11753 5732 11753 5740 11754 5578 11754 5576 11754 5740 11755 5691 11755 5578 11755 5741 11756 5576 11756 5532 11756 5742 11757 5740 11757 5576 11757 5742 11758 5576 11758 5741 11758 5741 11759 5532 11759 5691 11759 5743 11760 5691 11760 5740 11760 5741 11761 5691 11761 5743 11761 5744 11762 4861 11762 4865 11762 5745 11763 4868 11763 4861 11763 5745 11764 4861 11764 5746 11764 5744 11765 5746 11765 4861 11765 5744 11766 4865 11766 4918 11766 5747 11767 4918 11767 4915 11767 5744 11768 4918 11768 5747 11768 5748 11769 4915 11769 4902 11769 5747 11770 4915 11770 5748 11770 5749 11771 4902 11771 4894 11771 5748 11772 4902 11772 5749 11772 5750 11773 4894 11773 5136 11773 5749 11774 4894 11774 5750 11774 5751 11775 5136 11775 5137 11775 5750 11776 5136 11776 5751 11776 5752 11777 5137 11777 5138 11777 5751 11778 5137 11778 5752 11778 5753 11779 5138 11779 5135 11779 5754 11780 5138 11780 5753 11780 5752 11781 5138 11781 5754 11781 5753 11782 5135 11782 5281 11782 5755 11783 5281 11783 5292 11783 5753 11784 5281 11784 5755 11784 5756 11785 5292 11785 4784 11785 5755 11786 5292 11786 5756 11786 5757 11787 4784 11787 4788 11787 5756 11788 4784 11788 5757 11788 5758 11789 4788 11789 4866 11789 5757 11790 4788 11790 5758 11790 5759 11791 4866 11791 4868 11791 5758 11792 4866 11792 5759 11792 5759 11793 4868 11793 5745 11793 5760 11794 5235 11794 5325 11794 5760 11795 5236 11795 5235 11795 5761 11796 5325 11796 5366 11796 5761 11797 5760 11797 5325 11797 5762 11798 5366 11798 4994 11798 5761 11799 5366 11799 5762 11799 5763 11800 4994 11800 4991 11800 5762 11801 4994 11801 5763 11801 5764 11802 4991 11802 4987 11802 5763 11803 4991 11803 5764 11803 5765 11804 4987 11804 4990 11804 5764 11805 4987 11805 5765 11805 5766 11806 4990 11806 4982 11806 5765 11807 4990 11807 5766 11807 5767 11808 4982 11808 4986 11808 5768 11809 4982 11809 5767 11809 5766 11810 4982 11810 5768 11810 5767 11811 4986 11811 5034 11811 5769 11812 5034 11812 5027 11812 5767 11813 5034 11813 5769 11813 5770 11814 5027 11814 5031 11814 5769 11815 5027 11815 5770 11815 5771 11816 5031 11816 5083 11816 5770 11817 5031 11817 5771 11817 5772 11818 5083 11818 5237 11818 5771 11819 5083 11819 5772 11819 5773 11820 5237 11820 5238 11820 5772 11821 5237 11821 5773 11821 5774 11822 5238 11822 5236 11822 5773 11823 5238 11823 5774 11823 5775 11824 5236 11824 5760 11824 5774 11825 5236 11825 5775 11825 5776 11826 5737 11826 5736 11826 5777 11827 5735 11827 5737 11827 5777 11828 5737 11828 5778 11828 5776 11829 5778 11829 5737 11829 5776 11830 5736 11830 5738 11830 5779 11831 5738 11831 5502 11831 5776 11832 5738 11832 5779 11832 5780 11833 5502 11833 5503 11833 5779 11834 5502 11834 5780 11834 5781 11835 5503 11835 5394 11835 5780 11836 5503 11836 5781 11836 5782 11837 5394 11837 5392 11837 5781 11838 5394 11838 5782 11838 5783 11839 5392 11839 5385 11839 5782 11840 5392 11840 5783 11840 5784 11841 5385 11841 5388 11841 5783 11842 5385 11842 5784 11842 5785 11843 5388 11843 5389 11843 5786 11844 5388 11844 5785 11844 5784 11845 5388 11845 5786 11845 5785 11846 5389 11846 5390 11846 5787 11847 5390 11847 5382 11847 5785 11848 5390 11848 5787 11848 5788 11849 5382 11849 5378 11849 5787 11850 5382 11850 5788 11850 5789 11851 5378 11851 5381 11851 5788 11852 5378 11852 5789 11852 5790 11853 5381 11853 5731 11853 5789 11854 5381 11854 5790 11854 5791 11855 5731 11855 5735 11855 5790 11856 5731 11856 5791 11856 5791 11857 5735 11857 5777 11857 5792 11858 5727 11858 5726 11858 5792 11859 5728 11859 5727 11859 5793 11860 5726 11860 5614 11860 5793 11861 5792 11861 5726 11861 5794 11862 5614 11862 5615 11862 5793 11863 5614 11863 5794 11863 5795 11864 5615 11864 5422 11864 5794 11865 5615 11865 5795 11865 5796 11866 5422 11866 5420 11866 5795 11867 5422 11867 5796 11867 5797 11868 5420 11868 5413 11868 5796 11869 5420 11869 5797 11869 5798 11870 5413 11870 5416 11870 5797 11871 5413 11871 5798 11871 5799 11872 5416 11872 5417 11872 5800 11873 5416 11873 5799 11873 5798 11874 5416 11874 5800 11874 5799 11875 5417 11875 5418 11875 5801 11876 5418 11876 5410 11876 5799 11877 5418 11877 5801 11877 5802 11878 5410 11878 5406 11878 5801 11879 5410 11879 5802 11879 5803 11880 5406 11880 5409 11880 5802 11881 5406 11881 5803 11881 5804 11882 5409 11882 5721 11882 5803 11883 5409 11883 5804 11883 5805 11884 5721 11884 5725 11884 5804 11885 5721 11885 5805 11885 5806 11886 5725 11886 5728 11886 5805 11887 5725 11887 5806 11887 5807 11888 5728 11888 5792 11888 5806 11889 5728 11889 5807 11889 5759 11890 4790 11890 4787 11890 5758 11891 4787 11891 4792 11891 5758 11892 5759 11892 4787 11892 5745 11893 4867 11893 4790 11893 5759 11894 5745 11894 4790 11894 4921 11895 4863 11895 4867 11895 5746 11896 4921 11896 4867 11896 5745 11897 5746 11897 4867 11897 4922 11898 4860 11898 4863 11898 4921 11899 4922 11899 4863 11899 4923 11900 4857 11900 4860 11900 4922 11901 4923 11901 4860 11901 4924 11902 4854 11902 4857 11902 4923 11903 4924 11903 4857 11903 4925 11904 4851 11904 4854 11904 4924 11905 4925 11905 4854 11905 4928 11906 4847 11906 4851 11906 4925 11907 4928 11907 4851 11907 5312 11908 4844 11908 4847 11908 5163 11909 4847 11909 4928 11909 5312 11910 4847 11910 5163 11910 5285 11911 4842 11911 4844 11911 5312 11912 5285 11912 4844 11912 5285 11913 4840 11913 4842 11913 5285 11914 4837 11914 4840 11914 5284 11915 4835 11915 4837 11915 5285 11916 5284 11916 4837 11916 5284 11917 4832 11917 4835 11917 5286 11918 4830 11918 4832 11918 5286 11919 4832 11919 5284 11919 5286 11920 4827 11920 4830 11920 5287 11921 4824 11921 4827 11921 5286 11922 5287 11922 4827 11922 5289 11923 4821 11923 4824 11923 5288 11924 5289 11924 4824 11924 5287 11925 5288 11925 4824 11925 5274 11926 4818 11926 4821 11926 5272 11927 5274 11927 4821 11927 5289 11928 5272 11928 4821 11928 5274 11929 4816 11929 4818 11929 5274 11930 4814 11930 4816 11930 5274 11931 4812 11931 4814 11931 5274 11932 4809 11932 4812 11932 5274 11933 4806 11933 4809 11933 5757 11934 4804 11934 4806 11934 5278 11935 5279 11935 4806 11935 5757 11936 4806 11936 5279 11936 5276 11937 5278 11937 4806 11937 5274 11938 5276 11938 4806 11938 5757 11939 4802 11939 4804 11939 5758 11940 4800 11940 4802 11940 5757 11941 5758 11941 4802 11941 5758 11942 4798 11942 4800 11942 5758 11943 4796 11943 4798 11943 5758 11944 4794 11944 4796 11944 5758 11945 4792 11945 4794 11945 5158 11946 4875 11946 4872 11946 5157 11947 4872 11947 4878 11947 5157 11948 5158 11948 4872 11948 5159 11949 4941 11949 4875 11949 5158 11950 5159 11950 4875 11950 5159 11951 4940 11951 4941 11951 5160 11952 4938 11952 4940 11952 5159 11953 5160 11953 4940 11953 5160 11954 4935 11954 4938 11954 5163 11955 4933 11955 4935 11955 5160 11956 5163 11956 4935 11956 5163 11957 4931 11957 4933 11957 5163 11958 4928 11958 4931 11958 5744 11959 4920 11959 4921 11959 5744 11960 4921 11960 5746 11960 5748 11961 4919 11961 4920 11961 5747 11962 5748 11962 4920 11962 5744 11963 5747 11963 4920 11963 5749 11964 4917 11964 4919 11964 5748 11965 5749 11965 4919 11965 5750 11966 4914 11966 4917 11966 5749 11967 5750 11967 4917 11967 5750 11968 4912 11968 4914 11968 5750 11969 4910 11969 4912 11969 5750 11970 4908 11970 4910 11970 5750 11971 4906 11971 4908 11971 5750 11972 4904 11972 4906 11972 5750 11973 4901 11973 4904 11973 5750 11974 4896 11974 4901 11974 5750 11975 4893 11975 4896 11975 5154 11976 4891 11976 4893 11976 5750 11977 5154 11977 4893 11977 5155 11978 4889 11978 4891 11978 5154 11979 5155 11979 4891 11979 5155 11980 4887 11980 4889 11980 5155 11981 4885 11981 4887 11981 5155 11982 4882 11982 4885 11982 5156 11983 4878 11983 4882 11983 5155 11984 5156 11984 4882 11984 5156 11985 5157 11985 4878 11985 5361 11986 4948 11986 4945 11986 5360 11987 4945 11987 4951 11987 5360 11988 5361 11988 4945 11988 5363 11989 5026 11989 4948 11989 5362 11990 5363 11990 4948 11990 5361 11991 5362 11991 4948 11991 5316 11992 5024 11992 5026 11992 5318 11993 5316 11993 5026 11993 5363 11994 5318 11994 5026 11994 5316 11995 5022 11995 5024 11995 5316 11996 5020 11996 5022 11996 5316 11997 5018 11997 5020 11997 5316 11998 5015 11998 5018 11998 5316 11999 5012 11999 5015 11999 5763 12000 5010 12000 5012 12000 5320 12001 5012 12001 5316 12001 5322 12002 5323 12002 5012 12002 5763 12003 5012 12003 5323 12003 5320 12004 5322 12004 5012 12004 5763 12005 5008 12005 5010 12005 5764 12006 5006 12006 5008 12006 5763 12007 5764 12007 5008 12007 5764 12008 5004 12008 5006 12008 5764 12009 5002 12009 5004 12009 5764 12010 5000 12010 5002 12010 5764 12011 4998 12011 5000 12011 5764 12012 4996 12012 4998 12012 5765 12013 4993 12013 4996 12013 5764 12014 5765 12014 4996 12014 5766 12015 4989 12015 4993 12015 5765 12016 5766 12016 4993 12016 5037 12017 4984 12017 4989 12017 5768 12018 5037 12018 4989 12018 5766 12019 5768 12019 4989 12019 5038 12020 4981 12020 4984 12020 5037 12021 5038 12021 4984 12021 5039 12022 4978 12022 4981 12022 5038 12023 5039 12023 4981 12023 5040 12024 4975 12024 4978 12024 5039 12025 5040 12025 4978 12025 5041 12026 4972 12026 4975 12026 5040 12027 5041 12027 4975 12027 5044 12028 4968 12028 4972 12028 5041 12029 5044 12029 4972 12029 5357 12030 4965 12030 4968 12030 5184 12031 4968 12031 5044 12031 5357 12032 4968 12032 5184 12032 5358 12033 4963 12033 4965 12033 5357 12034 5358 12034 4965 12034 5358 12035 4961 12035 4963 12035 5358 12036 4958 12036 4961 12036 5359 12037 4956 12037 4958 12037 5358 12038 5359 12038 4958 12038 5359 12039 4953 12039 4956 12039 5360 12040 4951 12040 4953 12040 5359 12041 5360 12041 4953 12041 5772 12042 5033 12042 5030 12042 5771 12043 5030 12043 5035 12043 5771 12044 5772 12044 5030 12044 5772 12045 5099 12045 5033 12045 5772 12046 5098 12046 5099 12046 5772 12047 5096 12047 5098 12047 5772 12048 5094 12048 5096 12048 5772 12049 5092 12049 5094 12049 5772 12050 5090 12050 5092 12050 5772 12051 5085 12051 5090 12051 5772 12052 5082 12052 5085 12052 5214 12053 5080 12053 5082 12053 5772 12054 5214 12054 5082 12054 5215 12055 5078 12055 5080 12055 5214 12056 5215 12056 5080 12056 5215 12057 5076 12057 5078 12057 5215 12058 5074 12058 5076 12058 5215 12059 5071 12059 5074 12059 5216 12060 5067 12060 5071 12060 5215 12061 5216 12061 5071 12061 5217 12062 5064 12062 5067 12062 5216 12063 5217 12063 5067 12063 5180 12064 5061 12064 5064 12064 5217 12065 5180 12065 5064 12065 5179 12066 5059 12066 5061 12066 5180 12067 5179 12067 5061 12067 5179 12068 5056 12068 5059 12068 5181 12069 5054 12069 5056 12069 5181 12070 5056 12070 5179 12070 5181 12071 5051 12071 5054 12071 5184 12072 5049 12072 5051 12072 5181 12073 5184 12073 5051 12073 5184 12074 5047 12074 5049 12074 5184 12075 5044 12075 5047 12075 5767 12076 5036 12076 5037 12076 5768 12077 5767 12077 5037 12077 5770 12078 5035 12078 5036 12078 5769 12079 5770 12079 5036 12079 5767 12080 5769 12080 5036 12080 5770 12081 5771 12081 5035 12081 5424 12082 5101 12082 5100 12082 5424 12083 5100 12083 5104 12083 5424 12084 5140 12084 5101 12084 5424 12085 5139 12085 5140 12085 5424 12086 5134 12086 5139 12086 5282 12087 5133 12087 5134 12087 5424 12088 5154 12088 5134 12088 5752 12089 5134 12089 5154 12089 5280 12090 5282 12090 5134 12090 5754 12091 5280 12091 5134 12091 5752 12092 5754 12092 5134 12092 5283 12093 5130 12093 5133 12093 5282 12094 5283 12094 5133 12094 5259 12095 5127 12095 5130 12095 5283 12096 5259 12096 5130 12096 5258 12097 5124 12097 5127 12097 5259 12098 5258 12098 5127 12098 5260 12099 5121 12099 5124 12099 5260 12100 5124 12100 5258 12100 5261 12101 5118 12101 5121 12101 5260 12102 5261 12102 5121 12102 5262 12103 5115 12103 5118 12103 5261 12104 5262 12104 5118 12104 5265 12105 5111 12105 5115 12105 5262 12106 5265 12106 5115 12106 5425 12107 5108 12107 5111 12107 5475 12108 5111 12108 5265 12108 5475 12109 5425 12109 5111 12109 5425 12110 5106 12110 5108 12110 5424 12111 5104 12111 5106 12111 5425 12112 5424 12112 5106 12112 5491 12113 5147 12113 5144 12113 5487 12114 5144 12114 5150 12114 5489 12115 5491 12115 5144 12115 5488 12116 5489 12116 5144 12116 5487 12117 5488 12117 5144 12117 5493 12118 5175 12118 5147 12118 5492 12119 5493 12119 5147 12119 5491 12120 5492 12120 5147 12120 5496 12121 5173 12121 5175 12121 5493 12122 5496 12122 5175 12122 5496 12123 5169 12123 5173 12123 5311 12124 5166 12124 5169 12124 5310 12125 5311 12125 5169 12125 5496 12126 5310 12126 5169 12126 5312 12127 5163 12127 5166 12127 5311 12128 5312 12128 5166 12128 5424 12129 5153 12129 5154 12129 5751 12130 5752 12130 5154 12130 5750 12131 5751 12131 5154 12131 5424 12132 5150 12132 5153 12132 5487 12133 5150 12133 5424 12133 5700 12134 5213 12134 5214 12134 5700 12135 5214 12135 5234 12135 5774 12136 5234 12136 5214 12136 5773 12137 5774 12137 5214 12137 5772 12138 5773 12138 5214 12138 5700 12139 5209 12139 5213 12139 5601 12140 5206 12140 5209 12140 5700 12141 5601 12141 5209 12141 5605 12142 5200 12142 5206 12142 5603 12143 5605 12143 5206 12143 5602 12144 5603 12144 5206 12144 5601 12145 5602 12145 5206 12145 5607 12146 5197 12146 5200 12146 5606 12147 5607 12147 5200 12147 5605 12148 5606 12148 5200 12148 5608 12149 5194 12149 5197 12149 5607 12150 5608 12150 5197 12150 5608 12151 5190 12151 5194 12151 5356 12152 5187 12152 5190 12152 5355 12153 5356 12153 5190 12153 5608 12154 5355 12154 5190 12154 5357 12155 5184 12155 5187 12155 5356 12156 5357 12156 5187 12156 5330 12157 5224 12157 5221 12157 5329 12158 5221 12158 5227 12158 5329 12159 5330 12159 5221 12159 5331 12160 5257 12160 5224 12160 5330 12161 5331 12161 5224 12161 5332 12162 5255 12162 5257 12162 5331 12163 5332 12163 5257 12163 5335 12164 5251 12164 5255 12164 5332 12165 5335 12165 5255 12165 5701 12166 5248 12166 5251 12166 5693 12167 5251 12167 5335 12167 5701 12168 5251 12168 5693 12168 5701 12169 5246 12169 5248 12169 5700 12170 5244 12170 5246 12170 5701 12171 5700 12171 5246 12171 5700 12172 5242 12172 5244 12172 5700 12173 5241 12173 5242 12173 5700 12174 5240 12174 5241 12174 5700 12175 5239 12175 5240 12175 5700 12176 5234 12176 5239 12176 5326 12177 5233 12177 5234 12177 5324 12178 5326 12178 5234 12178 5775 12179 5324 12179 5234 12179 5774 12180 5775 12180 5234 12180 5327 12181 5230 12181 5233 12181 5326 12182 5327 12182 5233 12182 5328 12183 5227 12183 5230 12183 5327 12184 5328 12184 5230 12184 5328 12185 5329 12185 5227 12185 5757 12186 5279 12186 5280 12186 5756 12187 5757 12187 5280 12187 5755 12188 5756 12188 5280 12188 5753 12189 5755 12189 5280 12189 5754 12190 5753 12190 5280 12190 5475 12191 5270 12191 5272 12191 5475 12192 5272 12192 5289 12192 5475 12193 5267 12193 5270 12193 5475 12194 5265 12194 5267 12194 5622 12195 5309 12195 5310 12195 5621 12196 5622 12196 5310 12196 5496 12197 5621 12197 5310 12197 5622 12198 5308 12198 5309 12198 5624 12199 5305 12199 5308 12199 5622 12200 5624 12200 5308 12200 5628 12201 5300 12201 5305 12201 5627 12202 5628 12202 5305 12202 5625 12203 5627 12203 5305 12203 5626 12204 5625 12204 5305 12204 5624 12205 5626 12205 5305 12205 5629 12206 5297 12206 5300 12206 5628 12207 5629 12207 5300 12207 5472 12208 5294 12208 5297 12208 5471 12209 5472 12209 5297 12209 5629 12210 5471 12210 5297 12210 5475 12211 5291 12211 5294 12211 5472 12212 5475 12212 5294 12212 5475 12213 5289 12213 5291 12213 5693 12214 5338 12214 5318 12214 5693 12215 5318 12215 5363 12215 5693 12216 5337 12216 5338 12216 5693 12217 5335 12217 5337 12217 5763 12218 5323 12218 5324 12218 5775 12219 5760 12219 5324 12219 5761 12220 5324 12220 5760 12220 5762 12221 5763 12221 5324 12221 5761 12222 5762 12222 5324 12222 5521 12223 5345 12223 5342 12223 5518 12224 5342 12224 5350 12224 5518 12225 5521 12225 5342 12225 5690 12226 5367 12226 5345 12226 5689 12227 5345 12227 5521 12227 5689 12228 5690 12228 5345 12228 5693 12229 5365 12229 5367 12229 5690 12230 5693 12230 5367 12230 5693 12231 5363 12231 5365 12231 5512 12232 5354 12232 5355 12232 5511 12233 5355 12233 5608 12233 5511 12234 5512 12234 5355 12234 5512 12235 5353 12235 5354 12235 5514 12236 5350 12236 5353 12236 5512 12237 5514 12237 5353 12237 5517 12238 5518 12238 5350 12238 5515 12239 5517 12239 5350 12239 5516 12240 5515 12240 5350 12240 5514 12241 5516 12241 5350 12241 5720 12242 5373 12242 5374 12242 5509 12243 5374 12243 5371 12243 5509 12244 5612 12244 5374 12244 5720 12245 5374 12245 5612 12245 5796 12246 5423 12246 5373 12246 5795 12247 5373 12247 5720 12247 5795 12248 5796 12248 5373 12248 5797 12249 5415 12249 5423 12249 5796 12250 5797 12250 5423 12250 5801 12251 5419 12251 5415 12251 5799 12252 5801 12252 5415 12252 5800 12253 5799 12253 5415 12253 5798 12254 5800 12254 5415 12254 5797 12255 5798 12255 5415 12255 5802 12256 5412 12256 5419 12256 5801 12257 5802 12257 5419 12257 5803 12258 5408 12258 5412 12258 5802 12259 5803 12259 5412 12259 5619 12260 5401 12260 5408 12260 5803 12261 5619 12261 5408 12261 5619 12262 5402 12262 5401 12262 5734 12263 5399 12263 5402 12263 5500 12264 5402 12264 5619 12264 5734 12265 5402 12265 5500 12265 5782 12266 5396 12266 5399 12266 5781 12267 5399 12267 5734 12267 5781 12268 5782 12268 5399 12268 5783 12269 5387 12269 5396 12269 5782 12270 5783 12270 5396 12270 5787 12271 5391 12271 5387 12271 5785 12272 5787 12272 5387 12272 5786 12273 5785 12273 5387 12273 5784 12274 5786 12274 5387 12274 5783 12275 5784 12275 5387 12275 5788 12276 5384 12276 5391 12276 5787 12277 5788 12277 5391 12277 5789 12278 5380 12278 5384 12278 5788 12279 5789 12279 5384 12279 5509 12280 5371 12280 5380 12280 5789 12281 5509 12281 5380 12281 5487 12282 5424 12282 5428 12282 5717 12283 5452 12283 5425 12283 5718 12284 5425 12284 5475 12284 5718 12285 5717 12285 5425 12285 5719 12286 5451 12286 5452 12286 5717 12287 5719 12287 5452 12287 5719 12288 5449 12288 5451 12288 5719 12289 5446 12289 5449 12289 5485 12290 5444 12290 5446 12290 5719 12291 5485 12291 5446 12291 5485 12292 5442 12292 5444 12292 5484 12293 5440 12293 5442 12293 5485 12294 5484 12294 5442 12294 5484 12295 5437 12295 5440 12295 5486 12296 5435 12296 5437 12296 5486 12297 5437 12297 5484 12297 5486 12298 5432 12298 5435 12298 5487 12299 5430 12299 5432 12299 5486 12300 5487 12300 5432 12300 5487 12301 5428 12301 5430 12301 5633 12302 5459 12302 5456 12302 5633 12303 5456 12303 5461 12303 5633 12304 5483 12304 5459 12304 5633 12305 5482 12305 5483 12305 5718 12306 5480 12306 5482 12306 5718 12307 5482 12307 5633 12307 5718 12308 5478 12308 5480 12308 5718 12309 5475 12309 5478 12309 5630 12310 5470 12310 5471 12310 5629 12311 5630 12311 5471 12311 5630 12312 5468 12312 5470 12312 5630 12313 5466 12313 5468 12313 5631 12314 5464 12314 5466 12314 5630 12315 5631 12315 5466 12315 5631 12316 5461 12316 5464 12316 5631 12317 5633 12317 5461 12317 5719 12318 5681 12318 5485 12318 5719 12319 5680 12319 5681 12319 5719 12320 5678 12320 5680 12320 5719 12321 5676 12321 5678 12321 5719 12322 5671 12322 5676 12322 5644 12323 5672 12323 5671 12323 5646 12324 5644 12324 5671 12324 5719 12325 5646 12325 5671 12325 5651 12326 5670 12326 5672 12326 5644 12327 5651 12327 5672 12327 5654 12328 5669 12328 5670 12328 5651 12329 5654 12329 5670 12329 5657 12330 5668 12330 5669 12330 5654 12331 5657 12331 5669 12331 5660 12332 5667 12332 5668 12332 5657 12333 5660 12333 5668 12333 5663 12334 5666 12334 5667 12334 5660 12335 5663 12335 5667 12335 5665 12336 5664 12336 5666 12336 5663 12337 5665 12337 5666 12337 5716 12338 5641 12338 5646 12338 5719 12339 5716 12339 5646 12339 5718 12340 5639 12340 5641 12340 5718 12341 5641 12341 5716 12341 5718 12342 5637 12342 5639 12342 5718 12343 5635 12343 5637 12343 5718 12344 5633 12344 5635 12344 5497 12345 5620 12345 5621 12345 5496 12346 5497 12346 5621 12346 5500 12347 5619 12347 5620 12347 5497 12348 5500 12348 5620 12348 5724 12349 5617 12349 5619 12349 5723 12350 5724 12350 5619 12350 5805 12351 5723 12351 5619 12351 5804 12352 5805 12352 5619 12352 5803 12353 5804 12353 5619 12353 5720 12354 5618 12354 5617 12354 5720 12355 5617 12355 5724 12355 5720 12356 5612 12356 5618 12356 5510 12357 5609 12357 5612 12357 5509 12358 5510 12358 5612 12358 5511 12359 5608 12359 5609 12359 5510 12360 5511 12360 5609 12360 5605 12361 5604 12361 5606 12361 5704 12362 5598 12362 5601 12362 5702 12363 5601 12363 5700 12363 5703 12364 5704 12364 5601 12364 5702 12365 5703 12365 5601 12365 5706 12366 5596 12366 5598 12366 5705 12367 5706 12367 5598 12367 5704 12368 5705 12368 5598 12368 5708 12369 5589 12369 5596 12369 5707 12370 5708 12370 5596 12370 5706 12371 5707 12371 5596 12371 5742 12372 5586 12372 5589 12372 5709 12373 5710 12373 5589 12373 5742 12374 5589 12374 5710 12374 5708 12375 5709 12375 5589 12375 5742 12376 5584 12376 5586 12376 5742 12377 5582 12377 5584 12377 5742 12378 5580 12378 5582 12378 5742 12379 5574 12379 5580 12379 5547 12380 5575 12380 5574 12380 5549 12381 5547 12381 5574 12381 5742 12382 5549 12382 5574 12382 5554 12383 5573 12383 5575 12383 5547 12384 5554 12384 5575 12384 5557 12385 5572 12385 5573 12385 5554 12386 5557 12386 5573 12386 5560 12387 5571 12387 5572 12387 5557 12388 5560 12388 5572 12388 5563 12389 5570 12389 5571 12389 5560 12390 5563 12390 5571 12390 5566 12391 5569 12391 5570 12391 5563 12392 5566 12392 5570 12392 5568 12393 5567 12393 5569 12393 5566 12394 5568 12394 5569 12394 5741 12395 5544 12395 5549 12395 5742 12396 5741 12396 5549 12396 5743 12397 5542 12397 5544 12397 5741 12398 5743 12398 5544 12398 5743 12399 5540 12399 5542 12399 5743 12400 5538 12400 5540 12400 5743 12401 5534 12401 5538 12401 5684 12402 5530 12402 5534 12402 5683 12403 5682 12403 5534 12403 5684 12404 5534 12404 5682 12404 5699 12405 5683 12405 5534 12405 5698 12406 5699 12406 5534 12406 5743 12407 5698 12407 5534 12407 5686 12408 5526 12408 5530 12408 5685 12409 5686 12409 5530 12409 5684 12410 5685 12410 5530 12410 5689 12411 5521 12411 5526 12411 5688 12412 5689 12412 5526 12412 5687 12413 5688 12413 5526 12413 5686 12414 5687 12414 5526 12414 5730 12415 5505 12415 5509 12415 5733 12416 5730 12416 5509 12416 5791 12417 5733 12417 5509 12417 5790 12418 5791 12418 5509 12418 5789 12419 5790 12419 5509 12419 5734 12420 5506 12420 5505 12420 5734 12421 5505 12421 5730 12421 5734 12422 5500 12422 5506 12422 5491 12423 5490 12423 5492 12423 5743 12424 5697 12424 5698 12424 5743 12425 5695 12425 5697 12425 5743 12426 5693 12426 5695 12426 5743 12427 5701 12427 5693 12427 5740 12428 5715 12428 5701 12428 5743 12429 5740 12429 5701 12429 5742 12430 5714 12430 5715 12430 5742 12431 5715 12431 5740 12431 5742 12432 5712 12432 5714 12432 5742 12433 5710 12433 5712 12433 5793 12434 5729 12434 5723 12434 5807 12435 5792 12435 5723 12435 5793 12436 5723 12436 5792 12436 5806 12437 5807 12437 5723 12437 5805 12438 5806 12438 5723 12438 5794 12439 5720 12439 5729 12439 5793 12440 5794 12440 5729 12440 5794 12441 5795 12441 5720 12441 5779 12442 5739 12442 5733 12442 5777 12443 5778 12443 5733 12443 5776 12444 5733 12444 5778 12444 5791 12445 5777 12445 5733 12445 5776 12446 5779 12446 5733 12446 5780 12447 5734 12447 5739 12447 5779 12448 5780 12448 5739 12448 5780 12449 5781 12449 5734 12449 5808 12450 5809 12450 5810 12450 5811 12451 5810 12451 5809 12451 5812 12452 5808 12452 5810 12452 5813 12453 5812 12453 5810 12453 5814 12454 5813 12454 5810 12454 5814 12455 5810 12455 5811 12455 5815 12456 5816 12456 5809 12456 5817 12457 5809 12457 5816 12457 5808 12458 5815 12458 5809 12458 5817 12459 5811 12459 5809 12459 5818 12460 5819 12460 5816 12460 5817 12461 5816 12461 5819 12461 5815 12462 5818 12462 5816 12462 5820 12463 5821 12463 5819 12463 5822 12464 5819 12464 5821 12464 5818 12465 5820 12465 5819 12465 5817 12466 5819 12466 5822 12466 5823 12467 5824 12467 5821 12467 5822 12468 5821 12468 5824 12468 5820 12469 5823 12469 5821 12469 5825 12470 5826 12470 5824 12470 5827 12471 5824 12471 5826 12471 5823 12472 5825 12472 5824 12472 5822 12473 5824 12473 5827 12473 5828 12474 5829 12474 5826 12474 5827 12475 5826 12475 5829 12475 5825 12476 5828 12476 5826 12476 5830 12477 5831 12477 5829 12477 5832 12478 5829 12478 5831 12478 5828 12479 5830 12479 5829 12479 5827 12480 5829 12480 5832 12480 5833 12481 5834 12481 5831 12481 5832 12482 5831 12482 5834 12482 5830 12483 5833 12483 5831 12483 5835 12484 5836 12484 5834 12484 5837 12485 5834 12485 5836 12485 5833 12486 5835 12486 5834 12486 5832 12487 5834 12487 5837 12487 5838 12488 5839 12488 5836 12488 5837 12489 5836 12489 5839 12489 5835 12490 5838 12490 5836 12490 5840 12491 5841 12491 5839 12491 5842 12492 5839 12492 5841 12492 5838 12493 5840 12493 5839 12493 5837 12494 5839 12494 5842 12494 5840 12495 5843 12495 5841 12495 5842 12496 5841 12496 5843 12496 5844 12497 5843 12497 5840 12497 5842 12498 5843 12498 5844 12498 5845 12499 5840 12499 5838 12499 5844 12500 5840 12500 5845 12500 5845 12501 5838 12501 5835 12501 5846 12502 5835 12502 5833 12502 5845 12503 5835 12503 5846 12503 5846 12504 5833 12504 5830 12504 5847 12505 5830 12505 5828 12505 5846 12506 5830 12506 5847 12506 5847 12507 5828 12507 5825 12507 5848 12508 5825 12508 5823 12508 5847 12509 5825 12509 5848 12509 5848 12510 5823 12510 5820 12510 5849 12511 5820 12511 5818 12511 5848 12512 5820 12512 5849 12512 5849 12513 5818 12513 5815 12513 5850 12514 5815 12514 5808 12514 5849 12515 5815 12515 5850 12515 5850 12516 5808 12516 5812 12516 5813 12517 5851 12517 5812 12517 5852 12518 5812 12518 5851 12518 5850 12519 5812 12519 5852 12519 5853 12520 5854 12520 5851 12520 5855 12521 5851 12521 5854 12521 5813 12522 5853 12522 5851 12522 5852 12523 5851 12523 5855 12523 5856 12524 5857 12524 5854 12524 5855 12525 5854 12525 5857 12525 5853 12526 5856 12526 5854 12526 5858 12527 5859 12527 5857 12527 5860 12528 5857 12528 5859 12528 5856 12529 5858 12529 5857 12529 5855 12530 5857 12530 5860 12530 5861 12531 5862 12531 5859 12531 5860 12532 5859 12532 5862 12532 5858 12533 5861 12533 5859 12533 5863 12534 5864 12534 5862 12534 5865 12535 5862 12535 5864 12535 5861 12536 5863 12536 5862 12536 5860 12537 5862 12537 5865 12537 5866 12538 5867 12538 5864 12538 5865 12539 5864 12539 5867 12539 5863 12540 5866 12540 5864 12540 5868 12541 5869 12541 5867 12541 5870 12542 5867 12542 5869 12542 5866 12543 5868 12543 5867 12543 5865 12544 5867 12544 5870 12544 5871 12545 5872 12545 5869 12545 5870 12546 5869 12546 5872 12546 5868 12547 5871 12547 5869 12547 5873 12548 5874 12548 5872 12548 5875 12549 5872 12549 5874 12549 5871 12550 5873 12550 5872 12550 5870 12551 5872 12551 5875 12551 5876 12552 5877 12552 5874 12552 5875 12553 5874 12553 5877 12553 5873 12554 5876 12554 5874 12554 5878 12555 5879 12555 5877 12555 5880 12556 5877 12556 5879 12556 5876 12557 5878 12557 5877 12557 5875 12558 5877 12558 5880 12558 5878 12559 5881 12559 5879 12559 5880 12560 5879 12560 5881 12560 5882 12561 5881 12561 5878 12561 5880 12562 5881 12562 5882 12562 5883 12563 5878 12563 5876 12563 5882 12564 5878 12564 5883 12564 5883 12565 5876 12565 5873 12565 5884 12566 5873 12566 5871 12566 5883 12567 5873 12567 5884 12567 5884 12568 5871 12568 5868 12568 5885 12569 5868 12569 5866 12569 5884 12570 5868 12570 5885 12570 5885 12571 5866 12571 5863 12571 5886 12572 5863 12572 5861 12572 5885 12573 5863 12573 5886 12573 5886 12574 5861 12574 5858 12574 5887 12575 5858 12575 5856 12575 5886 12576 5858 12576 5887 12576 5887 12577 5856 12577 5853 12577 5814 12578 5853 12578 5813 12578 5887 12579 5853 12579 5814 12579 5888 12580 5889 12580 5890 12580 5891 12581 5890 12581 5889 12581 5892 12582 5888 12582 5890 12582 5892 12583 5890 12583 5891 12583 5893 12584 5894 12584 5889 12584 5895 12585 5889 12585 5894 12585 5888 12586 5893 12586 5889 12586 5895 12587 5891 12587 5889 12587 5896 12588 5897 12588 5894 12588 5895 12589 5894 12589 5897 12589 5893 12590 5896 12590 5894 12590 5898 12591 5899 12591 5897 12591 5900 12592 5897 12592 5899 12592 5896 12593 5898 12593 5897 12593 5895 12594 5897 12594 5900 12594 5901 12595 5902 12595 5899 12595 5903 12596 5899 12596 5902 12596 5898 12597 5901 12597 5899 12597 5900 12598 5899 12598 5903 12598 5904 12599 5905 12599 5902 12599 5903 12600 5902 12600 5905 12600 5901 12601 5904 12601 5902 12601 5906 12602 5907 12602 5905 12602 5908 12603 5905 12603 5907 12603 5904 12604 5906 12604 5905 12604 5903 12605 5905 12605 5908 12605 5909 12606 5910 12606 5907 12606 5911 12607 5907 12607 5910 12607 5906 12608 5909 12608 5907 12608 5908 12609 5907 12609 5911 12609 5912 12610 5913 12610 5910 12610 5911 12611 5910 12611 5913 12611 5909 12612 5912 12612 5910 12612 5914 12613 5915 12613 5913 12613 5916 12614 5913 12614 5915 12614 5917 12615 5913 12615 5912 12615 5914 12616 5913 12616 5917 12616 5911 12617 5913 12617 5916 12617 5918 12618 5919 12618 5915 12618 5916 12619 5915 12619 5919 12619 5920 12620 5918 12620 5915 12620 5914 12621 5920 12621 5915 12621 5921 12622 5922 12622 5919 12622 5923 12623 5919 12623 5922 12623 5918 12624 5921 12624 5919 12624 5916 12625 5919 12625 5923 12625 5924 12626 5925 12626 5922 12626 5926 12627 5922 12627 5925 12627 5927 12628 5924 12628 5922 12628 5921 12629 5927 12629 5922 12629 5923 12630 5922 12630 5926 12630 5928 12631 5929 12631 5925 12631 5926 12632 5925 12632 5929 12632 5930 12633 5928 12633 5925 12633 5924 12634 5930 12634 5925 12634 5931 12635 5932 12635 5929 12635 5933 12636 5929 12636 5932 12636 5928 12637 5931 12637 5929 12637 5926 12638 5929 12638 5933 12638 5934 12639 5935 12639 5932 12639 5936 12640 5932 12640 5935 12640 5931 12641 5934 12641 5932 12641 5933 12642 5932 12642 5936 12642 5937 12643 5938 12643 5935 12643 5936 12644 5935 12644 5938 12644 5934 12645 5937 12645 5935 12645 5939 12646 5940 12646 5938 12646 5941 12647 5938 12647 5940 12647 5937 12648 5939 12648 5938 12648 5936 12649 5938 12649 5941 12649 5942 12650 5943 12650 5940 12650 5944 12651 5940 12651 5943 12651 5939 12652 5942 12652 5940 12652 5941 12653 5940 12653 5944 12653 5945 12654 5946 12654 5943 12654 5944 12655 5943 12655 5946 12655 5942 12656 5945 12656 5943 12656 5947 12657 5948 12657 5946 12657 5949 12658 5946 12658 5948 12658 5945 12659 5947 12659 5946 12659 5944 12660 5946 12660 5949 12660 5947 12661 5950 12661 5948 12661 5949 12662 5948 12662 5950 12662 5951 12663 5950 12663 5947 12663 5949 12664 5950 12664 5951 12664 5952 12665 5947 12665 5945 12665 5951 12666 5947 12666 5952 12666 5952 12667 5945 12667 5942 12667 5953 12668 5942 12668 5939 12668 5952 12669 5942 12669 5953 12669 5954 12670 5939 12670 5937 12670 5953 12671 5939 12671 5954 12671 5954 12672 5937 12672 5934 12672 5955 12673 5934 12673 5931 12673 5954 12674 5934 12674 5955 12674 5956 12675 5931 12675 5928 12675 5955 12676 5931 12676 5956 12676 5956 12677 5928 12677 5930 12677 5957 12678 5958 12678 5930 12678 5959 12679 5930 12679 5958 12679 5924 12680 5957 12680 5930 12680 5956 12681 5930 12681 5959 12681 5960 12682 5961 12682 5958 12682 5959 12683 5958 12683 5961 12683 5962 12684 5960 12684 5958 12684 5957 12685 5962 12685 5958 12685 5963 12686 5964 12686 5961 12686 5965 12687 5961 12687 5964 12687 5960 12688 5963 12688 5961 12688 5959 12689 5961 12689 5965 12689 5917 12690 5912 12690 5964 12690 5966 12691 5964 12691 5912 12691 5967 12692 5917 12692 5964 12692 5963 12693 5967 12693 5964 12693 5965 12694 5964 12694 5966 12694 5966 12695 5912 12695 5909 12695 5968 12696 5909 12696 5906 12696 5966 12697 5909 12697 5968 12697 5969 12698 5906 12698 5904 12698 5968 12699 5906 12699 5969 12699 5969 12700 5904 12700 5901 12700 5970 12701 5901 12701 5898 12701 5969 12702 5901 12702 5970 12702 5971 12703 5898 12703 5896 12703 5970 12704 5898 12704 5971 12704 5971 12705 5896 12705 5893 12705 5892 12706 5893 12706 5888 12706 5971 12707 5893 12707 5892 12707 5972 12708 5917 12708 5967 12708 5973 12709 5914 12709 5917 12709 5973 12710 5917 12710 5972 12710 5974 12711 5967 12711 5963 12711 5974 12712 5972 12712 5967 12712 5975 12713 5963 12713 5960 12713 5974 12714 5963 12714 5975 12714 5976 12715 5960 12715 5962 12715 5975 12716 5960 12716 5976 12716 5977 12717 5962 12717 5957 12717 5976 12718 5962 12718 5977 12718 5978 12719 5957 12719 5924 12719 5977 12720 5957 12720 5978 12720 5979 12721 5924 12721 5927 12721 5978 12722 5924 12722 5979 12722 5980 12723 5927 12723 5921 12723 5979 12724 5927 12724 5980 12724 5981 12725 5921 12725 5918 12725 5980 12726 5921 12726 5981 12726 5982 12727 5918 12727 5920 12727 5981 12728 5918 12728 5982 12728 5983 12729 5920 12729 5914 12729 5982 12730 5920 12730 5983 12730 5983 12731 5914 12731 5973 12731 5855 12732 5892 12732 5891 12732 5852 12733 5855 12733 5891 12733 5895 12734 5852 12734 5891 12734 5860 12735 5971 12735 5892 12735 5855 12736 5860 12736 5892 12736 5865 12737 5970 12737 5971 12737 5860 12738 5865 12738 5971 12738 5870 12739 5969 12739 5970 12739 5865 12740 5870 12740 5970 12740 5875 12741 5968 12741 5969 12741 5870 12742 5875 12742 5969 12742 5880 12743 5966 12743 5968 12743 5875 12744 5880 12744 5968 12744 5882 12745 5965 12745 5966 12745 5880 12746 5882 12746 5966 12746 5883 12747 5959 12747 5965 12747 5882 12748 5883 12748 5965 12748 5884 12749 5956 12749 5959 12749 5883 12750 5884 12750 5959 12750 5885 12751 5955 12751 5956 12751 5884 12752 5885 12752 5956 12752 5886 12753 5954 12753 5955 12753 5885 12754 5886 12754 5955 12754 5887 12755 5953 12755 5954 12755 5886 12756 5887 12756 5954 12756 5814 12757 5952 12757 5953 12757 5887 12758 5814 12758 5953 12758 5811 12759 5951 12759 5952 12759 5814 12760 5811 12760 5952 12760 5817 12761 5951 12761 5811 12761 5817 12762 5949 12762 5951 12762 5850 12763 5852 12763 5895 12763 5822 12764 5944 12764 5949 12764 5817 12765 5822 12765 5949 12765 5827 12766 5941 12766 5944 12766 5822 12767 5827 12767 5944 12767 5832 12768 5936 12768 5941 12768 5827 12769 5832 12769 5941 12769 5837 12770 5933 12770 5936 12770 5832 12771 5837 12771 5936 12771 5842 12772 5926 12772 5933 12772 5837 12773 5842 12773 5933 12773 5844 12774 5923 12774 5926 12774 5842 12775 5844 12775 5926 12775 5845 12776 5916 12776 5923 12776 5844 12777 5845 12777 5923 12777 5846 12778 5911 12778 5916 12778 5845 12779 5846 12779 5916 12779 5847 12780 5908 12780 5911 12780 5846 12781 5847 12781 5911 12781 5848 12782 5903 12782 5908 12782 5847 12783 5848 12783 5908 12783 5849 12784 5900 12784 5903 12784 5848 12785 5849 12785 5903 12785 5850 12786 5895 12786 5900 12786 5849 12787 5850 12787 5900 12787 5980 12788 5973 12788 5972 12788 5979 12789 5980 12789 5972 12789 5974 12790 5979 12790 5972 12790 5981 12791 5983 12791 5973 12791 5980 12792 5981 12792 5973 12792 5981 12793 5982 12793 5983 12793 5974 12794 5978 12794 5979 12794 5975 12795 5977 12795 5978 12795 5974 12796 5975 12796 5978 12796 5975 12797 5976 12797 5977 12797 5984 12798 5985 12798 5986 12798 5987 12799 5986 12799 5985 12799 5988 12800 5984 12800 5986 12800 5989 12801 5988 12801 5986 12801 5990 12802 5989 12802 5986 12802 5990 12803 5986 12803 5987 12803 5991 12804 5992 12804 5985 12804 5993 12805 5985 12805 5992 12805 5984 12806 5991 12806 5985 12806 5993 12807 5987 12807 5985 12807 5994 12808 5995 12808 5992 12808 5993 12809 5992 12809 5995 12809 5991 12810 5994 12810 5992 12810 5996 12811 5997 12811 5995 12811 5998 12812 5995 12812 5997 12812 5994 12813 5996 12813 5995 12813 5993 12814 5995 12814 5998 12814 5999 12815 6000 12815 5997 12815 5998 12816 5997 12816 6000 12816 5996 12817 5999 12817 5997 12817 6001 12818 6002 12818 6000 12818 6003 12819 6000 12819 6002 12819 5999 12820 6001 12820 6000 12820 5998 12821 6000 12821 6003 12821 6004 12822 6005 12822 6002 12822 6003 12823 6002 12823 6005 12823 6001 12824 6004 12824 6002 12824 6006 12825 6007 12825 6005 12825 6008 12826 6005 12826 6007 12826 6004 12827 6006 12827 6005 12827 6003 12828 6005 12828 6008 12828 6009 12829 6010 12829 6007 12829 6008 12830 6007 12830 6010 12830 6006 12831 6009 12831 6007 12831 6011 12832 6012 12832 6010 12832 6013 12833 6010 12833 6012 12833 6009 12834 6011 12834 6010 12834 6008 12835 6010 12835 6013 12835 6014 12836 6015 12836 6012 12836 6013 12837 6012 12837 6015 12837 6011 12838 6014 12838 6012 12838 6016 12839 6017 12839 6015 12839 6018 12840 6015 12840 6017 12840 6014 12841 6016 12841 6015 12841 6013 12842 6015 12842 6018 12842 6016 12843 6019 12843 6017 12843 6018 12844 6017 12844 6019 12844 6020 12845 6019 12845 6016 12845 6018 12846 6019 12846 6020 12846 6021 12847 6016 12847 6014 12847 6020 12848 6016 12848 6021 12848 6021 12849 6014 12849 6011 12849 6022 12850 6011 12850 6009 12850 6021 12851 6011 12851 6022 12851 6022 12852 6009 12852 6006 12852 6023 12853 6006 12853 6004 12853 6022 12854 6006 12854 6023 12854 6023 12855 6004 12855 6001 12855 6024 12856 6001 12856 5999 12856 6023 12857 6001 12857 6024 12857 6024 12858 5999 12858 5996 12858 6025 12859 5996 12859 5994 12859 6024 12860 5996 12860 6025 12860 6025 12861 5994 12861 5991 12861 6026 12862 5991 12862 5984 12862 6025 12863 5991 12863 6026 12863 6026 12864 5984 12864 5988 12864 5989 12865 6027 12865 5988 12865 6028 12866 5988 12866 6027 12866 6026 12867 5988 12867 6028 12867 6029 12868 6030 12868 6027 12868 6031 12869 6027 12869 6030 12869 5989 12870 6029 12870 6027 12870 6028 12871 6027 12871 6031 12871 6032 12872 6033 12872 6030 12872 6031 12873 6030 12873 6033 12873 6029 12874 6032 12874 6030 12874 6034 12875 6035 12875 6033 12875 6036 12876 6033 12876 6035 12876 6032 12877 6034 12877 6033 12877 6031 12878 6033 12878 6036 12878 6037 12879 6038 12879 6035 12879 6036 12880 6035 12880 6038 12880 6034 12881 6037 12881 6035 12881 6039 12882 6040 12882 6038 12882 6041 12883 6038 12883 6040 12883 6037 12884 6039 12884 6038 12884 6036 12885 6038 12885 6041 12885 6042 12886 6043 12886 6040 12886 6041 12887 6040 12887 6043 12887 6039 12888 6042 12888 6040 12888 6044 12889 6045 12889 6043 12889 6046 12890 6043 12890 6045 12890 6042 12891 6044 12891 6043 12891 6041 12892 6043 12892 6046 12892 6047 12893 6048 12893 6045 12893 6046 12894 6045 12894 6048 12894 6044 12895 6047 12895 6045 12895 6049 12896 6050 12896 6048 12896 6051 12897 6048 12897 6050 12897 6047 12898 6049 12898 6048 12898 6046 12899 6048 12899 6051 12899 6052 12900 6053 12900 6050 12900 6051 12901 6050 12901 6053 12901 6049 12902 6052 12902 6050 12902 6054 12903 6055 12903 6053 12903 6056 12904 6053 12904 6055 12904 6052 12905 6054 12905 6053 12905 6051 12906 6053 12906 6056 12906 6054 12907 6057 12907 6055 12907 6056 12908 6055 12908 6057 12908 6058 12909 6057 12909 6054 12909 6056 12910 6057 12910 6058 12910 6059 12911 6054 12911 6052 12911 6058 12912 6054 12912 6059 12912 6059 12913 6052 12913 6049 12913 6060 12914 6049 12914 6047 12914 6059 12915 6049 12915 6060 12915 6060 12916 6047 12916 6044 12916 6061 12917 6044 12917 6042 12917 6060 12918 6044 12918 6061 12918 6061 12919 6042 12919 6039 12919 6062 12920 6039 12920 6037 12920 6061 12921 6039 12921 6062 12921 6062 12922 6037 12922 6034 12922 6063 12923 6034 12923 6032 12923 6062 12924 6034 12924 6063 12924 6063 12925 6032 12925 6029 12925 5990 12926 6029 12926 5989 12926 6063 12927 6029 12927 5990 12927 6064 12928 6065 12928 6066 12928 6067 12929 6066 12929 6065 12929 6068 12930 6064 12930 6066 12930 6068 12931 6066 12931 6067 12931 6069 12932 6070 12932 6065 12932 6071 12933 6065 12933 6070 12933 6064 12934 6069 12934 6065 12934 6071 12935 6067 12935 6065 12935 6072 12936 6073 12936 6070 12936 6071 12937 6070 12937 6073 12937 6069 12938 6072 12938 6070 12938 6074 12939 6075 12939 6073 12939 6076 12940 6073 12940 6075 12940 6072 12941 6074 12941 6073 12941 6071 12942 6073 12942 6076 12942 6077 12943 6078 12943 6075 12943 6079 12944 6075 12944 6078 12944 6074 12945 6077 12945 6075 12945 6076 12946 6075 12946 6079 12946 6080 12947 6081 12947 6078 12947 6079 12948 6078 12948 6081 12948 6077 12949 6080 12949 6078 12949 6082 12950 6083 12950 6081 12950 6084 12951 6081 12951 6083 12951 6080 12952 6082 12952 6081 12952 6079 12953 6081 12953 6084 12953 6085 12954 6086 12954 6083 12954 6087 12955 6083 12955 6086 12955 6082 12956 6085 12956 6083 12956 6084 12957 6083 12957 6087 12957 6088 12958 6089 12958 6086 12958 6087 12959 6086 12959 6089 12959 6085 12960 6088 12960 6086 12960 6090 12961 6091 12961 6089 12961 6092 12962 6089 12962 6091 12962 6093 12963 6089 12963 6088 12963 6090 12964 6089 12964 6093 12964 6087 12965 6089 12965 6092 12965 6094 12966 6095 12966 6091 12966 6092 12967 6091 12967 6095 12967 6096 12968 6094 12968 6091 12968 6090 12969 6096 12969 6091 12969 6097 12970 6098 12970 6095 12970 6099 12971 6095 12971 6098 12971 6094 12972 6097 12972 6095 12972 6092 12973 6095 12973 6099 12973 6100 12974 6101 12974 6098 12974 6102 12975 6098 12975 6101 12975 6103 12976 6100 12976 6098 12976 6097 12977 6103 12977 6098 12977 6099 12978 6098 12978 6102 12978 6104 12979 6105 12979 6101 12979 6102 12980 6101 12980 6105 12980 6106 12981 6104 12981 6101 12981 6100 12982 6106 12982 6101 12982 6107 12983 6108 12983 6105 12983 6109 12984 6105 12984 6108 12984 6104 12985 6107 12985 6105 12985 6102 12986 6105 12986 6109 12986 6110 12987 6111 12987 6108 12987 6112 12988 6108 12988 6111 12988 6107 12989 6110 12989 6108 12989 6109 12990 6108 12990 6112 12990 6113 12991 6114 12991 6111 12991 6112 12992 6111 12992 6114 12992 6110 12993 6113 12993 6111 12993 6115 12994 6116 12994 6114 12994 6117 12995 6114 12995 6116 12995 6113 12996 6115 12996 6114 12996 6112 12997 6114 12997 6117 12997 6118 12998 6119 12998 6116 12998 6120 12999 6116 12999 6119 12999 6115 13000 6118 13000 6116 13000 6117 13001 6116 13001 6120 13001 6121 13002 6122 13002 6119 13002 6120 13003 6119 13003 6122 13003 6118 13004 6121 13004 6119 13004 6123 13005 6124 13005 6122 13005 6125 13006 6122 13006 6124 13006 6121 13007 6123 13007 6122 13007 6120 13008 6122 13008 6125 13008 6123 13009 6126 13009 6124 13009 6125 13010 6124 13010 6126 13010 6127 13011 6126 13011 6123 13011 6125 13012 6126 13012 6127 13012 6128 13013 6123 13013 6121 13013 6127 13014 6123 13014 6128 13014 6128 13015 6121 13015 6118 13015 6129 13016 6118 13016 6115 13016 6128 13017 6118 13017 6129 13017 6130 13018 6115 13018 6113 13018 6129 13019 6115 13019 6130 13019 6130 13020 6113 13020 6110 13020 6131 13021 6110 13021 6107 13021 6130 13022 6110 13022 6131 13022 6132 13023 6107 13023 6104 13023 6131 13024 6107 13024 6132 13024 6132 13025 6104 13025 6106 13025 6133 13026 6134 13026 6106 13026 6135 13027 6106 13027 6134 13027 6100 13028 6133 13028 6106 13028 6132 13029 6106 13029 6135 13029 6136 13030 6137 13030 6134 13030 6135 13031 6134 13031 6137 13031 6138 13032 6136 13032 6134 13032 6133 13033 6138 13033 6134 13033 6139 13034 6140 13034 6137 13034 6141 13035 6137 13035 6140 13035 6136 13036 6139 13036 6137 13036 6135 13037 6137 13037 6141 13037 6093 13038 6088 13038 6140 13038 6142 13039 6140 13039 6088 13039 6143 13040 6093 13040 6140 13040 6139 13041 6143 13041 6140 13041 6141 13042 6140 13042 6142 13042 6142 13043 6088 13043 6085 13043 6144 13044 6085 13044 6082 13044 6142 13045 6085 13045 6144 13045 6145 13046 6082 13046 6080 13046 6144 13047 6082 13047 6145 13047 6145 13048 6080 13048 6077 13048 6146 13049 6077 13049 6074 13049 6145 13050 6077 13050 6146 13050 6147 13051 6074 13051 6072 13051 6146 13052 6074 13052 6147 13052 6147 13053 6072 13053 6069 13053 6068 13054 6069 13054 6064 13054 6147 13055 6069 13055 6068 13055 6148 13056 6093 13056 6143 13056 6149 13057 6090 13057 6093 13057 6149 13058 6093 13058 6148 13058 6150 13059 6143 13059 6139 13059 6150 13060 6148 13060 6143 13060 6151 13061 6139 13061 6136 13061 6150 13062 6139 13062 6151 13062 6152 13063 6136 13063 6138 13063 6151 13064 6136 13064 6152 13064 6153 13065 6138 13065 6133 13065 6152 13066 6138 13066 6153 13066 6154 13067 6133 13067 6100 13067 6153 13068 6133 13068 6154 13068 6155 13069 6100 13069 6103 13069 6154 13070 6100 13070 6155 13070 6156 13071 6103 13071 6097 13071 6155 13072 6103 13072 6156 13072 6157 13073 6097 13073 6094 13073 6156 13074 6097 13074 6157 13074 6158 13075 6094 13075 6096 13075 6157 13076 6094 13076 6158 13076 6159 13077 6096 13077 6090 13077 6158 13078 6096 13078 6159 13078 6159 13079 6090 13079 6149 13079 6031 13080 6068 13080 6067 13080 6028 13081 6031 13081 6067 13081 6071 13082 6028 13082 6067 13082 6036 13083 6147 13083 6068 13083 6031 13084 6036 13084 6068 13084 6041 13085 6146 13085 6147 13085 6036 13086 6041 13086 6147 13086 6046 13087 6145 13087 6146 13087 6041 13088 6046 13088 6146 13088 6051 13089 6144 13089 6145 13089 6046 13090 6051 13090 6145 13090 6056 13091 6142 13091 6144 13091 6051 13092 6056 13092 6144 13092 6058 13093 6141 13093 6142 13093 6056 13094 6058 13094 6142 13094 6059 13095 6135 13095 6141 13095 6058 13096 6059 13096 6141 13096 6060 13097 6132 13097 6135 13097 6059 13098 6060 13098 6135 13098 6061 13099 6131 13099 6132 13099 6060 13100 6061 13100 6132 13100 6062 13101 6130 13101 6131 13101 6061 13102 6062 13102 6131 13102 6063 13103 6129 13103 6130 13103 6062 13104 6063 13104 6130 13104 5990 13105 6128 13105 6129 13105 6063 13106 5990 13106 6129 13106 5987 13107 6127 13107 6128 13107 5990 13108 5987 13108 6128 13108 5993 13109 6127 13109 5987 13109 5993 13110 6125 13110 6127 13110 6026 13111 6028 13111 6071 13111 5998 13112 6120 13112 6125 13112 5993 13113 5998 13113 6125 13113 6003 13114 6117 13114 6120 13114 5998 13115 6003 13115 6120 13115 6008 13116 6112 13116 6117 13116 6003 13117 6008 13117 6117 13117 6013 13118 6109 13118 6112 13118 6008 13119 6013 13119 6112 13119 6018 13120 6102 13120 6109 13120 6013 13121 6018 13121 6109 13121 6020 13122 6099 13122 6102 13122 6018 13123 6020 13123 6102 13123 6021 13124 6092 13124 6099 13124 6020 13125 6021 13125 6099 13125 6022 13126 6087 13126 6092 13126 6021 13127 6022 13127 6092 13127 6023 13128 6084 13128 6087 13128 6022 13129 6023 13129 6087 13129 6024 13130 6079 13130 6084 13130 6023 13131 6024 13131 6084 13131 6025 13132 6076 13132 6079 13132 6024 13133 6025 13133 6079 13133 6026 13134 6071 13134 6076 13134 6025 13135 6026 13135 6076 13135 6156 13136 6149 13136 6148 13136 6155 13137 6156 13137 6148 13137 6150 13138 6155 13138 6148 13138 6157 13139 6159 13139 6149 13139 6156 13140 6157 13140 6149 13140 6157 13141 6158 13141 6159 13141 6150 13142 6154 13142 6155 13142 6151 13143 6153 13143 6154 13143 6150 13144 6151 13144 6154 13144 6151 13145 6152 13145 6153 13145 6160 13146 6161 13146 6162 13146 6163 13147 6162 13147 6161 13147 6164 13148 6160 13148 6162 13148 6165 13149 6164 13149 6162 13149 6166 13150 6165 13150 6162 13150 6166 13151 6162 13151 6163 13151 6167 13152 6168 13152 6161 13152 6169 13153 6161 13153 6168 13153 6160 13154 6167 13154 6161 13154 6169 13155 6163 13155 6161 13155 6170 13156 6171 13156 6168 13156 6169 13157 6168 13157 6171 13157 6167 13158 6170 13158 6168 13158 6172 13159 6173 13159 6171 13159 6174 13160 6171 13160 6173 13160 6170 13161 6172 13161 6171 13161 6169 13162 6171 13162 6174 13162 6175 13163 6176 13163 6173 13163 6174 13164 6173 13164 6176 13164 6172 13165 6175 13165 6173 13165 6177 13166 6178 13166 6176 13166 6179 13167 6176 13167 6178 13167 6175 13168 6177 13168 6176 13168 6174 13169 6176 13169 6179 13169 6180 13170 6181 13170 6178 13170 6179 13171 6178 13171 6181 13171 6177 13172 6180 13172 6178 13172 6182 13173 6183 13173 6181 13173 6184 13174 6181 13174 6183 13174 6180 13175 6182 13175 6181 13175 6179 13176 6181 13176 6184 13176 6185 13177 6186 13177 6183 13177 6184 13178 6183 13178 6186 13178 6182 13179 6185 13179 6183 13179 6187 13180 6188 13180 6186 13180 6189 13181 6186 13181 6188 13181 6185 13182 6187 13182 6186 13182 6184 13183 6186 13183 6189 13183 6190 13184 6191 13184 6188 13184 6189 13185 6188 13185 6191 13185 6187 13186 6190 13186 6188 13186 6192 13187 6193 13187 6191 13187 6194 13188 6191 13188 6193 13188 6190 13189 6192 13189 6191 13189 6189 13190 6191 13190 6194 13190 6192 13191 6195 13191 6193 13191 6194 13192 6193 13192 6195 13192 6196 13193 6195 13193 6192 13193 6194 13194 6195 13194 6196 13194 6197 13195 6192 13195 6190 13195 6196 13196 6192 13196 6197 13196 6197 13197 6190 13197 6187 13197 6198 13198 6187 13198 6185 13198 6197 13199 6187 13199 6198 13199 6198 13200 6185 13200 6182 13200 6199 13201 6182 13201 6180 13201 6198 13202 6182 13202 6199 13202 6199 13203 6180 13203 6177 13203 6200 13204 6177 13204 6175 13204 6199 13205 6177 13205 6200 13205 6200 13206 6175 13206 6172 13206 6201 13207 6172 13207 6170 13207 6200 13208 6172 13208 6201 13208 6201 13209 6170 13209 6167 13209 6202 13210 6167 13210 6160 13210 6201 13211 6167 13211 6202 13211 6202 13212 6160 13212 6164 13212 6165 13213 6203 13213 6164 13213 6204 13214 6164 13214 6203 13214 6202 13215 6164 13215 6204 13215 6205 13216 6206 13216 6203 13216 6207 13217 6203 13217 6206 13217 6165 13218 6205 13218 6203 13218 6204 13219 6203 13219 6207 13219 6208 13220 6209 13220 6206 13220 6207 13221 6206 13221 6209 13221 6205 13222 6208 13222 6206 13222 6210 13223 6211 13223 6209 13223 6212 13224 6209 13224 6211 13224 6208 13225 6210 13225 6209 13225 6207 13226 6209 13226 6212 13226 6213 13227 6214 13227 6211 13227 6212 13228 6211 13228 6214 13228 6210 13229 6213 13229 6211 13229 6215 13230 6216 13230 6214 13230 6217 13231 6214 13231 6216 13231 6213 13232 6215 13232 6214 13232 6212 13233 6214 13233 6217 13233 6218 13234 6219 13234 6216 13234 6217 13235 6216 13235 6219 13235 6215 13236 6218 13236 6216 13236 6220 13237 6221 13237 6219 13237 6222 13238 6219 13238 6221 13238 6218 13239 6220 13239 6219 13239 6217 13240 6219 13240 6222 13240 6223 13241 6224 13241 6221 13241 6222 13242 6221 13242 6224 13242 6220 13243 6223 13243 6221 13243 6225 13244 6226 13244 6224 13244 6227 13245 6224 13245 6226 13245 6223 13246 6225 13246 6224 13246 6222 13247 6224 13247 6227 13247 6228 13248 6229 13248 6226 13248 6227 13249 6226 13249 6229 13249 6225 13250 6228 13250 6226 13250 6230 13251 6231 13251 6229 13251 6232 13252 6229 13252 6231 13252 6228 13253 6230 13253 6229 13253 6227 13254 6229 13254 6232 13254 6230 13255 6233 13255 6231 13255 6232 13256 6231 13256 6233 13256 6234 13257 6233 13257 6230 13257 6232 13258 6233 13258 6234 13258 6235 13259 6230 13259 6228 13259 6234 13260 6230 13260 6235 13260 6235 13261 6228 13261 6225 13261 6236 13262 6225 13262 6223 13262 6235 13263 6225 13263 6236 13263 6236 13264 6223 13264 6220 13264 6237 13265 6220 13265 6218 13265 6236 13266 6220 13266 6237 13266 6237 13267 6218 13267 6215 13267 6238 13268 6215 13268 6213 13268 6237 13269 6215 13269 6238 13269 6238 13270 6213 13270 6210 13270 6239 13271 6210 13271 6208 13271 6238 13272 6210 13272 6239 13272 6239 13273 6208 13273 6205 13273 6166 13274 6205 13274 6165 13274 6239 13275 6205 13275 6166 13275 6240 13276 6241 13276 6242 13276 6243 13277 6242 13277 6241 13277 6244 13278 6240 13278 6242 13278 6244 13279 6242 13279 6243 13279 6245 13280 6246 13280 6241 13280 6247 13281 6241 13281 6246 13281 6240 13282 6245 13282 6241 13282 6247 13283 6243 13283 6241 13283 6248 13284 6249 13284 6246 13284 6247 13285 6246 13285 6249 13285 6245 13286 6248 13286 6246 13286 6250 13287 6251 13287 6249 13287 6252 13288 6249 13288 6251 13288 6248 13289 6250 13289 6249 13289 6247 13290 6249 13290 6252 13290 6253 13291 6254 13291 6251 13291 6255 13292 6251 13292 6254 13292 6250 13293 6253 13293 6251 13293 6252 13294 6251 13294 6255 13294 6256 13295 6257 13295 6254 13295 6255 13296 6254 13296 6257 13296 6253 13297 6256 13297 6254 13297 6258 13298 6259 13298 6257 13298 6260 13299 6257 13299 6259 13299 6256 13300 6258 13300 6257 13300 6255 13301 6257 13301 6260 13301 6261 13302 6262 13302 6259 13302 6263 13303 6259 13303 6262 13303 6258 13304 6261 13304 6259 13304 6260 13305 6259 13305 6263 13305 6264 13306 6265 13306 6262 13306 6263 13307 6262 13307 6265 13307 6261 13308 6264 13308 6262 13308 6266 13309 6267 13309 6265 13309 6268 13310 6265 13310 6267 13310 6269 13311 6265 13311 6264 13311 6266 13312 6265 13312 6269 13312 6263 13313 6265 13313 6268 13313 6270 13314 6271 13314 6267 13314 6268 13315 6267 13315 6271 13315 6272 13316 6270 13316 6267 13316 6266 13317 6272 13317 6267 13317 6273 13318 6274 13318 6271 13318 6275 13319 6271 13319 6274 13319 6270 13320 6273 13320 6271 13320 6268 13321 6271 13321 6275 13321 6276 13322 6277 13322 6274 13322 6278 13323 6274 13323 6277 13323 6279 13324 6276 13324 6274 13324 6273 13325 6279 13325 6274 13325 6275 13326 6274 13326 6278 13326 6280 13327 6281 13327 6277 13327 6278 13328 6277 13328 6281 13328 6282 13329 6280 13329 6277 13329 6276 13330 6282 13330 6277 13330 6283 13331 6284 13331 6281 13331 6285 13332 6281 13332 6284 13332 6280 13333 6283 13333 6281 13333 6278 13334 6281 13334 6285 13334 6286 13335 6287 13335 6284 13335 6288 13336 6284 13336 6287 13336 6283 13337 6286 13337 6284 13337 6285 13338 6284 13338 6288 13338 6289 13339 6290 13339 6287 13339 6288 13340 6287 13340 6290 13340 6286 13341 6289 13341 6287 13341 6291 13342 6292 13342 6290 13342 6293 13343 6290 13343 6292 13343 6289 13344 6291 13344 6290 13344 6288 13345 6290 13345 6293 13345 6294 13346 6295 13346 6292 13346 6296 13347 6292 13347 6295 13347 6291 13348 6294 13348 6292 13348 6293 13349 6292 13349 6296 13349 6297 13350 6298 13350 6295 13350 6296 13351 6295 13351 6298 13351 6294 13352 6297 13352 6295 13352 6299 13353 6300 13353 6298 13353 6301 13354 6298 13354 6300 13354 6297 13355 6299 13355 6298 13355 6296 13356 6298 13356 6301 13356 6299 13357 6302 13357 6300 13357 6301 13358 6300 13358 6302 13358 6303 13359 6302 13359 6299 13359 6301 13360 6302 13360 6303 13360 6304 13361 6299 13361 6297 13361 6303 13362 6299 13362 6304 13362 6304 13363 6297 13363 6294 13363 6305 13364 6294 13364 6291 13364 6304 13365 6294 13365 6305 13365 6306 13366 6291 13366 6289 13366 6305 13367 6291 13367 6306 13367 6306 13368 6289 13368 6286 13368 6307 13369 6286 13369 6283 13369 6306 13370 6286 13370 6307 13370 6308 13371 6283 13371 6280 13371 6307 13372 6283 13372 6308 13372 6308 13373 6280 13373 6282 13373 6309 13374 6310 13374 6282 13374 6311 13375 6282 13375 6310 13375 6276 13376 6309 13376 6282 13376 6308 13377 6282 13377 6311 13377 6312 13378 6313 13378 6310 13378 6311 13379 6310 13379 6313 13379 6314 13380 6312 13380 6310 13380 6309 13381 6314 13381 6310 13381 6315 13382 6316 13382 6313 13382 6317 13383 6313 13383 6316 13383 6312 13384 6315 13384 6313 13384 6311 13385 6313 13385 6317 13385 6269 13386 6264 13386 6316 13386 6318 13387 6316 13387 6264 13387 6319 13388 6269 13388 6316 13388 6315 13389 6319 13389 6316 13389 6317 13390 6316 13390 6318 13390 6318 13391 6264 13391 6261 13391 6320 13392 6261 13392 6258 13392 6318 13393 6261 13393 6320 13393 6321 13394 6258 13394 6256 13394 6320 13395 6258 13395 6321 13395 6321 13396 6256 13396 6253 13396 6322 13397 6253 13397 6250 13397 6321 13398 6253 13398 6322 13398 6323 13399 6250 13399 6248 13399 6322 13400 6250 13400 6323 13400 6323 13401 6248 13401 6245 13401 6244 13402 6245 13402 6240 13402 6323 13403 6245 13403 6244 13403 6324 13404 6269 13404 6319 13404 6325 13405 6266 13405 6269 13405 6325 13406 6269 13406 6324 13406 6326 13407 6319 13407 6315 13407 6326 13408 6324 13408 6319 13408 6327 13409 6315 13409 6312 13409 6326 13410 6315 13410 6327 13410 6328 13411 6312 13411 6314 13411 6327 13412 6312 13412 6328 13412 6329 13413 6314 13413 6309 13413 6328 13414 6314 13414 6329 13414 6330 13415 6309 13415 6276 13415 6329 13416 6309 13416 6330 13416 6331 13417 6276 13417 6279 13417 6330 13418 6276 13418 6331 13418 6332 13419 6279 13419 6273 13419 6331 13420 6279 13420 6332 13420 6333 13421 6273 13421 6270 13421 6332 13422 6273 13422 6333 13422 6334 13423 6270 13423 6272 13423 6333 13424 6270 13424 6334 13424 6335 13425 6272 13425 6266 13425 6334 13426 6272 13426 6335 13426 6335 13427 6266 13427 6325 13427 6207 13428 6244 13428 6243 13428 6204 13429 6207 13429 6243 13429 6247 13430 6204 13430 6243 13430 6212 13431 6323 13431 6244 13431 6207 13432 6212 13432 6244 13432 6217 13433 6322 13433 6323 13433 6212 13434 6217 13434 6323 13434 6222 13435 6321 13435 6322 13435 6217 13436 6222 13436 6322 13436 6227 13437 6320 13437 6321 13437 6222 13438 6227 13438 6321 13438 6232 13439 6318 13439 6320 13439 6227 13440 6232 13440 6320 13440 6234 13441 6317 13441 6318 13441 6232 13442 6234 13442 6318 13442 6235 13443 6311 13443 6317 13443 6234 13444 6235 13444 6317 13444 6236 13445 6308 13445 6311 13445 6235 13446 6236 13446 6311 13446 6237 13447 6307 13447 6308 13447 6236 13448 6237 13448 6308 13448 6238 13449 6306 13449 6307 13449 6237 13450 6238 13450 6307 13450 6239 13451 6305 13451 6306 13451 6238 13452 6239 13452 6306 13452 6166 13453 6304 13453 6305 13453 6239 13454 6166 13454 6305 13454 6163 13455 6303 13455 6304 13455 6166 13456 6163 13456 6304 13456 6169 13457 6303 13457 6163 13457 6169 13458 6301 13458 6303 13458 6202 13459 6204 13459 6247 13459 6174 13460 6296 13460 6301 13460 6169 13461 6174 13461 6301 13461 6179 13462 6293 13462 6296 13462 6174 13463 6179 13463 6296 13463 6184 13464 6288 13464 6293 13464 6179 13465 6184 13465 6293 13465 6189 13466 6285 13466 6288 13466 6184 13467 6189 13467 6288 13467 6194 13468 6278 13468 6285 13468 6189 13469 6194 13469 6285 13469 6196 13470 6275 13470 6278 13470 6194 13471 6196 13471 6278 13471 6197 13472 6268 13472 6275 13472 6196 13473 6197 13473 6275 13473 6198 13474 6263 13474 6268 13474 6197 13475 6198 13475 6268 13475 6199 13476 6260 13476 6263 13476 6198 13477 6199 13477 6263 13477 6200 13478 6255 13478 6260 13478 6199 13479 6200 13479 6260 13479 6201 13480 6252 13480 6255 13480 6200 13481 6201 13481 6255 13481 6202 13482 6247 13482 6252 13482 6201 13483 6202 13483 6252 13483 6332 13484 6325 13484 6324 13484 6331 13485 6332 13485 6324 13485 6326 13486 6331 13486 6324 13486 6333 13487 6335 13487 6325 13487 6332 13488 6333 13488 6325 13488 6333 13489 6334 13489 6335 13489 6326 13490 6330 13490 6331 13490 6327 13491 6329 13491 6330 13491 6326 13492 6327 13492 6330 13492 6327 13493 6328 13493 6329 13493 6336 13494 6337 13494 6338 13494 6339 13495 6338 13495 6337 13495 6340 13496 6336 13496 6338 13496 6341 13497 6340 13497 6338 13497 6342 13498 6341 13498 6338 13498 6342 13499 6338 13499 6339 13499 6343 13500 6344 13500 6337 13500 6345 13501 6337 13501 6344 13501 6336 13502 6343 13502 6337 13502 6345 13503 6339 13503 6337 13503 6346 13504 6347 13504 6344 13504 6345 13505 6344 13505 6347 13505 6343 13506 6346 13506 6344 13506 6348 13507 6349 13507 6347 13507 6350 13508 6347 13508 6349 13508 6346 13509 6348 13509 6347 13509 6345 13510 6347 13510 6350 13510 6351 13511 6352 13511 6349 13511 6350 13512 6349 13512 6352 13512 6348 13513 6351 13513 6349 13513 6353 13514 6354 13514 6352 13514 6355 13515 6352 13515 6354 13515 6351 13516 6353 13516 6352 13516 6350 13517 6352 13517 6355 13517 6356 13518 6357 13518 6354 13518 6355 13519 6354 13519 6357 13519 6353 13520 6356 13520 6354 13520 6358 13521 6359 13521 6357 13521 6360 13522 6357 13522 6359 13522 6356 13523 6358 13523 6357 13523 6355 13524 6357 13524 6360 13524 6361 13525 6362 13525 6359 13525 6360 13526 6359 13526 6362 13526 6358 13527 6361 13527 6359 13527 6363 13528 6364 13528 6362 13528 6365 13529 6362 13529 6364 13529 6361 13530 6363 13530 6362 13530 6360 13531 6362 13531 6365 13531 6366 13532 6367 13532 6364 13532 6365 13533 6364 13533 6367 13533 6363 13534 6366 13534 6364 13534 6368 13535 6369 13535 6367 13535 6370 13536 6367 13536 6369 13536 6366 13537 6368 13537 6367 13537 6365 13538 6367 13538 6370 13538 6368 13539 6371 13539 6369 13539 6370 13540 6369 13540 6371 13540 6372 13541 6371 13541 6368 13541 6370 13542 6371 13542 6372 13542 6373 13543 6368 13543 6366 13543 6372 13544 6368 13544 6373 13544 6373 13545 6366 13545 6363 13545 6374 13546 6363 13546 6361 13546 6373 13547 6363 13547 6374 13547 6374 13548 6361 13548 6358 13548 6375 13549 6358 13549 6356 13549 6374 13550 6358 13550 6375 13550 6375 13551 6356 13551 6353 13551 6376 13552 6353 13552 6351 13552 6375 13553 6353 13553 6376 13553 6376 13554 6351 13554 6348 13554 6377 13555 6348 13555 6346 13555 6376 13556 6348 13556 6377 13556 6377 13557 6346 13557 6343 13557 6378 13558 6343 13558 6336 13558 6377 13559 6343 13559 6378 13559 6378 13560 6336 13560 6340 13560 6341 13561 6379 13561 6340 13561 6380 13562 6340 13562 6379 13562 6378 13563 6340 13563 6380 13563 6381 13564 6382 13564 6379 13564 6383 13565 6379 13565 6382 13565 6341 13566 6381 13566 6379 13566 6380 13567 6379 13567 6383 13567 6384 13568 6385 13568 6382 13568 6383 13569 6382 13569 6385 13569 6381 13570 6384 13570 6382 13570 6386 13571 6387 13571 6385 13571 6388 13572 6385 13572 6387 13572 6384 13573 6386 13573 6385 13573 6383 13574 6385 13574 6388 13574 6389 13575 6390 13575 6387 13575 6388 13576 6387 13576 6390 13576 6386 13577 6389 13577 6387 13577 6391 13578 6392 13578 6390 13578 6393 13579 6390 13579 6392 13579 6389 13580 6391 13580 6390 13580 6388 13581 6390 13581 6393 13581 6394 13582 6395 13582 6392 13582 6393 13583 6392 13583 6395 13583 6391 13584 6394 13584 6392 13584 6396 13585 6397 13585 6395 13585 6398 13586 6395 13586 6397 13586 6394 13587 6396 13587 6395 13587 6393 13588 6395 13588 6398 13588 6399 13589 6400 13589 6397 13589 6398 13590 6397 13590 6400 13590 6396 13591 6399 13591 6397 13591 6401 13592 6402 13592 6400 13592 6403 13593 6400 13593 6402 13593 6399 13594 6401 13594 6400 13594 6398 13595 6400 13595 6403 13595 6404 13596 6405 13596 6402 13596 6403 13597 6402 13597 6405 13597 6401 13598 6404 13598 6402 13598 6406 13599 6407 13599 6405 13599 6408 13600 6405 13600 6407 13600 6404 13601 6406 13601 6405 13601 6403 13602 6405 13602 6408 13602 6406 13603 6409 13603 6407 13603 6408 13604 6407 13604 6409 13604 6410 13605 6409 13605 6406 13605 6408 13606 6409 13606 6410 13606 6411 13607 6406 13607 6404 13607 6410 13608 6406 13608 6411 13608 6411 13609 6404 13609 6401 13609 6412 13610 6401 13610 6399 13610 6411 13611 6401 13611 6412 13611 6412 13612 6399 13612 6396 13612 6413 13613 6396 13613 6394 13613 6412 13614 6396 13614 6413 13614 6413 13615 6394 13615 6391 13615 6414 13616 6391 13616 6389 13616 6413 13617 6391 13617 6414 13617 6414 13618 6389 13618 6386 13618 6415 13619 6386 13619 6384 13619 6414 13620 6386 13620 6415 13620 6415 13621 6384 13621 6381 13621 6342 13622 6381 13622 6341 13622 6415 13623 6381 13623 6342 13623 6416 13624 6417 13624 6418 13624 6419 13625 6418 13625 6417 13625 6420 13626 6416 13626 6418 13626 6420 13627 6418 13627 6419 13627 6421 13628 6422 13628 6417 13628 6423 13629 6417 13629 6422 13629 6416 13630 6421 13630 6417 13630 6423 13631 6419 13631 6417 13631 6424 13632 6425 13632 6422 13632 6423 13633 6422 13633 6425 13633 6421 13634 6424 13634 6422 13634 6426 13635 6427 13635 6425 13635 6428 13636 6425 13636 6427 13636 6424 13637 6426 13637 6425 13637 6423 13638 6425 13638 6428 13638 6429 13639 6430 13639 6427 13639 6431 13640 6427 13640 6430 13640 6426 13641 6429 13641 6427 13641 6428 13642 6427 13642 6431 13642 6432 13643 6433 13643 6430 13643 6431 13644 6430 13644 6433 13644 6429 13645 6432 13645 6430 13645 6434 13646 6435 13646 6433 13646 6436 13647 6433 13647 6435 13647 6432 13648 6434 13648 6433 13648 6431 13649 6433 13649 6436 13649 6437 13650 6438 13650 6435 13650 6439 13651 6435 13651 6438 13651 6434 13652 6437 13652 6435 13652 6436 13653 6435 13653 6439 13653 6440 13654 6441 13654 6438 13654 6439 13655 6438 13655 6441 13655 6437 13656 6440 13656 6438 13656 6442 13657 6443 13657 6441 13657 6444 13658 6441 13658 6443 13658 6445 13659 6441 13659 6440 13659 6442 13660 6441 13660 6445 13660 6439 13661 6441 13661 6444 13661 6446 13662 6447 13662 6443 13662 6444 13663 6443 13663 6447 13663 6448 13664 6446 13664 6443 13664 6442 13665 6448 13665 6443 13665 6449 13666 6450 13666 6447 13666 6451 13667 6447 13667 6450 13667 6446 13668 6449 13668 6447 13668 6444 13669 6447 13669 6451 13669 6452 13670 6453 13670 6450 13670 6454 13671 6450 13671 6453 13671 6455 13672 6452 13672 6450 13672 6449 13673 6455 13673 6450 13673 6451 13674 6450 13674 6454 13674 6456 13675 6457 13675 6453 13675 6454 13676 6453 13676 6457 13676 6458 13677 6456 13677 6453 13677 6452 13678 6458 13678 6453 13678 6459 13679 6460 13679 6457 13679 6461 13680 6457 13680 6460 13680 6456 13681 6459 13681 6457 13681 6454 13682 6457 13682 6461 13682 6462 13683 6463 13683 6460 13683 6464 13684 6460 13684 6463 13684 6459 13685 6462 13685 6460 13685 6461 13686 6460 13686 6464 13686 6465 13687 6466 13687 6463 13687 6464 13688 6463 13688 6466 13688 6462 13689 6465 13689 6463 13689 6467 13690 6468 13690 6466 13690 6469 13691 6466 13691 6468 13691 6465 13692 6467 13692 6466 13692 6464 13693 6466 13693 6469 13693 6470 13694 6471 13694 6468 13694 6472 13695 6468 13695 6471 13695 6467 13696 6470 13696 6468 13696 6469 13697 6468 13697 6472 13697 6473 13698 6474 13698 6471 13698 6472 13699 6471 13699 6474 13699 6470 13700 6473 13700 6471 13700 6475 13701 6476 13701 6474 13701 6477 13702 6474 13702 6476 13702 6473 13703 6475 13703 6474 13703 6472 13704 6474 13704 6477 13704 6475 13705 6478 13705 6476 13705 6477 13706 6476 13706 6478 13706 6479 13707 6478 13707 6475 13707 6477 13708 6478 13708 6479 13708 6480 13709 6475 13709 6473 13709 6479 13710 6475 13710 6480 13710 6480 13711 6473 13711 6470 13711 6481 13712 6470 13712 6467 13712 6480 13713 6470 13713 6481 13713 6482 13714 6467 13714 6465 13714 6481 13715 6467 13715 6482 13715 6482 13716 6465 13716 6462 13716 6483 13717 6462 13717 6459 13717 6482 13718 6462 13718 6483 13718 6484 13719 6459 13719 6456 13719 6483 13720 6459 13720 6484 13720 6484 13721 6456 13721 6458 13721 6485 13722 6486 13722 6458 13722 6487 13723 6458 13723 6486 13723 6452 13724 6485 13724 6458 13724 6484 13725 6458 13725 6487 13725 6488 13726 6489 13726 6486 13726 6487 13727 6486 13727 6489 13727 6490 13728 6488 13728 6486 13728 6485 13729 6490 13729 6486 13729 6491 13730 6492 13730 6489 13730 6493 13731 6489 13731 6492 13731 6488 13732 6491 13732 6489 13732 6487 13733 6489 13733 6493 13733 6445 13734 6440 13734 6492 13734 6494 13735 6492 13735 6440 13735 6495 13736 6445 13736 6492 13736 6491 13737 6495 13737 6492 13737 6493 13738 6492 13738 6494 13738 6494 13739 6440 13739 6437 13739 6496 13740 6437 13740 6434 13740 6494 13741 6437 13741 6496 13741 6497 13742 6434 13742 6432 13742 6496 13743 6434 13743 6497 13743 6497 13744 6432 13744 6429 13744 6498 13745 6429 13745 6426 13745 6497 13746 6429 13746 6498 13746 6499 13747 6426 13747 6424 13747 6498 13748 6426 13748 6499 13748 6499 13749 6424 13749 6421 13749 6420 13750 6421 13750 6416 13750 6499 13751 6421 13751 6420 13751 6500 13752 6445 13752 6495 13752 6501 13753 6442 13753 6445 13753 6501 13754 6445 13754 6500 13754 6502 13755 6495 13755 6491 13755 6502 13756 6500 13756 6495 13756 6503 13757 6491 13757 6488 13757 6502 13758 6491 13758 6503 13758 6504 13759 6488 13759 6490 13759 6503 13760 6488 13760 6504 13760 6505 13761 6490 13761 6485 13761 6504 13762 6490 13762 6505 13762 6506 13763 6485 13763 6452 13763 6505 13764 6485 13764 6506 13764 6507 13765 6452 13765 6455 13765 6506 13766 6452 13766 6507 13766 6508 13767 6455 13767 6449 13767 6507 13768 6455 13768 6508 13768 6509 13769 6449 13769 6446 13769 6508 13770 6449 13770 6509 13770 6510 13771 6446 13771 6448 13771 6509 13772 6446 13772 6510 13772 6511 13773 6448 13773 6442 13773 6510 13774 6448 13774 6511 13774 6511 13775 6442 13775 6501 13775 6383 13776 6420 13776 6419 13776 6380 13777 6383 13777 6419 13777 6423 13778 6380 13778 6419 13778 6388 13779 6499 13779 6420 13779 6383 13780 6388 13780 6420 13780 6393 13781 6498 13781 6499 13781 6388 13782 6393 13782 6499 13782 6398 13783 6497 13783 6498 13783 6393 13784 6398 13784 6498 13784 6403 13785 6496 13785 6497 13785 6398 13786 6403 13786 6497 13786 6408 13787 6494 13787 6496 13787 6403 13788 6408 13788 6496 13788 6410 13789 6493 13789 6494 13789 6408 13790 6410 13790 6494 13790 6411 13791 6487 13791 6493 13791 6410 13792 6411 13792 6493 13792 6412 13793 6484 13793 6487 13793 6411 13794 6412 13794 6487 13794 6413 13795 6483 13795 6484 13795 6412 13796 6413 13796 6484 13796 6414 13797 6482 13797 6483 13797 6413 13798 6414 13798 6483 13798 6415 13799 6481 13799 6482 13799 6414 13800 6415 13800 6482 13800 6342 13801 6480 13801 6481 13801 6415 13802 6342 13802 6481 13802 6339 13803 6479 13803 6480 13803 6342 13804 6339 13804 6480 13804 6345 13805 6479 13805 6339 13805 6345 13806 6477 13806 6479 13806 6378 13807 6380 13807 6423 13807 6350 13808 6472 13808 6477 13808 6345 13809 6350 13809 6477 13809 6355 13810 6469 13810 6472 13810 6350 13811 6355 13811 6472 13811 6360 13812 6464 13812 6469 13812 6355 13813 6360 13813 6469 13813 6365 13814 6461 13814 6464 13814 6360 13815 6365 13815 6464 13815 6370 13816 6454 13816 6461 13816 6365 13817 6370 13817 6461 13817 6372 13818 6451 13818 6454 13818 6370 13819 6372 13819 6454 13819 6373 13820 6444 13820 6451 13820 6372 13821 6373 13821 6451 13821 6374 13822 6439 13822 6444 13822 6373 13823 6374 13823 6444 13823 6375 13824 6436 13824 6439 13824 6374 13825 6375 13825 6439 13825 6376 13826 6431 13826 6436 13826 6375 13827 6376 13827 6436 13827 6377 13828 6428 13828 6431 13828 6376 13829 6377 13829 6431 13829 6378 13830 6423 13830 6428 13830 6377 13831 6378 13831 6428 13831 6508 13832 6501 13832 6500 13832 6507 13833 6508 13833 6500 13833 6502 13834 6507 13834 6500 13834 6509 13835 6511 13835 6501 13835 6508 13836 6509 13836 6501 13836 6509 13837 6510 13837 6511 13837 6502 13838 6506 13838 6507 13838 6503 13839 6505 13839 6506 13839 6502 13840 6503 13840 6506 13840 6503 13841 6504 13841 6505 13841 6513 13842 6512 13842 6516 13842 6517 13843 6518 13843 6513 13843 6518 13844 6519 13844 6514 13844 6512 13845 6515 13845 6516 13845 6512 13846 6513 13846 6515 13846 6519 13847 6518 13847 6517 13847 6517 25264 6513 25264 6516 25264 6518 25265 6514 25265 6513 25265 6519 25266 6515 25266 6514 25266 6515 25267 6519 25267 6516 25267 6513 25268 6514 25268 6515 25268 6516 25269 6519 25269 6517 25269</p> + </polylist> + <polylist material="mat_marker-material" count="24"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>6521 13848 6520 13848 6525 13848 6525 13849 6526 13849 6522 13849 6526 13850 6527 13850 6523 13850 6520 13851 6523 13851 6527 13851 6520 13852 6521 13852 6522 13852 6527 13853 6526 13853 6525 13853 6529 13854 6528 13854 6533 13854 6533 13855 6534 13855 6529 13855 6534 13856 6535 13856 6531 13856 6528 13857 6531 13857 6532 13857 6528 13858 6529 13858 6531 13858 6535 13859 6534 13859 6533 13859 6520 25270 6524 25270 6525 25270 6521 25271 6525 25271 6522 25271 6522 25272 6526 25272 6523 25272 6524 25273 6520 25273 6527 25273 6523 25274 6520 25274 6522 25274 6524 25275 6527 25275 6525 25275 6528 25276 6532 25276 6533 25276 6534 25277 6530 25277 6529 25277 6530 25278 6534 25278 6531 25278 6531 25279 6535 25279 6532 25279 6529 25280 6530 25280 6531 25280 6532 25281 6535 25281 6533 25281</p> + </polylist> + <polylist material="mat_helix_front-material" count="6304"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>6536 13860 6537 13860 6538 13860 6539 13861 6538 13861 6537 13861 6540 13862 6538 13862 6541 13862 6542 13863 6541 13863 6538 13863 6536 13864 6538 13864 6540 13864 6543 13865 6538 13865 6539 13865 6544 13866 6542 13866 6538 13866 6545 13867 6544 13867 6538 13867 6543 13868 6545 13868 6538 13868 6546 13869 6547 13869 6537 13869 6548 13870 6537 13870 6547 13870 6549 13871 6546 13871 6537 13871 6550 13872 6549 13872 6537 13872 6536 13873 6550 13873 6537 13873 6551 13874 6537 13874 6548 13874 6552 13875 6553 13875 6537 13875 6554 13876 6537 13876 6553 13876 6551 13877 6552 13877 6537 13877 6554 13878 6539 13878 6537 13878 6555 13879 6556 13879 6547 13879 6557 13880 6547 13880 6556 13880 6546 13881 6555 13881 6547 13881 6548 13882 6547 13882 6557 13882 6558 13883 6559 13883 6556 13883 6560 13884 6556 13884 6559 13884 6555 13885 6558 13885 6556 13885 6557 13886 6556 13886 6560 13886 6561 13887 6559 13887 6558 13887 6560 13888 6559 13888 6561 13888 6562 13889 6558 13889 6555 13889 6561 13890 6558 13890 6562 13890 6563 13891 6555 13891 6546 13891 6562 13892 6555 13892 6563 13892 6564 13893 6565 13893 6546 13893 6566 13894 6546 13894 6565 13894 6549 13895 6564 13895 6546 13895 6563 13896 6546 13896 6566 13896 6567 13897 6568 13897 6565 13897 6569 13898 6565 13898 6568 13898 6570 13899 6567 13899 6565 13899 6564 13900 6570 13900 6565 13900 6566 13901 6565 13901 6571 13901 6569 13902 6571 13902 6565 13902 6572 13903 6573 13903 6568 13903 6574 13904 6568 13904 6573 13904 6567 13905 6572 13905 6568 13905 6575 13906 6569 13906 6568 13906 6576 13907 6575 13907 6568 13907 6577 13908 6576 13908 6568 13908 6574 13909 6577 13909 6568 13909 6578 13910 6579 13910 6573 13910 6580 13911 6573 13911 6579 13911 6581 13912 6578 13912 6573 13912 6582 13913 6581 13913 6573 13913 6572 13914 6582 13914 6573 13914 6583 13915 6573 13915 6580 13915 6584 13916 6574 13916 6573 13916 6585 13917 6586 13917 6573 13917 6584 13918 6573 13918 6586 13918 6583 13919 6585 13919 6573 13919 6587 13920 6588 13920 6579 13920 6589 13921 6579 13921 6588 13921 6578 13922 6587 13922 6579 13922 6580 13923 6579 13923 6589 13923 6590 13924 6591 13924 6588 13924 6592 13925 6588 13925 6591 13925 6587 13926 6590 13926 6588 13926 6589 13927 6588 13927 6592 13927 6593 13928 6591 13928 6590 13928 6592 13929 6591 13929 6593 13929 6594 13930 6590 13930 6587 13930 6593 13931 6590 13931 6594 13931 6595 13932 6587 13932 6578 13932 6594 13933 6587 13933 6595 13933 6596 13934 6541 13934 6578 13934 6597 13935 6578 13935 6541 13935 6581 13936 6596 13936 6578 13936 6595 13937 6578 13937 6597 13937 6598 13938 6540 13938 6541 13938 6596 13939 6598 13939 6541 13939 6597 13940 6541 13940 6599 13940 6542 13941 6599 13941 6541 13941 6600 13942 6540 13942 6598 13942 6601 13943 6536 13943 6540 13943 6601 13944 6540 13944 6600 13944 6602 13945 6598 13945 6596 13945 6602 13946 6600 13946 6598 13946 6603 13947 6596 13947 6581 13947 6602 13948 6596 13948 6603 13948 6604 13949 6581 13949 6582 13949 6603 13950 6581 13950 6604 13950 6605 13951 6582 13951 6572 13951 6604 13952 6582 13952 6605 13952 6606 13953 6572 13953 6567 13953 6605 13954 6572 13954 6606 13954 6607 13955 6567 13955 6570 13955 6606 13956 6567 13956 6607 13956 6608 13957 6570 13957 6564 13957 6607 13958 6570 13958 6608 13958 6609 13959 6564 13959 6549 13959 6608 13960 6564 13960 6609 13960 6610 13961 6549 13961 6550 13961 6609 13962 6549 13962 6610 13962 6550 13963 6536 13963 6611 13963 6610 13964 6550 13964 6611 13964 6611 13965 6536 13965 6601 13965 6602 13966 6599 13966 6612 13966 6613 13967 6612 13967 6599 13967 6600 13968 6612 13968 6548 13968 6551 13969 6548 13969 6612 13969 6602 13970 6612 13970 6600 13970 6614 13971 6551 13971 6612 13971 6615 13972 6614 13972 6612 13972 6616 13973 6615 13973 6612 13973 6617 13974 6616 13974 6612 13974 6618 13975 6617 13975 6612 13975 6613 13976 6618 13976 6612 13976 6589 13977 6597 13977 6599 13977 6604 13978 6589 13978 6599 13978 6603 13979 6604 13979 6599 13979 6602 13980 6603 13980 6599 13980 6619 13981 6613 13981 6599 13981 6542 13982 6619 13982 6599 13982 6592 13983 6595 13983 6597 13983 6589 13984 6592 13984 6597 13984 6593 13985 6594 13985 6595 13985 6592 13986 6593 13986 6595 13986 6605 13987 6580 13987 6589 13987 6604 13988 6605 13988 6589 13988 6607 13989 6620 13989 6580 13989 6583 13990 6580 13990 6620 13990 6606 13991 6607 13991 6580 13991 6605 13992 6606 13992 6580 13992 6608 13993 6571 13993 6620 13993 6621 13994 6620 13994 6571 13994 6607 13995 6608 13995 6620 13995 6622 13996 6620 13996 6621 13996 6623 13997 6583 13997 6620 13997 6624 13998 6623 13998 6620 13998 6625 13999 6624 13999 6620 13999 6626 14000 6625 14000 6620 14000 6622 14001 6626 14001 6620 14001 6557 14002 6566 14002 6571 14002 6610 14003 6557 14003 6571 14003 6609 14004 6610 14004 6571 14004 6608 14005 6609 14005 6571 14005 6627 14006 6621 14006 6571 14006 6569 14007 6627 14007 6571 14007 6560 14008 6563 14008 6566 14008 6557 14009 6560 14009 6566 14009 6561 14010 6562 14010 6563 14010 6560 14011 6561 14011 6563 14011 6611 14012 6548 14012 6557 14012 6610 14013 6611 14013 6557 14013 6601 14014 6600 14014 6548 14014 6611 14015 6601 14015 6548 14015 6628 14016 6553 14016 6552 14016 6628 14017 6554 14017 6553 14017 6629 14018 6552 14018 6551 14018 6630 14019 6628 14019 6552 14019 6629 14020 6630 14020 6552 14020 6631 14021 6551 14021 6614 14021 6632 14022 6551 14022 6631 14022 6632 14023 6629 14023 6551 14023 6633 14024 6614 14024 6615 14024 6634 14025 6631 14025 6614 14025 6633 14026 6634 14026 6614 14026 6635 14027 6615 14027 6616 14027 6636 14028 6633 14028 6615 14028 6637 14029 6636 14029 6615 14029 6635 14030 6637 14030 6615 14030 6638 14031 6616 14031 6617 14031 6639 14032 6635 14032 6616 14032 6638 14033 6639 14033 6616 14033 6640 14034 6617 14034 6618 14034 6638 14035 6617 14035 6640 14035 6640 14036 6618 14036 6613 14036 6641 14037 6613 14037 6619 14037 6641 14038 6642 14038 6613 14038 6640 14039 6613 14039 6642 14039 6643 14040 6621 14040 6627 14040 6644 14041 6622 14041 6621 14041 6643 14042 6645 14042 6621 14042 6644 14043 6621 14043 6645 14043 6643 14044 6627 14044 6569 14044 6643 14045 6569 14045 6575 14045 6643 14046 6575 14046 6576 14046 6646 14047 6576 14047 6577 14047 6646 14048 6643 14048 6576 14048 6646 14049 6577 14049 6574 14049 6647 14050 6574 14050 6584 14050 6646 14051 6574 14051 6647 14051 6628 14052 6539 14052 6554 14052 6648 14053 6543 14053 6539 14053 6648 14054 6539 14054 6628 14054 6647 14055 6586 14055 6585 14055 6647 14056 6584 14056 6586 14056 6649 14057 6585 14057 6583 14057 6650 14058 6647 14058 6585 14058 6651 14059 6650 14059 6585 14059 6649 14060 6651 14060 6585 14060 6652 14061 6583 14061 6623 14061 6653 14062 6583 14062 6652 14062 6654 14063 6649 14063 6583 14063 6653 14064 6654 14064 6583 14064 6655 14065 6623 14065 6624 14065 6656 14066 6652 14066 6623 14066 6655 14067 6656 14067 6623 14067 6657 14068 6624 14068 6625 14068 6658 14069 6655 14069 6624 14069 6659 14070 6658 14070 6624 14070 6657 14071 6659 14071 6624 14071 6660 14072 6625 14072 6626 14072 6661 14073 6657 14073 6625 14073 6660 14074 6661 14074 6625 14074 6644 14075 6626 14075 6622 14075 6662 14076 6626 14076 6644 14076 6662 14077 6660 14077 6626 14077 6641 14078 6619 14078 6542 14078 6641 14079 6542 14079 6544 14079 6641 14080 6544 14080 6545 14080 6648 14081 6545 14081 6543 14081 6648 14082 6641 14082 6545 14082 6663 14083 6645 14083 6643 14083 6664 14084 6644 14084 6645 14084 6665 14085 6664 14085 6645 14085 6666 14086 6665 14086 6645 14086 6667 14087 6666 14087 6645 14087 6668 14088 6667 14088 6645 14088 6669 14089 6668 14089 6645 14089 6670 14090 6669 14090 6645 14090 6670 14091 6645 14091 6663 14091 6671 14092 6643 14092 6646 14092 6672 14093 6673 14093 6643 14093 6674 14094 6643 14094 6673 14094 6671 14095 6672 14095 6643 14095 6675 14096 6663 14096 6643 14096 6676 14097 6675 14097 6643 14097 6677 14098 6676 14098 6643 14098 6678 14099 6677 14099 6643 14099 6679 14100 6678 14100 6643 14100 6680 14101 6679 14101 6643 14101 6674 14102 6680 14102 6643 14102 6662 14103 6644 14103 6664 14103 6681 14104 6664 14104 6665 14104 6681 14105 6662 14105 6664 14105 6682 14106 6665 14106 6666 14106 6681 14107 6665 14107 6682 14107 6682 14108 6666 14108 6667 14108 6683 14109 6667 14109 6668 14109 6682 14110 6667 14110 6683 14110 6669 14111 6684 14111 6668 14111 6683 14112 6668 14112 6684 14112 6669 14113 6685 14113 6684 14113 6686 14114 6684 14114 6685 14114 6683 14115 6684 14115 6686 14115 6669 14116 6687 14116 6685 14116 6686 14117 6685 14117 6687 14117 6669 14118 6688 14118 6687 14118 6689 14119 6687 14119 6688 14119 6686 14120 6687 14120 6689 14120 6669 14121 6690 14121 6688 14121 6689 14122 6688 14122 6690 14122 6669 14123 6691 14123 6690 14123 6689 14124 6690 14124 6691 14124 6692 14125 6693 14125 6691 14125 6694 14126 6691 14126 6693 14126 6669 14127 6692 14127 6691 14127 6689 14128 6691 14128 6694 14128 6692 14129 6695 14129 6693 14129 6694 14130 6693 14130 6695 14130 6692 14131 6696 14131 6695 14131 6697 14132 6695 14132 6696 14132 6694 14133 6695 14133 6697 14133 6692 14134 6698 14134 6696 14134 6697 14135 6696 14135 6698 14135 6692 14136 6699 14136 6698 14136 6700 14137 6698 14137 6699 14137 6697 14138 6698 14138 6700 14138 6692 14139 6701 14139 6699 14139 6700 14140 6699 14140 6701 14140 6702 14141 6703 14141 6701 14141 6704 14142 6701 14142 6703 14142 6692 14143 6702 14143 6701 14143 6700 14144 6701 14144 6704 14144 6702 14145 6705 14145 6703 14145 6706 14146 6703 14146 6705 14146 6704 14147 6703 14147 6706 14147 6702 14148 6707 14148 6705 14148 6706 14149 6705 14149 6707 14149 6708 14150 6709 14150 6707 14150 6710 14151 6707 14151 6709 14151 6702 14152 6708 14152 6707 14152 6706 14153 6707 14153 6710 14153 6708 14154 6711 14154 6709 14154 6710 14155 6709 14155 6711 14155 6708 14156 6712 14156 6711 14156 6713 14157 6711 14157 6712 14157 6710 14158 6711 14158 6713 14158 6714 14159 6715 14159 6712 14159 6716 14160 6712 14160 6715 14160 6708 14161 6714 14161 6712 14161 6713 14162 6712 14162 6716 14162 6714 14163 6717 14163 6715 14163 6718 14164 6715 14164 6717 14164 6716 14165 6715 14165 6718 14165 6719 14166 6720 14166 6717 14166 6721 14167 6717 14167 6720 14167 6714 14168 6719 14168 6717 14168 6718 14169 6717 14169 6721 14169 6719 14170 6722 14170 6720 14170 6723 14171 6720 14171 6722 14171 6721 14172 6720 14172 6723 14172 6724 14173 6725 14173 6722 14173 6726 14174 6722 14174 6725 14174 6719 14175 6724 14175 6722 14175 6727 14176 6722 14176 6726 14176 6723 14177 6722 14177 6727 14177 6728 14178 6729 14178 6725 14178 6730 14179 6725 14179 6729 14179 6724 14180 6728 14180 6725 14180 6726 14181 6725 14181 6730 14181 6731 14182 6732 14182 6729 14182 6733 14183 6729 14183 6732 14183 6728 14184 6731 14184 6729 14184 6734 14185 6729 14185 6733 14185 6730 14186 6729 14186 6734 14186 6735 14187 6736 14187 6732 14187 6737 14188 6732 14188 6736 14188 6738 14189 6735 14189 6732 14189 6731 14190 6738 14190 6732 14190 6733 14191 6732 14191 6737 14191 6739 14192 6740 14192 6736 14192 6741 14193 6736 14193 6740 14193 6742 14194 6739 14194 6736 14194 6735 14195 6742 14195 6736 14195 6743 14196 6736 14196 6741 14196 6737 14197 6736 14197 6743 14197 6744 14198 6745 14198 6740 14198 6746 14199 6740 14199 6745 14199 6739 14200 6744 14200 6740 14200 6747 14201 6740 14201 6746 14201 6748 14202 6740 14202 6747 14202 6741 14203 6740 14203 6748 14203 6749 14204 6750 14204 6745 14204 6751 14205 6745 14205 6750 14205 6752 14206 6749 14206 6745 14206 6744 14207 6752 14207 6745 14207 6753 14208 6745 14208 6751 14208 6746 14209 6745 14209 6753 14209 6754 14210 6755 14210 6750 14210 6756 14211 6750 14211 6755 14211 6757 14212 6754 14212 6750 14212 6749 14213 6757 14213 6750 14213 6758 14214 6750 14214 6756 14214 6751 14215 6750 14215 6758 14215 6759 14216 6760 14216 6755 14216 6761 14217 6755 14217 6760 14217 6754 14218 6759 14218 6755 14218 6762 14219 6755 14219 6761 14219 6756 14220 6755 14220 6762 14220 6763 14221 6764 14221 6760 14221 6765 14222 6760 14222 6764 14222 6766 14223 6763 14223 6760 14223 6767 14224 6766 14224 6760 14224 6768 14225 6767 14225 6760 14225 6769 14226 6768 14226 6760 14226 6759 14227 6769 14227 6760 14227 6761 14228 6760 14228 6765 14228 6770 14229 6764 14229 6763 14229 6771 14230 6764 14230 6770 14230 6765 14231 6764 14231 6771 14231 6770 14232 6763 14232 6766 14232 6772 14233 6766 14233 6767 14233 6772 14234 6770 14234 6766 14234 6773 14235 6767 14235 6768 14235 6773 14236 6772 14236 6767 14236 6773 14237 6768 14237 6769 14237 6774 14238 6769 14238 6759 14238 6773 14239 6769 14239 6774 14239 6774 14240 6759 14240 6754 14240 6775 14241 6754 14241 6757 14241 6775 14242 6774 14242 6754 14242 6775 14243 6757 14243 6749 14243 6776 14244 6749 14244 6752 14244 6776 14245 6775 14245 6749 14245 6776 14246 6752 14246 6744 14246 6776 14247 6744 14247 6739 14247 6777 14248 6739 14248 6742 14248 6777 14249 6776 14249 6739 14249 6777 14250 6742 14250 6735 14250 6778 14251 6735 14251 6738 14251 6778 14252 6777 14252 6735 14252 6778 14253 6738 14253 6731 14253 6779 14254 6731 14254 6728 14254 6779 14255 6778 14255 6731 14255 6779 14256 6728 14256 6724 14256 6780 14257 6724 14257 6719 14257 6780 14258 6779 14258 6724 14258 6780 14259 6719 14259 6714 14259 6781 14260 6714 14260 6708 14260 6781 14261 6780 14261 6714 14261 6782 14262 6708 14262 6702 14262 6782 14263 6781 14263 6708 14263 6782 14264 6702 14264 6692 14264 6783 14265 6692 14265 6669 14265 6783 14266 6782 14266 6692 14266 6670 14267 6783 14267 6669 14267 6784 14268 6646 14268 6647 14268 6785 14269 6784 14269 6647 14269 6785 14270 6647 14270 6650 14270 6786 14271 6787 14271 6646 14271 6788 14272 6646 14272 6787 14272 6789 14273 6786 14273 6646 14273 6784 14274 6789 14274 6646 14274 6790 14275 6671 14275 6646 14275 6791 14276 6790 14276 6646 14276 6792 14277 6791 14277 6646 14277 6793 14278 6792 14278 6646 14278 6794 14279 6793 14279 6646 14279 6788 14280 6794 14280 6646 14280 6795 14281 6796 14281 6787 14281 6797 14282 6787 14282 6796 14282 6798 14283 6795 14283 6787 14283 6799 14284 6798 14284 6787 14284 6800 14285 6799 14285 6787 14285 6801 14286 6800 14286 6787 14286 6802 14287 6801 14287 6787 14287 6803 14288 6802 14288 6787 14288 6804 14289 6803 14289 6787 14289 6805 14290 6804 14290 6787 14290 6786 14291 6805 14291 6787 14291 6788 14292 6787 14292 6792 14292 6797 14293 6792 14293 6787 14293 6806 14294 6807 14294 6796 14294 6808 14295 6796 14295 6807 14295 6809 14296 6806 14296 6796 14296 6810 14297 6809 14297 6796 14297 6811 14298 6810 14298 6796 14298 6812 14299 6811 14299 6796 14299 6813 14300 6812 14300 6796 14300 6795 14301 6813 14301 6796 14301 6797 14302 6796 14302 6808 14302 6814 14303 6815 14303 6807 14303 6816 14304 6807 14304 6815 14304 6817 14305 6814 14305 6807 14305 6818 14306 6817 14306 6807 14306 6819 14307 6818 14307 6807 14307 6806 14308 6819 14308 6807 14308 6808 14309 6807 14309 6816 14309 6820 14310 6821 14310 6815 14310 6822 14311 6815 14311 6821 14311 6823 14312 6820 14312 6815 14312 6814 14313 6823 14313 6815 14313 6816 14314 6815 14314 6822 14314 6824 14315 6825 14315 6821 14315 6826 14316 6821 14316 6825 14316 6827 14317 6824 14317 6821 14317 6820 14318 6827 14318 6821 14318 6822 14319 6821 14319 6826 14319 6828 14320 6829 14320 6825 14320 6830 14321 6825 14321 6829 14321 6824 14322 6828 14322 6825 14322 6826 14323 6825 14323 6830 14323 6831 14324 6832 14324 6829 14324 6830 14325 6829 14325 6832 14325 6828 14326 6831 14326 6829 14326 6833 14327 6834 14327 6832 14327 6835 14328 6832 14328 6834 14328 6831 14329 6833 14329 6832 14329 6830 14330 6832 14330 6835 14330 6836 14331 6837 14331 6834 14331 6835 14332 6834 14332 6837 14332 6833 14333 6836 14333 6834 14333 6838 14334 6839 14334 6837 14334 6840 14335 6837 14335 6839 14335 6836 14336 6838 14336 6837 14336 6835 14337 6837 14337 6840 14337 6838 14338 6841 14338 6839 14338 6842 14339 6839 14339 6841 14339 6840 14340 6839 14340 6842 14340 6843 14341 6844 14341 6841 14341 6842 14342 6841 14342 6844 14342 6838 14343 6843 14343 6841 14343 6843 14344 6845 14344 6844 14344 6842 14345 6844 14345 6845 14345 6846 14346 6847 14346 6845 14346 6848 14347 6845 14347 6847 14347 6843 14348 6846 14348 6845 14348 6842 14349 6845 14349 6848 14349 6849 14350 6850 14350 6847 14350 6848 14351 6847 14351 6850 14351 6846 14352 6849 14352 6847 14352 6851 14353 6852 14353 6850 14353 6853 14354 6850 14354 6852 14354 6849 14355 6851 14355 6850 14355 6848 14356 6850 14356 6853 14356 6851 14357 6854 14357 6852 14357 6855 14358 6852 14358 6854 14358 6855 14359 6853 14359 6852 14359 6851 14360 6856 14360 6854 14360 6857 14361 6854 14361 6856 14361 6857 14362 6855 14362 6854 14362 6851 14363 6858 14363 6856 14363 6857 14364 6856 14364 6858 14364 6859 14365 6858 14365 6851 14365 6860 14366 6857 14366 6858 14366 6861 14367 6860 14367 6858 14367 6862 14368 6861 14368 6858 14368 6859 14369 6862 14369 6858 14369 6863 14370 6851 14370 6849 14370 6863 14371 6859 14371 6851 14371 6864 14372 6849 14372 6846 14372 6864 14373 6863 14373 6849 14373 6865 14374 6846 14374 6843 14374 6866 14375 6864 14375 6846 14375 6865 14376 6866 14376 6846 14376 6867 14377 6843 14377 6838 14377 6867 14378 6865 14378 6843 14378 6868 14379 6838 14379 6836 14379 6869 14380 6867 14380 6838 14380 6870 14381 6869 14381 6838 14381 6868 14382 6870 14382 6838 14382 6871 14383 6836 14383 6833 14383 6872 14384 6868 14384 6836 14384 6871 14385 6872 14385 6836 14385 6873 14386 6833 14386 6831 14386 6874 14387 6871 14387 6833 14387 6875 14388 6874 14388 6833 14388 6873 14389 6875 14389 6833 14389 6876 14390 6831 14390 6828 14390 6877 14391 6873 14391 6831 14391 6876 14392 6877 14392 6831 14392 6878 14393 6828 14393 6824 14393 6879 14394 6876 14394 6828 14394 6878 14395 6879 14395 6828 14395 6880 14396 6824 14396 6827 14396 6880 14397 6878 14397 6824 14397 6881 14398 6827 14398 6820 14398 6882 14399 6880 14399 6827 14399 6881 14400 6882 14400 6827 14400 6883 14401 6820 14401 6823 14401 6883 14402 6881 14402 6820 14402 6884 14403 6823 14403 6814 14403 6884 14404 6883 14404 6823 14404 6885 14405 6814 14405 6817 14405 6885 14406 6884 14406 6814 14406 6886 14407 6817 14407 6818 14407 6886 14408 6885 14408 6817 14408 6886 14409 6818 14409 6819 14409 6887 14410 6819 14410 6806 14410 6887 14411 6886 14411 6819 14411 6887 14412 6806 14412 6809 14412 6888 14413 6809 14413 6810 14413 6888 14414 6887 14414 6809 14414 6888 14415 6810 14415 6811 14415 6889 14416 6811 14416 6812 14416 6889 14417 6888 14417 6811 14417 6889 14418 6812 14418 6813 14418 6890 14419 6813 14419 6795 14419 6890 14420 6889 14420 6813 14420 6890 14421 6795 14421 6798 14421 6891 14422 6798 14422 6799 14422 6891 14423 6890 14423 6798 14423 6891 14424 6799 14424 6800 14424 6892 14425 6800 14425 6801 14425 6892 14426 6891 14426 6800 14426 6893 14427 6801 14427 6802 14427 6893 14428 6892 14428 6801 14428 6893 14429 6802 14429 6803 14429 6893 14430 6803 14430 6804 14430 6894 14431 6804 14431 6805 14431 6894 14432 6893 14432 6804 14432 6894 14433 6805 14433 6786 14433 6895 14434 6786 14434 6789 14434 6895 14435 6894 14435 6786 14435 6785 14436 6789 14436 6784 14436 6785 14437 6895 14437 6789 14437 6653 14438 6652 14438 6656 14438 6896 14439 6656 14439 6655 14439 6897 14440 6656 14440 6896 14440 6653 14441 6656 14441 6897 14441 6896 14442 6655 14442 6658 14442 6659 14443 6896 14443 6658 14443 6898 14444 6897 14444 6896 14444 6898 14445 6896 14445 6899 14445 6900 14446 6899 14446 6896 14446 6900 14447 6896 14447 6659 14447 6653 14448 6897 14448 6898 14448 6901 14449 6902 14449 6903 14449 6904 14450 6903 14450 6902 14450 6905 14451 6901 14451 6903 14451 6906 14452 6905 14452 6903 14452 6904 14453 6906 14453 6903 14453 6907 14454 6908 14454 6902 14454 6909 14455 6902 14455 6908 14455 6901 14456 6907 14456 6902 14456 6910 14457 6904 14457 6902 14457 6909 14458 6910 14458 6902 14458 6911 14459 6912 14459 6908 14459 6913 14460 6908 14460 6912 14460 6907 14461 6911 14461 6908 14461 6913 14462 6909 14462 6908 14462 6911 14463 6914 14463 6912 14463 6915 14464 6912 14464 6914 14464 6915 14465 6913 14465 6912 14465 6916 14466 6917 14466 6914 14466 6915 14467 6914 14467 6917 14467 6911 14468 6916 14468 6914 14468 6918 14469 6919 14469 6917 14469 6920 14470 6917 14470 6919 14470 6916 14471 6918 14471 6917 14471 6920 14472 6915 14472 6917 14472 6921 14473 6922 14473 6919 14473 6923 14474 6919 14474 6922 14474 6918 14475 6921 14475 6919 14475 6923 14476 6920 14476 6919 14476 6924 14477 6925 14477 6922 14477 6926 14478 6922 14478 6925 14478 6921 14479 6924 14479 6922 14479 6926 14480 6923 14480 6922 14480 6927 14481 6928 14481 6925 14481 6926 14482 6925 14482 6928 14482 6924 14483 6927 14483 6925 14483 6929 14484 6930 14484 6928 14484 6931 14485 6928 14485 6930 14485 6927 14486 6929 14486 6928 14486 6931 14487 6926 14487 6928 14487 6932 14488 6933 14488 6930 14488 6931 14489 6930 14489 6933 14489 6929 14490 6932 14490 6930 14490 6934 14491 6935 14491 6933 14491 6936 14492 6933 14492 6935 14492 6932 14493 6934 14493 6933 14493 6936 14494 6931 14494 6933 14494 6937 14495 6938 14495 6935 14495 6936 14496 6935 14496 6938 14496 6934 14497 6937 14497 6935 14497 6939 14498 6940 14498 6938 14498 6941 14499 6938 14499 6940 14499 6937 14500 6939 14500 6938 14500 6941 14501 6936 14501 6938 14501 6942 14502 6943 14502 6940 14502 6944 14503 6940 14503 6943 14503 6939 14504 6942 14504 6940 14504 6944 14505 6941 14505 6940 14505 6945 14506 6946 14506 6943 14506 6944 14507 6943 14507 6946 14507 6942 14508 6945 14508 6943 14508 6947 14509 6948 14509 6946 14509 6949 14510 6946 14510 6948 14510 6950 14511 6947 14511 6946 14511 6945 14512 6950 14512 6946 14512 6949 14513 6944 14513 6946 14513 6951 14514 6952 14514 6948 14514 6953 14515 6948 14515 6952 14515 6947 14516 6951 14516 6948 14516 6953 14517 6949 14517 6948 14517 6954 14518 6955 14518 6952 14518 6953 14519 6952 14519 6955 14519 6951 14520 6954 14520 6952 14520 6956 14521 6957 14521 6955 14521 6958 14522 6955 14522 6957 14522 6954 14523 6956 14523 6955 14523 6958 14524 6953 14524 6955 14524 6959 14525 6960 14525 6957 14525 6958 14526 6957 14526 6960 14526 6956 14527 6959 14527 6957 14527 6961 14528 6962 14528 6960 14528 6963 14529 6960 14529 6962 14529 6959 14530 6961 14530 6960 14530 6963 14531 6958 14531 6960 14531 6964 14532 6965 14532 6962 14532 6966 14533 6962 14533 6965 14533 6961 14534 6964 14534 6962 14534 6966 14535 6963 14535 6962 14535 6967 14536 6968 14536 6965 14536 6966 14537 6965 14537 6968 14537 6964 14538 6967 14538 6965 14538 6967 14539 6969 14539 6968 14539 6970 14540 6968 14540 6969 14540 6970 14541 6966 14541 6968 14541 6967 14542 6971 14542 6969 14542 6972 14543 6969 14543 6971 14543 6972 14544 6970 14544 6969 14544 6973 14545 6974 14545 6971 14545 6975 14546 6971 14546 6974 14546 6976 14547 6973 14547 6971 14547 6967 14548 6976 14548 6971 14548 6975 14549 6972 14549 6971 14549 6977 14550 6978 14550 6974 14550 6979 14551 6974 14551 6978 14551 6973 14552 6977 14552 6974 14552 6979 14553 6975 14553 6974 14553 6980 14554 6981 14554 6978 14554 6982 14555 6978 14555 6981 14555 6977 14556 6980 14556 6978 14556 6983 14557 6979 14557 6978 14557 6982 14558 6983 14558 6978 14558 6984 14559 6985 14559 6981 14559 6982 14560 6981 14560 6985 14560 6980 14561 6984 14561 6981 14561 6986 14562 6987 14562 6985 14562 6988 14563 6985 14563 6987 14563 6984 14564 6986 14564 6985 14564 6988 14565 6982 14565 6985 14565 6989 14566 6990 14566 6987 14566 6991 14567 6987 14567 6990 14567 6986 14568 6989 14568 6987 14568 6991 14569 6988 14569 6987 14569 6992 14570 6993 14570 6990 14570 6991 14571 6990 14571 6993 14571 6989 14572 6992 14572 6990 14572 6994 14573 6995 14573 6993 14573 6996 14574 6993 14574 6995 14574 6997 14575 6994 14575 6993 14575 6992 14576 6997 14576 6993 14576 6996 14577 6991 14577 6993 14577 6998 14578 6999 14578 6995 14578 7000 14579 6995 14579 6999 14579 6994 14580 6998 14580 6995 14580 7000 14581 6996 14581 6995 14581 7001 14582 7002 14582 6999 14582 7000 14583 6999 14583 7002 14583 6998 14584 7001 14584 6999 14584 7003 14585 7004 14585 7002 14585 7005 14586 7002 14586 7004 14586 7006 14587 7003 14587 7002 14587 7001 14588 7006 14588 7002 14588 7005 14589 7000 14589 7002 14589 7007 14590 7008 14590 7004 14590 7005 14591 7004 14591 7008 14591 7003 14592 7007 14592 7004 14592 7009 14593 7010 14593 7008 14593 7011 14594 7008 14594 7010 14594 7007 14595 7009 14595 7008 14595 7011 14596 7005 14596 7008 14596 7012 14597 7013 14597 7010 14597 7011 14598 7010 14598 7013 14598 7009 14599 7012 14599 7010 14599 7014 14600 7015 14600 7013 14600 7016 14601 7013 14601 7015 14601 7012 14602 7014 14602 7013 14602 7016 14603 7011 14603 7013 14603 7017 14604 7018 14604 7015 14604 7016 14605 7015 14605 7018 14605 7014 14606 7017 14606 7015 14606 7019 14607 7020 14607 7018 14607 7021 14608 7018 14608 7020 14608 7017 14609 7019 14609 7018 14609 7021 14610 7016 14610 7018 14610 7022 14611 7023 14611 7020 14611 7021 14612 7020 14612 7023 14612 7019 14613 7022 14613 7020 14613 7024 14614 7025 14614 7023 14614 7026 14615 7023 14615 7025 14615 7022 14616 7024 14616 7023 14616 7026 14617 7021 14617 7023 14617 7027 14618 7028 14618 7025 14618 7026 14619 7025 14619 7028 14619 7024 14620 7027 14620 7025 14620 7029 14621 7030 14621 7028 14621 7031 14622 7028 14622 7030 14622 7027 14623 7029 14623 7028 14623 7031 14624 7026 14624 7028 14624 7032 14625 7033 14625 7030 14625 7031 14626 7030 14626 7033 14626 7034 14627 7032 14627 7030 14627 7029 14628 7034 14628 7030 14628 7035 14629 7036 14629 7033 14629 7037 14630 7033 14630 7036 14630 7032 14631 7035 14631 7033 14631 7037 14632 7031 14632 7033 14632 7038 14633 6899 14633 7036 14633 6900 14634 7036 14634 6899 14634 7035 14635 7038 14635 7036 14635 6900 14636 7037 14636 7036 14636 7038 14637 6898 14637 6899 14637 7039 14638 6898 14638 7038 14638 7039 14639 6653 14639 6898 14639 7039 14640 7038 14640 7035 14640 7040 14641 7035 14641 7032 14641 7040 14642 7039 14642 7035 14642 7040 14643 7032 14643 7034 14643 7041 14644 7034 14644 7029 14644 7041 14645 7040 14645 7034 14645 7041 14646 7029 14646 7027 14646 7041 14647 7027 14647 7024 14647 7042 14648 7024 14648 7022 14648 7042 14649 7041 14649 7024 14649 7042 14650 7022 14650 7019 14650 7043 14651 7019 14651 7017 14651 7043 14652 7042 14652 7019 14652 7044 14653 7017 14653 7014 14653 7044 14654 7043 14654 7017 14654 7044 14655 7014 14655 7012 14655 7044 14656 7012 14656 7009 14656 7045 14657 7009 14657 7007 14657 7045 14658 7044 14658 7009 14658 7045 14659 7007 14659 7003 14659 7046 14660 7003 14660 7006 14660 7046 14661 7045 14661 7003 14661 7046 14662 7006 14662 7001 14662 7046 14663 7001 14663 6998 14663 7047 14664 6998 14664 6994 14664 7047 14665 7046 14665 6998 14665 7047 14666 6994 14666 6997 14666 7048 14667 6997 14667 6992 14667 7048 14668 7047 14668 6997 14668 7049 14669 6992 14669 6989 14669 7049 14670 7048 14670 6992 14670 7049 14671 6989 14671 6986 14671 7050 14672 6986 14672 6984 14672 7050 14673 7049 14673 6986 14673 7051 14674 6984 14674 6980 14674 7051 14675 7050 14675 6984 14675 7052 14676 6980 14676 6977 14676 7052 14677 7051 14677 6980 14677 7053 14678 6977 14678 6973 14678 7053 14679 7052 14679 6977 14679 7054 14680 6973 14680 6976 14680 7054 14681 7053 14681 6973 14681 7055 14682 6976 14682 6967 14682 7055 14683 7054 14683 6976 14683 7056 14684 6967 14684 6964 14684 7056 14685 7055 14685 6967 14685 7057 14686 6964 14686 6961 14686 7057 14687 7056 14687 6964 14687 7058 14688 6961 14688 6959 14688 7058 14689 7057 14689 6961 14689 7058 14690 6959 14690 6956 14690 7059 14691 6956 14691 6954 14691 7059 14692 7058 14692 6956 14692 7060 14693 6954 14693 6951 14693 7060 14694 7059 14694 6954 14694 7060 14695 6951 14695 6947 14695 7061 14696 6947 14696 6950 14696 7061 14697 7060 14697 6947 14697 7061 14698 6950 14698 6945 14698 7062 14699 6945 14699 6942 14699 7062 14700 7061 14700 6945 14700 7062 14701 6942 14701 6939 14701 7063 14702 6939 14702 6937 14702 7063 14703 7062 14703 6939 14703 7064 14704 6937 14704 6934 14704 7064 14705 7063 14705 6937 14705 7064 14706 6934 14706 6932 14706 7065 14707 6932 14707 6929 14707 7065 14708 7064 14708 6932 14708 7065 14709 6929 14709 6927 14709 7066 14710 6927 14710 6924 14710 7066 14711 7065 14711 6927 14711 7067 14712 6924 14712 6921 14712 7067 14713 7066 14713 6924 14713 7067 14714 6921 14714 6918 14714 7068 14715 6918 14715 6916 14715 7068 14716 7067 14716 6918 14716 7068 14717 6916 14717 6911 14717 7069 14718 6911 14718 6907 14718 7069 14719 7068 14719 6911 14719 7070 14720 6907 14720 6901 14720 7071 14721 7069 14721 6907 14721 7070 14722 7071 14722 6907 14722 7072 14723 6901 14723 6905 14723 7072 14724 7070 14724 6901 14724 7073 14725 6905 14725 6906 14725 6860 14726 6905 14726 7073 14726 7074 14727 6905 14727 6860 14727 7072 14728 6905 14728 7074 14728 7075 14729 7073 14729 6906 14729 6772 14730 7075 14730 6906 14730 6772 14731 6906 14731 6770 14731 7076 14732 6770 14732 6906 14732 7077 14733 7076 14733 6906 14733 7078 14734 7079 14734 7080 14734 6904 14735 7077 14735 6906 14735 7081 14736 7073 14736 7075 14736 6860 14737 7073 14737 7081 14737 7082 14738 7083 14738 7084 14738 6774 14739 7084 14739 7083 14739 7085 14740 7082 14740 7084 14740 7086 14741 7085 14741 7084 14741 6775 14742 7086 14742 7084 14742 6775 14743 7084 14743 6774 14743 7081 14744 7075 14744 7083 14744 6773 14745 7083 14745 7075 14745 7082 14746 7081 14746 7083 14746 6773 14747 6774 14747 7083 14747 6773 14748 7075 14748 6772 14748 6857 14749 7081 14749 7082 14749 6860 14750 7081 14750 6857 14750 6855 14751 7082 14751 7085 14751 6857 14752 7082 14752 6855 14752 7087 14753 7085 14753 7086 14753 6853 14754 7085 14754 7087 14754 6855 14755 7085 14755 6853 14755 7088 14756 7089 14756 6673 14756 6674 14757 6673 14757 7089 14757 6672 14758 7088 14758 6673 14758 7090 14759 7091 14759 7089 14759 6670 14760 7089 14760 7091 14760 7088 14761 7090 14761 7089 14761 6678 14762 7089 14762 6677 14762 6670 14763 6677 14763 7089 14763 6679 14764 7089 14764 6678 14764 6680 14765 7089 14765 6679 14765 6674 14766 7089 14766 6680 14766 7092 14767 7093 14767 7091 14767 6783 14768 7091 14768 7093 14768 7090 14769 7092 14769 7091 14769 6670 14770 7091 14770 6783 14770 7094 14771 7095 14771 7093 14771 6782 14772 7093 14772 7095 14772 7092 14773 7094 14773 7093 14773 6783 14774 7093 14774 6782 14774 7094 14775 7096 14775 7095 14775 6782 14776 7095 14776 7096 14776 7097 14777 7098 14777 7096 14777 6781 14778 7096 14778 7098 14778 7094 14779 7097 14779 7096 14779 6782 14780 7096 14780 6781 14780 7099 14781 7100 14781 7098 14781 6780 14782 7098 14782 7100 14782 7097 14783 7099 14783 7098 14783 6781 14784 7098 14784 6780 14784 7101 14785 7102 14785 7100 14785 6780 14786 7100 14786 7102 14786 7099 14787 7101 14787 7100 14787 7101 14788 7103 14788 7102 14788 6779 14789 7102 14789 7103 14789 6780 14790 7102 14790 6779 14790 7104 14791 7105 14791 7103 14791 6779 14792 7103 14792 7105 14792 7101 14793 7104 14793 7103 14793 7106 14794 7107 14794 7105 14794 6778 14795 7105 14795 7107 14795 7104 14796 7106 14796 7105 14796 6779 14797 7105 14797 6778 14797 7106 14798 7108 14798 7107 14798 6778 14799 7107 14799 7108 14799 7109 14800 7110 14800 7108 14800 6777 14801 7108 14801 7110 14801 7106 14802 7109 14802 7108 14802 6778 14803 7108 14803 6777 14803 7111 14804 7112 14804 7110 14804 6777 14805 7110 14805 7112 14805 7109 14806 7111 14806 7110 14806 7113 14807 7114 14807 7112 14807 6777 14808 7112 14808 7114 14808 7111 14809 7113 14809 7112 14809 7113 14810 7115 14810 7114 14810 6776 14811 7114 14811 7115 14811 6777 14812 7114 14812 6776 14812 7116 14813 7117 14813 7115 14813 6776 14814 7115 14814 7117 14814 7113 14815 7116 14815 7115 14815 7118 14816 7119 14816 7117 14816 6775 14817 7117 14817 7119 14817 7116 14818 7118 14818 7117 14818 6776 14819 7117 14819 6775 14819 7087 14820 7086 14820 7119 14820 6775 14821 7119 14821 7086 14821 7118 14822 7087 14822 7119 14822 6848 14823 7087 14823 7118 14823 6848 14824 6853 14824 7087 14824 6848 14825 7118 14825 7116 14825 6842 14826 7116 14826 7113 14826 6842 14827 6848 14827 7116 14827 6842 14828 7113 14828 7111 14828 6840 14829 7111 14829 7109 14829 6840 14830 6842 14830 7111 14830 6840 14831 7109 14831 7106 14831 6835 14832 7106 14832 7104 14832 6835 14833 6840 14833 7106 14833 6830 14834 7104 14834 7101 14834 6830 14835 6835 14835 7104 14835 6830 14836 7101 14836 7099 14836 6826 14837 7099 14837 7097 14837 6826 14838 6830 14838 7099 14838 6822 14839 7097 14839 7094 14839 6822 14840 6826 14840 7097 14840 6816 14841 7094 14841 7092 14841 6816 14842 6822 14842 7094 14842 6808 14843 7092 14843 7090 14843 6808 14844 6816 14844 7092 14844 6797 14845 7090 14845 7088 14845 6797 14846 6808 14846 7090 14846 6792 14847 7088 14847 6672 14847 6797 14848 7088 14848 6792 14848 6790 14849 6672 14849 6671 14849 6791 14850 6672 14850 6790 14850 6792 14851 6672 14851 6791 14851 6794 14852 6792 14852 6793 14852 6788 14853 6792 14853 6794 14853 6670 14854 6663 14854 6675 14854 6670 14855 6675 14855 6676 14855 6670 14856 6676 14856 6677 14856 7120 14857 6642 14857 6641 14857 7121 14858 6640 14858 6642 14858 7122 14859 7121 14859 6642 14859 7123 14860 7122 14860 6642 14860 7124 14861 7123 14861 6642 14861 7125 14862 7124 14862 6642 14862 7126 14863 7125 14863 6642 14863 7126 14864 6642 14864 7120 14864 7127 14865 6641 14865 6648 14865 7128 14866 7129 14866 6641 14866 7130 14867 6641 14867 7129 14867 7131 14868 7128 14868 6641 14868 7132 14869 7131 14869 6641 14869 7127 14870 7132 14870 6641 14870 7133 14871 7120 14871 6641 14871 7134 14872 7133 14872 6641 14872 7135 14873 7134 14873 6641 14873 7136 14874 7135 14874 6641 14874 7137 14875 7136 14875 6641 14875 7138 14876 7137 14876 6641 14876 7130 14877 7138 14877 6641 14877 6638 14878 6640 14878 7121 14878 7139 14879 7121 14879 7122 14879 7139 14880 6638 14880 7121 14880 7140 14881 7122 14881 7123 14881 7139 14882 7122 14882 7140 14882 7140 14883 7123 14883 7124 14883 7125 14884 7141 14884 7124 14884 7142 14885 7124 14885 7141 14885 7140 14886 7124 14886 7142 14886 7125 14887 7143 14887 7141 14887 7142 14888 7141 14888 7143 14888 7144 14889 7145 14889 7143 14889 7146 14890 7143 14890 7145 14890 7125 14891 7144 14891 7143 14891 7142 14892 7143 14892 7146 14892 7144 14893 7147 14893 7145 14893 7146 14894 7145 14894 7147 14894 7144 14895 7148 14895 7147 14895 7149 14896 7147 14896 7148 14896 7146 14897 7147 14897 7149 14897 7144 14898 7150 14898 7148 14898 7149 14899 7148 14899 7150 14899 7144 14900 7151 14900 7150 14900 7149 14901 7150 14901 7151 14901 7152 14902 7153 14902 7151 14902 7154 14903 7151 14903 7153 14903 7144 14904 7152 14904 7151 14904 7149 14905 7151 14905 7154 14905 7152 14906 7155 14906 7153 14906 7154 14907 7153 14907 7155 14907 7152 14908 7156 14908 7155 14908 7157 14909 7155 14909 7156 14909 7154 14910 7155 14910 7157 14910 7152 14911 7158 14911 7156 14911 7159 14912 7156 14912 7158 14912 7157 14913 7156 14913 7159 14913 7160 14914 7161 14914 7158 14914 7159 14915 7158 14915 7161 14915 7152 14916 7160 14916 7158 14916 7160 14917 7162 14917 7161 14917 7163 14918 7161 14918 7162 14918 7159 14919 7161 14919 7163 14919 7160 14920 7164 14920 7162 14920 7165 14921 7162 14921 7164 14921 7163 14922 7162 14922 7165 14922 7166 14923 7167 14923 7164 14923 7168 14924 7164 14924 7167 14924 7160 14925 7166 14925 7164 14925 7165 14926 7164 14926 7168 14926 7166 14927 7169 14927 7167 14927 7170 14928 7167 14928 7169 14928 7168 14929 7167 14929 7170 14929 7171 14930 7172 14930 7169 14930 7173 14931 7169 14931 7172 14931 7166 14932 7171 14932 7169 14932 7170 14933 7169 14933 7173 14933 7171 14934 7174 14934 7172 14934 7175 14935 7172 14935 7174 14935 7173 14936 7172 14936 7175 14936 7176 14937 7177 14937 7174 14937 7178 14938 7174 14938 7177 14938 7171 14939 7176 14939 7174 14939 7175 14940 7174 14940 7178 14940 7179 14941 7180 14941 7177 14941 7181 14942 7177 14942 7180 14942 7176 14943 7179 14943 7177 14943 7178 14944 7177 14944 7181 14944 7182 14945 7183 14945 7180 14945 7184 14946 7180 14946 7183 14946 7179 14947 7182 14947 7180 14947 7181 14948 7180 14948 7184 14948 7185 14949 7186 14949 7183 14949 7187 14950 7183 14950 7186 14950 7182 14951 7185 14951 7183 14951 7188 14952 7183 14952 7187 14952 7184 14953 7183 14953 7188 14953 7189 14954 7190 14954 7186 14954 7191 14955 7186 14955 7190 14955 7192 14956 7189 14956 7186 14956 7185 14957 7192 14957 7186 14957 7193 14958 7186 14958 7191 14958 7187 14959 7186 14959 7193 14959 7194 14960 7195 14960 7190 14960 7196 14961 7190 14961 7195 14961 7197 14962 7194 14962 7190 14962 7189 14963 7197 14963 7190 14963 7191 14964 7190 14964 7196 14964 7198 14965 7199 14965 7195 14965 7200 14966 7195 14966 7199 14966 7201 14967 7198 14967 7195 14967 7202 14968 7201 14968 7195 14968 7194 14969 7202 14969 7195 14969 7203 14970 7195 14970 7200 14970 7196 14971 7195 14971 7203 14971 7204 14972 7205 14972 7199 14972 7206 14973 7199 14973 7205 14973 7207 14974 7204 14974 7199 14974 7208 14975 7207 14975 7199 14975 7209 14976 7208 14976 7199 14976 7198 14977 7209 14977 7199 14977 7210 14978 7199 14978 7206 14978 7211 14979 7199 14979 7210 14979 7200 14980 7199 14980 7211 14980 7212 14981 7213 14981 7205 14981 7214 14982 7205 14982 7213 14982 7215 14983 7212 14983 7205 14983 7216 14984 7215 14984 7205 14984 7217 14985 7216 14985 7205 14985 7204 14986 7217 14986 7205 14986 7218 14987 7205 14987 7214 14987 7206 14988 7205 14988 7218 14988 7219 14989 7220 14989 7213 14989 7221 14990 7213 14990 7220 14990 7222 14991 7219 14991 7213 14991 7223 14992 7222 14992 7213 14992 7224 14993 7223 14993 7213 14993 7225 14994 7224 14994 7213 14994 7226 14995 7225 14995 7213 14995 7227 14996 7226 14996 7213 14996 7228 14997 7227 14997 7213 14997 7212 14998 7228 14998 7213 14998 7229 14999 7213 14999 7221 14999 7230 15000 7213 15000 7229 15000 7214 15001 7213 15001 7230 15001 7231 15002 7220 15002 7219 15002 7232 15003 7220 15003 7231 15003 7233 15004 7220 15004 7232 15004 7221 15005 7220 15005 7233 15005 7231 15006 7219 15006 7222 15006 7234 15007 7222 15007 7223 15007 7234 15008 7231 15008 7222 15008 7235 15009 7223 15009 7224 15009 7235 15010 7234 15010 7223 15010 7235 15011 7224 15011 7225 15011 7236 15012 7225 15012 7226 15012 7235 15013 7225 15013 7236 15013 7236 15014 7226 15014 7227 15014 7236 15015 7227 15015 7228 15015 7237 15016 7228 15016 7212 15016 7237 15017 7236 15017 7228 15017 7237 15018 7212 15018 7215 15018 7237 15019 7215 15019 7216 15019 7237 15020 7216 15020 7217 15020 7238 15021 7217 15021 7204 15021 7238 15022 7237 15022 7217 15022 7238 15023 7204 15023 7207 15023 7238 15024 7207 15024 7208 15024 7238 15025 7208 15025 7209 15025 7239 15026 7209 15026 7198 15026 7239 15027 7238 15027 7209 15027 7239 15028 7198 15028 7201 15028 7239 15029 7201 15029 7202 15029 7240 15030 7202 15030 7194 15030 7240 15031 7239 15031 7202 15031 7240 15032 7194 15032 7197 15032 7240 15033 7197 15033 7189 15033 7241 15034 7189 15034 7192 15034 7241 15035 7240 15035 7189 15035 7241 15036 7192 15036 7185 15036 7242 15037 7185 15037 7182 15037 7242 15038 7241 15038 7185 15038 7242 15039 7182 15039 7179 15039 7243 15040 7179 15040 7176 15040 7243 15041 7242 15041 7179 15041 7244 15042 7176 15042 7171 15042 7244 15043 7243 15043 7176 15043 7245 15044 7171 15044 7166 15044 7245 15045 7244 15045 7171 15045 7245 15046 7166 15046 7160 15046 7246 15047 7160 15047 7152 15047 7246 15048 7245 15048 7160 15048 7247 15049 7152 15049 7144 15049 7247 15050 7246 15050 7152 15050 7126 15051 7144 15051 7125 15051 7126 15052 7247 15052 7144 15052 7248 15053 7249 15053 7250 15053 7251 15054 7250 15054 7249 15054 7252 15055 7248 15055 7250 15055 7253 15056 7252 15056 7250 15056 7254 15057 7253 15057 7250 15057 7251 15058 7254 15058 7250 15058 7248 15059 7255 15059 7249 15059 7256 15060 7249 15060 7255 15060 7257 15061 7251 15061 7249 15061 7256 15062 7257 15062 7249 15062 7248 15063 7258 15063 7255 15063 7259 15064 7255 15064 7258 15064 7259 15065 7256 15065 7255 15065 7248 15066 7260 15066 7258 15066 7259 15067 7258 15067 7260 15067 7261 15068 7260 15068 7248 15068 7262 15069 7259 15069 7260 15069 7263 15070 7262 15070 7260 15070 7261 15071 7263 15071 7260 15071 7264 15072 7248 15072 7252 15072 7264 15073 7261 15073 7248 15073 7253 15074 7265 15074 7252 15074 7264 15075 7252 15075 7265 15075 7266 15076 7267 15076 7265 15076 7268 15077 7265 15077 7267 15077 7253 15078 7266 15078 7265 15078 7268 15079 7264 15079 7265 15079 7269 15080 7270 15080 7267 15080 7271 15081 7267 15081 7270 15081 7266 15082 7269 15082 7267 15082 7271 15083 7268 15083 7267 15083 7272 15084 7273 15084 7270 15084 7274 15085 7270 15085 7273 15085 7275 15086 7272 15086 7270 15086 7269 15087 7275 15087 7270 15087 7274 15088 7271 15088 7270 15088 7276 15089 7277 15089 7273 15089 7278 15090 7273 15090 7277 15090 7272 15091 7276 15091 7273 15091 7278 15092 7274 15092 7273 15092 7279 15093 7280 15093 7277 15093 7281 15094 7277 15094 7280 15094 7276 15095 7279 15095 7277 15095 7281 15096 7278 15096 7277 15096 7282 15097 7283 15097 7280 15097 7284 15098 7280 15098 7283 15098 7279 15099 7282 15099 7280 15099 7284 15100 7281 15100 7280 15100 7285 15101 7286 15101 7283 15101 7287 15102 7283 15102 7286 15102 7288 15103 7285 15103 7283 15103 7282 15104 7288 15104 7283 15104 7287 15105 7284 15105 7283 15105 7289 15106 7290 15106 7286 15106 7291 15107 7286 15107 7290 15107 7285 15108 7289 15108 7286 15108 7291 15109 7287 15109 7286 15109 7292 15110 7293 15110 7290 15110 7294 15111 7290 15111 7293 15111 7289 15112 7292 15112 7290 15112 7294 15113 7291 15113 7290 15113 7292 15114 7295 15114 7293 15114 7296 15115 7293 15115 7295 15115 7296 15116 7294 15116 7293 15116 7297 15117 7298 15117 7295 15117 7296 15118 7295 15118 7298 15118 7292 15119 7297 15119 7295 15119 7299 15120 7300 15120 7298 15120 7301 15121 7298 15121 7300 15121 7302 15122 7299 15122 7298 15122 7297 15123 7302 15123 7298 15123 7301 15124 7296 15124 7298 15124 7303 15125 7304 15125 7300 15125 7305 15126 7300 15126 7304 15126 7299 15127 7303 15127 7300 15127 7306 15128 7301 15128 7300 15128 7307 15129 7306 15129 7300 15129 7305 15130 7307 15130 7300 15130 7308 15131 7309 15131 7304 15131 7310 15132 7304 15132 7309 15132 7303 15133 7308 15133 7304 15133 7311 15134 7305 15134 7304 15134 7310 15135 7311 15135 7304 15135 7312 15136 7313 15136 7309 15136 7314 15137 7309 15137 7313 15137 7308 15138 7312 15138 7309 15138 7315 15139 7310 15139 7309 15139 7314 15140 7315 15140 7309 15140 7316 15141 7317 15141 7313 15141 7318 15142 7313 15142 7317 15142 7312 15143 7316 15143 7313 15143 7318 15144 7314 15144 7313 15144 7319 15145 7320 15145 7317 15145 7321 15146 7317 15146 7320 15146 7316 15147 7319 15147 7317 15147 7322 15148 7318 15148 7317 15148 7321 15149 7322 15149 7317 15149 7319 15150 7323 15150 7320 15150 7324 15151 7320 15151 7323 15151 7324 15152 7321 15152 7320 15152 7319 15153 7325 15153 7323 15153 7324 15154 7323 15154 7325 15154 7326 15155 7327 15155 7325 15155 7328 15156 7325 15156 7327 15156 7319 15157 7326 15157 7325 15157 7328 15158 7324 15158 7325 15158 7326 15159 7329 15159 7327 15159 7330 15160 7327 15160 7329 15160 7330 15161 7328 15161 7327 15161 7326 15162 7331 15162 7329 15162 7330 15163 7329 15163 7331 15163 7332 15164 7333 15164 7331 15164 7334 15165 7331 15165 7333 15165 7326 15166 7332 15166 7331 15166 7334 15167 7330 15167 7331 15167 7332 15168 7335 15168 7333 15168 7334 15169 7333 15169 7335 15169 7332 15170 7336 15170 7335 15170 7337 15171 7335 15171 7336 15171 7337 15172 7334 15172 7335 15172 7332 15173 7338 15173 7336 15173 7339 15174 7336 15174 7338 15174 7339 15175 7337 15175 7336 15175 7340 15176 7341 15176 7338 15176 7342 15177 7338 15177 7341 15177 7332 15178 7340 15178 7338 15178 7342 15179 7339 15179 7338 15179 7340 15180 7343 15180 7341 15180 7342 15181 7341 15181 7343 15181 7340 15182 7344 15182 7343 15182 7345 15183 7343 15183 7344 15183 7345 15184 7342 15184 7343 15184 7346 15185 7347 15185 7344 15185 7345 15186 7344 15186 7347 15186 7340 15187 7346 15187 7344 15187 7346 15188 7348 15188 7347 15188 7349 15189 7347 15189 7348 15189 7349 15190 7345 15190 7347 15190 7346 15191 7350 15191 7348 15191 7351 15192 7348 15192 7350 15192 7351 15193 7349 15193 7348 15193 6648 15194 7352 15194 7350 15194 7353 15195 7350 15195 7352 15195 7346 15196 6648 15196 7350 15196 7353 15197 7351 15197 7350 15197 6648 15198 6628 15198 7352 15198 7353 15199 7352 15199 6628 15199 7353 15200 6628 15200 6630 15200 7354 15201 6648 15201 7346 15201 7355 15202 7127 15202 6648 15202 7356 15203 7355 15203 6648 15203 7357 15204 7356 15204 6648 15204 7358 15205 7357 15205 6648 15205 7354 15206 7358 15206 6648 15206 7358 15207 7346 15207 7340 15207 7354 15208 7346 15208 7358 15208 7359 15209 7340 15209 7332 15209 7359 15210 7358 15210 7340 15210 7360 15211 7332 15211 7326 15211 7360 15212 7359 15212 7332 15212 7361 15213 7326 15213 7319 15213 7361 15214 7360 15214 7326 15214 7362 15215 7319 15215 7316 15215 7362 15216 7361 15216 7319 15216 7363 15217 7316 15217 7312 15217 7363 15218 7362 15218 7316 15218 7364 15219 7312 15219 7308 15219 7364 15220 7363 15220 7312 15220 7364 15221 7308 15221 7303 15221 7365 15222 7303 15222 7299 15222 7365 15223 7364 15223 7303 15223 7365 15224 7299 15224 7302 15224 7366 15225 7302 15225 7297 15225 7366 15226 7365 15226 7302 15226 7366 15227 7297 15227 7292 15227 7367 15228 7292 15228 7289 15228 7367 15229 7366 15229 7292 15229 7367 15230 7289 15230 7285 15230 7368 15231 7285 15231 7288 15231 7368 15232 7367 15232 7285 15232 7368 15233 7288 15233 7282 15233 7368 15234 7282 15234 7279 15234 7368 15235 7279 15235 7276 15235 7369 15236 7276 15236 7272 15236 7369 15237 7368 15237 7276 15237 7369 15238 7272 15238 7275 15238 7369 15239 7275 15239 7269 15239 7254 15240 7269 15240 7266 15240 7254 15241 7369 15241 7269 15241 7254 15242 7266 15242 7253 15242 6632 15243 6631 15243 6634 15243 6637 15244 6634 15244 6633 15244 7370 15245 6634 15245 6637 15245 6632 15246 6634 15246 7370 15246 6637 15247 6633 15247 6636 15247 7371 15248 7370 15248 6637 15248 7372 15249 7371 15249 6637 15249 7372 15250 6637 15250 6635 15250 7373 15251 7370 15251 7371 15251 6632 15252 7370 15252 7373 15252 7374 15253 7375 15253 7376 15253 7377 15254 7376 15254 7375 15254 7378 15255 7374 15255 7376 15255 7379 15256 7378 15256 7376 15256 7377 15257 7379 15257 7376 15257 7374 15258 7380 15258 7375 15258 7381 15259 7375 15259 7380 15259 7381 15260 7377 15260 7375 15260 7382 15261 7383 15261 7380 15261 7381 15262 7380 15262 7383 15262 7374 15263 7382 15263 7380 15263 7384 15264 7385 15264 7383 15264 7386 15265 7383 15265 7385 15265 7382 15266 7384 15266 7383 15266 7386 15267 7381 15267 7383 15267 7387 15268 7388 15268 7385 15268 7386 15269 7385 15269 7388 15269 7384 15270 7387 15270 7385 15270 7389 15271 7390 15271 7388 15271 7391 15272 7388 15272 7390 15272 7387 15273 7389 15273 7388 15273 7391 15274 7386 15274 7388 15274 7392 15275 7393 15275 7390 15275 7394 15276 7390 15276 7393 15276 7389 15277 7392 15277 7390 15277 7394 15278 7391 15278 7390 15278 7395 15279 7396 15279 7393 15279 7397 15280 7393 15280 7396 15280 7392 15281 7395 15281 7393 15281 7397 15282 7394 15282 7393 15282 7398 15283 7399 15283 7396 15283 7397 15284 7396 15284 7399 15284 7395 15285 7398 15285 7396 15285 7400 15286 7401 15286 7399 15286 7402 15287 7399 15287 7401 15287 7398 15288 7400 15288 7399 15288 7402 15289 7397 15289 7399 15289 7403 15290 7404 15290 7401 15290 7402 15291 7401 15291 7404 15291 7400 15292 7403 15292 7401 15292 7405 15293 7406 15293 7404 15293 7407 15294 7404 15294 7406 15294 7403 15295 7405 15295 7404 15295 7407 15296 7402 15296 7404 15296 7408 15297 7409 15297 7406 15297 7410 15298 7406 15298 7409 15298 7405 15299 7408 15299 7406 15299 7410 15300 7407 15300 7406 15300 7411 15301 7412 15301 7409 15301 7410 15302 7409 15302 7412 15302 7408 15303 7411 15303 7409 15303 7413 15304 7414 15304 7412 15304 7415 15305 7412 15305 7414 15305 7411 15306 7413 15306 7412 15306 7415 15307 7410 15307 7412 15307 7416 15308 7417 15308 7414 15308 7415 15309 7414 15309 7417 15309 7413 15310 7416 15310 7414 15310 7418 15311 7419 15311 7417 15311 7420 15312 7417 15312 7419 15312 7416 15313 7418 15313 7417 15313 7420 15314 7415 15314 7417 15314 7421 15315 7422 15315 7419 15315 7423 15316 7419 15316 7422 15316 7418 15317 7421 15317 7419 15317 7423 15318 7420 15318 7419 15318 7424 15319 7425 15319 7422 15319 7423 15320 7422 15320 7425 15320 7421 15321 7424 15321 7422 15321 7426 15322 7427 15322 7425 15322 7428 15323 7425 15323 7427 15323 7424 15324 7426 15324 7425 15324 7428 15325 7423 15325 7425 15325 7429 15326 7430 15326 7427 15326 7431 15327 7427 15327 7430 15327 7426 15328 7429 15328 7427 15328 7431 15329 7428 15329 7427 15329 7432 15330 7433 15330 7430 15330 7431 15331 7430 15331 7433 15331 7429 15332 7432 15332 7430 15332 7434 15333 7435 15333 7433 15333 7436 15334 7433 15334 7435 15334 7432 15335 7434 15335 7433 15335 7436 15336 7431 15336 7433 15336 7437 15337 7438 15337 7435 15337 7436 15338 7435 15338 7438 15338 7434 15339 7437 15339 7435 15339 7437 15340 7439 15340 7438 15340 7440 15341 7438 15341 7439 15341 7440 15342 7436 15342 7438 15342 7441 15343 7442 15343 7439 15343 7440 15344 7439 15344 7442 15344 7437 15345 7441 15345 7439 15345 7443 15346 7444 15346 7442 15346 7445 15347 7442 15347 7444 15347 7446 15348 7443 15348 7442 15348 7441 15349 7446 15349 7442 15349 7445 15350 7440 15350 7442 15350 7447 15351 7448 15351 7444 15351 7449 15352 7444 15352 7448 15352 7450 15353 7447 15353 7444 15353 7443 15354 7450 15354 7444 15354 7451 15355 7445 15355 7444 15355 7449 15356 7451 15356 7444 15356 7452 15357 7453 15357 7448 15357 7454 15358 7448 15358 7453 15358 7447 15359 7452 15359 7448 15359 7454 15360 7449 15360 7448 15360 7455 15361 7456 15361 7453 15361 7457 15362 7453 15362 7456 15362 7452 15363 7455 15363 7453 15363 7458 15364 7454 15364 7453 15364 7457 15365 7458 15365 7453 15365 7459 15366 7460 15366 7456 15366 7461 15367 7456 15367 7460 15367 7455 15368 7459 15368 7456 15368 7461 15369 7457 15369 7456 15369 7462 15370 7463 15370 7460 15370 7464 15371 7460 15371 7463 15371 7459 15372 7462 15372 7460 15372 7464 15373 7461 15373 7460 15373 7465 15374 7466 15374 7463 15374 7467 15375 7463 15375 7466 15375 7462 15376 7465 15376 7463 15376 7467 15377 7464 15377 7463 15377 7468 15378 7469 15378 7466 15378 7467 15379 7466 15379 7469 15379 7465 15380 7468 15380 7466 15380 7470 15381 7471 15381 7469 15381 7472 15382 7469 15382 7471 15382 7468 15383 7470 15383 7469 15383 7472 15384 7467 15384 7469 15384 7473 15385 7474 15385 7471 15385 7475 15386 7471 15386 7474 15386 7476 15387 7473 15387 7471 15387 7470 15388 7476 15388 7471 15388 7475 15389 7472 15389 7471 15389 7477 15390 7478 15390 7474 15390 7475 15391 7474 15391 7478 15391 7473 15392 7477 15392 7474 15392 7479 15393 7480 15393 7478 15393 7481 15394 7478 15394 7480 15394 7477 15395 7479 15395 7478 15395 7481 15396 7475 15396 7478 15396 7482 15397 7483 15397 7480 15397 7481 15398 7480 15398 7483 15398 7479 15399 7482 15399 7480 15399 7484 15400 7485 15400 7483 15400 7486 15401 7483 15401 7485 15401 7482 15402 7484 15402 7483 15402 7486 15403 7481 15403 7483 15403 7484 15404 7487 15404 7485 15404 7486 15405 7485 15405 7487 15405 7488 15406 7489 15406 7487 15406 7490 15407 7487 15407 7489 15407 7484 15408 7488 15408 7487 15408 7490 15409 7486 15409 7487 15409 7488 15410 7491 15410 7489 15410 7490 15411 7489 15411 7491 15411 7492 15412 7493 15412 7491 15412 7494 15413 7491 15413 7493 15413 7488 15414 7492 15414 7491 15414 7494 15415 7490 15415 7491 15415 7495 15416 7496 15416 7493 15416 7494 15417 7493 15417 7496 15417 7492 15418 7495 15418 7493 15418 7497 15419 7498 15419 7496 15419 7499 15420 7496 15420 7498 15420 7495 15421 7497 15421 7496 15421 7499 15422 7494 15422 7496 15422 7500 15423 7501 15423 7498 15423 7499 15424 7498 15424 7501 15424 7497 15425 7500 15425 7498 15425 7502 15426 7503 15426 7501 15426 7504 15427 7501 15427 7503 15427 7500 15428 7502 15428 7501 15428 7504 15429 7499 15429 7501 15429 7373 15430 7371 15430 7503 15430 7372 15431 7503 15431 7371 15431 7502 15432 7373 15432 7503 15432 7372 15433 7504 15433 7503 15433 7505 15434 7373 15434 7502 15434 7505 15435 6632 15435 7373 15435 7506 15436 7502 15436 7500 15436 7506 15437 7505 15437 7502 15437 7506 15438 7500 15438 7497 15438 7507 15439 7497 15439 7495 15439 7507 15440 7506 15440 7497 15440 7507 15441 7495 15441 7492 15441 7508 15442 7492 15442 7488 15442 7508 15443 7507 15443 7492 15443 7509 15444 7488 15444 7484 15444 7509 15445 7508 15445 7488 15445 7510 15446 7484 15446 7482 15446 7510 15447 7509 15447 7484 15447 7510 15448 7482 15448 7479 15448 7511 15449 7479 15449 7477 15449 7511 15450 7510 15450 7479 15450 7511 15451 7477 15451 7473 15451 7512 15452 7473 15452 7476 15452 7512 15453 7511 15453 7473 15453 7512 15454 7476 15454 7470 15454 7513 15455 7470 15455 7468 15455 7513 15456 7512 15456 7470 15456 7514 15457 7468 15457 7465 15457 7514 15458 7513 15458 7468 15458 7515 15459 7465 15459 7462 15459 7515 15460 7514 15460 7465 15460 7516 15461 7462 15461 7459 15461 7516 15462 7515 15462 7462 15462 7517 15463 7459 15463 7455 15463 7517 15464 7516 15464 7459 15464 7518 15465 7455 15465 7452 15465 7518 15466 7517 15466 7455 15466 7519 15467 7452 15467 7447 15467 7519 15468 7518 15468 7452 15468 7520 15469 7447 15469 7450 15469 7520 15470 7519 15470 7447 15470 7521 15471 7450 15471 7443 15471 7521 15472 7520 15472 7450 15472 7521 15473 7443 15473 7446 15473 7522 15474 7446 15474 7441 15474 7522 15475 7521 15475 7446 15475 7523 15476 7441 15476 7437 15476 7523 15477 7522 15477 7441 15477 7523 15478 7437 15478 7434 15478 7524 15479 7434 15479 7432 15479 7524 15480 7523 15480 7434 15480 7525 15481 7432 15481 7429 15481 7525 15482 7524 15482 7432 15482 7525 15483 7429 15483 7426 15483 7526 15484 7426 15484 7424 15484 7526 15485 7525 15485 7426 15485 7527 15486 7424 15486 7421 15486 7527 15487 7526 15487 7424 15487 7527 15488 7421 15488 7418 15488 7528 15489 7418 15489 7416 15489 7528 15490 7527 15490 7418 15490 7529 15491 7416 15491 7413 15491 7529 15492 7528 15492 7416 15492 7529 15493 7413 15493 7411 15493 7530 15494 7411 15494 7408 15494 7530 15495 7529 15495 7411 15495 7530 15496 7408 15496 7405 15496 7531 15497 7405 15497 7403 15497 7531 15498 7530 15498 7405 15498 7532 15499 7403 15499 7400 15499 7532 15500 7531 15500 7403 15500 7532 15501 7400 15501 7398 15501 7533 15502 7398 15502 7395 15502 7533 15503 7532 15503 7398 15503 7534 15504 7395 15504 7392 15504 7534 15505 7533 15505 7395 15505 7534 15506 7392 15506 7389 15506 7535 15507 7389 15507 7387 15507 7535 15508 7534 15508 7389 15508 7536 15509 7387 15509 7384 15509 7536 15510 7535 15510 7387 15510 7536 15511 7384 15511 7382 15511 7537 15512 7382 15512 7374 15512 7537 15513 7536 15513 7382 15513 7538 15514 7374 15514 7378 15514 7537 15515 7374 15515 7538 15515 7539 15516 7378 15516 7379 15516 7262 15517 7378 15517 7539 15517 7538 15518 7378 15518 7262 15518 7540 15519 7539 15519 7379 15519 7234 15520 7540 15520 7379 15520 7234 15521 7379 15521 7231 15521 7541 15522 7231 15522 7379 15522 7542 15523 7541 15523 7379 15523 7377 15524 7542 15524 7379 15524 7543 15525 7539 15525 7540 15525 7262 15526 7539 15526 7543 15526 7544 15527 7545 15527 7546 15527 7547 15528 7546 15528 7545 15528 7548 15529 7544 15529 7546 15529 7549 15530 7548 15530 7546 15530 7550 15531 7549 15531 7546 15531 7550 15532 7546 15532 7547 15532 7543 15533 7540 15533 7545 15533 7235 15534 7545 15534 7540 15534 7544 15535 7543 15535 7545 15535 7547 15536 7545 15536 7551 15536 7235 15537 7551 15537 7545 15537 7235 15538 7540 15538 7234 15538 7259 15539 7543 15539 7544 15539 7262 15540 7543 15540 7259 15540 7256 15541 7544 15541 7548 15541 7259 15542 7544 15542 7256 15542 7552 15543 7548 15543 7549 15543 7553 15544 7548 15544 7552 15544 7256 15545 7548 15545 7553 15545 7554 15546 7555 15546 7129 15546 7130 15547 7129 15547 7555 15547 7128 15548 7554 15548 7129 15548 7554 15549 7556 15549 7555 15549 7557 15550 7555 15550 7556 15550 7130 15551 7555 15551 7138 15551 7557 15552 7138 15552 7555 15552 7558 15553 7559 15553 7556 15553 7557 15554 7556 15554 7559 15554 7554 15555 7558 15555 7556 15555 7560 15556 7561 15556 7559 15556 7562 15557 7559 15557 7561 15557 7558 15558 7560 15558 7559 15558 7557 15559 7559 15559 7562 15559 7563 15560 7564 15560 7561 15560 7565 15561 7561 15561 7564 15561 7560 15562 7563 15562 7561 15562 7562 15563 7561 15563 7565 15563 7566 15564 7567 15564 7564 15564 7568 15565 7564 15565 7567 15565 7563 15566 7566 15566 7564 15566 7565 15567 7564 15567 7568 15567 7569 15568 7570 15568 7567 15568 7568 15569 7567 15569 7570 15569 7566 15570 7569 15570 7567 15570 7571 15571 7572 15571 7570 15571 7573 15572 7570 15572 7572 15572 7569 15573 7571 15573 7570 15573 7568 15574 7570 15574 7573 15574 7571 15575 7574 15575 7572 15575 7575 15576 7572 15576 7574 15576 7573 15577 7572 15577 7575 15577 7576 15578 7577 15578 7574 15578 7575 15579 7574 15579 7577 15579 7571 15580 7576 15580 7574 15580 7578 15581 7579 15581 7577 15581 7580 15582 7577 15582 7579 15582 7576 15583 7578 15583 7577 15583 7575 15584 7577 15584 7580 15584 7581 15585 7582 15585 7579 15585 7580 15586 7579 15586 7582 15586 7578 15587 7581 15587 7579 15587 7583 15588 7584 15588 7582 15588 7585 15589 7582 15589 7584 15589 7581 15590 7583 15590 7582 15590 7580 15591 7582 15591 7585 15591 7586 15592 7587 15592 7584 15592 7585 15593 7584 15593 7587 15593 7583 15594 7586 15594 7584 15594 7586 15595 7588 15595 7587 15595 7585 15596 7587 15596 7588 15596 7589 15597 7590 15597 7588 15597 7591 15598 7588 15598 7590 15598 7586 15599 7589 15599 7588 15599 7585 15600 7588 15600 7591 15600 7592 15601 7593 15601 7590 15601 7591 15602 7590 15602 7593 15602 7589 15603 7592 15603 7590 15603 7594 15604 7595 15604 7593 15604 7591 15605 7593 15605 7595 15605 7592 15606 7594 15606 7593 15606 7596 15607 7597 15607 7595 15607 7598 15608 7595 15608 7597 15608 7594 15609 7596 15609 7595 15609 7591 15610 7595 15610 7598 15610 7599 15611 7600 15611 7597 15611 7598 15612 7597 15612 7600 15612 7596 15613 7599 15613 7597 15613 7599 15614 7601 15614 7600 15614 7598 15615 7600 15615 7601 15615 7602 15616 7603 15616 7601 15616 7598 15617 7601 15617 7603 15617 7599 15618 7602 15618 7601 15618 7604 15619 7605 15619 7603 15619 7606 15620 7603 15620 7605 15620 7602 15621 7604 15621 7603 15621 7598 15622 7603 15622 7606 15622 7607 15623 7608 15623 7605 15623 7606 15624 7605 15624 7608 15624 7604 15625 7607 15625 7605 15625 7609 15626 7610 15626 7608 15626 7606 15627 7608 15627 7610 15627 7607 15628 7609 15628 7608 15628 7611 15629 7612 15629 7610 15629 7606 15630 7610 15630 7612 15630 7609 15631 7611 15631 7610 15631 7611 15632 7613 15632 7612 15632 7550 15633 7612 15633 7613 15633 7606 15634 7612 15634 7550 15634 7614 15635 7615 15635 7613 15635 7550 15636 7613 15636 7615 15636 7611 15637 7614 15637 7613 15637 7552 15638 7549 15638 7615 15638 7550 15639 7615 15639 7549 15639 7614 15640 7552 15640 7615 15640 7553 15641 7552 15641 7614 15641 7616 15642 7614 15642 7611 15642 7616 15643 7553 15643 7614 15643 7616 15644 7611 15644 7609 15644 7616 15645 7609 15645 7607 15645 7616 15646 7607 15646 7604 15646 7617 15647 7604 15647 7602 15647 7617 15648 7616 15648 7604 15648 7617 15649 7602 15649 7599 15649 7617 15650 7599 15650 7596 15650 7618 15651 7596 15651 7594 15651 7618 15652 7617 15652 7596 15652 7618 15653 7594 15653 7592 15653 7618 15654 7592 15654 7589 15654 7619 15655 7589 15655 7586 15655 7619 15656 7618 15656 7589 15656 7619 15657 7586 15657 7583 15657 7620 15658 7583 15658 7581 15658 7620 15659 7619 15659 7583 15659 7621 15660 7581 15660 7578 15660 7621 15661 7620 15661 7581 15661 7621 15662 7578 15662 7576 15662 7622 15663 7576 15663 7571 15663 7622 15664 7621 15664 7576 15664 7623 15665 7571 15665 7569 15665 7623 15666 7622 15666 7571 15666 7624 15667 7569 15667 7566 15667 7624 15668 7623 15668 7569 15668 7625 15669 7566 15669 7563 15669 7625 15670 7624 15670 7566 15670 7625 15671 7563 15671 7560 15671 7626 15672 7560 15672 7558 15672 7626 15673 7625 15673 7560 15673 7627 15674 7558 15674 7554 15674 7627 15675 7626 15675 7558 15675 7132 15676 7554 15676 7128 15676 7627 15677 7554 15677 7132 15677 7132 15678 7128 15678 7131 15678 7355 15679 7132 15679 7127 15679 7627 15680 7132 15680 7355 15680 7357 15681 7355 15681 7356 15681 7358 15682 7355 15682 7357 15682 7628 15683 7355 15683 7358 15683 7628 15684 7627 15684 7355 15684 7628 15685 7358 15685 7359 15685 7126 15686 7120 15686 7133 15686 7629 15687 7133 15687 7134 15687 7629 15688 7126 15688 7133 15688 7629 15689 7134 15689 7135 15689 7629 15690 7135 15690 7136 15690 7557 15691 7136 15691 7137 15691 7557 15692 7629 15692 7136 15692 7557 15693 7137 15693 7138 15693 7551 15694 7236 15694 7237 15694 7235 15695 7236 15695 7551 15695 7630 15696 7237 15696 7238 15696 7630 15697 7551 15697 7237 15697 7631 15698 7238 15698 7239 15698 7631 15699 7630 15699 7238 15699 7632 15700 7239 15700 7240 15700 7632 15701 7631 15701 7239 15701 7633 15702 7240 15702 7241 15702 7633 15703 7632 15703 7240 15703 7634 15704 7241 15704 7242 15704 7634 15705 7633 15705 7241 15705 7635 15706 7242 15706 7243 15706 7635 15707 7634 15707 7242 15707 7636 15708 7243 15708 7244 15708 7636 15709 7635 15709 7243 15709 7637 15710 7244 15710 7245 15710 7637 15711 7636 15711 7244 15711 7638 15712 7245 15712 7246 15712 7638 15713 7637 15713 7245 15713 7639 15714 7246 15714 7247 15714 7639 15715 7638 15715 7246 15715 7640 15716 7247 15716 7126 15716 7640 15717 7639 15717 7247 15717 7629 15718 7640 15718 7126 15718 7547 15719 7551 15719 7630 15719 7550 15720 7630 15720 7631 15720 7550 15721 7547 15721 7630 15721 7606 15722 7631 15722 7632 15722 7606 15723 7550 15723 7631 15723 7598 15724 7632 15724 7633 15724 7598 15725 7606 15725 7632 15725 7591 15726 7633 15726 7634 15726 7591 15727 7598 15727 7633 15727 7585 15728 7634 15728 7635 15728 7585 15729 7591 15729 7634 15729 7580 15730 7635 15730 7636 15730 7580 15731 7585 15731 7635 15731 7575 15732 7636 15732 7637 15732 7575 15733 7580 15733 7636 15733 7573 15734 7637 15734 7638 15734 7573 15735 7575 15735 7637 15735 7568 15736 7638 15736 7639 15736 7568 15737 7573 15737 7638 15737 7565 15738 7639 15738 7640 15738 7565 15739 7568 15739 7639 15739 7562 15740 7640 15740 7629 15740 7562 15741 7565 15741 7640 15741 7557 15742 7562 15742 7629 15742 7641 15743 7232 15743 7231 15743 7541 15744 7641 15744 7231 15744 7642 15745 7232 15745 7641 15745 7233 15746 7232 15746 7642 15746 7642 15747 7641 15747 7541 15747 7381 15748 7541 15748 7542 15748 7642 15749 7541 15749 7381 15749 7381 15750 7542 15750 7377 15750 7643 15751 6635 15751 6639 15751 7643 15752 7372 15752 6635 15752 7139 15753 6639 15753 6638 15753 7139 15754 7643 15754 6639 15754 7642 15755 7381 15755 7386 15755 7644 15756 7386 15756 7391 15756 7644 15757 7642 15757 7386 15757 7645 15758 7391 15758 7394 15758 7645 15759 7644 15759 7391 15759 7646 15760 7394 15760 7397 15760 7646 15761 7645 15761 7394 15761 7647 15762 7397 15762 7402 15762 7647 15763 7646 15763 7397 15763 7648 15764 7402 15764 7407 15764 7648 15765 7647 15765 7402 15765 7649 15766 7407 15766 7410 15766 7649 15767 7648 15767 7407 15767 7650 15768 7410 15768 7415 15768 7650 15769 7649 15769 7410 15769 7651 15770 7415 15770 7420 15770 7651 15771 7650 15771 7415 15771 7652 15772 7420 15772 7423 15772 7652 15773 7651 15773 7420 15773 7653 15774 7423 15774 7428 15774 7653 15775 7652 15775 7423 15775 7654 15776 7428 15776 7431 15776 7654 15777 7653 15777 7428 15777 7655 15778 7431 15778 7436 15778 7655 15779 7654 15779 7431 15779 7656 15780 7436 15780 7440 15780 7656 15781 7655 15781 7436 15781 7657 15782 7440 15782 7445 15782 7657 15783 7656 15783 7440 15783 7658 15784 7445 15784 7451 15784 7658 15785 7657 15785 7445 15785 7659 15786 7451 15786 7449 15786 7659 15787 7658 15787 7451 15787 7660 15788 7449 15788 7454 15788 7660 15789 7659 15789 7449 15789 7661 15790 7454 15790 7458 15790 7661 15791 7660 15791 7454 15791 7662 15792 7458 15792 7457 15792 7662 15793 7661 15793 7458 15793 7663 15794 7457 15794 7461 15794 7663 15795 7662 15795 7457 15795 7664 15796 7461 15796 7464 15796 7664 15797 7663 15797 7461 15797 7665 15798 7464 15798 7467 15798 7665 15799 7664 15799 7464 15799 7666 15800 7467 15800 7472 15800 7666 15801 7665 15801 7467 15801 7667 15802 7472 15802 7475 15802 7667 15803 7666 15803 7472 15803 7668 15804 7475 15804 7481 15804 7668 15805 7667 15805 7475 15805 7669 15806 7481 15806 7486 15806 7669 15807 7668 15807 7481 15807 7670 15808 7486 15808 7490 15808 7670 15809 7669 15809 7486 15809 7671 15810 7490 15810 7494 15810 7671 15811 7670 15811 7490 15811 7672 15812 7494 15812 7499 15812 7672 15813 7671 15813 7494 15813 7673 15814 7499 15814 7504 15814 7673 15815 7672 15815 7499 15815 7674 15816 7504 15816 7372 15816 7674 15817 7673 15817 7504 15817 7643 15818 7674 15818 7372 15818 7233 15819 7642 15819 7644 15819 7221 15820 7644 15820 7645 15820 7221 15821 7233 15821 7644 15821 7229 15822 7645 15822 7646 15822 7229 15823 7221 15823 7645 15823 7230 15824 7646 15824 7647 15824 7230 15825 7229 15825 7646 15825 7214 15826 7647 15826 7648 15826 7214 15827 7230 15827 7647 15827 7218 15828 7648 15828 7649 15828 7218 15829 7214 15829 7648 15829 7206 15830 7649 15830 7650 15830 7206 15831 7218 15831 7649 15831 7210 15832 7650 15832 7651 15832 7210 15833 7206 15833 7650 15833 7211 15834 7651 15834 7652 15834 7211 15835 7210 15835 7651 15835 7200 15836 7652 15836 7653 15836 7200 15837 7211 15837 7652 15837 7203 15838 7653 15838 7654 15838 7203 15839 7200 15839 7653 15839 7196 15840 7654 15840 7655 15840 7196 15841 7203 15841 7654 15841 7191 15842 7655 15842 7656 15842 7191 15843 7196 15843 7655 15843 7193 15844 7656 15844 7657 15844 7193 15845 7191 15845 7656 15845 7187 15846 7657 15846 7658 15846 7187 15847 7193 15847 7657 15847 7188 15848 7658 15848 7659 15848 7188 15849 7187 15849 7658 15849 7184 15850 7659 15850 7660 15850 7184 15851 7188 15851 7659 15851 7181 15852 7660 15852 7661 15852 7181 15853 7184 15853 7660 15853 7178 15854 7661 15854 7662 15854 7178 15855 7181 15855 7661 15855 7175 15856 7662 15856 7663 15856 7175 15857 7178 15857 7662 15857 7173 15858 7663 15858 7664 15858 7173 15859 7175 15859 7663 15859 7170 15860 7664 15860 7665 15860 7170 15861 7173 15861 7664 15861 7168 15862 7665 15862 7666 15862 7168 15863 7170 15863 7665 15863 7165 15864 7666 15864 7667 15864 7165 15865 7168 15865 7666 15865 7163 15866 7667 15866 7668 15866 7163 15867 7165 15867 7667 15867 7159 15868 7668 15868 7669 15868 7159 15869 7163 15869 7668 15869 7157 15870 7669 15870 7670 15870 7157 15871 7159 15871 7669 15871 7154 15872 7670 15872 7671 15872 7154 15873 7157 15873 7670 15873 7149 15874 7671 15874 7672 15874 7149 15875 7154 15875 7671 15875 7146 15876 7672 15876 7673 15876 7146 15877 7149 15877 7672 15877 7142 15878 7673 15878 7674 15878 7142 15879 7146 15879 7673 15879 7140 15880 7674 15880 7643 15880 7140 15881 7142 15881 7674 15881 7139 15882 7140 15882 7643 15882 7257 15883 7553 15883 7616 15883 7256 15884 7553 15884 7257 15884 7675 15885 7616 15885 7617 15885 7676 15886 7257 15886 7616 15886 7676 15887 7616 15887 7675 15887 7677 15888 7617 15888 7618 15888 7675 15889 7617 15889 7677 15889 7678 15890 7618 15890 7619 15890 7677 15891 7618 15891 7678 15891 7679 15892 7619 15892 7620 15892 7678 15893 7619 15893 7679 15893 7680 15894 7620 15894 7621 15894 7679 15895 7620 15895 7680 15895 7681 15896 7621 15896 7622 15896 7680 15897 7621 15897 7681 15897 7682 15898 7622 15898 7623 15898 7681 15899 7622 15899 7682 15899 7683 15900 7623 15900 7624 15900 7682 15901 7623 15901 7683 15901 7684 15902 7624 15902 7625 15902 7683 15903 7624 15903 7684 15903 7685 15904 7625 15904 7626 15904 7684 15905 7625 15905 7685 15905 7628 15906 7626 15906 7627 15906 7685 15907 7626 15907 7628 15907 7685 15908 7359 15908 7360 15908 7685 15909 7628 15909 7359 15909 7684 15910 7360 15910 7361 15910 7684 15911 7685 15911 7360 15911 7683 15912 7361 15912 7362 15912 7683 15913 7684 15913 7361 15913 7682 15914 7362 15914 7363 15914 7682 15915 7683 15915 7362 15915 7681 15916 7363 15916 7364 15916 7681 15917 7682 15917 7363 15917 7680 15918 7364 15918 7365 15918 7680 15919 7681 15919 7364 15919 7679 15920 7365 15920 7366 15920 7679 15921 7680 15921 7365 15921 7678 15922 7366 15922 7367 15922 7678 15923 7679 15923 7366 15923 7677 15924 7367 15924 7368 15924 7677 15925 7678 15925 7367 15925 7675 15926 7368 15926 7369 15926 7675 15927 7677 15927 7368 15927 7676 15928 7369 15928 7254 15928 7676 15929 7675 15929 7369 15929 7676 15930 7254 15930 7251 15930 7676 15931 7251 15931 7257 15931 7686 15932 7538 15932 7262 15932 7687 15933 7686 15933 7262 15933 7263 15934 7687 15934 7262 15934 7687 15935 7538 15935 7686 15935 7537 15936 7538 15936 7687 15936 7261 15937 7687 15937 7263 15937 7688 15938 7687 15938 7261 15938 7688 15939 7537 15939 7687 15939 7688 15940 7261 15940 7264 15940 7689 15941 6630 15941 6629 15941 7689 15942 7353 15942 6630 15942 7505 15943 6629 15943 6632 15943 7689 15944 6629 15944 7505 15944 7690 15945 7264 15945 7268 15945 7688 15946 7264 15946 7690 15946 7691 15947 7268 15947 7271 15947 7690 15948 7268 15948 7691 15948 7692 15949 7271 15949 7274 15949 7691 15950 7271 15950 7692 15950 7693 15951 7274 15951 7278 15951 7692 15952 7274 15952 7693 15952 7694 15953 7278 15953 7281 15953 7693 15954 7278 15954 7694 15954 7695 15955 7281 15955 7284 15955 7694 15956 7281 15956 7695 15956 7696 15957 7284 15957 7287 15957 7695 15958 7284 15958 7696 15958 7697 15959 7287 15959 7291 15959 7696 15960 7287 15960 7697 15960 7698 15961 7291 15961 7294 15961 7697 15962 7291 15962 7698 15962 7699 15963 7294 15963 7296 15963 7698 15964 7294 15964 7699 15964 7700 15965 7296 15965 7301 15965 7699 15966 7296 15966 7700 15966 7701 15967 7301 15967 7306 15967 7700 15968 7301 15968 7701 15968 7702 15969 7306 15969 7307 15969 7701 15970 7306 15970 7702 15970 7703 15971 7307 15971 7305 15971 7702 15972 7307 15972 7703 15972 7704 15973 7305 15973 7311 15973 7703 15974 7305 15974 7704 15974 7705 15975 7311 15975 7310 15975 7704 15976 7311 15976 7705 15976 7706 15977 7310 15977 7315 15977 7705 15978 7310 15978 7706 15978 7707 15979 7315 15979 7314 15979 7706 15980 7315 15980 7707 15980 7708 15981 7314 15981 7318 15981 7707 15982 7314 15982 7708 15982 7709 15983 7318 15983 7322 15983 7708 15984 7318 15984 7709 15984 7710 15985 7322 15985 7321 15985 7709 15986 7322 15986 7710 15986 7711 15987 7321 15987 7324 15987 7710 15988 7321 15988 7711 15988 7712 15989 7324 15989 7328 15989 7711 15990 7324 15990 7712 15990 7713 15991 7328 15991 7330 15991 7712 15992 7328 15992 7713 15992 7714 15993 7330 15993 7334 15993 7713 15994 7330 15994 7714 15994 7715 15995 7334 15995 7337 15995 7714 15996 7334 15996 7715 15996 7716 15997 7337 15997 7339 15997 7715 15998 7337 15998 7716 15998 7717 15999 7339 15999 7342 15999 7716 16000 7339 16000 7717 16000 7718 16001 7342 16001 7345 16001 7717 16002 7342 16002 7718 16002 7719 16003 7345 16003 7349 16003 7718 16004 7345 16004 7719 16004 7720 16005 7349 16005 7351 16005 7719 16006 7349 16006 7720 16006 7689 16007 7351 16007 7353 16007 7720 16008 7351 16008 7689 16008 7720 16009 7505 16009 7506 16009 7720 16010 7689 16010 7505 16010 7719 16011 7506 16011 7507 16011 7719 16012 7720 16012 7506 16012 7718 16013 7507 16013 7508 16013 7718 16014 7719 16014 7507 16014 7717 16015 7508 16015 7509 16015 7717 16016 7718 16016 7508 16016 7716 16017 7509 16017 7510 16017 7716 16018 7717 16018 7509 16018 7715 16019 7510 16019 7511 16019 7715 16020 7716 16020 7510 16020 7714 16021 7511 16021 7512 16021 7714 16022 7715 16022 7511 16022 7713 16023 7512 16023 7513 16023 7713 16024 7714 16024 7512 16024 7712 16025 7513 16025 7514 16025 7712 16026 7713 16026 7513 16026 7711 16027 7514 16027 7515 16027 7711 16028 7712 16028 7514 16028 7710 16029 7515 16029 7516 16029 7710 16030 7711 16030 7515 16030 7709 16031 7516 16031 7517 16031 7709 16032 7710 16032 7516 16032 7708 16033 7517 16033 7518 16033 7708 16034 7709 16034 7517 16034 7707 16035 7518 16035 7519 16035 7707 16036 7708 16036 7518 16036 7706 16037 7519 16037 7520 16037 7706 16038 7707 16038 7519 16038 7705 16039 7520 16039 7521 16039 7705 16040 7706 16040 7520 16040 7704 16041 7521 16041 7522 16041 7704 16042 7705 16042 7521 16042 7703 16043 7522 16043 7523 16043 7703 16044 7704 16044 7522 16044 7702 16045 7523 16045 7524 16045 7702 16046 7703 16046 7523 16046 7701 16047 7524 16047 7525 16047 7701 16048 7702 16048 7524 16048 7700 16049 7525 16049 7526 16049 7700 16050 7701 16050 7525 16050 7699 16051 7526 16051 7527 16051 7699 16052 7700 16052 7526 16052 7698 16053 7527 16053 7528 16053 7698 16054 7699 16054 7527 16054 7697 16055 7528 16055 7529 16055 7697 16056 7698 16056 7528 16056 7696 16057 7529 16057 7530 16057 7696 16058 7697 16058 7529 16058 7695 16059 7530 16059 7531 16059 7695 16060 7696 16060 7530 16060 7694 16061 7531 16061 7532 16061 7694 16062 7695 16062 7531 16062 7693 16063 7532 16063 7533 16063 7693 16064 7694 16064 7532 16064 7692 16065 7533 16065 7534 16065 7692 16066 7693 16066 7533 16066 7691 16067 7534 16067 7535 16067 7691 16068 7692 16068 7534 16068 7690 16069 7535 16069 7536 16069 7690 16070 7691 16070 7535 16070 7688 16071 7536 16071 7537 16071 7688 16072 7690 16072 7536 16072 7721 16073 6771 16073 6770 16073 7722 16074 7721 16074 6770 16074 7076 16075 7722 16075 6770 16075 7723 16076 6771 16076 7721 16076 6765 16077 6771 16077 7723 16077 7724 16078 7721 16078 7722 16078 7723 16079 7721 16079 7724 16079 7724 16080 7722 16080 7076 16080 7725 16081 7076 16081 7077 16081 7724 16082 7076 16082 7725 16082 7078 16083 7726 16083 7079 16083 7725 16084 7077 16084 6910 16084 6910 16085 7077 16085 6904 16085 7727 16086 6659 16086 6657 16086 7727 16087 6900 16087 6659 16087 7728 16088 6657 16088 6661 16088 7728 16089 7727 16089 6657 16089 7729 16090 6661 16090 6660 16090 7729 16091 7728 16091 6661 16091 6681 16092 6660 16092 6662 16092 6681 16093 7729 16093 6660 16093 7725 16094 6910 16094 6909 16094 7730 16095 6909 16095 6913 16095 7730 16096 7725 16096 6909 16096 7731 16097 6913 16097 6915 16097 7731 16098 7730 16098 6913 16098 7732 16099 6915 16099 6920 16099 7732 16100 7731 16100 6915 16100 7733 16101 6920 16101 6923 16101 7733 16102 7732 16102 6920 16102 7734 16103 6923 16103 6926 16103 7734 16104 7733 16104 6923 16104 7735 16105 6926 16105 6931 16105 7735 16106 7734 16106 6926 16106 7736 16107 6931 16107 6936 16107 7736 16108 7735 16108 6931 16108 7737 16109 6936 16109 6941 16109 7737 16110 7736 16110 6936 16110 7738 16111 6941 16111 6944 16111 7738 16112 7737 16112 6941 16112 7739 16113 6944 16113 6949 16113 7739 16114 7738 16114 6944 16114 7740 16115 6949 16115 6953 16115 7740 16116 7739 16116 6949 16116 7741 16117 6953 16117 6958 16117 7741 16118 7740 16118 6953 16118 7742 16119 6958 16119 6963 16119 7742 16120 7741 16120 6958 16120 7743 16121 6963 16121 6966 16121 7743 16122 7742 16122 6963 16122 7744 16123 6966 16123 6970 16123 7744 16124 7743 16124 6966 16124 7745 16125 6970 16125 6972 16125 7745 16126 7744 16126 6970 16126 7746 16127 6972 16127 6975 16127 7746 16128 7745 16128 6972 16128 7747 16129 6975 16129 6979 16129 7747 16130 7746 16130 6975 16130 7748 16131 6979 16131 6983 16131 7748 16132 7747 16132 6979 16132 7749 16133 6983 16133 6982 16133 7749 16134 7748 16134 6983 16134 7750 16135 6982 16135 6988 16135 7750 16136 7749 16136 6982 16136 7751 16137 6988 16137 6991 16137 7751 16138 7750 16138 6988 16138 7752 16139 6991 16139 6996 16139 7752 16140 7751 16140 6991 16140 7753 16141 6996 16141 7000 16141 7753 16142 7752 16142 6996 16142 7754 16143 7000 16143 7005 16143 7754 16144 7753 16144 7000 16144 7755 16145 7005 16145 7011 16145 7755 16146 7754 16146 7005 16146 7756 16147 7011 16147 7016 16147 7756 16148 7755 16148 7011 16148 7757 16149 7016 16149 7021 16149 7757 16150 7756 16150 7016 16150 7758 16151 7021 16151 7026 16151 7758 16152 7757 16152 7021 16152 7759 16153 7026 16153 7031 16153 7759 16154 7758 16154 7026 16154 7760 16155 7031 16155 7037 16155 7760 16156 7759 16156 7031 16156 7761 16157 7037 16157 6900 16157 7761 16158 7760 16158 7037 16158 7727 16159 7761 16159 6900 16159 7724 16160 7725 16160 7730 16160 7762 16161 7730 16161 7731 16161 7762 16162 7724 16162 7730 16162 7763 16163 7731 16163 7732 16163 7763 16164 7762 16164 7731 16164 7764 16165 7732 16165 7733 16165 7764 16166 7763 16166 7732 16166 7765 16167 7733 16167 7734 16167 7765 16168 7764 16168 7733 16168 7766 16169 7734 16169 7735 16169 7766 16170 7765 16170 7734 16170 7767 16171 7735 16171 7736 16171 7767 16172 7766 16172 7735 16172 7768 16173 7736 16173 7737 16173 7768 16174 7767 16174 7736 16174 7769 16175 7737 16175 7738 16175 7769 16176 7768 16176 7737 16176 7770 16177 7738 16177 7739 16177 7770 16178 7769 16178 7738 16178 7771 16179 7739 16179 7740 16179 7771 16180 7770 16180 7739 16180 7772 16181 7740 16181 7741 16181 7772 16182 7771 16182 7740 16182 7773 16183 7741 16183 7742 16183 7773 16184 7772 16184 7741 16184 7774 16185 7742 16185 7743 16185 7774 16186 7773 16186 7742 16186 7775 16187 7743 16187 7744 16187 7775 16188 7774 16188 7743 16188 7776 16189 7744 16189 7745 16189 7776 16190 7775 16190 7744 16190 7777 16191 7745 16191 7746 16191 7777 16192 7776 16192 7745 16192 7778 16193 7746 16193 7747 16193 7778 16194 7777 16194 7746 16194 7779 16195 7747 16195 7748 16195 7779 16196 7778 16196 7747 16196 7780 16197 7748 16197 7749 16197 7780 16198 7779 16198 7748 16198 7781 16199 7749 16199 7750 16199 7781 16200 7780 16200 7749 16200 7782 16201 7750 16201 7751 16201 7782 16202 7781 16202 7750 16202 7783 16203 7751 16203 7752 16203 7783 16204 7782 16204 7751 16204 7784 16205 7752 16205 7753 16205 7784 16206 7783 16206 7752 16206 7785 16207 7753 16207 7754 16207 7785 16208 7784 16208 7753 16208 7786 16209 7754 16209 7755 16209 7786 16210 7785 16210 7754 16210 7787 16211 7755 16211 7756 16211 7787 16212 7786 16212 7755 16212 7788 16213 7756 16213 7757 16213 7788 16214 7787 16214 7756 16214 7789 16215 7757 16215 7758 16215 7789 16216 7788 16216 7757 16216 7790 16217 7758 16217 7759 16217 7790 16218 7789 16218 7758 16218 7791 16219 7759 16219 7760 16219 7791 16220 7790 16220 7759 16220 7792 16221 7760 16221 7761 16221 7792 16222 7791 16222 7760 16222 7793 16223 7761 16223 7727 16223 7793 16224 7792 16224 7761 16224 7728 16225 7793 16225 7727 16225 7723 16226 7724 16226 7762 16226 7794 16227 7762 16227 7763 16227 7794 16228 7723 16228 7762 16228 7795 16229 7763 16229 7764 16229 7795 16230 7794 16230 7763 16230 7796 16231 7764 16231 7765 16231 7796 16232 7795 16232 7764 16232 7797 16233 7765 16233 7766 16233 7797 16234 7796 16234 7765 16234 7798 16235 7766 16235 7767 16235 7798 16236 7797 16236 7766 16236 7799 16237 7767 16237 7768 16237 7799 16238 7798 16238 7767 16238 7800 16239 7768 16239 7769 16239 7800 16240 7799 16240 7768 16240 7801 16241 7769 16241 7770 16241 7801 16242 7800 16242 7769 16242 7802 16243 7770 16243 7771 16243 7802 16244 7801 16244 7770 16244 7803 16245 7771 16245 7772 16245 7803 16246 7802 16246 7771 16246 7804 16247 7772 16247 7773 16247 7804 16248 7803 16248 7772 16248 7805 16249 7773 16249 7774 16249 7805 16250 7804 16250 7773 16250 7806 16251 7774 16251 7775 16251 7806 16252 7805 16252 7774 16252 7807 16253 7775 16253 7776 16253 7807 16254 7806 16254 7775 16254 7808 16255 7776 16255 7777 16255 7808 16256 7807 16256 7776 16256 7809 16257 7777 16257 7778 16257 7809 16258 7808 16258 7777 16258 7810 16259 7778 16259 7779 16259 7810 16260 7809 16260 7778 16260 7811 16261 7779 16261 7780 16261 7811 16262 7810 16262 7779 16262 7812 16263 7780 16263 7781 16263 7812 16264 7811 16264 7780 16264 7813 16265 7781 16265 7782 16265 7813 16266 7812 16266 7781 16266 7814 16267 7782 16267 7783 16267 7814 16268 7813 16268 7782 16268 7815 16269 7783 16269 7784 16269 7815 16270 7814 16270 7783 16270 7816 16271 7784 16271 7785 16271 7816 16272 7815 16272 7784 16272 7817 16273 7785 16273 7786 16273 7817 16274 7816 16274 7785 16274 7818 16275 7786 16275 7787 16275 7818 16276 7817 16276 7786 16276 7819 16277 7787 16277 7788 16277 7819 16278 7818 16278 7787 16278 7820 16279 7788 16279 7789 16279 7820 16280 7819 16280 7788 16280 7821 16281 7789 16281 7790 16281 7821 16282 7820 16282 7789 16282 7822 16283 7790 16283 7791 16283 7822 16284 7821 16284 7790 16284 7823 16285 7791 16285 7792 16285 7823 16286 7822 16286 7791 16286 7824 16287 7792 16287 7793 16287 7824 16288 7823 16288 7792 16288 7825 16289 7793 16289 7728 16289 7825 16290 7824 16290 7793 16290 7729 16291 7825 16291 7728 16291 6765 16292 7723 16292 7794 16292 6761 16293 7794 16293 7795 16293 6761 16294 6765 16294 7794 16294 6762 16295 7795 16295 7796 16295 6762 16296 6761 16296 7795 16296 6756 16297 7796 16297 7797 16297 6756 16298 6762 16298 7796 16298 6758 16299 7797 16299 7798 16299 6758 16300 6756 16300 7797 16300 6751 16301 7798 16301 7799 16301 6751 16302 6758 16302 7798 16302 6753 16303 7799 16303 7800 16303 6753 16304 6751 16304 7799 16304 6746 16305 7800 16305 7801 16305 6746 16306 6753 16306 7800 16306 6747 16307 7801 16307 7802 16307 6747 16308 6746 16308 7801 16308 6748 16309 7802 16309 7803 16309 6748 16310 6747 16310 7802 16310 6741 16311 7803 16311 7804 16311 6741 16312 6748 16312 7803 16312 6743 16313 7804 16313 7805 16313 6743 16314 6741 16314 7804 16314 6737 16315 7805 16315 7806 16315 6737 16316 6743 16316 7805 16316 6733 16317 7806 16317 7807 16317 6733 16318 6737 16318 7806 16318 6734 16319 7807 16319 7808 16319 6734 16320 6733 16320 7807 16320 6730 16321 7808 16321 7809 16321 6730 16322 6734 16322 7808 16322 6726 16323 7809 16323 7810 16323 6726 16324 6730 16324 7809 16324 6727 16325 7810 16325 7811 16325 6727 16326 6726 16326 7810 16326 6723 16327 7811 16327 7812 16327 6723 16328 6727 16328 7811 16328 6721 16329 7812 16329 7813 16329 6721 16330 6723 16330 7812 16330 6718 16331 7813 16331 7814 16331 6718 16332 6721 16332 7813 16332 6716 16333 7814 16333 7815 16333 6716 16334 6718 16334 7814 16334 6713 16335 7815 16335 7816 16335 6713 16336 6716 16336 7815 16336 6710 16337 7816 16337 7817 16337 6710 16338 6713 16338 7816 16338 6706 16339 7817 16339 7818 16339 6706 16340 6710 16340 7817 16340 6704 16341 7818 16341 7819 16341 6704 16342 6706 16342 7818 16342 6700 16343 7819 16343 7820 16343 6700 16344 6704 16344 7819 16344 6697 16345 7820 16345 7821 16345 6697 16346 6700 16346 7820 16346 6694 16347 7821 16347 7822 16347 6694 16348 6697 16348 7821 16348 6689 16349 7822 16349 7823 16349 6689 16350 6694 16350 7822 16350 6686 16351 7823 16351 7824 16351 6686 16352 6689 16352 7823 16352 6683 16353 7824 16353 7825 16353 6683 16354 6686 16354 7824 16354 6682 16355 7825 16355 7729 16355 6682 16356 6683 16356 7825 16356 6681 16357 6682 16357 7729 16357 7826 16358 7074 16358 6860 16358 7726 16359 7827 16359 7079 16359 7828 16360 7826 16360 6860 16360 6861 16361 7828 16361 6860 16361 7726 16362 7829 16362 7827 16362 7072 16363 7074 16363 7826 16363 7830 16364 7826 16364 7828 16364 7830 16365 7072 16365 7826 16365 6862 16366 7828 16366 6861 16366 7831 16367 7828 16367 6862 16367 7830 16368 7828 16368 7831 16368 7832 16369 6862 16369 6859 16369 7831 16370 6862 16370 7832 16370 7832 16371 6859 16371 6863 16371 7833 16372 6650 16372 6651 16372 7833 16373 6785 16373 6650 16373 7080 16374 6651 16374 6649 16374 7080 16375 7833 16375 6651 16375 7078 16376 6649 16376 6654 16376 7078 16377 7080 16377 6649 16377 7039 16378 6654 16378 6653 16378 7078 16379 6654 16379 7039 16379 7726 16380 7039 16380 7040 16380 7078 16381 7039 16381 7726 16381 7829 16382 7040 16382 7041 16382 7726 16383 7040 16383 7829 16383 7834 16384 7041 16384 7042 16384 7829 16385 7041 16385 7834 16385 7835 16386 7042 16386 7043 16386 7834 16387 7042 16387 7835 16387 7836 16388 7043 16388 7044 16388 7835 16389 7043 16389 7836 16389 7837 16390 7044 16390 7045 16390 7836 16391 7044 16391 7837 16391 7838 16392 7045 16392 7046 16392 7837 16393 7045 16393 7838 16393 7839 16394 7046 16394 7047 16394 7838 16395 7046 16395 7839 16395 7840 16396 7047 16396 7048 16396 7839 16397 7047 16397 7840 16397 7841 16398 7048 16398 7049 16398 7840 16399 7048 16399 7841 16399 7842 16400 7049 16400 7050 16400 7841 16401 7049 16401 7842 16401 7843 16402 7050 16402 7051 16402 7842 16403 7050 16403 7843 16403 7844 16404 7051 16404 7052 16404 7843 16405 7051 16405 7844 16405 7845 16406 7052 16406 7053 16406 7844 16407 7052 16407 7845 16407 7846 16408 7053 16408 7054 16408 7845 16409 7053 16409 7846 16409 7847 16410 7054 16410 7055 16410 7846 16411 7054 16411 7847 16411 7848 16412 7055 16412 7056 16412 7847 16413 7055 16413 7848 16413 7849 16414 7056 16414 7057 16414 7848 16415 7056 16415 7849 16415 7850 16416 7057 16416 7058 16416 7849 16417 7057 16417 7850 16417 7851 16418 7058 16418 7059 16418 7850 16419 7058 16419 7851 16419 7852 16420 7059 16420 7060 16420 7851 16421 7059 16421 7852 16421 7853 16422 7060 16422 7061 16422 7852 16423 7060 16423 7853 16423 7854 16424 7061 16424 7062 16424 7853 16425 7061 16425 7854 16425 7855 16426 7062 16426 7063 16426 7854 16427 7062 16427 7855 16427 7856 16428 7063 16428 7064 16428 7855 16429 7063 16429 7856 16429 7857 16430 7064 16430 7065 16430 7856 16431 7064 16431 7857 16431 7858 16432 7065 16432 7066 16432 7857 16433 7065 16433 7858 16433 7859 16434 7066 16434 7067 16434 7858 16435 7066 16435 7859 16435 7860 16436 7067 16436 7068 16436 7859 16437 7067 16437 7860 16437 7861 16438 7068 16438 7069 16438 7860 16439 7068 16439 7861 16439 7862 16440 7069 16440 7071 16440 7861 16441 7069 16441 7862 16441 7863 16442 7071 16442 7070 16442 7862 16443 7071 16443 7863 16443 7830 16444 7070 16444 7072 16444 7863 16445 7070 16445 7830 16445 7864 16446 6863 16446 6864 16446 7864 16447 7832 16447 6863 16447 7865 16448 6864 16448 6866 16448 7865 16449 7864 16449 6864 16449 7866 16450 6866 16450 6865 16450 7866 16451 7865 16451 6866 16451 7867 16452 6865 16452 6867 16452 7867 16453 7866 16453 6865 16453 7868 16454 6867 16454 6869 16454 7868 16455 7867 16455 6867 16455 7869 16456 6869 16456 6870 16456 7869 16457 7868 16457 6869 16457 7870 16458 6870 16458 6868 16458 7870 16459 7869 16459 6870 16459 7871 16460 6868 16460 6872 16460 7871 16461 7870 16461 6868 16461 7872 16462 6872 16462 6871 16462 7872 16463 7871 16463 6872 16463 7873 16464 6871 16464 6874 16464 7873 16465 7872 16465 6871 16465 7874 16466 6874 16466 6875 16466 7874 16467 7873 16467 6874 16467 7875 16468 6875 16468 6873 16468 7875 16469 7874 16469 6875 16469 7876 16470 6873 16470 6877 16470 7876 16471 7875 16471 6873 16471 7877 16472 6877 16472 6876 16472 7877 16473 7876 16473 6877 16473 7878 16474 6876 16474 6879 16474 7878 16475 7877 16475 6876 16475 7879 16476 6879 16476 6878 16476 7879 16477 7878 16477 6879 16477 7880 16478 6878 16478 6880 16478 7880 16479 7879 16479 6878 16479 7881 16480 6880 16480 6882 16480 7881 16481 7880 16481 6880 16481 7882 16482 6882 16482 6881 16482 7882 16483 7881 16483 6882 16483 7883 16484 6881 16484 6883 16484 7883 16485 7882 16485 6881 16485 7884 16486 6883 16486 6884 16486 7884 16487 7883 16487 6883 16487 7885 16488 6884 16488 6885 16488 7885 16489 7884 16489 6884 16489 7886 16490 6885 16490 6886 16490 7886 16491 7885 16491 6885 16491 7887 16492 6886 16492 6887 16492 7887 16493 7886 16493 6886 16493 7888 16494 6887 16494 6888 16494 7888 16495 7887 16495 6887 16495 7889 16496 6888 16496 6889 16496 7889 16497 7888 16497 6888 16497 7890 16498 6889 16498 6890 16498 7890 16499 7889 16499 6889 16499 7891 16500 6890 16500 6891 16500 7891 16501 7890 16501 6890 16501 7892 16502 6891 16502 6892 16502 7892 16503 7891 16503 6891 16503 7893 16504 6892 16504 6893 16504 7893 16505 7892 16505 6892 16505 7894 16506 6893 16506 6894 16506 7894 16507 7893 16507 6893 16507 7895 16508 6894 16508 6895 16508 7895 16509 7894 16509 6894 16509 7833 16510 6895 16510 6785 16510 7833 16511 7895 16511 6895 16511 7896 16512 7832 16512 7864 16512 7896 16513 7831 16513 7832 16513 7897 16514 7864 16514 7865 16514 7897 16515 7896 16515 7864 16515 7898 16516 7865 16516 7866 16516 7898 16517 7897 16517 7865 16517 7899 16518 7866 16518 7867 16518 7899 16519 7898 16519 7866 16519 7900 16520 7867 16520 7868 16520 7900 16521 7899 16521 7867 16521 7901 16522 7868 16522 7869 16522 7901 16523 7900 16523 7868 16523 7902 16524 7869 16524 7870 16524 7902 16525 7901 16525 7869 16525 7903 16526 7870 16526 7871 16526 7903 16527 7902 16527 7870 16527 7904 16528 7871 16528 7872 16528 7904 16529 7903 16529 7871 16529 7905 16530 7872 16530 7873 16530 7905 16531 7904 16531 7872 16531 7906 16532 7873 16532 7874 16532 7906 16533 7905 16533 7873 16533 7907 16534 7874 16534 7875 16534 7907 16535 7906 16535 7874 16535 7908 16536 7875 16536 7876 16536 7908 16537 7907 16537 7875 16537 7909 16538 7876 16538 7877 16538 7909 16539 7908 16539 7876 16539 7910 16540 7877 16540 7878 16540 7910 16541 7909 16541 7877 16541 7911 16542 7878 16542 7879 16542 7911 16543 7910 16543 7878 16543 7912 16544 7879 16544 7880 16544 7912 16545 7911 16545 7879 16545 7913 16546 7880 16546 7881 16546 7913 16547 7912 16547 7880 16547 7914 16548 7881 16548 7882 16548 7914 16549 7913 16549 7881 16549 7915 16550 7882 16550 7883 16550 7915 16551 7914 16551 7882 16551 7916 16552 7883 16552 7884 16552 7916 16553 7915 16553 7883 16553 7917 16554 7884 16554 7885 16554 7917 16555 7916 16555 7884 16555 7918 16556 7885 16556 7886 16556 7918 16557 7917 16557 7885 16557 7919 16558 7886 16558 7887 16558 7919 16559 7918 16559 7886 16559 7920 16560 7887 16560 7888 16560 7920 16561 7919 16561 7887 16561 7921 16562 7888 16562 7889 16562 7921 16563 7920 16563 7888 16563 7922 16564 7889 16564 7890 16564 7922 16565 7921 16565 7889 16565 7923 16566 7890 16566 7891 16566 7923 16567 7922 16567 7890 16567 7924 16568 7891 16568 7892 16568 7924 16569 7923 16569 7891 16569 7925 16570 7892 16570 7893 16570 7925 16571 7924 16571 7892 16571 7827 16572 7893 16572 7894 16572 7827 16573 7925 16573 7893 16573 7079 16574 7894 16574 7895 16574 7079 16575 7827 16575 7894 16575 7080 16576 7895 16576 7833 16576 7080 16577 7079 16577 7895 16577 7863 16578 7831 16578 7896 16578 7863 16579 7830 16579 7831 16579 7862 16580 7896 16580 7897 16580 7862 16581 7863 16581 7896 16581 7861 16582 7897 16582 7898 16582 7861 16583 7862 16583 7897 16583 7860 16584 7898 16584 7899 16584 7860 16585 7861 16585 7898 16585 7859 16586 7899 16586 7900 16586 7859 16587 7860 16587 7899 16587 7858 16588 7900 16588 7901 16588 7858 16589 7859 16589 7900 16589 7857 16590 7901 16590 7902 16590 7857 16591 7858 16591 7901 16591 7856 16592 7902 16592 7903 16592 7856 16593 7857 16593 7902 16593 7855 16594 7903 16594 7904 16594 7855 16595 7856 16595 7903 16595 7854 16596 7904 16596 7905 16596 7854 16597 7855 16597 7904 16597 7853 16598 7905 16598 7906 16598 7853 16599 7854 16599 7905 16599 7852 16600 7906 16600 7907 16600 7852 16601 7853 16601 7906 16601 7851 16602 7907 16602 7908 16602 7851 16603 7852 16603 7907 16603 7850 16604 7908 16604 7909 16604 7850 16605 7851 16605 7908 16605 7849 16606 7909 16606 7910 16606 7849 16607 7850 16607 7909 16607 7848 16608 7910 16608 7911 16608 7848 16609 7849 16609 7910 16609 7847 16610 7911 16610 7912 16610 7847 16611 7848 16611 7911 16611 7846 16612 7912 16612 7913 16612 7846 16613 7847 16613 7912 16613 7845 16614 7913 16614 7914 16614 7845 16615 7846 16615 7913 16615 7844 16616 7914 16616 7915 16616 7844 16617 7845 16617 7914 16617 7843 16618 7915 16618 7916 16618 7843 16619 7844 16619 7915 16619 7842 16620 7916 16620 7917 16620 7842 16621 7843 16621 7916 16621 7841 16622 7917 16622 7918 16622 7841 16623 7842 16623 7917 16623 7840 16624 7918 16624 7919 16624 7840 16625 7841 16625 7918 16625 7839 16626 7919 16626 7920 16626 7839 16627 7840 16627 7919 16627 7838 16628 7920 16628 7921 16628 7838 16629 7839 16629 7920 16629 7837 16630 7921 16630 7922 16630 7837 16631 7838 16631 7921 16631 7836 16632 7922 16632 7923 16632 7836 16633 7837 16633 7922 16633 7835 16634 7923 16634 7924 16634 7835 16635 7836 16635 7923 16635 7834 16636 7924 16636 7925 16636 7834 16637 7835 16637 7924 16637 7829 16638 7925 16638 7827 16638 7829 16639 7834 16639 7925 16639 7926 16640 7927 16640 7928 16640 7929 16641 7928 16641 7927 16641 7930 16642 7928 16642 7931 16642 7932 16643 7931 16643 7928 16643 7926 16644 7928 16644 7930 16644 7933 16645 7928 16645 7929 16645 7934 16646 7932 16646 7928 16646 7935 16647 7934 16647 7928 16647 7933 16648 7935 16648 7928 16648 7936 16649 7937 16649 7927 16649 7938 16650 7927 16650 7937 16650 7939 16651 7936 16651 7927 16651 7940 16652 7939 16652 7927 16652 7926 16653 7940 16653 7927 16653 7941 16654 7927 16654 7938 16654 7942 16655 7943 16655 7927 16655 7944 16656 7927 16656 7943 16656 7941 16657 7942 16657 7927 16657 7944 16658 7929 16658 7927 16658 7945 16659 7946 16659 7937 16659 7947 16660 7937 16660 7946 16660 7936 16661 7945 16661 7937 16661 7938 16662 7937 16662 7947 16662 7948 16663 7949 16663 7946 16663 7950 16664 7946 16664 7949 16664 7945 16665 7948 16665 7946 16665 7947 16666 7946 16666 7950 16666 7951 16667 7949 16667 7948 16667 7950 16668 7949 16668 7951 16668 7952 16669 7948 16669 7945 16669 7951 16670 7948 16670 7952 16670 7953 16671 7945 16671 7936 16671 7952 16672 7945 16672 7953 16672 7954 16673 7955 16673 7936 16673 7956 16674 7936 16674 7955 16674 7939 16675 7954 16675 7936 16675 7953 16676 7936 16676 7956 16676 7957 16677 7958 16677 7955 16677 7959 16678 7955 16678 7958 16678 7960 16679 7957 16679 7955 16679 7954 16680 7960 16680 7955 16680 7956 16681 7955 16681 7961 16681 7959 16682 7961 16682 7955 16682 7962 16683 7963 16683 7958 16683 7964 16684 7958 16684 7963 16684 7957 16685 7962 16685 7958 16685 7965 16686 7959 16686 7958 16686 7966 16687 7965 16687 7958 16687 7967 16688 7966 16688 7958 16688 7964 16689 7967 16689 7958 16689 7968 16690 7969 16690 7963 16690 7970 16691 7963 16691 7969 16691 7971 16692 7968 16692 7963 16692 7972 16693 7971 16693 7963 16693 7962 16694 7972 16694 7963 16694 7973 16695 7963 16695 7970 16695 7974 16696 7964 16696 7963 16696 7975 16697 7976 16697 7963 16697 7974 16698 7963 16698 7976 16698 7973 16699 7975 16699 7963 16699 7977 16700 7978 16700 7969 16700 7979 16701 7969 16701 7978 16701 7968 16702 7977 16702 7969 16702 7970 16703 7969 16703 7979 16703 7980 16704 7981 16704 7978 16704 7982 16705 7978 16705 7981 16705 7977 16706 7980 16706 7978 16706 7979 16707 7978 16707 7982 16707 7983 16708 7981 16708 7980 16708 7982 16709 7981 16709 7983 16709 7984 16710 7980 16710 7977 16710 7983 16711 7980 16711 7984 16711 7985 16712 7977 16712 7968 16712 7984 16713 7977 16713 7985 16713 7986 16714 7931 16714 7968 16714 7987 16715 7968 16715 7931 16715 7971 16716 7986 16716 7968 16716 7985 16717 7968 16717 7987 16717 7988 16718 7930 16718 7931 16718 7986 16719 7988 16719 7931 16719 7987 16720 7931 16720 7989 16720 7932 16721 7989 16721 7931 16721 7990 16722 7930 16722 7988 16722 7991 16723 7926 16723 7930 16723 7991 16724 7930 16724 7990 16724 7992 16725 7988 16725 7986 16725 7992 16726 7990 16726 7988 16726 7993 16727 7986 16727 7971 16727 7992 16728 7986 16728 7993 16728 7994 16729 7971 16729 7972 16729 7993 16730 7971 16730 7994 16730 7995 16731 7972 16731 7962 16731 7994 16732 7972 16732 7995 16732 7996 16733 7962 16733 7957 16733 7995 16734 7962 16734 7996 16734 7997 16735 7957 16735 7960 16735 7996 16736 7957 16736 7997 16736 7998 16737 7960 16737 7954 16737 7997 16738 7960 16738 7998 16738 7999 16739 7954 16739 7939 16739 7998 16740 7954 16740 7999 16740 8000 16741 7939 16741 7940 16741 7999 16742 7939 16742 8000 16742 7940 16743 7926 16743 8001 16743 8000 16744 7940 16744 8001 16744 8001 16745 7926 16745 7991 16745 7992 16746 7989 16746 8002 16746 8003 16747 8002 16747 7989 16747 7990 16748 8002 16748 7938 16748 7941 16749 7938 16749 8002 16749 7992 16750 8002 16750 7990 16750 8004 16751 7941 16751 8002 16751 8005 16752 8004 16752 8002 16752 8006 16753 8005 16753 8002 16753 8007 16754 8006 16754 8002 16754 8008 16755 8007 16755 8002 16755 8003 16756 8008 16756 8002 16756 7979 16757 7987 16757 7989 16757 7994 16758 7979 16758 7989 16758 7993 16759 7994 16759 7989 16759 7992 16760 7993 16760 7989 16760 8009 16761 8003 16761 7989 16761 7932 16762 8009 16762 7989 16762 7982 16763 7985 16763 7987 16763 7979 16764 7982 16764 7987 16764 7983 16765 7984 16765 7985 16765 7982 16766 7983 16766 7985 16766 7995 16767 7970 16767 7979 16767 7994 16768 7995 16768 7979 16768 7997 16769 8010 16769 7970 16769 7973 16770 7970 16770 8010 16770 7996 16771 7997 16771 7970 16771 7995 16772 7996 16772 7970 16772 7998 16773 7961 16773 8010 16773 8011 16774 8010 16774 7961 16774 7997 16775 7998 16775 8010 16775 8012 16776 8010 16776 8011 16776 8013 16777 7973 16777 8010 16777 8014 16778 8013 16778 8010 16778 8015 16779 8014 16779 8010 16779 8016 16780 8015 16780 8010 16780 8012 16781 8016 16781 8010 16781 7947 16782 7956 16782 7961 16782 8000 16783 7947 16783 7961 16783 7999 16784 8000 16784 7961 16784 7998 16785 7999 16785 7961 16785 8017 16786 8011 16786 7961 16786 7959 16787 8017 16787 7961 16787 7950 16788 7953 16788 7956 16788 7947 16789 7950 16789 7956 16789 7951 16790 7952 16790 7953 16790 7950 16791 7951 16791 7953 16791 8001 16792 7938 16792 7947 16792 8000 16793 8001 16793 7947 16793 7991 16794 7990 16794 7938 16794 8001 16795 7991 16795 7938 16795 8018 16796 7943 16796 7942 16796 8018 16797 7944 16797 7943 16797 8019 16798 7942 16798 7941 16798 8020 16799 8018 16799 7942 16799 8019 16800 8020 16800 7942 16800 8021 16801 7941 16801 8004 16801 8022 16802 7941 16802 8021 16802 8022 16803 8019 16803 7941 16803 8023 16804 8004 16804 8005 16804 8024 16805 8021 16805 8004 16805 8023 16806 8024 16806 8004 16806 8025 16807 8005 16807 8006 16807 8026 16808 8023 16808 8005 16808 8027 16809 8026 16809 8005 16809 8025 16810 8027 16810 8005 16810 8028 16811 8006 16811 8007 16811 8029 16812 8025 16812 8006 16812 8028 16813 8029 16813 8006 16813 8030 16814 8007 16814 8008 16814 8028 16815 8007 16815 8030 16815 8030 16816 8008 16816 8003 16816 8031 16817 8003 16817 8009 16817 8031 16818 8032 16818 8003 16818 8030 16819 8003 16819 8032 16819 8033 16820 8011 16820 8017 16820 8034 16821 8012 16821 8011 16821 8033 16822 8035 16822 8011 16822 8034 16823 8011 16823 8035 16823 8033 16824 8017 16824 7959 16824 8033 16825 7959 16825 7965 16825 8033 16826 7965 16826 7966 16826 8036 16827 7966 16827 7967 16827 8036 16828 8033 16828 7966 16828 8036 16829 7967 16829 7964 16829 8037 16830 7964 16830 7974 16830 8036 16831 7964 16831 8037 16831 8018 16832 7929 16832 7944 16832 8038 16833 7933 16833 7929 16833 8038 16834 7929 16834 8018 16834 8037 16835 7976 16835 7975 16835 8037 16836 7974 16836 7976 16836 8039 16837 7975 16837 7973 16837 8040 16838 8037 16838 7975 16838 8041 16839 8040 16839 7975 16839 8039 16840 8041 16840 7975 16840 8042 16841 7973 16841 8013 16841 8043 16842 7973 16842 8042 16842 8044 16843 8039 16843 7973 16843 8043 16844 8044 16844 7973 16844 8045 16845 8013 16845 8014 16845 8046 16846 8042 16846 8013 16846 8045 16847 8046 16847 8013 16847 8047 16848 8014 16848 8015 16848 8048 16849 8045 16849 8014 16849 8049 16850 8048 16850 8014 16850 8047 16851 8049 16851 8014 16851 8050 16852 8015 16852 8016 16852 8051 16853 8047 16853 8015 16853 8050 16854 8051 16854 8015 16854 8034 16855 8016 16855 8012 16855 8052 16856 8016 16856 8034 16856 8052 16857 8050 16857 8016 16857 8031 16858 8009 16858 7932 16858 8031 16859 7932 16859 7934 16859 8031 16860 7934 16860 7935 16860 8038 16861 7935 16861 7933 16861 8038 16862 8031 16862 7935 16862 8053 16863 8035 16863 8033 16863 8054 16864 8034 16864 8035 16864 8055 16865 8054 16865 8035 16865 8056 16866 8055 16866 8035 16866 8057 16867 8056 16867 8035 16867 8058 16868 8057 16868 8035 16868 8059 16869 8058 16869 8035 16869 8060 16870 8059 16870 8035 16870 8060 16871 8035 16871 8053 16871 8061 16872 8033 16872 8036 16872 8062 16873 8063 16873 8033 16873 8064 16874 8033 16874 8063 16874 8061 16875 8062 16875 8033 16875 8065 16876 8053 16876 8033 16876 8066 16877 8065 16877 8033 16877 8067 16878 8066 16878 8033 16878 8068 16879 8067 16879 8033 16879 8069 16880 8068 16880 8033 16880 8070 16881 8069 16881 8033 16881 8064 16882 8070 16882 8033 16882 8052 16883 8034 16883 8054 16883 8071 16884 8054 16884 8055 16884 8071 16885 8052 16885 8054 16885 8072 16886 8055 16886 8056 16886 8071 16887 8055 16887 8072 16887 8072 16888 8056 16888 8057 16888 8073 16889 8057 16889 8058 16889 8072 16890 8057 16890 8073 16890 8059 16891 8074 16891 8058 16891 8073 16892 8058 16892 8074 16892 8059 16893 8075 16893 8074 16893 8076 16894 8074 16894 8075 16894 8073 16895 8074 16895 8076 16895 8059 16896 8077 16896 8075 16896 8076 16897 8075 16897 8077 16897 8059 16898 8078 16898 8077 16898 8079 16899 8077 16899 8078 16899 8076 16900 8077 16900 8079 16900 8059 16901 8080 16901 8078 16901 8079 16902 8078 16902 8080 16902 8059 16903 8081 16903 8080 16903 8079 16904 8080 16904 8081 16904 8082 16905 8083 16905 8081 16905 8084 16906 8081 16906 8083 16906 8059 16907 8082 16907 8081 16907 8079 16908 8081 16908 8084 16908 8082 16909 8085 16909 8083 16909 8084 16910 8083 16910 8085 16910 8082 16911 8086 16911 8085 16911 8087 16912 8085 16912 8086 16912 8084 16913 8085 16913 8087 16913 8082 16914 8088 16914 8086 16914 8087 16915 8086 16915 8088 16915 8082 16916 8089 16916 8088 16916 8090 16917 8088 16917 8089 16917 8087 16918 8088 16918 8090 16918 8082 16919 8091 16919 8089 16919 8090 16920 8089 16920 8091 16920 8092 16921 8093 16921 8091 16921 8094 16922 8091 16922 8093 16922 8082 16923 8092 16923 8091 16923 8090 16924 8091 16924 8094 16924 8092 16925 8095 16925 8093 16925 8096 16926 8093 16926 8095 16926 8094 16927 8093 16927 8096 16927 8092 16928 8097 16928 8095 16928 8096 16929 8095 16929 8097 16929 8098 16930 8099 16930 8097 16930 8100 16931 8097 16931 8099 16931 8092 16932 8098 16932 8097 16932 8096 16933 8097 16933 8100 16933 8098 16934 8101 16934 8099 16934 8100 16935 8099 16935 8101 16935 8098 16936 8102 16936 8101 16936 8103 16937 8101 16937 8102 16937 8100 16938 8101 16938 8103 16938 8104 16939 8105 16939 8102 16939 8106 16940 8102 16940 8105 16940 8098 16941 8104 16941 8102 16941 8103 16942 8102 16942 8106 16942 8104 16943 8107 16943 8105 16943 8108 16944 8105 16944 8107 16944 8106 16945 8105 16945 8108 16945 8109 16946 8110 16946 8107 16946 8111 16947 8107 16947 8110 16947 8104 16948 8109 16948 8107 16948 8108 16949 8107 16949 8111 16949 8109 16950 8112 16950 8110 16950 8113 16951 8110 16951 8112 16951 8111 16952 8110 16952 8113 16952 8114 16953 8115 16953 8112 16953 8116 16954 8112 16954 8115 16954 8109 16955 8114 16955 8112 16955 8117 16956 8112 16956 8116 16956 8113 16957 8112 16957 8117 16957 8118 16958 8119 16958 8115 16958 8120 16959 8115 16959 8119 16959 8114 16960 8118 16960 8115 16960 8116 16961 8115 16961 8120 16961 8121 16962 8122 16962 8119 16962 8123 16963 8119 16963 8122 16963 8118 16964 8121 16964 8119 16964 8124 16965 8119 16965 8123 16965 8120 16966 8119 16966 8124 16966 8125 16967 8126 16967 8122 16967 8127 16968 8122 16968 8126 16968 8128 16969 8125 16969 8122 16969 8121 16970 8128 16970 8122 16970 8123 16971 8122 16971 8127 16971 8129 16972 8130 16972 8126 16972 8131 16973 8126 16973 8130 16973 8132 16974 8129 16974 8126 16974 8125 16975 8132 16975 8126 16975 8133 16976 8126 16976 8131 16976 8127 16977 8126 16977 8133 16977 8134 16978 8135 16978 8130 16978 8136 16979 8130 16979 8135 16979 8129 16980 8134 16980 8130 16980 8137 16981 8130 16981 8136 16981 8138 16982 8130 16982 8137 16982 8131 16983 8130 16983 8138 16983 8139 16984 8140 16984 8135 16984 8141 16985 8135 16985 8140 16985 8142 16986 8139 16986 8135 16986 8134 16987 8142 16987 8135 16987 8143 16988 8135 16988 8141 16988 8136 16989 8135 16989 8143 16989 8144 16990 8145 16990 8140 16990 8146 16991 8140 16991 8145 16991 8147 16992 8144 16992 8140 16992 8139 16993 8147 16993 8140 16993 8148 16994 8140 16994 8146 16994 8141 16995 8140 16995 8148 16995 8149 16996 8150 16996 8145 16996 8151 16997 8145 16997 8150 16997 8144 16998 8149 16998 8145 16998 8152 16999 8145 16999 8151 16999 8146 17000 8145 17000 8152 17000 8153 17001 8154 17001 8150 17001 8155 17002 8150 17002 8154 17002 8156 17003 8153 17003 8150 17003 8157 17004 8156 17004 8150 17004 8158 17005 8157 17005 8150 17005 8159 17006 8158 17006 8150 17006 8149 17007 8159 17007 8150 17007 8151 17008 8150 17008 8155 17008 8160 17009 8154 17009 8153 17009 8161 17010 8154 17010 8160 17010 8155 17011 8154 17011 8161 17011 8160 17012 8153 17012 8156 17012 8162 17013 8156 17013 8157 17013 8162 17014 8160 17014 8156 17014 8163 17015 8157 17015 8158 17015 8163 17016 8162 17016 8157 17016 8163 17017 8158 17017 8159 17017 8164 17018 8159 17018 8149 17018 8163 17019 8159 17019 8164 17019 8164 17020 8149 17020 8144 17020 8165 17021 8144 17021 8147 17021 8165 17022 8164 17022 8144 17022 8165 17023 8147 17023 8139 17023 8166 17024 8139 17024 8142 17024 8166 17025 8165 17025 8139 17025 8166 17026 8142 17026 8134 17026 8166 17027 8134 17027 8129 17027 8167 17028 8129 17028 8132 17028 8167 17029 8166 17029 8129 17029 8167 17030 8132 17030 8125 17030 8168 17031 8125 17031 8128 17031 8168 17032 8167 17032 8125 17032 8168 17033 8128 17033 8121 17033 8169 17034 8121 17034 8118 17034 8169 17035 8168 17035 8121 17035 8169 17036 8118 17036 8114 17036 8170 17037 8114 17037 8109 17037 8170 17038 8169 17038 8114 17038 8170 17039 8109 17039 8104 17039 8171 17040 8104 17040 8098 17040 8171 17041 8170 17041 8104 17041 8172 17042 8098 17042 8092 17042 8172 17043 8171 17043 8098 17043 8172 17044 8092 17044 8082 17044 8173 17045 8082 17045 8059 17045 8173 17046 8172 17046 8082 17046 8060 17047 8173 17047 8059 17047 8174 17048 8036 17048 8037 17048 8175 17049 8174 17049 8037 17049 8175 17050 8037 17050 8040 17050 8176 17051 8177 17051 8036 17051 8178 17052 8036 17052 8177 17052 8179 17053 8176 17053 8036 17053 8174 17054 8179 17054 8036 17054 8180 17055 8061 17055 8036 17055 8181 17056 8180 17056 8036 17056 8182 17057 8181 17057 8036 17057 8183 17058 8182 17058 8036 17058 8184 17059 8183 17059 8036 17059 8178 17060 8184 17060 8036 17060 8185 17061 8186 17061 8177 17061 8187 17062 8177 17062 8186 17062 8188 17063 8185 17063 8177 17063 8189 17064 8188 17064 8177 17064 8190 17065 8189 17065 8177 17065 8191 17066 8190 17066 8177 17066 8192 17067 8191 17067 8177 17067 8193 17068 8192 17068 8177 17068 8194 17069 8193 17069 8177 17069 8195 17070 8194 17070 8177 17070 8176 17071 8195 17071 8177 17071 8178 17072 8177 17072 8182 17072 8187 17073 8182 17073 8177 17073 8196 17074 8197 17074 8186 17074 8198 17075 8186 17075 8197 17075 8199 17076 8196 17076 8186 17076 8200 17077 8199 17077 8186 17077 8201 17078 8200 17078 8186 17078 8202 17079 8201 17079 8186 17079 8203 17080 8202 17080 8186 17080 8185 17081 8203 17081 8186 17081 8187 17082 8186 17082 8198 17082 8204 17083 8205 17083 8197 17083 8206 17084 8197 17084 8205 17084 8207 17085 8204 17085 8197 17085 8208 17086 8207 17086 8197 17086 8209 17087 8208 17087 8197 17087 8196 17088 8209 17088 8197 17088 8198 17089 8197 17089 8206 17089 8210 17090 8211 17090 8205 17090 8212 17091 8205 17091 8211 17091 8213 17092 8210 17092 8205 17092 8204 17093 8213 17093 8205 17093 8206 17094 8205 17094 8212 17094 8214 17095 8215 17095 8211 17095 8216 17096 8211 17096 8215 17096 8217 17097 8214 17097 8211 17097 8210 17098 8217 17098 8211 17098 8212 17099 8211 17099 8216 17099 8218 17100 8219 17100 8215 17100 8220 17101 8215 17101 8219 17101 8214 17102 8218 17102 8215 17102 8216 17103 8215 17103 8220 17103 8221 17104 8222 17104 8219 17104 8220 17105 8219 17105 8222 17105 8218 17106 8221 17106 8219 17106 8223 17107 8224 17107 8222 17107 8225 17108 8222 17108 8224 17108 8221 17109 8223 17109 8222 17109 8220 17110 8222 17110 8225 17110 8226 17111 8227 17111 8224 17111 8225 17112 8224 17112 8227 17112 8223 17113 8226 17113 8224 17113 8228 17114 8229 17114 8227 17114 8230 17115 8227 17115 8229 17115 8226 17116 8228 17116 8227 17116 8225 17117 8227 17117 8230 17117 8228 17118 8231 17118 8229 17118 8232 17119 8229 17119 8231 17119 8230 17120 8229 17120 8232 17120 8233 17121 8234 17121 8231 17121 8232 17122 8231 17122 8234 17122 8228 17123 8233 17123 8231 17123 8233 17124 8235 17124 8234 17124 8232 17125 8234 17125 8235 17125 8236 17126 8237 17126 8235 17126 8238 17127 8235 17127 8237 17127 8233 17128 8236 17128 8235 17128 8232 17129 8235 17129 8238 17129 8239 17130 8240 17130 8237 17130 8238 17131 8237 17131 8240 17131 8236 17132 8239 17132 8237 17132 8241 17133 8242 17133 8240 17133 8243 17134 8240 17134 8242 17134 8239 17135 8241 17135 8240 17135 8238 17136 8240 17136 8243 17136 8241 17137 8244 17137 8242 17137 8245 17138 8242 17138 8244 17138 8245 17139 8243 17139 8242 17139 8241 17140 8246 17140 8244 17140 8247 17141 8244 17141 8246 17141 8247 17142 8245 17142 8244 17142 8241 17143 8248 17143 8246 17143 8247 17144 8246 17144 8248 17144 8249 17145 8248 17145 8241 17145 8250 17146 8247 17146 8248 17146 8251 17147 8250 17147 8248 17147 8252 17148 8251 17148 8248 17148 8249 17149 8252 17149 8248 17149 8253 17150 8241 17150 8239 17150 8253 17151 8249 17151 8241 17151 8254 17152 8239 17152 8236 17152 8254 17153 8253 17153 8239 17153 8255 17154 8236 17154 8233 17154 8256 17155 8254 17155 8236 17155 8255 17156 8256 17156 8236 17156 8257 17157 8233 17157 8228 17157 8257 17158 8255 17158 8233 17158 8258 17159 8228 17159 8226 17159 8259 17160 8257 17160 8228 17160 8260 17161 8259 17161 8228 17161 8258 17162 8260 17162 8228 17162 8261 17163 8226 17163 8223 17163 8262 17164 8258 17164 8226 17164 8261 17165 8262 17165 8226 17165 8263 17166 8223 17166 8221 17166 8264 17167 8261 17167 8223 17167 8265 17168 8264 17168 8223 17168 8263 17169 8265 17169 8223 17169 8266 17170 8221 17170 8218 17170 8267 17171 8263 17171 8221 17171 8266 17172 8267 17172 8221 17172 8268 17173 8218 17173 8214 17173 8269 17174 8266 17174 8218 17174 8268 17175 8269 17175 8218 17175 8270 17176 8214 17176 8217 17176 8270 17177 8268 17177 8214 17177 8271 17178 8217 17178 8210 17178 8272 17179 8270 17179 8217 17179 8271 17180 8272 17180 8217 17180 8273 17181 8210 17181 8213 17181 8273 17182 8271 17182 8210 17182 8274 17183 8213 17183 8204 17183 8274 17184 8273 17184 8213 17184 8275 17185 8204 17185 8207 17185 8275 17186 8274 17186 8204 17186 8276 17187 8207 17187 8208 17187 8276 17188 8275 17188 8207 17188 8276 17189 8208 17189 8209 17189 8277 17190 8209 17190 8196 17190 8277 17191 8276 17191 8209 17191 8277 17192 8196 17192 8199 17192 8278 17193 8199 17193 8200 17193 8278 17194 8277 17194 8199 17194 8278 17195 8200 17195 8201 17195 8279 17196 8201 17196 8202 17196 8279 17197 8278 17197 8201 17197 8279 17198 8202 17198 8203 17198 8280 17199 8203 17199 8185 17199 8280 17200 8279 17200 8203 17200 8280 17201 8185 17201 8188 17201 8281 17202 8188 17202 8189 17202 8281 17203 8280 17203 8188 17203 8281 17204 8189 17204 8190 17204 8282 17205 8190 17205 8191 17205 8282 17206 8281 17206 8190 17206 8283 17207 8191 17207 8192 17207 8283 17208 8282 17208 8191 17208 8283 17209 8192 17209 8193 17209 8283 17210 8193 17210 8194 17210 8284 17211 8194 17211 8195 17211 8284 17212 8283 17212 8194 17212 8284 17213 8195 17213 8176 17213 8285 17214 8176 17214 8179 17214 8285 17215 8284 17215 8176 17215 8175 17216 8179 17216 8174 17216 8175 17217 8285 17217 8179 17217 8043 17218 8042 17218 8046 17218 8286 17219 8046 17219 8045 17219 8287 17220 8046 17220 8286 17220 8043 17221 8046 17221 8287 17221 8286 17222 8045 17222 8048 17222 8049 17223 8286 17223 8048 17223 8288 17224 8287 17224 8286 17224 8288 17225 8286 17225 8289 17225 8290 17226 8289 17226 8286 17226 8290 17227 8286 17227 8049 17227 8043 17228 8287 17228 8288 17228 8291 17229 8292 17229 8293 17229 8294 17230 8293 17230 8292 17230 8295 17231 8291 17231 8293 17231 8296 17232 8295 17232 8293 17232 8294 17233 8296 17233 8293 17233 8297 17234 8298 17234 8292 17234 8299 17235 8292 17235 8298 17235 8291 17236 8297 17236 8292 17236 8300 17237 8294 17237 8292 17237 8299 17238 8300 17238 8292 17238 8301 17239 8302 17239 8298 17239 8303 17240 8298 17240 8302 17240 8297 17241 8301 17241 8298 17241 8303 17242 8299 17242 8298 17242 8301 17243 8304 17243 8302 17243 8305 17244 8302 17244 8304 17244 8305 17245 8303 17245 8302 17245 8306 17246 8307 17246 8304 17246 8305 17247 8304 17247 8307 17247 8301 17248 8306 17248 8304 17248 8308 17249 8309 17249 8307 17249 8310 17250 8307 17250 8309 17250 8306 17251 8308 17251 8307 17251 8310 17252 8305 17252 8307 17252 8311 17253 8312 17253 8309 17253 8313 17254 8309 17254 8312 17254 8308 17255 8311 17255 8309 17255 8313 17256 8310 17256 8309 17256 8314 17257 8315 17257 8312 17257 8316 17258 8312 17258 8315 17258 8311 17259 8314 17259 8312 17259 8316 17260 8313 17260 8312 17260 8317 17261 8318 17261 8315 17261 8316 17262 8315 17262 8318 17262 8314 17263 8317 17263 8315 17263 8319 17264 8320 17264 8318 17264 8321 17265 8318 17265 8320 17265 8317 17266 8319 17266 8318 17266 8321 17267 8316 17267 8318 17267 8322 17268 8323 17268 8320 17268 8321 17269 8320 17269 8323 17269 8319 17270 8322 17270 8320 17270 8324 17271 8325 17271 8323 17271 8326 17272 8323 17272 8325 17272 8322 17273 8324 17273 8323 17273 8326 17274 8321 17274 8323 17274 8327 17275 8328 17275 8325 17275 8326 17276 8325 17276 8328 17276 8324 17277 8327 17277 8325 17277 8329 17278 8330 17278 8328 17278 8331 17279 8328 17279 8330 17279 8327 17280 8329 17280 8328 17280 8331 17281 8326 17281 8328 17281 8332 17282 8333 17282 8330 17282 8334 17283 8330 17283 8333 17283 8329 17284 8332 17284 8330 17284 8334 17285 8331 17285 8330 17285 8335 17286 8336 17286 8333 17286 8334 17287 8333 17287 8336 17287 8332 17288 8335 17288 8333 17288 8337 17289 8338 17289 8336 17289 8339 17290 8336 17290 8338 17290 8340 17291 8337 17291 8336 17291 8335 17292 8340 17292 8336 17292 8339 17293 8334 17293 8336 17293 8341 17294 8342 17294 8338 17294 8343 17295 8338 17295 8342 17295 8337 17296 8341 17296 8338 17296 8343 17297 8339 17297 8338 17297 8344 17298 8345 17298 8342 17298 8343 17299 8342 17299 8345 17299 8341 17300 8344 17300 8342 17300 8346 17301 8347 17301 8345 17301 8348 17302 8345 17302 8347 17302 8344 17303 8346 17303 8345 17303 8348 17304 8343 17304 8345 17304 8349 17305 8350 17305 8347 17305 8348 17306 8347 17306 8350 17306 8346 17307 8349 17307 8347 17307 8351 17308 8352 17308 8350 17308 8353 17309 8350 17309 8352 17309 8349 17310 8351 17310 8350 17310 8353 17311 8348 17311 8350 17311 8354 17312 8355 17312 8352 17312 8356 17313 8352 17313 8355 17313 8351 17314 8354 17314 8352 17314 8356 17315 8353 17315 8352 17315 8357 17316 8358 17316 8355 17316 8356 17317 8355 17317 8358 17317 8354 17318 8357 17318 8355 17318 8357 17319 8359 17319 8358 17319 8360 17320 8358 17320 8359 17320 8360 17321 8356 17321 8358 17321 8357 17322 8361 17322 8359 17322 8362 17323 8359 17323 8361 17323 8362 17324 8360 17324 8359 17324 8363 17325 8364 17325 8361 17325 8365 17326 8361 17326 8364 17326 8366 17327 8363 17327 8361 17327 8357 17328 8366 17328 8361 17328 8365 17329 8362 17329 8361 17329 8367 17330 8368 17330 8364 17330 8369 17331 8364 17331 8368 17331 8363 17332 8367 17332 8364 17332 8369 17333 8365 17333 8364 17333 8370 17334 8371 17334 8368 17334 8372 17335 8368 17335 8371 17335 8367 17336 8370 17336 8368 17336 8373 17337 8369 17337 8368 17337 8372 17338 8373 17338 8368 17338 8374 17339 8375 17339 8371 17339 8372 17340 8371 17340 8375 17340 8370 17341 8374 17341 8371 17341 8376 17342 8377 17342 8375 17342 8378 17343 8375 17343 8377 17343 8374 17344 8376 17344 8375 17344 8378 17345 8372 17345 8375 17345 8379 17346 8380 17346 8377 17346 8381 17347 8377 17347 8380 17347 8376 17348 8379 17348 8377 17348 8381 17349 8378 17349 8377 17349 8382 17350 8383 17350 8380 17350 8381 17351 8380 17351 8383 17351 8379 17352 8382 17352 8380 17352 8384 17353 8385 17353 8383 17353 8386 17354 8383 17354 8385 17354 8387 17355 8384 17355 8383 17355 8382 17356 8387 17356 8383 17356 8386 17357 8381 17357 8383 17357 8388 17358 8389 17358 8385 17358 8390 17359 8385 17359 8389 17359 8384 17360 8388 17360 8385 17360 8390 17361 8386 17361 8385 17361 8391 17362 8392 17362 8389 17362 8390 17363 8389 17363 8392 17363 8388 17364 8391 17364 8389 17364 8393 17365 8394 17365 8392 17365 8395 17366 8392 17366 8394 17366 8396 17367 8393 17367 8392 17367 8391 17368 8396 17368 8392 17368 8395 17369 8390 17369 8392 17369 8397 17370 8398 17370 8394 17370 8395 17371 8394 17371 8398 17371 8393 17372 8397 17372 8394 17372 8399 17373 8400 17373 8398 17373 8401 17374 8398 17374 8400 17374 8397 17375 8399 17375 8398 17375 8401 17376 8395 17376 8398 17376 8402 17377 8403 17377 8400 17377 8401 17378 8400 17378 8403 17378 8399 17379 8402 17379 8400 17379 8404 17380 8405 17380 8403 17380 8406 17381 8403 17381 8405 17381 8402 17382 8404 17382 8403 17382 8406 17383 8401 17383 8403 17383 8407 17384 8408 17384 8405 17384 8406 17385 8405 17385 8408 17385 8404 17386 8407 17386 8405 17386 8409 17387 8410 17387 8408 17387 8411 17388 8408 17388 8410 17388 8407 17389 8409 17389 8408 17389 8411 17390 8406 17390 8408 17390 8412 17391 8413 17391 8410 17391 8411 17392 8410 17392 8413 17392 8409 17393 8412 17393 8410 17393 8414 17394 8415 17394 8413 17394 8416 17395 8413 17395 8415 17395 8412 17396 8414 17396 8413 17396 8416 17397 8411 17397 8413 17397 8417 17398 8418 17398 8415 17398 8416 17399 8415 17399 8418 17399 8414 17400 8417 17400 8415 17400 8419 17401 8420 17401 8418 17401 8421 17402 8418 17402 8420 17402 8417 17403 8419 17403 8418 17403 8421 17404 8416 17404 8418 17404 8422 17405 8423 17405 8420 17405 8421 17406 8420 17406 8423 17406 8424 17407 8422 17407 8420 17407 8419 17408 8424 17408 8420 17408 8425 17409 8426 17409 8423 17409 8427 17410 8423 17410 8426 17410 8422 17411 8425 17411 8423 17411 8427 17412 8421 17412 8423 17412 8428 17413 8289 17413 8426 17413 8290 17414 8426 17414 8289 17414 8425 17415 8428 17415 8426 17415 8290 17416 8427 17416 8426 17416 8428 17417 8288 17417 8289 17417 8429 17418 8288 17418 8428 17418 8429 17419 8043 17419 8288 17419 8429 17420 8428 17420 8425 17420 8430 17421 8425 17421 8422 17421 8430 17422 8429 17422 8425 17422 8430 17423 8422 17423 8424 17423 8431 17424 8424 17424 8419 17424 8431 17425 8430 17425 8424 17425 8431 17426 8419 17426 8417 17426 8431 17427 8417 17427 8414 17427 8432 17428 8414 17428 8412 17428 8432 17429 8431 17429 8414 17429 8432 17430 8412 17430 8409 17430 8433 17431 8409 17431 8407 17431 8433 17432 8432 17432 8409 17432 8434 17433 8407 17433 8404 17433 8434 17434 8433 17434 8407 17434 8434 17435 8404 17435 8402 17435 8434 17436 8402 17436 8399 17436 8435 17437 8399 17437 8397 17437 8435 17438 8434 17438 8399 17438 8435 17439 8397 17439 8393 17439 8436 17440 8393 17440 8396 17440 8436 17441 8435 17441 8393 17441 8436 17442 8396 17442 8391 17442 8436 17443 8391 17443 8388 17443 8437 17444 8388 17444 8384 17444 8437 17445 8436 17445 8388 17445 8437 17446 8384 17446 8387 17446 8438 17447 8387 17447 8382 17447 8438 17448 8437 17448 8387 17448 8439 17449 8382 17449 8379 17449 8439 17450 8438 17450 8382 17450 8439 17451 8379 17451 8376 17451 8440 17452 8376 17452 8374 17452 8440 17453 8439 17453 8376 17453 8441 17454 8374 17454 8370 17454 8441 17455 8440 17455 8374 17455 8442 17456 8370 17456 8367 17456 8442 17457 8441 17457 8370 17457 8443 17458 8367 17458 8363 17458 8443 17459 8442 17459 8367 17459 8444 17460 8363 17460 8366 17460 8444 17461 8443 17461 8363 17461 8445 17462 8366 17462 8357 17462 8445 17463 8444 17463 8366 17463 8446 17464 8357 17464 8354 17464 8446 17465 8445 17465 8357 17465 8447 17466 8354 17466 8351 17466 8447 17467 8446 17467 8354 17467 8448 17468 8351 17468 8349 17468 8448 17469 8447 17469 8351 17469 8448 17470 8349 17470 8346 17470 8449 17471 8346 17471 8344 17471 8449 17472 8448 17472 8346 17472 8450 17473 8344 17473 8341 17473 8450 17474 8449 17474 8344 17474 8450 17475 8341 17475 8337 17475 8451 17476 8337 17476 8340 17476 8451 17477 8450 17477 8337 17477 8451 17478 8340 17478 8335 17478 8452 17479 8335 17479 8332 17479 8452 17480 8451 17480 8335 17480 8452 17481 8332 17481 8329 17481 8453 17482 8329 17482 8327 17482 8453 17483 8452 17483 8329 17483 8454 17484 8327 17484 8324 17484 8454 17485 8453 17485 8327 17485 8454 17486 8324 17486 8322 17486 8455 17487 8322 17487 8319 17487 8455 17488 8454 17488 8322 17488 8455 17489 8319 17489 8317 17489 8456 17490 8317 17490 8314 17490 8456 17491 8455 17491 8317 17491 8457 17492 8314 17492 8311 17492 8457 17493 8456 17493 8314 17493 8457 17494 8311 17494 8308 17494 8458 17495 8308 17495 8306 17495 8458 17496 8457 17496 8308 17496 8458 17497 8306 17497 8301 17497 8459 17498 8301 17498 8297 17498 8459 17499 8458 17499 8301 17499 8460 17500 8297 17500 8291 17500 8461 17501 8459 17501 8297 17501 8460 17502 8461 17502 8297 17502 8462 17503 8291 17503 8295 17503 8462 17504 8460 17504 8291 17504 8463 17505 8295 17505 8296 17505 8250 17506 8295 17506 8463 17506 8464 17507 8295 17507 8250 17507 8462 17508 8295 17508 8464 17508 8465 17509 8463 17509 8296 17509 8162 17510 8465 17510 8296 17510 8162 17511 8296 17511 8160 17511 8466 17512 8160 17512 8296 17512 8467 17513 8466 17513 8296 17513 8468 17514 8469 17514 8470 17514 8294 17515 8467 17515 8296 17515 8471 17516 8463 17516 8465 17516 8250 17517 8463 17517 8471 17517 8472 17518 8473 17518 8474 17518 8164 17519 8474 17519 8473 17519 8475 17520 8472 17520 8474 17520 8476 17521 8475 17521 8474 17521 8165 17522 8476 17522 8474 17522 8165 17523 8474 17523 8164 17523 8471 17524 8465 17524 8473 17524 8163 17525 8473 17525 8465 17525 8472 17526 8471 17526 8473 17526 8163 17527 8164 17527 8473 17527 8163 17528 8465 17528 8162 17528 8247 17529 8471 17529 8472 17529 8250 17530 8471 17530 8247 17530 8245 17531 8472 17531 8475 17531 8247 17532 8472 17532 8245 17532 8477 17533 8475 17533 8476 17533 8243 17534 8475 17534 8477 17534 8245 17535 8475 17535 8243 17535 8478 17536 8479 17536 8063 17536 8064 17537 8063 17537 8479 17537 8062 17538 8478 17538 8063 17538 8480 17539 8481 17539 8479 17539 8060 17540 8479 17540 8481 17540 8478 17541 8480 17541 8479 17541 8068 17542 8479 17542 8067 17542 8060 17543 8067 17543 8479 17543 8069 17544 8479 17544 8068 17544 8070 17545 8479 17545 8069 17545 8064 17546 8479 17546 8070 17546 8482 17547 8483 17547 8481 17547 8173 17548 8481 17548 8483 17548 8480 17549 8482 17549 8481 17549 8060 17550 8481 17550 8173 17550 8484 17551 8485 17551 8483 17551 8172 17552 8483 17552 8485 17552 8482 17553 8484 17553 8483 17553 8173 17554 8483 17554 8172 17554 8484 17555 8486 17555 8485 17555 8172 17556 8485 17556 8486 17556 8487 17557 8488 17557 8486 17557 8171 17558 8486 17558 8488 17558 8484 17559 8487 17559 8486 17559 8172 17560 8486 17560 8171 17560 8489 17561 8490 17561 8488 17561 8170 17562 8488 17562 8490 17562 8487 17563 8489 17563 8488 17563 8171 17564 8488 17564 8170 17564 8491 17565 8492 17565 8490 17565 8170 17566 8490 17566 8492 17566 8489 17567 8491 17567 8490 17567 8491 17568 8493 17568 8492 17568 8169 17569 8492 17569 8493 17569 8170 17570 8492 17570 8169 17570 8494 17571 8495 17571 8493 17571 8169 17572 8493 17572 8495 17572 8491 17573 8494 17573 8493 17573 8496 17574 8497 17574 8495 17574 8168 17575 8495 17575 8497 17575 8494 17576 8496 17576 8495 17576 8169 17577 8495 17577 8168 17577 8496 17578 8498 17578 8497 17578 8168 17579 8497 17579 8498 17579 8499 17580 8500 17580 8498 17580 8167 17581 8498 17581 8500 17581 8496 17582 8499 17582 8498 17582 8168 17583 8498 17583 8167 17583 8501 17584 8502 17584 8500 17584 8167 17585 8500 17585 8502 17585 8499 17586 8501 17586 8500 17586 8503 17587 8504 17587 8502 17587 8167 17588 8502 17588 8504 17588 8501 17589 8503 17589 8502 17589 8503 17590 8505 17590 8504 17590 8166 17591 8504 17591 8505 17591 8167 17592 8504 17592 8166 17592 8506 17593 8507 17593 8505 17593 8166 17594 8505 17594 8507 17594 8503 17595 8506 17595 8505 17595 8508 17596 8509 17596 8507 17596 8165 17597 8507 17597 8509 17597 8506 17598 8508 17598 8507 17598 8166 17599 8507 17599 8165 17599 8477 17600 8476 17600 8509 17600 8165 17601 8509 17601 8476 17601 8508 17602 8477 17602 8509 17602 8238 17603 8477 17603 8508 17603 8238 17604 8243 17604 8477 17604 8238 17605 8508 17605 8506 17605 8232 17606 8506 17606 8503 17606 8232 17607 8238 17607 8506 17607 8232 17608 8503 17608 8501 17608 8230 17609 8501 17609 8499 17609 8230 17610 8232 17610 8501 17610 8230 17611 8499 17611 8496 17611 8225 17612 8496 17612 8494 17612 8225 17613 8230 17613 8496 17613 8220 17614 8494 17614 8491 17614 8220 17615 8225 17615 8494 17615 8220 17616 8491 17616 8489 17616 8216 17617 8489 17617 8487 17617 8216 17618 8220 17618 8489 17618 8212 17619 8487 17619 8484 17619 8212 17620 8216 17620 8487 17620 8206 17621 8484 17621 8482 17621 8206 17622 8212 17622 8484 17622 8198 17623 8482 17623 8480 17623 8198 17624 8206 17624 8482 17624 8187 17625 8480 17625 8478 17625 8187 17626 8198 17626 8480 17626 8182 17627 8478 17627 8062 17627 8187 17628 8478 17628 8182 17628 8180 17629 8062 17629 8061 17629 8181 17630 8062 17630 8180 17630 8182 17631 8062 17631 8181 17631 8184 17632 8182 17632 8183 17632 8178 17633 8182 17633 8184 17633 8060 17634 8053 17634 8065 17634 8060 17635 8065 17635 8066 17635 8060 17636 8066 17636 8067 17636 8510 17637 8032 17637 8031 17637 8511 17638 8030 17638 8032 17638 8512 17639 8511 17639 8032 17639 8513 17640 8512 17640 8032 17640 8514 17641 8513 17641 8032 17641 8515 17642 8514 17642 8032 17642 8516 17643 8515 17643 8032 17643 8516 17644 8032 17644 8510 17644 8517 17645 8031 17645 8038 17645 8518 17646 8519 17646 8031 17646 8520 17647 8031 17647 8519 17647 8521 17648 8518 17648 8031 17648 8522 17649 8521 17649 8031 17649 8517 17650 8522 17650 8031 17650 8523 17651 8510 17651 8031 17651 8524 17652 8523 17652 8031 17652 8525 17653 8524 17653 8031 17653 8526 17654 8525 17654 8031 17654 8527 17655 8526 17655 8031 17655 8528 17656 8527 17656 8031 17656 8520 17657 8528 17657 8031 17657 8028 17658 8030 17658 8511 17658 8529 17659 8511 17659 8512 17659 8529 17660 8028 17660 8511 17660 8530 17661 8512 17661 8513 17661 8529 17662 8512 17662 8530 17662 8530 17663 8513 17663 8514 17663 8515 17664 8531 17664 8514 17664 8532 17665 8514 17665 8531 17665 8530 17666 8514 17666 8532 17666 8515 17667 8533 17667 8531 17667 8532 17668 8531 17668 8533 17668 8534 17669 8535 17669 8533 17669 8536 17670 8533 17670 8535 17670 8515 17671 8534 17671 8533 17671 8532 17672 8533 17672 8536 17672 8534 17673 8537 17673 8535 17673 8536 17674 8535 17674 8537 17674 8534 17675 8538 17675 8537 17675 8539 17676 8537 17676 8538 17676 8536 17677 8537 17677 8539 17677 8534 17678 8540 17678 8538 17678 8539 17679 8538 17679 8540 17679 8534 17680 8541 17680 8540 17680 8539 17681 8540 17681 8541 17681 8542 17682 8543 17682 8541 17682 8544 17683 8541 17683 8543 17683 8534 17684 8542 17684 8541 17684 8539 17685 8541 17685 8544 17685 8542 17686 8545 17686 8543 17686 8544 17687 8543 17687 8545 17687 8542 17688 8546 17688 8545 17688 8547 17689 8545 17689 8546 17689 8544 17690 8545 17690 8547 17690 8542 17691 8548 17691 8546 17691 8549 17692 8546 17692 8548 17692 8547 17693 8546 17693 8549 17693 8550 17694 8551 17694 8548 17694 8549 17695 8548 17695 8551 17695 8542 17696 8550 17696 8548 17696 8550 17697 8552 17697 8551 17697 8553 17698 8551 17698 8552 17698 8549 17699 8551 17699 8553 17699 8550 17700 8554 17700 8552 17700 8555 17701 8552 17701 8554 17701 8553 17702 8552 17702 8555 17702 8556 17703 8557 17703 8554 17703 8558 17704 8554 17704 8557 17704 8550 17705 8556 17705 8554 17705 8555 17706 8554 17706 8558 17706 8556 17707 8559 17707 8557 17707 8560 17708 8557 17708 8559 17708 8558 17709 8557 17709 8560 17709 8561 17710 8562 17710 8559 17710 8563 17711 8559 17711 8562 17711 8556 17712 8561 17712 8559 17712 8560 17713 8559 17713 8563 17713 8561 17714 8564 17714 8562 17714 8565 17715 8562 17715 8564 17715 8563 17716 8562 17716 8565 17716 8566 17717 8567 17717 8564 17717 8568 17718 8564 17718 8567 17718 8561 17719 8566 17719 8564 17719 8565 17720 8564 17720 8568 17720 8569 17721 8570 17721 8567 17721 8571 17722 8567 17722 8570 17722 8566 17723 8569 17723 8567 17723 8568 17724 8567 17724 8571 17724 8572 17725 8573 17725 8570 17725 8574 17726 8570 17726 8573 17726 8569 17727 8572 17727 8570 17727 8571 17728 8570 17728 8574 17728 8575 17729 8576 17729 8573 17729 8577 17730 8573 17730 8576 17730 8572 17731 8575 17731 8573 17731 8578 17732 8573 17732 8577 17732 8574 17733 8573 17733 8578 17733 8579 17734 8580 17734 8576 17734 8581 17735 8576 17735 8580 17735 8582 17736 8579 17736 8576 17736 8575 17737 8582 17737 8576 17737 8583 17738 8576 17738 8581 17738 8577 17739 8576 17739 8583 17739 8584 17740 8585 17740 8580 17740 8586 17741 8580 17741 8585 17741 8587 17742 8584 17742 8580 17742 8579 17743 8587 17743 8580 17743 8581 17744 8580 17744 8586 17744 8588 17745 8589 17745 8585 17745 8590 17746 8585 17746 8589 17746 8591 17747 8588 17747 8585 17747 8592 17748 8591 17748 8585 17748 8584 17749 8592 17749 8585 17749 8593 17750 8585 17750 8590 17750 8586 17751 8585 17751 8593 17751 8594 17752 8595 17752 8589 17752 8596 17753 8589 17753 8595 17753 8597 17754 8594 17754 8589 17754 8598 17755 8597 17755 8589 17755 8599 17756 8598 17756 8589 17756 8588 17757 8599 17757 8589 17757 8600 17758 8589 17758 8596 17758 8601 17759 8589 17759 8600 17759 8590 17760 8589 17760 8601 17760 8602 17761 8603 17761 8595 17761 8604 17762 8595 17762 8603 17762 8605 17763 8602 17763 8595 17763 8606 17764 8605 17764 8595 17764 8607 17765 8606 17765 8595 17765 8594 17766 8607 17766 8595 17766 8608 17767 8595 17767 8604 17767 8596 17768 8595 17768 8608 17768 8609 17769 8610 17769 8603 17769 8611 17770 8603 17770 8610 17770 8612 17771 8609 17771 8603 17771 8613 17772 8612 17772 8603 17772 8614 17773 8613 17773 8603 17773 8615 17774 8614 17774 8603 17774 8616 17775 8615 17775 8603 17775 8617 17776 8616 17776 8603 17776 8618 17777 8617 17777 8603 17777 8602 17778 8618 17778 8603 17778 8619 17779 8603 17779 8611 17779 8620 17780 8603 17780 8619 17780 8604 17781 8603 17781 8620 17781 8621 17782 8610 17782 8609 17782 8622 17783 8610 17783 8621 17783 8623 17784 8610 17784 8622 17784 8611 17785 8610 17785 8623 17785 8621 17786 8609 17786 8612 17786 8624 17787 8612 17787 8613 17787 8624 17788 8621 17788 8612 17788 8625 17789 8613 17789 8614 17789 8625 17790 8624 17790 8613 17790 8625 17791 8614 17791 8615 17791 8626 17792 8615 17792 8616 17792 8625 17793 8615 17793 8626 17793 8626 17794 8616 17794 8617 17794 8626 17795 8617 17795 8618 17795 8627 17796 8618 17796 8602 17796 8627 17797 8626 17797 8618 17797 8627 17798 8602 17798 8605 17798 8627 17799 8605 17799 8606 17799 8627 17800 8606 17800 8607 17800 8628 17801 8607 17801 8594 17801 8628 17802 8627 17802 8607 17802 8628 17803 8594 17803 8597 17803 8628 17804 8597 17804 8598 17804 8628 17805 8598 17805 8599 17805 8629 17806 8599 17806 8588 17806 8629 17807 8628 17807 8599 17807 8629 17808 8588 17808 8591 17808 8629 17809 8591 17809 8592 17809 8630 17810 8592 17810 8584 17810 8630 17811 8629 17811 8592 17811 8630 17812 8584 17812 8587 17812 8630 17813 8587 17813 8579 17813 8631 17814 8579 17814 8582 17814 8631 17815 8630 17815 8579 17815 8631 17816 8582 17816 8575 17816 8632 17817 8575 17817 8572 17817 8632 17818 8631 17818 8575 17818 8632 17819 8572 17819 8569 17819 8633 17820 8569 17820 8566 17820 8633 17821 8632 17821 8569 17821 8634 17822 8566 17822 8561 17822 8634 17823 8633 17823 8566 17823 8635 17824 8561 17824 8556 17824 8635 17825 8634 17825 8561 17825 8635 17826 8556 17826 8550 17826 8636 17827 8550 17827 8542 17827 8636 17828 8635 17828 8550 17828 8637 17829 8542 17829 8534 17829 8637 17830 8636 17830 8542 17830 8516 17831 8534 17831 8515 17831 8516 17832 8637 17832 8534 17832 8638 17833 8639 17833 8640 17833 8641 17834 8640 17834 8639 17834 8642 17835 8638 17835 8640 17835 8643 17836 8642 17836 8640 17836 8644 17837 8643 17837 8640 17837 8641 17838 8644 17838 8640 17838 8638 17839 8645 17839 8639 17839 8646 17840 8639 17840 8645 17840 8647 17841 8641 17841 8639 17841 8646 17842 8647 17842 8639 17842 8638 17843 8648 17843 8645 17843 8649 17844 8645 17844 8648 17844 8649 17845 8646 17845 8645 17845 8638 17846 8650 17846 8648 17846 8649 17847 8648 17847 8650 17847 8651 17848 8650 17848 8638 17848 8652 17849 8649 17849 8650 17849 8653 17850 8652 17850 8650 17850 8651 17851 8653 17851 8650 17851 8654 17852 8638 17852 8642 17852 8654 17853 8651 17853 8638 17853 8643 17854 8655 17854 8642 17854 8654 17855 8642 17855 8655 17855 8656 17856 8657 17856 8655 17856 8658 17857 8655 17857 8657 17857 8643 17858 8656 17858 8655 17858 8658 17859 8654 17859 8655 17859 8659 17860 8660 17860 8657 17860 8661 17861 8657 17861 8660 17861 8656 17862 8659 17862 8657 17862 8661 17863 8658 17863 8657 17863 8662 17864 8663 17864 8660 17864 8664 17865 8660 17865 8663 17865 8665 17866 8662 17866 8660 17866 8659 17867 8665 17867 8660 17867 8664 17868 8661 17868 8660 17868 8666 17869 8667 17869 8663 17869 8668 17870 8663 17870 8667 17870 8662 17871 8666 17871 8663 17871 8668 17872 8664 17872 8663 17872 8669 17873 8670 17873 8667 17873 8671 17874 8667 17874 8670 17874 8666 17875 8669 17875 8667 17875 8671 17876 8668 17876 8667 17876 8672 17877 8673 17877 8670 17877 8674 17878 8670 17878 8673 17878 8669 17879 8672 17879 8670 17879 8674 17880 8671 17880 8670 17880 8675 17881 8676 17881 8673 17881 8677 17882 8673 17882 8676 17882 8678 17883 8675 17883 8673 17883 8672 17884 8678 17884 8673 17884 8677 17885 8674 17885 8673 17885 8679 17886 8680 17886 8676 17886 8681 17887 8676 17887 8680 17887 8675 17888 8679 17888 8676 17888 8681 17889 8677 17889 8676 17889 8682 17890 8683 17890 8680 17890 8684 17891 8680 17891 8683 17891 8679 17892 8682 17892 8680 17892 8684 17893 8681 17893 8680 17893 8682 17894 8685 17894 8683 17894 8686 17895 8683 17895 8685 17895 8686 17896 8684 17896 8683 17896 8687 17897 8688 17897 8685 17897 8686 17898 8685 17898 8688 17898 8682 17899 8687 17899 8685 17899 8689 17900 8690 17900 8688 17900 8691 17901 8688 17901 8690 17901 8692 17902 8689 17902 8688 17902 8687 17903 8692 17903 8688 17903 8691 17904 8686 17904 8688 17904 8693 17905 8694 17905 8690 17905 8695 17906 8690 17906 8694 17906 8689 17907 8693 17907 8690 17907 8696 17908 8691 17908 8690 17908 8697 17909 8696 17909 8690 17909 8695 17910 8697 17910 8690 17910 8698 17911 8699 17911 8694 17911 8700 17912 8694 17912 8699 17912 8693 17913 8698 17913 8694 17913 8701 17914 8695 17914 8694 17914 8700 17915 8701 17915 8694 17915 8702 17916 8703 17916 8699 17916 8704 17917 8699 17917 8703 17917 8698 17918 8702 17918 8699 17918 8705 17919 8700 17919 8699 17919 8704 17920 8705 17920 8699 17920 8706 17921 8707 17921 8703 17921 8708 17922 8703 17922 8707 17922 8702 17923 8706 17923 8703 17923 8708 17924 8704 17924 8703 17924 8709 17925 8710 17925 8707 17925 8711 17926 8707 17926 8710 17926 8706 17927 8709 17927 8707 17927 8712 17928 8708 17928 8707 17928 8711 17929 8712 17929 8707 17929 8709 17930 8713 17930 8710 17930 8714 17931 8710 17931 8713 17931 8714 17932 8711 17932 8710 17932 8709 17933 8715 17933 8713 17933 8714 17934 8713 17934 8715 17934 8716 17935 8717 17935 8715 17935 8718 17936 8715 17936 8717 17936 8709 17937 8716 17937 8715 17937 8718 17938 8714 17938 8715 17938 8716 17939 8719 17939 8717 17939 8720 17940 8717 17940 8719 17940 8720 17941 8718 17941 8717 17941 8716 17942 8721 17942 8719 17942 8720 17943 8719 17943 8721 17943 8722 17944 8723 17944 8721 17944 8724 17945 8721 17945 8723 17945 8716 17946 8722 17946 8721 17946 8724 17947 8720 17947 8721 17947 8722 17948 8725 17948 8723 17948 8724 17949 8723 17949 8725 17949 8722 17950 8726 17950 8725 17950 8727 17951 8725 17951 8726 17951 8727 17952 8724 17952 8725 17952 8722 17953 8728 17953 8726 17953 8729 17954 8726 17954 8728 17954 8729 17955 8727 17955 8726 17955 8730 17956 8731 17956 8728 17956 8732 17957 8728 17957 8731 17957 8722 17958 8730 17958 8728 17958 8732 17959 8729 17959 8728 17959 8730 17960 8733 17960 8731 17960 8732 17961 8731 17961 8733 17961 8730 17962 8734 17962 8733 17962 8735 17963 8733 17963 8734 17963 8735 17964 8732 17964 8733 17964 8736 17965 8737 17965 8734 17965 8735 17966 8734 17966 8737 17966 8730 17967 8736 17967 8734 17967 8736 17968 8738 17968 8737 17968 8739 17969 8737 17969 8738 17969 8739 17970 8735 17970 8737 17970 8736 17971 8740 17971 8738 17971 8741 17972 8738 17972 8740 17972 8741 17973 8739 17973 8738 17973 8038 17974 8742 17974 8740 17974 8743 17975 8740 17975 8742 17975 8736 17976 8038 17976 8740 17976 8743 17977 8741 17977 8740 17977 8038 17978 8018 17978 8742 17978 8743 17979 8742 17979 8018 17979 8743 17980 8018 17980 8020 17980 8744 17981 8038 17981 8736 17981 8745 17982 8517 17982 8038 17982 8746 17983 8745 17983 8038 17983 8747 17984 8746 17984 8038 17984 8748 17985 8747 17985 8038 17985 8744 17986 8748 17986 8038 17986 8748 17987 8736 17987 8730 17987 8744 17988 8736 17988 8748 17988 8749 17989 8730 17989 8722 17989 8749 17990 8748 17990 8730 17990 8750 17991 8722 17991 8716 17991 8750 17992 8749 17992 8722 17992 8751 17993 8716 17993 8709 17993 8751 17994 8750 17994 8716 17994 8752 17995 8709 17995 8706 17995 8752 17996 8751 17996 8709 17996 8753 17997 8706 17997 8702 17997 8753 17998 8752 17998 8706 17998 8754 17999 8702 17999 8698 17999 8754 18000 8753 18000 8702 18000 8754 18001 8698 18001 8693 18001 8755 18002 8693 18002 8689 18002 8755 18003 8754 18003 8693 18003 8755 18004 8689 18004 8692 18004 8756 18005 8692 18005 8687 18005 8756 18006 8755 18006 8692 18006 8756 18007 8687 18007 8682 18007 8757 18008 8682 18008 8679 18008 8757 18009 8756 18009 8682 18009 8757 18010 8679 18010 8675 18010 8758 18011 8675 18011 8678 18011 8758 18012 8757 18012 8675 18012 8758 18013 8678 18013 8672 18013 8758 18014 8672 18014 8669 18014 8758 18015 8669 18015 8666 18015 8759 18016 8666 18016 8662 18016 8759 18017 8758 18017 8666 18017 8759 18018 8662 18018 8665 18018 8759 18019 8665 18019 8659 18019 8644 18020 8659 18020 8656 18020 8644 18021 8759 18021 8659 18021 8644 18022 8656 18022 8643 18022 8022 18023 8021 18023 8024 18023 8027 18024 8024 18024 8023 18024 8760 18025 8024 18025 8027 18025 8022 18026 8024 18026 8760 18026 8027 18027 8023 18027 8026 18027 8761 18028 8760 18028 8027 18028 8762 18029 8761 18029 8027 18029 8762 18030 8027 18030 8025 18030 8763 18031 8760 18031 8761 18031 8022 18032 8760 18032 8763 18032 8764 18033 8765 18033 8766 18033 8767 18034 8766 18034 8765 18034 8768 18035 8764 18035 8766 18035 8769 18036 8768 18036 8766 18036 8767 18037 8769 18037 8766 18037 8764 18038 8770 18038 8765 18038 8771 18039 8765 18039 8770 18039 8771 18040 8767 18040 8765 18040 8772 18041 8773 18041 8770 18041 8771 18042 8770 18042 8773 18042 8764 18043 8772 18043 8770 18043 8774 18044 8775 18044 8773 18044 8776 18045 8773 18045 8775 18045 8772 18046 8774 18046 8773 18046 8776 18047 8771 18047 8773 18047 8777 18048 8778 18048 8775 18048 8776 18049 8775 18049 8778 18049 8774 18050 8777 18050 8775 18050 8779 18051 8780 18051 8778 18051 8781 18052 8778 18052 8780 18052 8777 18053 8779 18053 8778 18053 8781 18054 8776 18054 8778 18054 8782 18055 8783 18055 8780 18055 8784 18056 8780 18056 8783 18056 8779 18057 8782 18057 8780 18057 8784 18058 8781 18058 8780 18058 8785 18059 8786 18059 8783 18059 8787 18060 8783 18060 8786 18060 8782 18061 8785 18061 8783 18061 8787 18062 8784 18062 8783 18062 8788 18063 8789 18063 8786 18063 8787 18064 8786 18064 8789 18064 8785 18065 8788 18065 8786 18065 8790 18066 8791 18066 8789 18066 8792 18067 8789 18067 8791 18067 8788 18068 8790 18068 8789 18068 8792 18069 8787 18069 8789 18069 8793 18070 8794 18070 8791 18070 8792 18071 8791 18071 8794 18071 8790 18072 8793 18072 8791 18072 8795 18073 8796 18073 8794 18073 8797 18074 8794 18074 8796 18074 8793 18075 8795 18075 8794 18075 8797 18076 8792 18076 8794 18076 8798 18077 8799 18077 8796 18077 8800 18078 8796 18078 8799 18078 8795 18079 8798 18079 8796 18079 8800 18080 8797 18080 8796 18080 8801 18081 8802 18081 8799 18081 8800 18082 8799 18082 8802 18082 8798 18083 8801 18083 8799 18083 8803 18084 8804 18084 8802 18084 8805 18085 8802 18085 8804 18085 8801 18086 8803 18086 8802 18086 8805 18087 8800 18087 8802 18087 8806 18088 8807 18088 8804 18088 8805 18089 8804 18089 8807 18089 8803 18090 8806 18090 8804 18090 8808 18091 8809 18091 8807 18091 8810 18092 8807 18092 8809 18092 8806 18093 8808 18093 8807 18093 8810 18094 8805 18094 8807 18094 8811 18095 8812 18095 8809 18095 8813 18096 8809 18096 8812 18096 8808 18097 8811 18097 8809 18097 8813 18098 8810 18098 8809 18098 8814 18099 8815 18099 8812 18099 8813 18100 8812 18100 8815 18100 8811 18101 8814 18101 8812 18101 8816 18102 8817 18102 8815 18102 8818 18103 8815 18103 8817 18103 8814 18104 8816 18104 8815 18104 8818 18105 8813 18105 8815 18105 8819 18106 8820 18106 8817 18106 8821 18107 8817 18107 8820 18107 8816 18108 8819 18108 8817 18108 8821 18109 8818 18109 8817 18109 8822 18110 8823 18110 8820 18110 8821 18111 8820 18111 8823 18111 8819 18112 8822 18112 8820 18112 8824 18113 8825 18113 8823 18113 8826 18114 8823 18114 8825 18114 8822 18115 8824 18115 8823 18115 8826 18116 8821 18116 8823 18116 8827 18117 8828 18117 8825 18117 8826 18118 8825 18118 8828 18118 8824 18119 8827 18119 8825 18119 8827 18120 8829 18120 8828 18120 8830 18121 8828 18121 8829 18121 8830 18122 8826 18122 8828 18122 8831 18123 8832 18123 8829 18123 8830 18124 8829 18124 8832 18124 8827 18125 8831 18125 8829 18125 8833 18126 8834 18126 8832 18126 8835 18127 8832 18127 8834 18127 8836 18128 8833 18128 8832 18128 8831 18129 8836 18129 8832 18129 8835 18130 8830 18130 8832 18130 8837 18131 8838 18131 8834 18131 8839 18132 8834 18132 8838 18132 8840 18133 8837 18133 8834 18133 8833 18134 8840 18134 8834 18134 8841 18135 8835 18135 8834 18135 8839 18136 8841 18136 8834 18136 8842 18137 8843 18137 8838 18137 8844 18138 8838 18138 8843 18138 8837 18139 8842 18139 8838 18139 8844 18140 8839 18140 8838 18140 8845 18141 8846 18141 8843 18141 8847 18142 8843 18142 8846 18142 8842 18143 8845 18143 8843 18143 8848 18144 8844 18144 8843 18144 8847 18145 8848 18145 8843 18145 8849 18146 8850 18146 8846 18146 8851 18147 8846 18147 8850 18147 8845 18148 8849 18148 8846 18148 8851 18149 8847 18149 8846 18149 8852 18150 8853 18150 8850 18150 8854 18151 8850 18151 8853 18151 8849 18152 8852 18152 8850 18152 8854 18153 8851 18153 8850 18153 8855 18154 8856 18154 8853 18154 8857 18155 8853 18155 8856 18155 8852 18156 8855 18156 8853 18156 8857 18157 8854 18157 8853 18157 8858 18158 8859 18158 8856 18158 8857 18159 8856 18159 8859 18159 8855 18160 8858 18160 8856 18160 8860 18161 8861 18161 8859 18161 8862 18162 8859 18162 8861 18162 8858 18163 8860 18163 8859 18163 8862 18164 8857 18164 8859 18164 8863 18165 8864 18165 8861 18165 8865 18166 8861 18166 8864 18166 8866 18167 8863 18167 8861 18167 8860 18168 8866 18168 8861 18168 8865 18169 8862 18169 8861 18169 8867 18170 8868 18170 8864 18170 8865 18171 8864 18171 8868 18171 8863 18172 8867 18172 8864 18172 8869 18173 8870 18173 8868 18173 8871 18174 8868 18174 8870 18174 8867 18175 8869 18175 8868 18175 8871 18176 8865 18176 8868 18176 8872 18177 8873 18177 8870 18177 8871 18178 8870 18178 8873 18178 8869 18179 8872 18179 8870 18179 8874 18180 8875 18180 8873 18180 8876 18181 8873 18181 8875 18181 8872 18182 8874 18182 8873 18182 8876 18183 8871 18183 8873 18183 8874 18184 8877 18184 8875 18184 8876 18185 8875 18185 8877 18185 8878 18186 8879 18186 8877 18186 8880 18187 8877 18187 8879 18187 8874 18188 8878 18188 8877 18188 8880 18189 8876 18189 8877 18189 8878 18190 8881 18190 8879 18190 8880 18191 8879 18191 8881 18191 8882 18192 8883 18192 8881 18192 8884 18193 8881 18193 8883 18193 8878 18194 8882 18194 8881 18194 8884 18195 8880 18195 8881 18195 8885 18196 8886 18196 8883 18196 8884 18197 8883 18197 8886 18197 8882 18198 8885 18198 8883 18198 8887 18199 8888 18199 8886 18199 8889 18200 8886 18200 8888 18200 8885 18201 8887 18201 8886 18201 8889 18202 8884 18202 8886 18202 8890 18203 8891 18203 8888 18203 8889 18204 8888 18204 8891 18204 8887 18205 8890 18205 8888 18205 8892 18206 8893 18206 8891 18206 8894 18207 8891 18207 8893 18207 8890 18208 8892 18208 8891 18208 8894 18209 8889 18209 8891 18209 8763 18210 8761 18210 8893 18210 8762 18211 8893 18211 8761 18211 8892 18212 8763 18212 8893 18212 8762 18213 8894 18213 8893 18213 8895 18214 8763 18214 8892 18214 8895 18215 8022 18215 8763 18215 8896 18216 8892 18216 8890 18216 8896 18217 8895 18217 8892 18217 8896 18218 8890 18218 8887 18218 8897 18219 8887 18219 8885 18219 8897 18220 8896 18220 8887 18220 8897 18221 8885 18221 8882 18221 8898 18222 8882 18222 8878 18222 8898 18223 8897 18223 8882 18223 8899 18224 8878 18224 8874 18224 8899 18225 8898 18225 8878 18225 8900 18226 8874 18226 8872 18226 8900 18227 8899 18227 8874 18227 8900 18228 8872 18228 8869 18228 8901 18229 8869 18229 8867 18229 8901 18230 8900 18230 8869 18230 8901 18231 8867 18231 8863 18231 8902 18232 8863 18232 8866 18232 8902 18233 8901 18233 8863 18233 8902 18234 8866 18234 8860 18234 8903 18235 8860 18235 8858 18235 8903 18236 8902 18236 8860 18236 8904 18237 8858 18237 8855 18237 8904 18238 8903 18238 8858 18238 8905 18239 8855 18239 8852 18239 8905 18240 8904 18240 8855 18240 8906 18241 8852 18241 8849 18241 8906 18242 8905 18242 8852 18242 8907 18243 8849 18243 8845 18243 8907 18244 8906 18244 8849 18244 8908 18245 8845 18245 8842 18245 8908 18246 8907 18246 8845 18246 8909 18247 8842 18247 8837 18247 8909 18248 8908 18248 8842 18248 8910 18249 8837 18249 8840 18249 8910 18250 8909 18250 8837 18250 8911 18251 8840 18251 8833 18251 8911 18252 8910 18252 8840 18252 8911 18253 8833 18253 8836 18253 8912 18254 8836 18254 8831 18254 8912 18255 8911 18255 8836 18255 8913 18256 8831 18256 8827 18256 8913 18257 8912 18257 8831 18257 8913 18258 8827 18258 8824 18258 8914 18259 8824 18259 8822 18259 8914 18260 8913 18260 8824 18260 8915 18261 8822 18261 8819 18261 8915 18262 8914 18262 8822 18262 8915 18263 8819 18263 8816 18263 8916 18264 8816 18264 8814 18264 8916 18265 8915 18265 8816 18265 8917 18266 8814 18266 8811 18266 8917 18267 8916 18267 8814 18267 8917 18268 8811 18268 8808 18268 8918 18269 8808 18269 8806 18269 8918 18270 8917 18270 8808 18270 8919 18271 8806 18271 8803 18271 8919 18272 8918 18272 8806 18272 8919 18273 8803 18273 8801 18273 8920 18274 8801 18274 8798 18274 8920 18275 8919 18275 8801 18275 8920 18276 8798 18276 8795 18276 8921 18277 8795 18277 8793 18277 8921 18278 8920 18278 8795 18278 8922 18279 8793 18279 8790 18279 8922 18280 8921 18280 8793 18280 8922 18281 8790 18281 8788 18281 8923 18282 8788 18282 8785 18282 8923 18283 8922 18283 8788 18283 8924 18284 8785 18284 8782 18284 8924 18285 8923 18285 8785 18285 8924 18286 8782 18286 8779 18286 8925 18287 8779 18287 8777 18287 8925 18288 8924 18288 8779 18288 8926 18289 8777 18289 8774 18289 8926 18290 8925 18290 8777 18290 8926 18291 8774 18291 8772 18291 8927 18292 8772 18292 8764 18292 8927 18293 8926 18293 8772 18293 8928 18294 8764 18294 8768 18294 8927 18295 8764 18295 8928 18295 8929 18296 8768 18296 8769 18296 8652 18297 8768 18297 8929 18297 8928 18298 8768 18298 8652 18298 8930 18299 8929 18299 8769 18299 8624 18300 8930 18300 8769 18300 8624 18301 8769 18301 8621 18301 8931 18302 8621 18302 8769 18302 8932 18303 8931 18303 8769 18303 8767 18304 8932 18304 8769 18304 8933 18305 8929 18305 8930 18305 8652 18306 8929 18306 8933 18306 8934 18307 8935 18307 8936 18307 8937 18308 8936 18308 8935 18308 8938 18309 8934 18309 8936 18309 8939 18310 8938 18310 8936 18310 8940 18311 8939 18311 8936 18311 8940 18312 8936 18312 8937 18312 8933 18313 8930 18313 8935 18313 8625 18314 8935 18314 8930 18314 8934 18315 8933 18315 8935 18315 8937 18316 8935 18316 8941 18316 8625 18317 8941 18317 8935 18317 8625 18318 8930 18318 8624 18318 8649 18319 8933 18319 8934 18319 8652 18320 8933 18320 8649 18320 8646 18321 8934 18321 8938 18321 8649 18322 8934 18322 8646 18322 8942 18323 8938 18323 8939 18323 8943 18324 8938 18324 8942 18324 8646 18325 8938 18325 8943 18325 8944 18326 8945 18326 8519 18326 8520 18327 8519 18327 8945 18327 8518 18328 8944 18328 8519 18328 8944 18329 8946 18329 8945 18329 8947 18330 8945 18330 8946 18330 8520 18331 8945 18331 8528 18331 8947 18332 8528 18332 8945 18332 8948 18333 8949 18333 8946 18333 8947 18334 8946 18334 8949 18334 8944 18335 8948 18335 8946 18335 8950 18336 8951 18336 8949 18336 8952 18337 8949 18337 8951 18337 8948 18338 8950 18338 8949 18338 8947 18339 8949 18339 8952 18339 8953 18340 8954 18340 8951 18340 8955 18341 8951 18341 8954 18341 8950 18342 8953 18342 8951 18342 8952 18343 8951 18343 8955 18343 8956 18344 8957 18344 8954 18344 8958 18345 8954 18345 8957 18345 8953 18346 8956 18346 8954 18346 8955 18347 8954 18347 8958 18347 8959 18348 8960 18348 8957 18348 8958 18349 8957 18349 8960 18349 8956 18350 8959 18350 8957 18350 8961 18351 8962 18351 8960 18351 8963 18352 8960 18352 8962 18352 8959 18353 8961 18353 8960 18353 8958 18354 8960 18354 8963 18354 8961 18355 8964 18355 8962 18355 8965 18356 8962 18356 8964 18356 8963 18357 8962 18357 8965 18357 8966 18358 8967 18358 8964 18358 8965 18359 8964 18359 8967 18359 8961 18360 8966 18360 8964 18360 8968 18361 8969 18361 8967 18361 8970 18362 8967 18362 8969 18362 8966 18363 8968 18363 8967 18363 8965 18364 8967 18364 8970 18364 8971 18365 8972 18365 8969 18365 8970 18366 8969 18366 8972 18366 8968 18367 8971 18367 8969 18367 8973 18368 8974 18368 8972 18368 8975 18369 8972 18369 8974 18369 8971 18370 8973 18370 8972 18370 8970 18371 8972 18371 8975 18371 8976 18372 8977 18372 8974 18372 8975 18373 8974 18373 8977 18373 8973 18374 8976 18374 8974 18374 8976 18375 8978 18375 8977 18375 8975 18376 8977 18376 8978 18376 8979 18377 8980 18377 8978 18377 8981 18378 8978 18378 8980 18378 8976 18379 8979 18379 8978 18379 8975 18380 8978 18380 8981 18380 8982 18381 8983 18381 8980 18381 8981 18382 8980 18382 8983 18382 8979 18383 8982 18383 8980 18383 8984 18384 8985 18384 8983 18384 8981 18385 8983 18385 8985 18385 8982 18386 8984 18386 8983 18386 8986 18387 8987 18387 8985 18387 8988 18388 8985 18388 8987 18388 8984 18389 8986 18389 8985 18389 8981 18390 8985 18390 8988 18390 8989 18391 8990 18391 8987 18391 8988 18392 8987 18392 8990 18392 8986 18393 8989 18393 8987 18393 8989 18394 8991 18394 8990 18394 8988 18395 8990 18395 8991 18395 8992 18396 8993 18396 8991 18396 8988 18397 8991 18397 8993 18397 8989 18398 8992 18398 8991 18398 8994 18399 8995 18399 8993 18399 8996 18400 8993 18400 8995 18400 8992 18401 8994 18401 8993 18401 8988 18402 8993 18402 8996 18402 8997 18403 8998 18403 8995 18403 8996 18404 8995 18404 8998 18404 8994 18405 8997 18405 8995 18405 8999 18406 9000 18406 8998 18406 8996 18407 8998 18407 9000 18407 8997 18408 8999 18408 8998 18408 9001 18409 9002 18409 9000 18409 8996 18410 9000 18410 9002 18410 8999 18411 9001 18411 9000 18411 9001 18412 9003 18412 9002 18412 8940 18413 9002 18413 9003 18413 8996 18414 9002 18414 8940 18414 9004 18415 9005 18415 9003 18415 8940 18416 9003 18416 9005 18416 9001 18417 9004 18417 9003 18417 8942 18418 8939 18418 9005 18418 8940 18419 9005 18419 8939 18419 9004 18420 8942 18420 9005 18420 8943 18421 8942 18421 9004 18421 9006 18422 9004 18422 9001 18422 9006 18423 8943 18423 9004 18423 9006 18424 9001 18424 8999 18424 9006 18425 8999 18425 8997 18425 9006 18426 8997 18426 8994 18426 9007 18427 8994 18427 8992 18427 9007 18428 9006 18428 8994 18428 9007 18429 8992 18429 8989 18429 9007 18430 8989 18430 8986 18430 9008 18431 8986 18431 8984 18431 9008 18432 9007 18432 8986 18432 9008 18433 8984 18433 8982 18433 9008 18434 8982 18434 8979 18434 9009 18435 8979 18435 8976 18435 9009 18436 9008 18436 8979 18436 9009 18437 8976 18437 8973 18437 9010 18438 8973 18438 8971 18438 9010 18439 9009 18439 8973 18439 9011 18440 8971 18440 8968 18440 9011 18441 9010 18441 8971 18441 9011 18442 8968 18442 8966 18442 9012 18443 8966 18443 8961 18443 9012 18444 9011 18444 8966 18444 9013 18445 8961 18445 8959 18445 9013 18446 9012 18446 8961 18446 9014 18447 8959 18447 8956 18447 9014 18448 9013 18448 8959 18448 9015 18449 8956 18449 8953 18449 9015 18450 9014 18450 8956 18450 9015 18451 8953 18451 8950 18451 9016 18452 8950 18452 8948 18452 9016 18453 9015 18453 8950 18453 9017 18454 8948 18454 8944 18454 9017 18455 9016 18455 8948 18455 8522 18456 8944 18456 8518 18456 9017 18457 8944 18457 8522 18457 8522 18458 8518 18458 8521 18458 8745 18459 8522 18459 8517 18459 9017 18460 8522 18460 8745 18460 8747 18461 8745 18461 8746 18461 8748 18462 8745 18462 8747 18462 9018 18463 8745 18463 8748 18463 9018 18464 9017 18464 8745 18464 9018 18465 8748 18465 8749 18465 8516 18466 8510 18466 8523 18466 9019 18467 8523 18467 8524 18467 9019 18468 8516 18468 8523 18468 9019 18469 8524 18469 8525 18469 9019 18470 8525 18470 8526 18470 8947 18471 8526 18471 8527 18471 8947 18472 9019 18472 8526 18472 8947 18473 8527 18473 8528 18473 8941 18474 8626 18474 8627 18474 8625 18475 8626 18475 8941 18475 9020 18476 8627 18476 8628 18476 9020 18477 8941 18477 8627 18477 9021 18478 8628 18478 8629 18478 9021 18479 9020 18479 8628 18479 9022 18480 8629 18480 8630 18480 9022 18481 9021 18481 8629 18481 9023 18482 8630 18482 8631 18482 9023 18483 9022 18483 8630 18483 9024 18484 8631 18484 8632 18484 9024 18485 9023 18485 8631 18485 9025 18486 8632 18486 8633 18486 9025 18487 9024 18487 8632 18487 9026 18488 8633 18488 8634 18488 9026 18489 9025 18489 8633 18489 9027 18490 8634 18490 8635 18490 9027 18491 9026 18491 8634 18491 9028 18492 8635 18492 8636 18492 9028 18493 9027 18493 8635 18493 9029 18494 8636 18494 8637 18494 9029 18495 9028 18495 8636 18495 9030 18496 8637 18496 8516 18496 9030 18497 9029 18497 8637 18497 9019 18498 9030 18498 8516 18498 8937 18499 8941 18499 9020 18499 8940 18500 9020 18500 9021 18500 8940 18501 8937 18501 9020 18501 8996 18502 9021 18502 9022 18502 8996 18503 8940 18503 9021 18503 8988 18504 9022 18504 9023 18504 8988 18505 8996 18505 9022 18505 8981 18506 9023 18506 9024 18506 8981 18507 8988 18507 9023 18507 8975 18508 9024 18508 9025 18508 8975 18509 8981 18509 9024 18509 8970 18510 9025 18510 9026 18510 8970 18511 8975 18511 9025 18511 8965 18512 9026 18512 9027 18512 8965 18513 8970 18513 9026 18513 8963 18514 9027 18514 9028 18514 8963 18515 8965 18515 9027 18515 8958 18516 9028 18516 9029 18516 8958 18517 8963 18517 9028 18517 8955 18518 9029 18518 9030 18518 8955 18519 8958 18519 9029 18519 8952 18520 9030 18520 9019 18520 8952 18521 8955 18521 9030 18521 8947 18522 8952 18522 9019 18522 9031 18523 8622 18523 8621 18523 8931 18524 9031 18524 8621 18524 9032 18525 8622 18525 9031 18525 8623 18526 8622 18526 9032 18526 9032 18527 9031 18527 8931 18527 8771 18528 8931 18528 8932 18528 9032 18529 8931 18529 8771 18529 8771 18530 8932 18530 8767 18530 9033 18531 8025 18531 8029 18531 9033 18532 8762 18532 8025 18532 8529 18533 8029 18533 8028 18533 8529 18534 9033 18534 8029 18534 9032 18535 8771 18535 8776 18535 9034 18536 8776 18536 8781 18536 9034 18537 9032 18537 8776 18537 9035 18538 8781 18538 8784 18538 9035 18539 9034 18539 8781 18539 9036 18540 8784 18540 8787 18540 9036 18541 9035 18541 8784 18541 9037 18542 8787 18542 8792 18542 9037 18543 9036 18543 8787 18543 9038 18544 8792 18544 8797 18544 9038 18545 9037 18545 8792 18545 9039 18546 8797 18546 8800 18546 9039 18547 9038 18547 8797 18547 9040 18548 8800 18548 8805 18548 9040 18549 9039 18549 8800 18549 9041 18550 8805 18550 8810 18550 9041 18551 9040 18551 8805 18551 9042 18552 8810 18552 8813 18552 9042 18553 9041 18553 8810 18553 9043 18554 8813 18554 8818 18554 9043 18555 9042 18555 8813 18555 9044 18556 8818 18556 8821 18556 9044 18557 9043 18557 8818 18557 9045 18558 8821 18558 8826 18558 9045 18559 9044 18559 8821 18559 9046 18560 8826 18560 8830 18560 9046 18561 9045 18561 8826 18561 9047 18562 8830 18562 8835 18562 9047 18563 9046 18563 8830 18563 9048 18564 8835 18564 8841 18564 9048 18565 9047 18565 8835 18565 9049 18566 8841 18566 8839 18566 9049 18567 9048 18567 8841 18567 9050 18568 8839 18568 8844 18568 9050 18569 9049 18569 8839 18569 9051 18570 8844 18570 8848 18570 9051 18571 9050 18571 8844 18571 9052 18572 8848 18572 8847 18572 9052 18573 9051 18573 8848 18573 9053 18574 8847 18574 8851 18574 9053 18575 9052 18575 8847 18575 9054 18576 8851 18576 8854 18576 9054 18577 9053 18577 8851 18577 9055 18578 8854 18578 8857 18578 9055 18579 9054 18579 8854 18579 9056 18580 8857 18580 8862 18580 9056 18581 9055 18581 8857 18581 9057 18582 8862 18582 8865 18582 9057 18583 9056 18583 8862 18583 9058 18584 8865 18584 8871 18584 9058 18585 9057 18585 8865 18585 9059 18586 8871 18586 8876 18586 9059 18587 9058 18587 8871 18587 9060 18588 8876 18588 8880 18588 9060 18589 9059 18589 8876 18589 9061 18590 8880 18590 8884 18590 9061 18591 9060 18591 8880 18591 9062 18592 8884 18592 8889 18592 9062 18593 9061 18593 8884 18593 9063 18594 8889 18594 8894 18594 9063 18595 9062 18595 8889 18595 9064 18596 8894 18596 8762 18596 9064 18597 9063 18597 8894 18597 9033 18598 9064 18598 8762 18598 8623 18599 9032 18599 9034 18599 8611 18600 9034 18600 9035 18600 8611 18601 8623 18601 9034 18601 8619 18602 9035 18602 9036 18602 8619 18603 8611 18603 9035 18603 8620 18604 9036 18604 9037 18604 8620 18605 8619 18605 9036 18605 8604 18606 9037 18606 9038 18606 8604 18607 8620 18607 9037 18607 8608 18608 9038 18608 9039 18608 8608 18609 8604 18609 9038 18609 8596 18610 9039 18610 9040 18610 8596 18611 8608 18611 9039 18611 8600 18612 9040 18612 9041 18612 8600 18613 8596 18613 9040 18613 8601 18614 9041 18614 9042 18614 8601 18615 8600 18615 9041 18615 8590 18616 9042 18616 9043 18616 8590 18617 8601 18617 9042 18617 8593 18618 9043 18618 9044 18618 8593 18619 8590 18619 9043 18619 8586 18620 9044 18620 9045 18620 8586 18621 8593 18621 9044 18621 8581 18622 9045 18622 9046 18622 8581 18623 8586 18623 9045 18623 8583 18624 9046 18624 9047 18624 8583 18625 8581 18625 9046 18625 8577 18626 9047 18626 9048 18626 8577 18627 8583 18627 9047 18627 8578 18628 9048 18628 9049 18628 8578 18629 8577 18629 9048 18629 8574 18630 9049 18630 9050 18630 8574 18631 8578 18631 9049 18631 8571 18632 9050 18632 9051 18632 8571 18633 8574 18633 9050 18633 8568 18634 9051 18634 9052 18634 8568 18635 8571 18635 9051 18635 8565 18636 9052 18636 9053 18636 8565 18637 8568 18637 9052 18637 8563 18638 9053 18638 9054 18638 8563 18639 8565 18639 9053 18639 8560 18640 9054 18640 9055 18640 8560 18641 8563 18641 9054 18641 8558 18642 9055 18642 9056 18642 8558 18643 8560 18643 9055 18643 8555 18644 9056 18644 9057 18644 8555 18645 8558 18645 9056 18645 8553 18646 9057 18646 9058 18646 8553 18647 8555 18647 9057 18647 8549 18648 9058 18648 9059 18648 8549 18649 8553 18649 9058 18649 8547 18650 9059 18650 9060 18650 8547 18651 8549 18651 9059 18651 8544 18652 9060 18652 9061 18652 8544 18653 8547 18653 9060 18653 8539 18654 9061 18654 9062 18654 8539 18655 8544 18655 9061 18655 8536 18656 9062 18656 9063 18656 8536 18657 8539 18657 9062 18657 8532 18658 9063 18658 9064 18658 8532 18659 8536 18659 9063 18659 8530 18660 9064 18660 9033 18660 8530 18661 8532 18661 9064 18661 8529 18662 8530 18662 9033 18662 8647 18663 8943 18663 9006 18663 8646 18664 8943 18664 8647 18664 9065 18665 9006 18665 9007 18665 9066 18666 8647 18666 9006 18666 9066 18667 9006 18667 9065 18667 9067 18668 9007 18668 9008 18668 9065 18669 9007 18669 9067 18669 9068 18670 9008 18670 9009 18670 9067 18671 9008 18671 9068 18671 9069 18672 9009 18672 9010 18672 9068 18673 9009 18673 9069 18673 9070 18674 9010 18674 9011 18674 9069 18675 9010 18675 9070 18675 9071 18676 9011 18676 9012 18676 9070 18677 9011 18677 9071 18677 9072 18678 9012 18678 9013 18678 9071 18679 9012 18679 9072 18679 9073 18680 9013 18680 9014 18680 9072 18681 9013 18681 9073 18681 9074 18682 9014 18682 9015 18682 9073 18683 9014 18683 9074 18683 9075 18684 9015 18684 9016 18684 9074 18685 9015 18685 9075 18685 9018 18686 9016 18686 9017 18686 9075 18687 9016 18687 9018 18687 9075 18688 8749 18688 8750 18688 9075 18689 9018 18689 8749 18689 9074 18690 8750 18690 8751 18690 9074 18691 9075 18691 8750 18691 9073 18692 8751 18692 8752 18692 9073 18693 9074 18693 8751 18693 9072 18694 8752 18694 8753 18694 9072 18695 9073 18695 8752 18695 9071 18696 8753 18696 8754 18696 9071 18697 9072 18697 8753 18697 9070 18698 8754 18698 8755 18698 9070 18699 9071 18699 8754 18699 9069 18700 8755 18700 8756 18700 9069 18701 9070 18701 8755 18701 9068 18702 8756 18702 8757 18702 9068 18703 9069 18703 8756 18703 9067 18704 8757 18704 8758 18704 9067 18705 9068 18705 8757 18705 9065 18706 8758 18706 8759 18706 9065 18707 9067 18707 8758 18707 9066 18708 8759 18708 8644 18708 9066 18709 9065 18709 8759 18709 9066 18710 8644 18710 8641 18710 9066 18711 8641 18711 8647 18711 9076 18712 8928 18712 8652 18712 9077 18713 9076 18713 8652 18713 8653 18714 9077 18714 8652 18714 9077 18715 8928 18715 9076 18715 8927 18716 8928 18716 9077 18716 8651 18717 9077 18717 8653 18717 9078 18718 9077 18718 8651 18718 9078 18719 8927 18719 9077 18719 9078 18720 8651 18720 8654 18720 9079 18721 8020 18721 8019 18721 9079 18722 8743 18722 8020 18722 8895 18723 8019 18723 8022 18723 9079 18724 8019 18724 8895 18724 9080 18725 8654 18725 8658 18725 9078 18726 8654 18726 9080 18726 9081 18727 8658 18727 8661 18727 9080 18728 8658 18728 9081 18728 9082 18729 8661 18729 8664 18729 9081 18730 8661 18730 9082 18730 9083 18731 8664 18731 8668 18731 9082 18732 8664 18732 9083 18732 9084 18733 8668 18733 8671 18733 9083 18734 8668 18734 9084 18734 9085 18735 8671 18735 8674 18735 9084 18736 8671 18736 9085 18736 9086 18737 8674 18737 8677 18737 9085 18738 8674 18738 9086 18738 9087 18739 8677 18739 8681 18739 9086 18740 8677 18740 9087 18740 9088 18741 8681 18741 8684 18741 9087 18742 8681 18742 9088 18742 9089 18743 8684 18743 8686 18743 9088 18744 8684 18744 9089 18744 9090 18745 8686 18745 8691 18745 9089 18746 8686 18746 9090 18746 9091 18747 8691 18747 8696 18747 9090 18748 8691 18748 9091 18748 9092 18749 8696 18749 8697 18749 9091 18750 8696 18750 9092 18750 9093 18751 8697 18751 8695 18751 9092 18752 8697 18752 9093 18752 9094 18753 8695 18753 8701 18753 9093 18754 8695 18754 9094 18754 9095 18755 8701 18755 8700 18755 9094 18756 8701 18756 9095 18756 9096 18757 8700 18757 8705 18757 9095 18758 8700 18758 9096 18758 9097 18759 8705 18759 8704 18759 9096 18760 8705 18760 9097 18760 9098 18761 8704 18761 8708 18761 9097 18762 8704 18762 9098 18762 9099 18763 8708 18763 8712 18763 9098 18764 8708 18764 9099 18764 9100 18765 8712 18765 8711 18765 9099 18766 8712 18766 9100 18766 9101 18767 8711 18767 8714 18767 9100 18768 8711 18768 9101 18768 9102 18769 8714 18769 8718 18769 9101 18770 8714 18770 9102 18770 9103 18771 8718 18771 8720 18771 9102 18772 8718 18772 9103 18772 9104 18773 8720 18773 8724 18773 9103 18774 8720 18774 9104 18774 9105 18775 8724 18775 8727 18775 9104 18776 8724 18776 9105 18776 9106 18777 8727 18777 8729 18777 9105 18778 8727 18778 9106 18778 9107 18779 8729 18779 8732 18779 9106 18780 8729 18780 9107 18780 9108 18781 8732 18781 8735 18781 9107 18782 8732 18782 9108 18782 9109 18783 8735 18783 8739 18783 9108 18784 8735 18784 9109 18784 9110 18785 8739 18785 8741 18785 9109 18786 8739 18786 9110 18786 9079 18787 8741 18787 8743 18787 9110 18788 8741 18788 9079 18788 9110 18789 8895 18789 8896 18789 9110 18790 9079 18790 8895 18790 9109 18791 8896 18791 8897 18791 9109 18792 9110 18792 8896 18792 9108 18793 8897 18793 8898 18793 9108 18794 9109 18794 8897 18794 9107 18795 8898 18795 8899 18795 9107 18796 9108 18796 8898 18796 9106 18797 8899 18797 8900 18797 9106 18798 9107 18798 8899 18798 9105 18799 8900 18799 8901 18799 9105 18800 9106 18800 8900 18800 9104 18801 8901 18801 8902 18801 9104 18802 9105 18802 8901 18802 9103 18803 8902 18803 8903 18803 9103 18804 9104 18804 8902 18804 9102 18805 8903 18805 8904 18805 9102 18806 9103 18806 8903 18806 9101 18807 8904 18807 8905 18807 9101 18808 9102 18808 8904 18808 9100 18809 8905 18809 8906 18809 9100 18810 9101 18810 8905 18810 9099 18811 8906 18811 8907 18811 9099 18812 9100 18812 8906 18812 9098 18813 8907 18813 8908 18813 9098 18814 9099 18814 8907 18814 9097 18815 8908 18815 8909 18815 9097 18816 9098 18816 8908 18816 9096 18817 8909 18817 8910 18817 9096 18818 9097 18818 8909 18818 9095 18819 8910 18819 8911 18819 9095 18820 9096 18820 8910 18820 9094 18821 8911 18821 8912 18821 9094 18822 9095 18822 8911 18822 9093 18823 8912 18823 8913 18823 9093 18824 9094 18824 8912 18824 9092 18825 8913 18825 8914 18825 9092 18826 9093 18826 8913 18826 9091 18827 8914 18827 8915 18827 9091 18828 9092 18828 8914 18828 9090 18829 8915 18829 8916 18829 9090 18830 9091 18830 8915 18830 9089 18831 8916 18831 8917 18831 9089 18832 9090 18832 8916 18832 9088 18833 8917 18833 8918 18833 9088 18834 9089 18834 8917 18834 9087 18835 8918 18835 8919 18835 9087 18836 9088 18836 8918 18836 9086 18837 8919 18837 8920 18837 9086 18838 9087 18838 8919 18838 9085 18839 8920 18839 8921 18839 9085 18840 9086 18840 8920 18840 9084 18841 8921 18841 8922 18841 9084 18842 9085 18842 8921 18842 9083 18843 8922 18843 8923 18843 9083 18844 9084 18844 8922 18844 9082 18845 8923 18845 8924 18845 9082 18846 9083 18846 8923 18846 9081 18847 8924 18847 8925 18847 9081 18848 9082 18848 8924 18848 9080 18849 8925 18849 8926 18849 9080 18850 9081 18850 8925 18850 9078 18851 8926 18851 8927 18851 9078 18852 9080 18852 8926 18852 9111 18853 8161 18853 8160 18853 9112 18854 9111 18854 8160 18854 8466 18855 9112 18855 8160 18855 9113 18856 8161 18856 9111 18856 8155 18857 8161 18857 9113 18857 9114 18858 9111 18858 9112 18858 9113 18859 9111 18859 9114 18859 9114 18860 9112 18860 8466 18860 9115 18861 8466 18861 8467 18861 9114 18862 8466 18862 9115 18862 8468 18863 9116 18863 8469 18863 9115 18864 8467 18864 8300 18864 8300 18865 8467 18865 8294 18865 9117 18866 8049 18866 8047 18866 9117 18867 8290 18867 8049 18867 9118 18868 8047 18868 8051 18868 9118 18869 9117 18869 8047 18869 9119 18870 8051 18870 8050 18870 9119 18871 9118 18871 8051 18871 8071 18872 8050 18872 8052 18872 8071 18873 9119 18873 8050 18873 9115 18874 8300 18874 8299 18874 9120 18875 8299 18875 8303 18875 9120 18876 9115 18876 8299 18876 9121 18877 8303 18877 8305 18877 9121 18878 9120 18878 8303 18878 9122 18879 8305 18879 8310 18879 9122 18880 9121 18880 8305 18880 9123 18881 8310 18881 8313 18881 9123 18882 9122 18882 8310 18882 9124 18883 8313 18883 8316 18883 9124 18884 9123 18884 8313 18884 9125 18885 8316 18885 8321 18885 9125 18886 9124 18886 8316 18886 9126 18887 8321 18887 8326 18887 9126 18888 9125 18888 8321 18888 9127 18889 8326 18889 8331 18889 9127 18890 9126 18890 8326 18890 9128 18891 8331 18891 8334 18891 9128 18892 9127 18892 8331 18892 9129 18893 8334 18893 8339 18893 9129 18894 9128 18894 8334 18894 9130 18895 8339 18895 8343 18895 9130 18896 9129 18896 8339 18896 9131 18897 8343 18897 8348 18897 9131 18898 9130 18898 8343 18898 9132 18899 8348 18899 8353 18899 9132 18900 9131 18900 8348 18900 9133 18901 8353 18901 8356 18901 9133 18902 9132 18902 8353 18902 9134 18903 8356 18903 8360 18903 9134 18904 9133 18904 8356 18904 9135 18905 8360 18905 8362 18905 9135 18906 9134 18906 8360 18906 9136 18907 8362 18907 8365 18907 9136 18908 9135 18908 8362 18908 9137 18909 8365 18909 8369 18909 9137 18910 9136 18910 8365 18910 9138 18911 8369 18911 8373 18911 9138 18912 9137 18912 8369 18912 9139 18913 8373 18913 8372 18913 9139 18914 9138 18914 8373 18914 9140 18915 8372 18915 8378 18915 9140 18916 9139 18916 8372 18916 9141 18917 8378 18917 8381 18917 9141 18918 9140 18918 8378 18918 9142 18919 8381 18919 8386 18919 9142 18920 9141 18920 8381 18920 9143 18921 8386 18921 8390 18921 9143 18922 9142 18922 8386 18922 9144 18923 8390 18923 8395 18923 9144 18924 9143 18924 8390 18924 9145 18925 8395 18925 8401 18925 9145 18926 9144 18926 8395 18926 9146 18927 8401 18927 8406 18927 9146 18928 9145 18928 8401 18928 9147 18929 8406 18929 8411 18929 9147 18930 9146 18930 8406 18930 9148 18931 8411 18931 8416 18931 9148 18932 9147 18932 8411 18932 9149 18933 8416 18933 8421 18933 9149 18934 9148 18934 8416 18934 9150 18935 8421 18935 8427 18935 9150 18936 9149 18936 8421 18936 9151 18937 8427 18937 8290 18937 9151 18938 9150 18938 8427 18938 9117 18939 9151 18939 8290 18939 9114 18940 9115 18940 9120 18940 9152 18941 9120 18941 9121 18941 9152 18942 9114 18942 9120 18942 9153 18943 9121 18943 9122 18943 9153 18944 9152 18944 9121 18944 9154 18945 9122 18945 9123 18945 9154 18946 9153 18946 9122 18946 9155 18947 9123 18947 9124 18947 9155 18948 9154 18948 9123 18948 9156 18949 9124 18949 9125 18949 9156 18950 9155 18950 9124 18950 9157 18951 9125 18951 9126 18951 9157 18952 9156 18952 9125 18952 9158 18953 9126 18953 9127 18953 9158 18954 9157 18954 9126 18954 9159 18955 9127 18955 9128 18955 9159 18956 9158 18956 9127 18956 9160 18957 9128 18957 9129 18957 9160 18958 9159 18958 9128 18958 9161 18959 9129 18959 9130 18959 9161 18960 9160 18960 9129 18960 9162 18961 9130 18961 9131 18961 9162 18962 9161 18962 9130 18962 9163 18963 9131 18963 9132 18963 9163 18964 9162 18964 9131 18964 9164 18965 9132 18965 9133 18965 9164 18966 9163 18966 9132 18966 9165 18967 9133 18967 9134 18967 9165 18968 9164 18968 9133 18968 9166 18969 9134 18969 9135 18969 9166 18970 9165 18970 9134 18970 9167 18971 9135 18971 9136 18971 9167 18972 9166 18972 9135 18972 9168 18973 9136 18973 9137 18973 9168 18974 9167 18974 9136 18974 9169 18975 9137 18975 9138 18975 9169 18976 9168 18976 9137 18976 9170 18977 9138 18977 9139 18977 9170 18978 9169 18978 9138 18978 9171 18979 9139 18979 9140 18979 9171 18980 9170 18980 9139 18980 9172 18981 9140 18981 9141 18981 9172 18982 9171 18982 9140 18982 9173 18983 9141 18983 9142 18983 9173 18984 9172 18984 9141 18984 9174 18985 9142 18985 9143 18985 9174 18986 9173 18986 9142 18986 9175 18987 9143 18987 9144 18987 9175 18988 9174 18988 9143 18988 9176 18989 9144 18989 9145 18989 9176 18990 9175 18990 9144 18990 9177 18991 9145 18991 9146 18991 9177 18992 9176 18992 9145 18992 9178 18993 9146 18993 9147 18993 9178 18994 9177 18994 9146 18994 9179 18995 9147 18995 9148 18995 9179 18996 9178 18996 9147 18996 9180 18997 9148 18997 9149 18997 9180 18998 9179 18998 9148 18998 9181 18999 9149 18999 9150 18999 9181 19000 9180 19000 9149 19000 9182 19001 9150 19001 9151 19001 9182 19002 9181 19002 9150 19002 9183 19003 9151 19003 9117 19003 9183 19004 9182 19004 9151 19004 9118 19005 9183 19005 9117 19005 9113 19006 9114 19006 9152 19006 9184 19007 9152 19007 9153 19007 9184 19008 9113 19008 9152 19008 9185 19009 9153 19009 9154 19009 9185 19010 9184 19010 9153 19010 9186 19011 9154 19011 9155 19011 9186 19012 9185 19012 9154 19012 9187 19013 9155 19013 9156 19013 9187 19014 9186 19014 9155 19014 9188 19015 9156 19015 9157 19015 9188 19016 9187 19016 9156 19016 9189 19017 9157 19017 9158 19017 9189 19018 9188 19018 9157 19018 9190 19019 9158 19019 9159 19019 9190 19020 9189 19020 9158 19020 9191 19021 9159 19021 9160 19021 9191 19022 9190 19022 9159 19022 9192 19023 9160 19023 9161 19023 9192 19024 9191 19024 9160 19024 9193 19025 9161 19025 9162 19025 9193 19026 9192 19026 9161 19026 9194 19027 9162 19027 9163 19027 9194 19028 9193 19028 9162 19028 9195 19029 9163 19029 9164 19029 9195 19030 9194 19030 9163 19030 9196 19031 9164 19031 9165 19031 9196 19032 9195 19032 9164 19032 9197 19033 9165 19033 9166 19033 9197 19034 9196 19034 9165 19034 9198 19035 9166 19035 9167 19035 9198 19036 9197 19036 9166 19036 9199 19037 9167 19037 9168 19037 9199 19038 9198 19038 9167 19038 9200 19039 9168 19039 9169 19039 9200 19040 9199 19040 9168 19040 9201 19041 9169 19041 9170 19041 9201 19042 9200 19042 9169 19042 9202 19043 9170 19043 9171 19043 9202 19044 9201 19044 9170 19044 9203 19045 9171 19045 9172 19045 9203 19046 9202 19046 9171 19046 9204 19047 9172 19047 9173 19047 9204 19048 9203 19048 9172 19048 9205 19049 9173 19049 9174 19049 9205 19050 9204 19050 9173 19050 9206 19051 9174 19051 9175 19051 9206 19052 9205 19052 9174 19052 9207 19053 9175 19053 9176 19053 9207 19054 9206 19054 9175 19054 9208 19055 9176 19055 9177 19055 9208 19056 9207 19056 9176 19056 9209 19057 9177 19057 9178 19057 9209 19058 9208 19058 9177 19058 9210 19059 9178 19059 9179 19059 9210 19060 9209 19060 9178 19060 9211 19061 9179 19061 9180 19061 9211 19062 9210 19062 9179 19062 9212 19063 9180 19063 9181 19063 9212 19064 9211 19064 9180 19064 9213 19065 9181 19065 9182 19065 9213 19066 9212 19066 9181 19066 9214 19067 9182 19067 9183 19067 9214 19068 9213 19068 9182 19068 9215 19069 9183 19069 9118 19069 9215 19070 9214 19070 9183 19070 9119 19071 9215 19071 9118 19071 8155 19072 9113 19072 9184 19072 8151 19073 9184 19073 9185 19073 8151 19074 8155 19074 9184 19074 8152 19075 9185 19075 9186 19075 8152 19076 8151 19076 9185 19076 8146 19077 9186 19077 9187 19077 8146 19078 8152 19078 9186 19078 8148 19079 9187 19079 9188 19079 8148 19080 8146 19080 9187 19080 8141 19081 9188 19081 9189 19081 8141 19082 8148 19082 9188 19082 8143 19083 9189 19083 9190 19083 8143 19084 8141 19084 9189 19084 8136 19085 9190 19085 9191 19085 8136 19086 8143 19086 9190 19086 8137 19087 9191 19087 9192 19087 8137 19088 8136 19088 9191 19088 8138 19089 9192 19089 9193 19089 8138 19090 8137 19090 9192 19090 8131 19091 9193 19091 9194 19091 8131 19092 8138 19092 9193 19092 8133 19093 9194 19093 9195 19093 8133 19094 8131 19094 9194 19094 8127 19095 9195 19095 9196 19095 8127 19096 8133 19096 9195 19096 8123 19097 9196 19097 9197 19097 8123 19098 8127 19098 9196 19098 8124 19099 9197 19099 9198 19099 8124 19100 8123 19100 9197 19100 8120 19101 9198 19101 9199 19101 8120 19102 8124 19102 9198 19102 8116 19103 9199 19103 9200 19103 8116 19104 8120 19104 9199 19104 8117 19105 9200 19105 9201 19105 8117 19106 8116 19106 9200 19106 8113 19107 9201 19107 9202 19107 8113 19108 8117 19108 9201 19108 8111 19109 9202 19109 9203 19109 8111 19110 8113 19110 9202 19110 8108 19111 9203 19111 9204 19111 8108 19112 8111 19112 9203 19112 8106 19113 9204 19113 9205 19113 8106 19114 8108 19114 9204 19114 8103 19115 9205 19115 9206 19115 8103 19116 8106 19116 9205 19116 8100 19117 9206 19117 9207 19117 8100 19118 8103 19118 9206 19118 8096 19119 9207 19119 9208 19119 8096 19120 8100 19120 9207 19120 8094 19121 9208 19121 9209 19121 8094 19122 8096 19122 9208 19122 8090 19123 9209 19123 9210 19123 8090 19124 8094 19124 9209 19124 8087 19125 9210 19125 9211 19125 8087 19126 8090 19126 9210 19126 8084 19127 9211 19127 9212 19127 8084 19128 8087 19128 9211 19128 8079 19129 9212 19129 9213 19129 8079 19130 8084 19130 9212 19130 8076 19131 9213 19131 9214 19131 8076 19132 8079 19132 9213 19132 8073 19133 9214 19133 9215 19133 8073 19134 8076 19134 9214 19134 8072 19135 9215 19135 9119 19135 8072 19136 8073 19136 9215 19136 8071 19137 8072 19137 9119 19137 9216 19138 8464 19138 8250 19138 9116 19139 9217 19139 8469 19139 9218 19140 9216 19140 8250 19140 8251 19141 9218 19141 8250 19141 9116 19142 9219 19142 9217 19142 8462 19143 8464 19143 9216 19143 9220 19144 9216 19144 9218 19144 9220 19145 8462 19145 9216 19145 8252 19146 9218 19146 8251 19146 9221 19147 9218 19147 8252 19147 9220 19148 9218 19148 9221 19148 9222 19149 8252 19149 8249 19149 9221 19150 8252 19150 9222 19150 9222 19151 8249 19151 8253 19151 9223 19152 8040 19152 8041 19152 9223 19153 8175 19153 8040 19153 8470 19154 8041 19154 8039 19154 8470 19155 9223 19155 8041 19155 8468 19156 8039 19156 8044 19156 8468 19157 8470 19157 8039 19157 8429 19158 8044 19158 8043 19158 8468 19159 8044 19159 8429 19159 9116 19160 8429 19160 8430 19160 8468 19161 8429 19161 9116 19161 9219 19162 8430 19162 8431 19162 9116 19163 8430 19163 9219 19163 9224 19164 8431 19164 8432 19164 9219 19165 8431 19165 9224 19165 9225 19166 8432 19166 8433 19166 9224 19167 8432 19167 9225 19167 9226 19168 8433 19168 8434 19168 9225 19169 8433 19169 9226 19169 9227 19170 8434 19170 8435 19170 9226 19171 8434 19171 9227 19171 9228 19172 8435 19172 8436 19172 9227 19173 8435 19173 9228 19173 9229 19174 8436 19174 8437 19174 9228 19175 8436 19175 9229 19175 9230 19176 8437 19176 8438 19176 9229 19177 8437 19177 9230 19177 9231 19178 8438 19178 8439 19178 9230 19179 8438 19179 9231 19179 9232 19180 8439 19180 8440 19180 9231 19181 8439 19181 9232 19181 9233 19182 8440 19182 8441 19182 9232 19183 8440 19183 9233 19183 9234 19184 8441 19184 8442 19184 9233 19185 8441 19185 9234 19185 9235 19186 8442 19186 8443 19186 9234 19187 8442 19187 9235 19187 9236 19188 8443 19188 8444 19188 9235 19189 8443 19189 9236 19189 9237 19190 8444 19190 8445 19190 9236 19191 8444 19191 9237 19191 9238 19192 8445 19192 8446 19192 9237 19193 8445 19193 9238 19193 9239 19194 8446 19194 8447 19194 9238 19195 8446 19195 9239 19195 9240 19196 8447 19196 8448 19196 9239 19197 8447 19197 9240 19197 9241 19198 8448 19198 8449 19198 9240 19199 8448 19199 9241 19199 9242 19200 8449 19200 8450 19200 9241 19201 8449 19201 9242 19201 9243 19202 8450 19202 8451 19202 9242 19203 8450 19203 9243 19203 9244 19204 8451 19204 8452 19204 9243 19205 8451 19205 9244 19205 9245 19206 8452 19206 8453 19206 9244 19207 8452 19207 9245 19207 9246 19208 8453 19208 8454 19208 9245 19209 8453 19209 9246 19209 9247 19210 8454 19210 8455 19210 9246 19211 8454 19211 9247 19211 9248 19212 8455 19212 8456 19212 9247 19213 8455 19213 9248 19213 9249 19214 8456 19214 8457 19214 9248 19215 8456 19215 9249 19215 9250 19216 8457 19216 8458 19216 9249 19217 8457 19217 9250 19217 9251 19218 8458 19218 8459 19218 9250 19219 8458 19219 9251 19219 9252 19220 8459 19220 8461 19220 9251 19221 8459 19221 9252 19221 9253 19222 8461 19222 8460 19222 9252 19223 8461 19223 9253 19223 9220 19224 8460 19224 8462 19224 9253 19225 8460 19225 9220 19225 9254 19226 8253 19226 8254 19226 9254 19227 9222 19227 8253 19227 9255 19228 8254 19228 8256 19228 9255 19229 9254 19229 8254 19229 9256 19230 8256 19230 8255 19230 9256 19231 9255 19231 8256 19231 9257 19232 8255 19232 8257 19232 9257 19233 9256 19233 8255 19233 9258 19234 8257 19234 8259 19234 9258 19235 9257 19235 8257 19235 9259 19236 8259 19236 8260 19236 9259 19237 9258 19237 8259 19237 9260 19238 8260 19238 8258 19238 9260 19239 9259 19239 8260 19239 9261 19240 8258 19240 8262 19240 9261 19241 9260 19241 8258 19241 9262 19242 8262 19242 8261 19242 9262 19243 9261 19243 8262 19243 9263 19244 8261 19244 8264 19244 9263 19245 9262 19245 8261 19245 9264 19246 8264 19246 8265 19246 9264 19247 9263 19247 8264 19247 9265 19248 8265 19248 8263 19248 9265 19249 9264 19249 8265 19249 9266 19250 8263 19250 8267 19250 9266 19251 9265 19251 8263 19251 9267 19252 8267 19252 8266 19252 9267 19253 9266 19253 8267 19253 9268 19254 8266 19254 8269 19254 9268 19255 9267 19255 8266 19255 9269 19256 8269 19256 8268 19256 9269 19257 9268 19257 8269 19257 9270 19258 8268 19258 8270 19258 9270 19259 9269 19259 8268 19259 9271 19260 8270 19260 8272 19260 9271 19261 9270 19261 8270 19261 9272 19262 8272 19262 8271 19262 9272 19263 9271 19263 8272 19263 9273 19264 8271 19264 8273 19264 9273 19265 9272 19265 8271 19265 9274 19266 8273 19266 8274 19266 9274 19267 9273 19267 8273 19267 9275 19268 8274 19268 8275 19268 9275 19269 9274 19269 8274 19269 9276 19270 8275 19270 8276 19270 9276 19271 9275 19271 8275 19271 9277 19272 8276 19272 8277 19272 9277 19273 9276 19273 8276 19273 9278 19274 8277 19274 8278 19274 9278 19275 9277 19275 8277 19275 9279 19276 8278 19276 8279 19276 9279 19277 9278 19277 8278 19277 9280 19278 8279 19278 8280 19278 9280 19279 9279 19279 8279 19279 9281 19280 8280 19280 8281 19280 9281 19281 9280 19281 8280 19281 9282 19282 8281 19282 8282 19282 9282 19283 9281 19283 8281 19283 9283 19284 8282 19284 8283 19284 9283 19285 9282 19285 8282 19285 9284 19286 8283 19286 8284 19286 9284 19287 9283 19287 8283 19287 9285 19288 8284 19288 8285 19288 9285 19289 9284 19289 8284 19289 9223 19290 8285 19290 8175 19290 9223 19291 9285 19291 8285 19291 9286 19292 9222 19292 9254 19292 9286 19293 9221 19293 9222 19293 9287 19294 9254 19294 9255 19294 9287 19295 9286 19295 9254 19295 9288 19296 9255 19296 9256 19296 9288 19297 9287 19297 9255 19297 9289 19298 9256 19298 9257 19298 9289 19299 9288 19299 9256 19299 9290 19300 9257 19300 9258 19300 9290 19301 9289 19301 9257 19301 9291 19302 9258 19302 9259 19302 9291 19303 9290 19303 9258 19303 9292 19304 9259 19304 9260 19304 9292 19305 9291 19305 9259 19305 9293 19306 9260 19306 9261 19306 9293 19307 9292 19307 9260 19307 9294 19308 9261 19308 9262 19308 9294 19309 9293 19309 9261 19309 9295 19310 9262 19310 9263 19310 9295 19311 9294 19311 9262 19311 9296 19312 9263 19312 9264 19312 9296 19313 9295 19313 9263 19313 9297 19314 9264 19314 9265 19314 9297 19315 9296 19315 9264 19315 9298 19316 9265 19316 9266 19316 9298 19317 9297 19317 9265 19317 9299 19318 9266 19318 9267 19318 9299 19319 9298 19319 9266 19319 9300 19320 9267 19320 9268 19320 9300 19321 9299 19321 9267 19321 9301 19322 9268 19322 9269 19322 9301 19323 9300 19323 9268 19323 9302 19324 9269 19324 9270 19324 9302 19325 9301 19325 9269 19325 9303 19326 9270 19326 9271 19326 9303 19327 9302 19327 9270 19327 9304 19328 9271 19328 9272 19328 9304 19329 9303 19329 9271 19329 9305 19330 9272 19330 9273 19330 9305 19331 9304 19331 9272 19331 9306 19332 9273 19332 9274 19332 9306 19333 9305 19333 9273 19333 9307 19334 9274 19334 9275 19334 9307 19335 9306 19335 9274 19335 9308 19336 9275 19336 9276 19336 9308 19337 9307 19337 9275 19337 9309 19338 9276 19338 9277 19338 9309 19339 9308 19339 9276 19339 9310 19340 9277 19340 9278 19340 9310 19341 9309 19341 9277 19341 9311 19342 9278 19342 9279 19342 9311 19343 9310 19343 9278 19343 9312 19344 9279 19344 9280 19344 9312 19345 9311 19345 9279 19345 9313 19346 9280 19346 9281 19346 9313 19347 9312 19347 9280 19347 9314 19348 9281 19348 9282 19348 9314 19349 9313 19349 9281 19349 9315 19350 9282 19350 9283 19350 9315 19351 9314 19351 9282 19351 9217 19352 9283 19352 9284 19352 9217 19353 9315 19353 9283 19353 8469 19354 9284 19354 9285 19354 8469 19355 9217 19355 9284 19355 8470 19356 9285 19356 9223 19356 8470 19357 8469 19357 9285 19357 9253 19358 9221 19358 9286 19358 9253 19359 9220 19359 9221 19359 9252 19360 9286 19360 9287 19360 9252 19361 9253 19361 9286 19361 9251 19362 9287 19362 9288 19362 9251 19363 9252 19363 9287 19363 9250 19364 9288 19364 9289 19364 9250 19365 9251 19365 9288 19365 9249 19366 9289 19366 9290 19366 9249 19367 9250 19367 9289 19367 9248 19368 9290 19368 9291 19368 9248 19369 9249 19369 9290 19369 9247 19370 9291 19370 9292 19370 9247 19371 9248 19371 9291 19371 9246 19372 9292 19372 9293 19372 9246 19373 9247 19373 9292 19373 9245 19374 9293 19374 9294 19374 9245 19375 9246 19375 9293 19375 9244 19376 9294 19376 9295 19376 9244 19377 9245 19377 9294 19377 9243 19378 9295 19378 9296 19378 9243 19379 9244 19379 9295 19379 9242 19380 9296 19380 9297 19380 9242 19381 9243 19381 9296 19381 9241 19382 9297 19382 9298 19382 9241 19383 9242 19383 9297 19383 9240 19384 9298 19384 9299 19384 9240 19385 9241 19385 9298 19385 9239 19386 9299 19386 9300 19386 9239 19387 9240 19387 9299 19387 9238 19388 9300 19388 9301 19388 9238 19389 9239 19389 9300 19389 9237 19390 9301 19390 9302 19390 9237 19391 9238 19391 9301 19391 9236 19392 9302 19392 9303 19392 9236 19393 9237 19393 9302 19393 9235 19394 9303 19394 9304 19394 9235 19395 9236 19395 9303 19395 9234 19396 9304 19396 9305 19396 9234 19397 9235 19397 9304 19397 9233 19398 9305 19398 9306 19398 9233 19399 9234 19399 9305 19399 9232 19400 9306 19400 9307 19400 9232 19401 9233 19401 9306 19401 9231 19402 9307 19402 9308 19402 9231 19403 9232 19403 9307 19403 9230 19404 9308 19404 9309 19404 9230 19405 9231 19405 9308 19405 9229 19406 9309 19406 9310 19406 9229 19407 9230 19407 9309 19407 9228 19408 9310 19408 9311 19408 9228 19409 9229 19409 9310 19409 9227 19410 9311 19410 9312 19410 9227 19411 9228 19411 9311 19411 9226 19412 9312 19412 9313 19412 9226 19413 9227 19413 9312 19413 9225 19414 9313 19414 9314 19414 9225 19415 9226 19415 9313 19415 9224 19416 9314 19416 9315 19416 9224 19417 9225 19417 9314 19417 9219 19418 9315 19418 9217 19418 9219 19419 9224 19419 9315 19419 12096 24980 12097 24980 12098 24980 12098 24981 12099 24981 12100 24981 12100 24982 12101 24982 12102 24982 12102 24983 12103 24983 12104 24983 12104 24984 12105 24984 12106 24984 12106 24985 12107 24985 12108 24985 12108 24986 12109 24986 12110 24986 12110 24987 12111 24987 12112 24987 12112 24988 12113 24988 12114 24988 12114 24989 12115 24989 12116 24989 12116 24990 12117 24990 12118 24990 12118 24991 12119 24991 12120 24991 12120 24992 12121 24992 12123 24992 12122 24993 12123 24993 12125 24993 12124 24994 12125 24994 12127 24994 12126 24995 12127 24995 12129 24995 12128 24996 12129 24996 12130 24996 12130 24997 12131 24997 12132 24997 12132 24998 12133 24998 12134 24998 12134 24999 12135 24999 12136 24999 12136 25000 12137 25000 12138 25000 12138 25001 12139 25001 12140 25001 12140 25002 12141 25002 12142 25002 12142 25003 12143 25003 12144 25003 12144 25004 12145 25004 12146 25004 12146 25005 12147 25005 12148 25005 12148 25006 12149 25006 12150 25006 12150 25007 12151 25007 12152 25007 12152 25008 12153 25008 12155 25008 12154 25009 12155 25009 12157 25009 12099 25010 12097 25010 12101 25010 12158 25011 12159 25011 12097 25011 12156 25012 12157 25012 12159 25012 12096 25013 12098 25013 12158 25013 12160 25014 12161 25014 12163 25014 12162 25015 12163 25015 12165 25015 12164 25016 12165 25016 12167 25016 12166 25017 12167 25017 12169 25017 12168 25018 12169 25018 12171 25018 12170 25019 12171 25019 12173 25019 12172 25020 12173 25020 12175 25020 12174 25021 12175 25021 12177 25021 12176 25022 12177 25022 12179 25022 12178 25023 12179 25023 12181 25023 12180 25024 12181 25024 12183 25024 12182 25025 12183 25025 12185 25025 12184 25026 12185 25026 12186 25026 12186 25027 12187 25027 12188 25027 12188 25028 12189 25028 12190 25028 12190 25029 12191 25029 12192 25029 12192 25030 12193 25030 12195 25030 12194 25031 12195 25031 12197 25031 12196 25032 12197 25032 12199 25032 12198 25033 12199 25033 12201 25033 12200 25034 12201 25034 12203 25034 12202 25035 12203 25035 12205 25035 12204 25036 12205 25036 12207 25036 12206 25037 12207 25037 12208 25037 12208 25038 12209 25038 12210 25038 12210 25039 12211 25039 12213 25039 12212 25040 12213 25040 12215 25040 12214 25041 12215 25041 12217 25041 12216 25042 12217 25042 12218 25042 12218 25043 12219 25043 12220 25043 12163 25044 12161 25044 12165 25044 12222 25045 12223 25045 12160 25045 12220 25046 12221 25046 12222 25046 12160 25047 12162 25047 12222 25047 12224 25048 12225 25048 12226 25048 12226 25049 12227 25049 12228 25049 12228 25050 12229 25050 12230 25050 12230 25051 12231 25051 12232 25051 12232 25052 12233 25052 12234 25052 12234 25053 12235 25053 12236 25053 12236 25054 12237 25054 12238 25054 12238 25055 12239 25055 12240 25055 12240 25056 12241 25056 12243 25056 12242 25057 12243 25057 12245 25057 12244 25058 12245 25058 12247 25058 12246 25059 12247 25059 12249 25059 12248 25060 12249 25060 12250 25060 12250 25061 12251 25061 12252 25061 12252 25062 12253 25062 12254 25062 12254 25063 12255 25063 12256 25063 12256 25064 12257 25064 12258 25064 12258 25065 12259 25065 12260 25065 12260 25066 12261 25066 12262 25066 12262 25067 12263 25067 12264 25067 12264 25068 12265 25068 12266 25068 12266 25069 12267 25069 12268 25069 12268 25070 12269 25070 12270 25070 12270 25071 12271 25071 12272 25071 12272 25072 12273 25072 12275 25072 12274 25073 12275 25073 12277 25073 12276 25074 12277 25074 12279 25074 12278 25075 12279 25075 12281 25075 12280 25076 12281 25076 12282 25076 12282 25077 12283 25077 12284 25077 12227 25078 12225 25078 12229 25078 12286 25079 12287 25079 12224 25079 12284 25080 12285 25080 12286 25080 12224 25081 12226 25081 12286 25081 12288 25082 12289 25082 12291 25082 12290 25083 12291 25083 12293 25083 12292 25084 12293 25084 12295 25084 12294 25085 12295 25085 12297 25085 12296 25086 12297 25086 12299 25086 12298 25087 12299 25087 12301 25087 12300 25088 12301 25088 12303 25088 12302 25089 12303 25089 12305 25089 12304 25090 12305 25090 12306 25090 12306 25091 12307 25091 12308 25091 12308 25092 12309 25092 12310 25092 12310 25093 12311 25093 12312 25093 12312 25094 12313 25094 12315 25094 12314 25095 12315 25095 12317 25095 12316 25096 12317 25096 12319 25096 12318 25097 12319 25097 12321 25097 12320 25098 12321 25098 12323 25098 12322 25099 12323 25099 12325 25099 12324 25100 12325 25100 12327 25100 12326 25101 12327 25101 12329 25101 12328 25102 12329 25102 12331 25102 12330 25103 12331 25103 12333 25103 12332 25104 12333 25104 12335 25104 12334 25105 12335 25105 12337 25105 12336 25106 12337 25106 12338 25106 12338 25107 12339 25107 12340 25107 12340 25108 12341 25108 12342 25108 12342 25109 12343 25109 12344 25109 12344 25110 12345 25110 12347 25110 12346 25111 12347 25111 12349 25111 12291 25112 12289 25112 12293 25112 12350 25113 12351 25113 12289 25113 12348 25114 12349 25114 12351 25114 12288 25115 12290 25115 12350 25115 12352 25116 12353 25116 12354 25116 12354 25117 12355 25117 12357 25117 12356 25118 12357 25118 12358 25118 12358 25119 12359 25119 12360 25119 12360 25120 12361 25120 12362 25120 12362 25121 12363 25121 12364 25121 12364 25122 12365 25122 12366 25122 12366 25123 12367 25123 12368 25123 12368 25124 12369 25124 12371 25124 12370 25125 12371 25125 12373 25125 12372 25126 12373 25126 12375 25126 12374 25127 12375 25127 12377 25127 12376 25128 12377 25128 12379 25128 12378 25129 12379 25129 12381 25129 12380 25130 12381 25130 12383 25130 12382 25131 12383 25131 12385 25131 12384 25132 12385 25132 12387 25132 12386 25133 12387 25133 12389 25133 12388 25134 12389 25134 12391 25134 12390 25135 12391 25135 12392 25135 12392 25136 12393 25136 12395 25136 12394 25137 12395 25137 12396 25137 12396 25138 12397 25138 12398 25138 12398 25139 12399 25139 12400 25139 12400 25140 12401 25140 12403 25140 12402 25141 12403 25141 12405 25141 12404 25142 12405 25142 12407 25142 12406 25143 12407 25143 12409 25143 12408 25144 12409 25144 12411 25144 12410 25145 12411 25145 12413 25145 12355 25146 12353 25146 12357 25146 12414 25147 12415 25147 12353 25147 12412 25148 12413 25148 12415 25148 12352 25149 12354 25149 12414 25149 12416 25150 12417 25150 12419 25150 12418 25151 12419 25151 12420 25151 12420 25152 12421 25152 12422 25152 12422 25153 12423 25153 12424 25153 12424 25154 12425 25154 12426 25154 12426 25155 12427 25155 12428 25155 12428 25156 12429 25156 12430 25156 12430 25157 12431 25157 12432 25157 12432 25158 12433 25158 12435 25158 12434 25159 12435 25159 12437 25159 12436 25160 12437 25160 12439 25160 12438 25161 12439 25161 12441 25161 12440 25162 12441 25162 12443 25162 12442 25163 12443 25163 12445 25163 12444 25164 12445 25164 12447 25164 12446 25165 12447 25165 12449 25165 12448 25166 12449 25166 12451 25166 12450 25167 12451 25167 12453 25167 12452 25168 12453 25168 12455 25168 12454 25169 12455 25169 12456 25169 12456 25170 12457 25170 12458 25170 12458 25171 12459 25171 12460 25171 12460 25172 12461 25172 12462 25172 12462 25173 12463 25173 12464 25173 12464 25174 12465 25174 12467 25174 12466 25175 12467 25175 12469 25175 12468 25176 12469 25176 12471 25176 12470 25177 12471 25177 12473 25177 12472 25178 12473 25178 12475 25178 12474 25179 12475 25179 12477 25179 12473 25180 12477 25180 12475 25180 12478 25181 12479 25181 12417 25181 12476 25182 12477 25182 12479 25182 12416 25183 12418 25183 12478 25183 12097 25282 12099 25282 12098 25282 12099 25283 12101 25283 12100 25283 12101 25284 12103 25284 12102 25284 12103 25285 12105 25285 12104 25285 12105 25286 12107 25286 12106 25286 12107 25287 12109 25287 12108 25287 12109 25288 12111 25288 12110 25288 12111 25289 12113 25289 12112 25289 12113 25290 12115 25290 12114 25290 12115 25291 12117 25291 12116 25291 12117 25292 12119 25292 12118 25292 12119 25293 12121 25293 12120 25293 12122 25294 12120 25294 12123 25294 12124 25295 12122 25295 12125 25295 12126 25296 12124 25296 12127 25296 12128 25297 12126 25297 12129 25297 12129 25298 12131 25298 12130 25298 12131 25299 12133 25299 12132 25299 12133 25300 12135 25300 12134 25300 12135 25301 12137 25301 12136 25301 12137 25302 12139 25302 12138 25302 12139 25303 12141 25303 12140 25303 12141 25304 12143 25304 12142 25304 12143 25305 12145 25305 12144 25305 12145 25306 12147 25306 12146 25306 12147 25307 12149 25307 12148 25307 12149 25308 12151 25308 12150 25308 12151 25309 12153 25309 12152 25309 12154 25310 12152 25310 12155 25310 12156 25311 12154 25311 12157 25311 12097 25312 12159 25312 12101 25312 12159 25313 12157 25313 12101 25313 12157 25314 12155 25314 12101 25314 12155 25315 12153 25315 12101 25315 12153 25316 12151 25316 12101 25316 12151 25317 12149 25317 12101 25317 12149 25318 12147 25318 12101 25318 12147 25319 12145 25319 12101 25319 12145 25320 12143 25320 12101 25320 12143 25321 12141 25321 12101 25321 12141 25322 12139 25322 12101 25322 12139 25323 12137 25323 12101 25323 12137 25324 12135 25324 12101 25324 12135 25325 12133 25325 12101 25325 12133 25326 12131 25326 12101 25326 12131 25327 12129 25327 12101 25327 12129 25328 12127 25328 12101 25328 12127 25329 12125 25329 12101 25329 12125 25330 12123 25330 12101 25330 12123 25331 12121 25331 12101 25331 12121 25332 12119 25332 12101 25332 12119 25333 12117 25333 12101 25333 12117 25334 12115 25334 12101 25334 12115 25335 12113 25335 12101 25335 12113 25336 12111 25336 12101 25336 12111 25337 12109 25337 12101 25337 12109 25338 12107 25338 12101 25338 12107 25339 12105 25339 12103 25339 12101 25340 12107 25340 12103 25340 12096 25341 12158 25341 12097 25341 12158 25342 12156 25342 12159 25342 12098 25343 12100 25343 12158 25343 12100 25344 12102 25344 12158 25344 12102 25345 12104 25345 12158 25345 12104 25346 12106 25346 12158 25346 12106 25347 12108 25347 12158 25347 12108 25348 12110 25348 12158 25348 12110 25349 12112 25349 12158 25349 12112 25350 12114 25350 12158 25350 12114 25351 12116 25351 12158 25351 12116 25352 12118 25352 12158 25352 12118 25353 12120 25353 12158 25353 12120 25354 12122 25354 12158 25354 12122 25355 12124 25355 12158 25355 12124 25356 12126 25356 12158 25356 12126 25357 12128 25357 12130 25357 12156 25358 12158 25358 12154 25358 12154 25359 12158 25359 12152 25359 12158 25360 12126 25360 12152 25360 12130 25361 12132 25361 12134 25361 12130 25362 12134 25362 12136 25362 12130 25363 12136 25363 12138 25363 12126 25364 12130 25364 12152 25364 12130 25365 12138 25365 12152 25365 12138 25366 12140 25366 12152 25366 12140 25367 12142 25367 12152 25367 12142 25368 12144 25368 12152 25368 12144 25369 12146 25369 12152 25369 12146 25370 12148 25370 12152 25370 12148 25371 12150 25371 12152 25371 12162 25372 12160 25372 12163 25372 12164 25373 12162 25373 12165 25373 12166 25374 12164 25374 12167 25374 12168 25375 12166 25375 12169 25375 12170 25376 12168 25376 12171 25376 12172 25377 12170 25377 12173 25377 12174 25378 12172 25378 12175 25378 12176 25379 12174 25379 12177 25379 12178 25380 12176 25380 12179 25380 12180 25381 12178 25381 12181 25381 12182 25382 12180 25382 12183 25382 12184 25383 12182 25383 12185 25383 12185 25384 12187 25384 12186 25384 12187 25385 12189 25385 12188 25385 12189 25386 12191 25386 12190 25386 12191 25387 12193 25387 12192 25387 12194 25388 12192 25388 12195 25388 12196 25389 12194 25389 12197 25389 12198 25390 12196 25390 12199 25390 12200 25391 12198 25391 12201 25391 12202 25392 12200 25392 12203 25392 12204 25393 12202 25393 12205 25393 12206 25394 12204 25394 12207 25394 12207 25395 12209 25395 12208 25395 12209 25396 12211 25396 12210 25396 12212 25397 12210 25397 12213 25397 12214 25398 12212 25398 12215 25398 12216 25399 12214 25399 12217 25399 12217 25400 12219 25400 12218 25400 12219 25401 12221 25401 12220 25401 12161 25402 12223 25402 12165 25402 12223 25403 12221 25403 12165 25403 12221 25404 12219 25404 12165 25404 12219 25405 12217 25405 12165 25405 12217 25406 12215 25406 12165 25406 12215 25407 12213 25407 12165 25407 12213 25408 12211 25408 12165 25408 12211 25409 12209 25409 12165 25409 12209 25410 12207 25410 12165 25410 12207 25411 12205 25411 12165 25411 12205 25412 12203 25412 12165 25412 12203 25413 12201 25413 12165 25413 12201 25414 12199 25414 12165 25414 12199 25415 12197 25415 12165 25415 12197 25416 12195 25416 12165 25416 12193 25417 12191 25417 12189 25417 12193 25418 12189 25418 12187 25418 12193 25419 12187 25419 12185 25419 12193 25420 12185 25420 12183 25420 12193 25421 12183 25421 12181 25421 12193 25422 12181 25422 12179 25422 12165 25423 12169 25423 12167 25423 12165 25424 12195 25424 12169 25424 12193 25425 12179 25425 12177 25425 12193 25426 12177 25426 12175 25426 12193 25427 12175 25427 12173 25427 12169 25428 12195 25428 12171 25428 12195 25429 12193 25429 12173 25429 12171 25430 12195 25430 12173 25430 12223 25431 12161 25431 12160 25431 12221 25432 12223 25432 12222 25432 12162 25433 12164 25433 12222 25433 12164 25434 12166 25434 12222 25434 12166 25435 12168 25435 12222 25435 12168 25436 12170 25436 12222 25436 12170 25437 12172 25437 12222 25437 12172 25438 12174 25438 12222 25438 12174 25439 12176 25439 12222 25439 12176 25440 12178 25440 12222 25440 12178 25441 12180 25441 12222 25441 12180 25442 12182 25442 12222 25442 12182 25443 12184 25443 12222 25443 12184 25444 12186 25444 12222 25444 12186 25445 12188 25445 12222 25445 12188 25446 12190 25446 12222 25446 12190 25447 12192 25447 12222 25447 12192 25448 12194 25448 12222 25448 12194 25449 12196 25449 12222 25449 12196 25450 12198 25450 12222 25450 12198 25451 12200 25451 12222 25451 12200 25452 12202 25452 12222 25452 12202 25453 12204 25453 12222 25453 12204 25454 12206 25454 12222 25454 12206 25455 12208 25455 12222 25455 12208 25456 12210 25456 12222 25456 12210 25457 12212 25457 12222 25457 12212 25458 12214 25458 12222 25458 12214 25459 12216 25459 12222 25459 12216 25460 12218 25460 12222 25460 12218 25461 12220 25461 12222 25461 12225 25462 12227 25462 12226 25462 12227 25463 12229 25463 12228 25463 12229 25464 12231 25464 12230 25464 12231 25465 12233 25465 12232 25465 12233 25466 12235 25466 12234 25466 12235 25467 12237 25467 12236 25467 12237 25468 12239 25468 12238 25468 12239 25469 12241 25469 12240 25469 12242 25470 12240 25470 12243 25470 12244 25471 12242 25471 12245 25471 12246 25472 12244 25472 12247 25472 12248 25473 12246 25473 12249 25473 12249 25474 12251 25474 12250 25474 12251 25475 12253 25475 12252 25475 12253 25476 12255 25476 12254 25476 12255 25477 12257 25477 12256 25477 12257 25478 12259 25478 12258 25478 12259 25479 12261 25479 12260 25479 12261 25480 12263 25480 12262 25480 12263 25481 12265 25481 12264 25481 12265 25482 12267 25482 12266 25482 12267 25483 12269 25483 12268 25483 12269 25484 12271 25484 12270 25484 12271 25485 12273 25485 12272 25485 12274 25486 12272 25486 12275 25486 12276 25487 12274 25487 12277 25487 12278 25488 12276 25488 12279 25488 12280 25489 12278 25489 12281 25489 12281 25490 12283 25490 12282 25490 12283 25491 12285 25491 12284 25491 12225 25492 12287 25492 12229 25492 12287 25493 12285 25493 12229 25493 12285 25494 12283 25494 12229 25494 12283 25495 12281 25495 12229 25495 12281 25496 12279 25496 12229 25496 12279 25497 12277 25497 12229 25497 12277 25498 12275 25498 12229 25498 12275 25499 12273 25499 12229 25499 12273 25500 12271 25500 12229 25500 12271 25501 12269 25501 12229 25501 12269 25502 12267 25502 12229 25502 12267 25503 12265 25503 12229 25503 12265 25504 12263 25504 12229 25504 12263 25505 12261 25505 12229 25505 12261 25506 12259 25506 12229 25506 12239 25507 12243 25507 12241 25507 12237 25508 12243 25508 12239 25508 12237 25509 12245 25509 12243 25509 12235 25510 12245 25510 12237 25510 12235 25511 12247 25511 12245 25511 12235 25512 12249 25512 12247 25512 12233 25513 12249 25513 12235 25513 12231 25514 12249 25514 12233 25514 12231 25515 12251 25515 12249 25515 12229 25516 12251 25516 12231 25516 12229 25517 12253 25517 12251 25517 12229 25518 12255 25518 12253 25518 12259 25519 12257 25519 12229 25519 12257 25520 12255 25520 12229 25520 12287 25521 12225 25521 12224 25521 12285 25522 12287 25522 12286 25522 12226 25523 12228 25523 12286 25523 12228 25524 12230 25524 12286 25524 12230 25525 12232 25525 12286 25525 12232 25526 12234 25526 12286 25526 12234 25527 12236 25527 12286 25527 12236 25528 12238 25528 12286 25528 12238 25529 12240 25529 12286 25529 12240 25530 12242 25530 12286 25530 12242 25531 12244 25531 12286 25531 12244 25532 12246 25532 12286 25532 12246 25533 12248 25533 12286 25533 12248 25534 12250 25534 12286 25534 12250 25535 12252 25535 12286 25535 12252 25536 12254 25536 12286 25536 12254 25537 12256 25537 12286 25537 12256 25538 12258 25538 12286 25538 12258 25539 12260 25539 12286 25539 12260 25540 12262 25540 12286 25540 12262 25541 12264 25541 12286 25541 12264 25542 12266 25542 12286 25542 12266 25543 12268 25543 12286 25543 12268 25544 12270 25544 12286 25544 12270 25545 12272 25545 12286 25545 12272 25546 12274 25546 12286 25546 12274 25547 12276 25547 12286 25547 12276 25548 12278 25548 12286 25548 12278 25549 12280 25549 12286 25549 12280 25550 12282 25550 12284 25550 12286 25551 12280 25551 12284 25551 12290 25552 12288 25552 12291 25552 12292 25553 12290 25553 12293 25553 12294 25554 12292 25554 12295 25554 12296 25555 12294 25555 12297 25555 12298 25556 12296 25556 12299 25556 12300 25557 12298 25557 12301 25557 12302 25558 12300 25558 12303 25558 12304 25559 12302 25559 12305 25559 12305 25560 12307 25560 12306 25560 12307 25561 12309 25561 12308 25561 12309 25562 12311 25562 12310 25562 12311 25563 12313 25563 12312 25563 12314 25564 12312 25564 12315 25564 12316 25565 12314 25565 12317 25565 12318 25566 12316 25566 12319 25566 12320 25567 12318 25567 12321 25567 12322 25568 12320 25568 12323 25568 12324 25569 12322 25569 12325 25569 12326 25570 12324 25570 12327 25570 12328 25571 12326 25571 12329 25571 12330 25572 12328 25572 12331 25572 12332 25573 12330 25573 12333 25573 12334 25574 12332 25574 12335 25574 12336 25575 12334 25575 12337 25575 12337 25576 12339 25576 12338 25576 12339 25577 12341 25577 12340 25577 12341 25578 12343 25578 12342 25578 12343 25579 12345 25579 12344 25579 12346 25580 12344 25580 12347 25580 12348 25581 12346 25581 12349 25581 12289 25582 12351 25582 12293 25582 12351 25583 12349 25583 12293 25583 12349 25584 12347 25584 12293 25584 12347 25585 12345 25585 12293 25585 12345 25586 12343 25586 12293 25586 12343 25587 12341 25587 12293 25587 12341 25588 12339 25588 12293 25588 12339 25589 12337 25589 12293 25589 12337 25590 12335 25590 12293 25590 12335 25591 12333 25591 12293 25591 12333 25592 12331 25592 12293 25592 12331 25593 12329 25593 12293 25593 12329 25594 12327 25594 12293 25594 12327 25595 12325 25595 12293 25595 12325 25596 12323 25596 12293 25596 12323 25597 12321 25597 12293 25597 12321 25598 12319 25598 12293 25598 12319 25599 12317 25599 12293 25599 12317 25600 12315 25600 12293 25600 12315 25601 12313 25601 12293 25601 12313 25602 12311 25602 12293 25602 12311 25603 12309 25603 12293 25603 12309 25604 12307 25604 12293 25604 12307 25605 12305 25605 12293 25605 12305 25606 12303 25606 12293 25606 12303 25607 12301 25607 12293 25607 12301 25608 12299 25608 12293 25608 12299 25609 12297 25609 12293 25609 12297 25610 12295 25610 12293 25610 12288 25611 12350 25611 12289 25611 12350 25612 12348 25612 12351 25612 12290 25613 12292 25613 12350 25613 12292 25614 12294 25614 12350 25614 12294 25615 12296 25615 12350 25615 12296 25616 12298 25616 12350 25616 12298 25617 12300 25617 12350 25617 12300 25618 12302 25618 12350 25618 12302 25619 12304 25619 12350 25619 12304 25620 12306 25620 12350 25620 12306 25621 12308 25621 12350 25621 12308 25622 12310 25622 12350 25622 12310 25623 12312 25623 12350 25623 12312 25624 12314 25624 12350 25624 12314 25625 12316 25625 12350 25625 12316 25626 12318 25626 12350 25626 12338 25627 12334 25627 12336 25627 12340 25628 12334 25628 12338 25628 12340 25629 12332 25629 12334 25629 12340 25630 12330 25630 12332 25630 12342 25631 12330 25631 12340 25631 12344 25632 12330 25632 12342 25632 12344 25633 12328 25633 12330 25633 12346 25634 12328 25634 12344 25634 12346 25635 12326 25635 12328 25635 12346 25636 12324 25636 12326 25636 12348 25637 12324 25637 12346 25637 12348 25638 12322 25638 12324 25638 12350 25639 12322 25639 12348 25639 12318 25640 12320 25640 12350 25640 12320 25641 12322 25641 12350 25641 12353 25642 12355 25642 12354 25642 12356 25643 12354 25643 12357 25643 12357 25644 12359 25644 12358 25644 12359 25645 12361 25645 12360 25645 12361 25646 12363 25646 12362 25646 12363 25647 12365 25647 12364 25647 12365 25648 12367 25648 12366 25648 12367 25649 12369 25649 12368 25649 12370 25650 12368 25650 12371 25650 12372 25651 12370 25651 12373 25651 12374 25652 12372 25652 12375 25652 12376 25653 12374 25653 12377 25653 12378 25654 12376 25654 12379 25654 12380 25655 12378 25655 12381 25655 12382 25656 12380 25656 12383 25656 12384 25657 12382 25657 12385 25657 12386 25658 12384 25658 12387 25658 12388 25659 12386 25659 12389 25659 12390 25660 12388 25660 12391 25660 12391 25661 12393 25661 12392 25661 12394 25662 12392 25662 12395 25662 12395 25663 12397 25663 12396 25663 12397 25664 12399 25664 12398 25664 12399 25665 12401 25665 12400 25665 12402 25666 12400 25666 12403 25666 12404 25667 12402 25667 12405 25667 12406 25668 12404 25668 12407 25668 12408 25669 12406 25669 12409 25669 12410 25670 12408 25670 12411 25670 12412 25671 12410 25671 12413 25671 12409 25672 12413 25672 12411 25672 12395 25673 12399 25673 12397 25673 12391 25674 12395 25674 12393 25674 12387 25675 12391 25675 12389 25675 12383 25676 12387 25676 12385 25676 12379 25677 12383 25677 12381 25677 12371 25678 12375 25678 12373 25678 12357 25679 12361 25679 12359 25679 12353 25680 12415 25680 12357 25680 12415 25681 12413 25681 12357 25681 12413 25682 12409 25682 12357 25682 12409 25683 12407 25683 12357 25683 12407 25684 12405 25684 12357 25684 12405 25685 12403 25685 12357 25685 12403 25686 12401 25686 12357 25686 12401 25687 12399 25687 12357 25687 12399 25688 12395 25688 12357 25688 12395 25689 12391 25689 12357 25689 12391 25690 12387 25690 12357 25690 12387 25691 12383 25691 12357 25691 12383 25692 12379 25692 12357 25692 12379 25693 12377 25693 12357 25693 12377 25694 12375 25694 12357 25694 12375 25695 12371 25695 12357 25695 12371 25696 12369 25696 12357 25696 12369 25697 12367 25697 12357 25697 12367 25698 12365 25698 12357 25698 12365 25699 12363 25699 12361 25699 12357 25700 12365 25700 12361 25700 12352 25701 12414 25701 12353 25701 12414 25702 12412 25702 12415 25702 12354 25703 12356 25703 12358 25703 12414 25704 12354 25704 12412 25704 12354 25705 12358 25705 12412 25705 12358 25706 12360 25706 12412 25706 12360 25707 12362 25707 12412 25707 12362 25708 12364 25708 12412 25708 12364 25709 12366 25709 12412 25709 12366 25710 12368 25710 12412 25710 12368 25711 12370 25711 12412 25711 12370 25712 12372 25712 12412 25712 12372 25713 12374 25713 12412 25713 12374 25714 12376 25714 12412 25714 12376 25715 12378 25715 12412 25715 12378 25716 12380 25716 12412 25716 12380 25717 12382 25717 12384 25717 12412 25718 12380 25718 12384 25718 12410 25719 12412 25719 12384 25719 12408 25720 12410 25720 12406 25720 12410 25721 12384 25721 12406 25721 12396 25722 12392 25722 12394 25722 12398 25723 12392 25723 12396 25723 12406 25724 12384 25724 12404 25724 12404 25725 12384 25725 12402 25725 12384 25726 12386 25726 12402 25726 12386 25727 12388 25727 12402 25727 12388 25728 12390 25728 12402 25728 12390 25729 12392 25729 12402 25729 12392 25730 12398 25730 12400 25730 12402 25731 12392 25731 12400 25731 12418 25732 12416 25732 12419 25732 12419 25733 12421 25733 12420 25733 12421 25734 12423 25734 12422 25734 12423 25735 12425 25735 12424 25735 12425 25736 12427 25736 12426 25736 12427 25737 12429 25737 12428 25737 12429 25738 12431 25738 12430 25738 12431 25739 12433 25739 12432 25739 12434 25740 12432 25740 12435 25740 12436 25741 12434 25741 12437 25741 12438 25742 12436 25742 12439 25742 12440 25743 12438 25743 12441 25743 12442 25744 12440 25744 12443 25744 12444 25745 12442 25745 12445 25745 12446 25746 12444 25746 12447 25746 12448 25747 12446 25747 12449 25747 12450 25748 12448 25748 12451 25748 12452 25749 12450 25749 12453 25749 12454 25750 12452 25750 12455 25750 12455 25751 12457 25751 12456 25751 12457 25752 12459 25752 12458 25752 12459 25753 12461 25753 12460 25753 12461 25754 12463 25754 12462 25754 12463 25755 12465 25755 12464 25755 12466 25756 12464 25756 12467 25756 12468 25757 12466 25757 12469 25757 12470 25758 12468 25758 12471 25758 12472 25759 12470 25759 12473 25759 12474 25760 12472 25760 12475 25760 12476 25761 12474 25761 12477 25761 12447 25762 12451 25762 12449 25762 12441 25763 12445 25763 12443 25763 12419 25764 12417 25764 12421 25764 12417 25765 12479 25765 12421 25765 12479 25766 12477 25766 12421 25766 12477 25767 12473 25767 12421 25767 12473 25768 12471 25768 12421 25768 12471 25769 12469 25769 12421 25769 12469 25770 12467 25770 12421 25770 12467 25771 12465 25771 12421 25771 12465 25772 12463 25772 12421 25772 12463 25773 12461 25773 12421 25773 12461 25774 12459 25774 12421 25774 12459 25775 12457 25775 12421 25775 12457 25776 12455 25776 12421 25776 12455 25777 12453 25777 12421 25777 12453 25778 12451 25778 12421 25778 12451 25779 12447 25779 12421 25779 12447 25780 12445 25780 12421 25780 12445 25781 12441 25781 12421 25781 12441 25782 12439 25782 12421 25782 12439 25783 12437 25783 12421 25783 12437 25784 12435 25784 12421 25784 12435 25785 12433 25785 12421 25785 12433 25786 12431 25786 12421 25786 12431 25787 12429 25787 12421 25787 12429 25788 12427 25788 12421 25788 12427 25789 12425 25789 12421 25789 12425 25790 12423 25790 12421 25790 12416 25791 12478 25791 12417 25791 12478 25792 12476 25792 12479 25792 12418 25793 12420 25793 12478 25793 12420 25794 12422 25794 12478 25794 12422 25795 12424 25795 12478 25795 12424 25796 12426 25796 12478 25796 12426 25797 12428 25797 12478 25797 12428 25798 12430 25798 12478 25798 12430 25799 12432 25799 12478 25799 12432 25800 12434 25800 12478 25800 12434 25801 12436 25801 12478 25801 12436 25802 12438 25802 12478 25802 12438 25803 12440 25803 12478 25803 12442 25804 12444 25804 12446 25804 12442 25805 12446 25805 12448 25805 12442 25806 12448 25806 12450 25806 12442 25807 12450 25807 12452 25807 12440 25808 12442 25808 12452 25808 12478 25809 12440 25809 12452 25809 12462 25810 12458 25810 12460 25810 12478 25811 12452 25811 12454 25811 12476 25812 12478 25812 12454 25812 12462 25813 12456 25813 12458 25813 12466 25814 12462 25814 12464 25814 12466 25815 12456 25815 12462 25815 12468 25816 12456 25816 12466 25816 12470 25817 12456 25817 12468 25817 12472 25818 12456 25818 12470 25818 12472 25819 12454 25819 12456 25819 12474 25820 12476 25820 12454 25820 12472 25821 12474 25821 12454 25821</p> + </polylist> + <polylist material="mat_helix_back-material" count="5808"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>9316 19420 9317 19420 9318 19420 9319 19421 9318 19421 9317 19421 9320 19422 9318 19422 9321 19422 9322 19423 9321 19423 9318 19423 9316 19424 9318 19424 9320 19424 9323 19425 9318 19425 9319 19425 9324 19426 9322 19426 9318 19426 9325 19427 9324 19427 9318 19427 9323 19428 9325 19428 9318 19428 9326 19429 9327 19429 9317 19429 9328 19430 9317 19430 9327 19430 9329 19431 9326 19431 9317 19431 9330 19432 9329 19432 9317 19432 9316 19433 9330 19433 9317 19433 9331 19434 9317 19434 9328 19434 9332 19435 9333 19435 9317 19435 9334 19436 9317 19436 9333 19436 9331 19437 9332 19437 9317 19437 9334 19438 9319 19438 9317 19438 9335 19439 9336 19439 9327 19439 9337 19440 9327 19440 9336 19440 9326 19441 9335 19441 9327 19441 9328 19442 9327 19442 9337 19442 9338 19443 9339 19443 9336 19443 9340 19444 9336 19444 9339 19444 9335 19445 9338 19445 9336 19445 9337 19446 9336 19446 9340 19446 9341 19447 9339 19447 9338 19447 9340 19448 9339 19448 9341 19448 9342 19449 9338 19449 9335 19449 9341 19450 9338 19450 9342 19450 9343 19451 9335 19451 9326 19451 9342 19452 9335 19452 9343 19452 9344 19453 9345 19453 9326 19453 9346 19454 9326 19454 9345 19454 9329 19455 9344 19455 9326 19455 9343 19456 9326 19456 9346 19456 9347 19457 9348 19457 9345 19457 9349 19458 9345 19458 9348 19458 9350 19459 9347 19459 9345 19459 9344 19460 9350 19460 9345 19460 9346 19461 9345 19461 9351 19461 9349 19462 9351 19462 9345 19462 9352 19463 9353 19463 9348 19463 9354 19464 9348 19464 9353 19464 9347 19465 9352 19465 9348 19465 9355 19466 9349 19466 9348 19466 9356 19467 9355 19467 9348 19467 9357 19468 9356 19468 9348 19468 9354 19469 9357 19469 9348 19469 9358 19470 9359 19470 9353 19470 9360 19471 9353 19471 9359 19471 9361 19472 9358 19472 9353 19472 9362 19473 9361 19473 9353 19473 9352 19474 9362 19474 9353 19474 9363 19475 9353 19475 9360 19475 9364 19476 9354 19476 9353 19476 9365 19477 9366 19477 9353 19477 9364 19478 9353 19478 9366 19478 9363 19479 9365 19479 9353 19479 9367 19480 9368 19480 9359 19480 9369 19481 9359 19481 9368 19481 9358 19482 9367 19482 9359 19482 9360 19483 9359 19483 9369 19483 9370 19484 9371 19484 9368 19484 9372 19485 9368 19485 9371 19485 9367 19486 9370 19486 9368 19486 9369 19487 9368 19487 9372 19487 9373 19488 9371 19488 9370 19488 9372 19489 9371 19489 9373 19489 9374 19490 9370 19490 9367 19490 9373 19491 9370 19491 9374 19491 9375 19492 9367 19492 9358 19492 9374 19493 9367 19493 9375 19493 9376 19494 9321 19494 9358 19494 9377 19495 9358 19495 9321 19495 9361 19496 9376 19496 9358 19496 9375 19497 9358 19497 9377 19497 9378 19498 9320 19498 9321 19498 9376 19499 9378 19499 9321 19499 9377 19500 9321 19500 9379 19500 9322 19501 9379 19501 9321 19501 9380 19502 9320 19502 9378 19502 9381 19503 9316 19503 9320 19503 9381 19504 9320 19504 9380 19504 9382 19505 9378 19505 9376 19505 9382 19506 9380 19506 9378 19506 9383 19507 9376 19507 9361 19507 9382 19508 9376 19508 9383 19508 9384 19509 9361 19509 9362 19509 9383 19510 9361 19510 9384 19510 9385 19511 9362 19511 9352 19511 9384 19512 9362 19512 9385 19512 9386 19513 9352 19513 9347 19513 9385 19514 9352 19514 9386 19514 9387 19515 9347 19515 9350 19515 9386 19516 9347 19516 9387 19516 9388 19517 9350 19517 9344 19517 9387 19518 9350 19518 9388 19518 9389 19519 9344 19519 9329 19519 9388 19520 9344 19520 9389 19520 9390 19521 9329 19521 9330 19521 9389 19522 9329 19522 9390 19522 9330 19523 9316 19523 9391 19523 9390 19524 9330 19524 9391 19524 9391 19525 9316 19525 9381 19525 9382 19526 9379 19526 9392 19526 9393 19527 9392 19527 9379 19527 9380 19528 9392 19528 9328 19528 9331 19529 9328 19529 9392 19529 9382 19530 9392 19530 9380 19530 9394 19531 9331 19531 9392 19531 9395 19532 9394 19532 9392 19532 9396 19533 9395 19533 9392 19533 9397 19534 9396 19534 9392 19534 9398 19535 9397 19535 9392 19535 9393 19536 9398 19536 9392 19536 9369 19537 9377 19537 9379 19537 9384 19538 9369 19538 9379 19538 9383 19539 9384 19539 9379 19539 9382 19540 9383 19540 9379 19540 9399 19541 9393 19541 9379 19541 9322 19542 9399 19542 9379 19542 9372 19543 9375 19543 9377 19543 9369 19544 9372 19544 9377 19544 9373 19545 9374 19545 9375 19545 9372 19546 9373 19546 9375 19546 9385 19547 9360 19547 9369 19547 9384 19548 9385 19548 9369 19548 9387 19549 9400 19549 9360 19549 9363 19550 9360 19550 9400 19550 9386 19551 9387 19551 9360 19551 9385 19552 9386 19552 9360 19552 9388 19553 9351 19553 9400 19553 9401 19554 9400 19554 9351 19554 9387 19555 9388 19555 9400 19555 9402 19556 9400 19556 9401 19556 9403 19557 9363 19557 9400 19557 9404 19558 9403 19558 9400 19558 9405 19559 9404 19559 9400 19559 9406 19560 9405 19560 9400 19560 9402 19561 9406 19561 9400 19561 9337 19562 9346 19562 9351 19562 9390 19563 9337 19563 9351 19563 9389 19564 9390 19564 9351 19564 9388 19565 9389 19565 9351 19565 9407 19566 9401 19566 9351 19566 9349 19567 9407 19567 9351 19567 9340 19568 9343 19568 9346 19568 9337 19569 9340 19569 9346 19569 9341 19570 9342 19570 9343 19570 9340 19571 9341 19571 9343 19571 9391 19572 9328 19572 9337 19572 9390 19573 9391 19573 9337 19573 9381 19574 9380 19574 9328 19574 9391 19575 9381 19575 9328 19575 9408 19576 9333 19576 9332 19576 9408 19577 9334 19577 9333 19577 9409 19578 9332 19578 9331 19578 9410 19579 9408 19579 9332 19579 9409 19580 9410 19580 9332 19580 9411 19581 9331 19581 9394 19581 9412 19582 9331 19582 9411 19582 9412 19583 9409 19583 9331 19583 9413 19584 9394 19584 9395 19584 9414 19585 9411 19585 9394 19585 9413 19586 9414 19586 9394 19586 9415 19587 9395 19587 9396 19587 9416 19588 9413 19588 9395 19588 9417 19589 9416 19589 9395 19589 9415 19590 9417 19590 9395 19590 9418 19591 9396 19591 9397 19591 9419 19592 9415 19592 9396 19592 9418 19593 9419 19593 9396 19593 9420 19594 9397 19594 9398 19594 9418 19595 9397 19595 9420 19595 9420 19596 9398 19596 9393 19596 9421 19597 9393 19597 9399 19597 9421 19598 9422 19598 9393 19598 9420 19599 9393 19599 9422 19599 9423 19600 9401 19600 9407 19600 9424 19601 9402 19601 9401 19601 9423 19602 9425 19602 9401 19602 9424 19603 9401 19603 9425 19603 9423 19604 9407 19604 9349 19604 9423 19605 9349 19605 9355 19605 9423 19606 9355 19606 9356 19606 9426 19607 9356 19607 9357 19607 9426 19608 9423 19608 9356 19608 9426 19609 9357 19609 9354 19609 9427 19610 9354 19610 9364 19610 9426 19611 9354 19611 9427 19611 9408 19612 9319 19612 9334 19612 9428 19613 9323 19613 9319 19613 9428 19614 9319 19614 9408 19614 9427 19615 9366 19615 9365 19615 9427 19616 9364 19616 9366 19616 9429 19617 9365 19617 9363 19617 9430 19618 9427 19618 9365 19618 9431 19619 9430 19619 9365 19619 9429 19620 9431 19620 9365 19620 9432 19621 9363 19621 9403 19621 9433 19622 9363 19622 9432 19622 9434 19623 9429 19623 9363 19623 9433 19624 9434 19624 9363 19624 9435 19625 9403 19625 9404 19625 9436 19626 9432 19626 9403 19626 9435 19627 9436 19627 9403 19627 9437 19628 9404 19628 9405 19628 9438 19629 9435 19629 9404 19629 9439 19630 9438 19630 9404 19630 9437 19631 9439 19631 9404 19631 9440 19632 9405 19632 9406 19632 9441 19633 9437 19633 9405 19633 9440 19634 9441 19634 9405 19634 9424 19635 9406 19635 9402 19635 9442 19636 9406 19636 9424 19636 9442 19637 9440 19637 9406 19637 9421 19638 9399 19638 9322 19638 9421 19639 9322 19639 9324 19639 9421 19640 9324 19640 9325 19640 9428 19641 9325 19641 9323 19641 9428 19642 9421 19642 9325 19642 9443 19643 9425 19643 9423 19643 9444 19644 9424 19644 9425 19644 9445 19645 9444 19645 9425 19645 9446 19646 9445 19646 9425 19646 9447 19647 9446 19647 9425 19647 9448 19648 9447 19648 9425 19648 9449 19649 9448 19649 9425 19649 9450 19650 9449 19650 9425 19650 9450 19651 9425 19651 9443 19651 9451 19652 9423 19652 9426 19652 9452 19653 9453 19653 9423 19653 9454 19654 9423 19654 9453 19654 9451 19655 9452 19655 9423 19655 9455 19656 9443 19656 9423 19656 9456 19657 9455 19657 9423 19657 9457 19658 9456 19658 9423 19658 9458 19659 9457 19659 9423 19659 9459 19660 9458 19660 9423 19660 9460 19661 9459 19661 9423 19661 9454 19662 9460 19662 9423 19662 9442 19663 9424 19663 9444 19663 9461 19664 9444 19664 9445 19664 9461 19665 9442 19665 9444 19665 9462 19666 9445 19666 9446 19666 9461 19667 9445 19667 9462 19667 9462 19668 9446 19668 9447 19668 9463 19669 9447 19669 9448 19669 9462 19670 9447 19670 9463 19670 9449 19671 9464 19671 9448 19671 9463 19672 9448 19672 9464 19672 9449 19673 9465 19673 9464 19673 9466 19674 9464 19674 9465 19674 9463 19675 9464 19675 9466 19675 9449 19676 9467 19676 9465 19676 9466 19677 9465 19677 9467 19677 9449 19678 9468 19678 9467 19678 9469 19679 9467 19679 9468 19679 9466 19680 9467 19680 9469 19680 9449 19681 9470 19681 9468 19681 9469 19682 9468 19682 9470 19682 9449 19683 9471 19683 9470 19683 9469 19684 9470 19684 9471 19684 9472 19685 9473 19685 9471 19685 9474 19686 9471 19686 9473 19686 9449 19687 9472 19687 9471 19687 9469 19688 9471 19688 9474 19688 9472 19689 9475 19689 9473 19689 9474 19690 9473 19690 9475 19690 9472 19691 9476 19691 9475 19691 9477 19692 9475 19692 9476 19692 9474 19693 9475 19693 9477 19693 9472 19694 9478 19694 9476 19694 9477 19695 9476 19695 9478 19695 9472 19696 9479 19696 9478 19696 9480 19697 9478 19697 9479 19697 9477 19698 9478 19698 9480 19698 9472 19699 9481 19699 9479 19699 9480 19700 9479 19700 9481 19700 9482 19701 9483 19701 9481 19701 9484 19702 9481 19702 9483 19702 9472 19703 9482 19703 9481 19703 9480 19704 9481 19704 9484 19704 9482 19705 9485 19705 9483 19705 9486 19706 9483 19706 9485 19706 9484 19707 9483 19707 9486 19707 9482 19708 9487 19708 9485 19708 9486 19709 9485 19709 9487 19709 9488 19710 9489 19710 9487 19710 9490 19711 9487 19711 9489 19711 9482 19712 9488 19712 9487 19712 9486 19713 9487 19713 9490 19713 9488 19714 9491 19714 9489 19714 9490 19715 9489 19715 9491 19715 9488 19716 9492 19716 9491 19716 9493 19717 9491 19717 9492 19717 9490 19718 9491 19718 9493 19718 9494 19719 9495 19719 9492 19719 9496 19720 9492 19720 9495 19720 9488 19721 9494 19721 9492 19721 9493 19722 9492 19722 9496 19722 9494 19723 9497 19723 9495 19723 9498 19724 9495 19724 9497 19724 9496 19725 9495 19725 9498 19725 9499 19726 9500 19726 9497 19726 9501 19727 9497 19727 9500 19727 9494 19728 9499 19728 9497 19728 9498 19729 9497 19729 9501 19729 9499 19730 9502 19730 9500 19730 9503 19731 9500 19731 9502 19731 9501 19732 9500 19732 9503 19732 9504 19733 9505 19733 9502 19733 9506 19734 9502 19734 9505 19734 9499 19735 9504 19735 9502 19735 9507 19736 9502 19736 9506 19736 9503 19737 9502 19737 9507 19737 9508 19738 9509 19738 9505 19738 9510 19739 9505 19739 9509 19739 9504 19740 9508 19740 9505 19740 9506 19741 9505 19741 9510 19741 9511 19742 9512 19742 9509 19742 9513 19743 9509 19743 9512 19743 9508 19744 9511 19744 9509 19744 9514 19745 9509 19745 9513 19745 9510 19746 9509 19746 9514 19746 9515 19747 9516 19747 9512 19747 9517 19748 9512 19748 9516 19748 9518 19749 9515 19749 9512 19749 9511 19750 9518 19750 9512 19750 9513 19751 9512 19751 9517 19751 9519 19752 9520 19752 9516 19752 9521 19753 9516 19753 9520 19753 9522 19754 9519 19754 9516 19754 9515 19755 9522 19755 9516 19755 9523 19756 9516 19756 9521 19756 9517 19757 9516 19757 9523 19757 9524 19758 9525 19758 9520 19758 9526 19759 9520 19759 9525 19759 9519 19760 9524 19760 9520 19760 9527 19761 9520 19761 9526 19761 9528 19762 9520 19762 9527 19762 9521 19763 9520 19763 9528 19763 9529 19764 9530 19764 9525 19764 9531 19765 9525 19765 9530 19765 9532 19766 9529 19766 9525 19766 9524 19767 9532 19767 9525 19767 9533 19768 9525 19768 9531 19768 9526 19769 9525 19769 9533 19769 9534 19770 9535 19770 9530 19770 9536 19771 9530 19771 9535 19771 9537 19772 9534 19772 9530 19772 9529 19773 9537 19773 9530 19773 9538 19774 9530 19774 9536 19774 9531 19775 9530 19775 9538 19775 9539 19776 9540 19776 9535 19776 9541 19777 9535 19777 9540 19777 9534 19778 9539 19778 9535 19778 9542 19779 9535 19779 9541 19779 9536 19780 9535 19780 9542 19780 9543 19781 9544 19781 9540 19781 9545 19782 9540 19782 9544 19782 9546 19783 9543 19783 9540 19783 9547 19784 9546 19784 9540 19784 9548 19785 9547 19785 9540 19785 9549 19786 9548 19786 9540 19786 9539 19787 9549 19787 9540 19787 9541 19788 9540 19788 9545 19788 9550 19789 9544 19789 9543 19789 9551 19790 9544 19790 9550 19790 9545 19791 9544 19791 9551 19791 9550 19792 9543 19792 9546 19792 9552 19793 9546 19793 9547 19793 9552 19794 9550 19794 9546 19794 9553 19795 9547 19795 9548 19795 9553 19796 9552 19796 9547 19796 9553 19797 9548 19797 9549 19797 9554 19798 9549 19798 9539 19798 9553 19799 9549 19799 9554 19799 9554 19800 9539 19800 9534 19800 9555 19801 9534 19801 9537 19801 9555 19802 9554 19802 9534 19802 9555 19803 9537 19803 9529 19803 9556 19804 9529 19804 9532 19804 9556 19805 9555 19805 9529 19805 9556 19806 9532 19806 9524 19806 9556 19807 9524 19807 9519 19807 9557 19808 9519 19808 9522 19808 9557 19809 9556 19809 9519 19809 9557 19810 9522 19810 9515 19810 9558 19811 9515 19811 9518 19811 9558 19812 9557 19812 9515 19812 9558 19813 9518 19813 9511 19813 9559 19814 9511 19814 9508 19814 9559 19815 9558 19815 9511 19815 9559 19816 9508 19816 9504 19816 9560 19817 9504 19817 9499 19817 9560 19818 9559 19818 9504 19818 9560 19819 9499 19819 9494 19819 9561 19820 9494 19820 9488 19820 9561 19821 9560 19821 9494 19821 9562 19822 9488 19822 9482 19822 9562 19823 9561 19823 9488 19823 9562 19824 9482 19824 9472 19824 9563 19825 9472 19825 9449 19825 9563 19826 9562 19826 9472 19826 9450 19827 9563 19827 9449 19827 9564 19828 9426 19828 9427 19828 9565 19829 9564 19829 9427 19829 9565 19830 9427 19830 9430 19830 9566 19831 9567 19831 9426 19831 9568 19832 9426 19832 9567 19832 9569 19833 9566 19833 9426 19833 9564 19834 9569 19834 9426 19834 9570 19835 9451 19835 9426 19835 9571 19836 9570 19836 9426 19836 9572 19837 9571 19837 9426 19837 9573 19838 9572 19838 9426 19838 9574 19839 9573 19839 9426 19839 9568 19840 9574 19840 9426 19840 9575 19841 9576 19841 9567 19841 9577 19842 9567 19842 9576 19842 9578 19843 9575 19843 9567 19843 9579 19844 9578 19844 9567 19844 9580 19845 9579 19845 9567 19845 9581 19846 9580 19846 9567 19846 9582 19847 9581 19847 9567 19847 9583 19848 9582 19848 9567 19848 9584 19849 9583 19849 9567 19849 9585 19850 9584 19850 9567 19850 9566 19851 9585 19851 9567 19851 9568 19852 9567 19852 9572 19852 9577 19853 9572 19853 9567 19853 9586 19854 9587 19854 9576 19854 9588 19855 9576 19855 9587 19855 9589 19856 9586 19856 9576 19856 9590 19857 9589 19857 9576 19857 9591 19858 9590 19858 9576 19858 9592 19859 9591 19859 9576 19859 9593 19860 9592 19860 9576 19860 9575 19861 9593 19861 9576 19861 9577 19862 9576 19862 9588 19862 9594 19863 9595 19863 9587 19863 9596 19864 9587 19864 9595 19864 9597 19865 9594 19865 9587 19865 9598 19866 9597 19866 9587 19866 9599 19867 9598 19867 9587 19867 9586 19868 9599 19868 9587 19868 9588 19869 9587 19869 9596 19869 9600 19870 9601 19870 9595 19870 9602 19871 9595 19871 9601 19871 9603 19872 9600 19872 9595 19872 9594 19873 9603 19873 9595 19873 9596 19874 9595 19874 9602 19874 9604 19875 9605 19875 9601 19875 9606 19876 9601 19876 9605 19876 9607 19877 9604 19877 9601 19877 9600 19878 9607 19878 9601 19878 9602 19879 9601 19879 9606 19879 9608 19880 9609 19880 9605 19880 9610 19881 9605 19881 9609 19881 9604 19882 9608 19882 9605 19882 9606 19883 9605 19883 9610 19883 9611 19884 9612 19884 9609 19884 9610 19885 9609 19885 9612 19885 9608 19886 9611 19886 9609 19886 9613 19887 9614 19887 9612 19887 9615 19888 9612 19888 9614 19888 9611 19889 9613 19889 9612 19889 9610 19890 9612 19890 9615 19890 9616 19891 9617 19891 9614 19891 9615 19892 9614 19892 9617 19892 9613 19893 9616 19893 9614 19893 9618 19894 9619 19894 9617 19894 9620 19895 9617 19895 9619 19895 9616 19896 9618 19896 9617 19896 9615 19897 9617 19897 9620 19897 9618 19898 9621 19898 9619 19898 9622 19899 9619 19899 9621 19899 9620 19900 9619 19900 9622 19900 9623 19901 9624 19901 9621 19901 9622 19902 9621 19902 9624 19902 9618 19903 9623 19903 9621 19903 9623 19904 9625 19904 9624 19904 9622 19905 9624 19905 9625 19905 9626 19906 9627 19906 9625 19906 9628 19907 9625 19907 9627 19907 9623 19908 9626 19908 9625 19908 9622 19909 9625 19909 9628 19909 9629 19910 9630 19910 9627 19910 9628 19911 9627 19911 9630 19911 9626 19912 9629 19912 9627 19912 9631 19913 9632 19913 9630 19913 9633 19914 9630 19914 9632 19914 9629 19915 9631 19915 9630 19915 9628 19916 9630 19916 9633 19916 9631 19917 9634 19917 9632 19917 9635 19918 9632 19918 9634 19918 9635 19919 9633 19919 9632 19919 9631 19920 9636 19920 9634 19920 9637 19921 9634 19921 9636 19921 9637 19922 9635 19922 9634 19922 9631 19923 9638 19923 9636 19923 9637 19924 9636 19924 9638 19924 9639 19925 9638 19925 9631 19925 9640 19926 9637 19926 9638 19926 9641 19927 9640 19927 9638 19927 9642 19928 9641 19928 9638 19928 9639 19929 9642 19929 9638 19929 9643 19930 9631 19930 9629 19930 9643 19931 9639 19931 9631 19931 9644 19932 9629 19932 9626 19932 9644 19933 9643 19933 9629 19933 9645 19934 9626 19934 9623 19934 9646 19935 9644 19935 9626 19935 9645 19936 9646 19936 9626 19936 9647 19937 9623 19937 9618 19937 9647 19938 9645 19938 9623 19938 9648 19939 9618 19939 9616 19939 9649 19940 9647 19940 9618 19940 9650 19941 9649 19941 9618 19941 9648 19942 9650 19942 9618 19942 9651 19943 9616 19943 9613 19943 9652 19944 9648 19944 9616 19944 9651 19945 9652 19945 9616 19945 9653 19946 9613 19946 9611 19946 9654 19947 9651 19947 9613 19947 9655 19948 9654 19948 9613 19948 9653 19949 9655 19949 9613 19949 9656 19950 9611 19950 9608 19950 9657 19951 9653 19951 9611 19951 9656 19952 9657 19952 9611 19952 9658 19953 9608 19953 9604 19953 9659 19954 9656 19954 9608 19954 9658 19955 9659 19955 9608 19955 9660 19956 9604 19956 9607 19956 9660 19957 9658 19957 9604 19957 9661 19958 9607 19958 9600 19958 9662 19959 9660 19959 9607 19959 9661 19960 9662 19960 9607 19960 9663 19961 9600 19961 9603 19961 9663 19962 9661 19962 9600 19962 9664 19963 9603 19963 9594 19963 9664 19964 9663 19964 9603 19964 9665 19965 9594 19965 9597 19965 9665 19966 9664 19966 9594 19966 9666 19967 9597 19967 9598 19967 9666 19968 9665 19968 9597 19968 9666 19969 9598 19969 9599 19969 9667 19970 9599 19970 9586 19970 9667 19971 9666 19971 9599 19971 9667 19972 9586 19972 9589 19972 9668 19973 9589 19973 9590 19973 9668 19974 9667 19974 9589 19974 9668 19975 9590 19975 9591 19975 9669 19976 9591 19976 9592 19976 9669 19977 9668 19977 9591 19977 9669 19978 9592 19978 9593 19978 9670 19979 9593 19979 9575 19979 9670 19980 9669 19980 9593 19980 9670 19981 9575 19981 9578 19981 9671 19982 9578 19982 9579 19982 9671 19983 9670 19983 9578 19983 9671 19984 9579 19984 9580 19984 9672 19985 9580 19985 9581 19985 9672 19986 9671 19986 9580 19986 9673 19987 9581 19987 9582 19987 9673 19988 9672 19988 9581 19988 9673 19989 9582 19989 9583 19989 9673 19990 9583 19990 9584 19990 9674 19991 9584 19991 9585 19991 9674 19992 9673 19992 9584 19992 9674 19993 9585 19993 9566 19993 9675 19994 9566 19994 9569 19994 9675 19995 9674 19995 9566 19995 9565 19996 9569 19996 9564 19996 9565 19997 9675 19997 9569 19997 9433 19998 9432 19998 9436 19998 9676 19999 9436 19999 9435 19999 9677 20000 9436 20000 9676 20000 9433 20001 9436 20001 9677 20001 9676 20002 9435 20002 9438 20002 9439 20003 9676 20003 9438 20003 9678 20004 9677 20004 9676 20004 9678 20005 9676 20005 9679 20005 9680 20006 9679 20006 9676 20006 9680 20007 9676 20007 9439 20007 9433 20008 9677 20008 9678 20008 9681 20009 9682 20009 9683 20009 9684 20010 9683 20010 9682 20010 9685 20011 9681 20011 9683 20011 9686 20012 9685 20012 9683 20012 9684 20013 9686 20013 9683 20013 9687 20014 9688 20014 9682 20014 9689 20015 9682 20015 9688 20015 9681 20016 9687 20016 9682 20016 9690 20017 9684 20017 9682 20017 9689 20018 9690 20018 9682 20018 9691 20019 9692 20019 9688 20019 9693 20020 9688 20020 9692 20020 9687 20021 9691 20021 9688 20021 9693 20022 9689 20022 9688 20022 9691 20023 9694 20023 9692 20023 9695 20024 9692 20024 9694 20024 9695 20025 9693 20025 9692 20025 9696 20026 9697 20026 9694 20026 9695 20027 9694 20027 9697 20027 9691 20028 9696 20028 9694 20028 9698 20029 9699 20029 9697 20029 9700 20030 9697 20030 9699 20030 9696 20031 9698 20031 9697 20031 9700 20032 9695 20032 9697 20032 9701 20033 9702 20033 9699 20033 9703 20034 9699 20034 9702 20034 9698 20035 9701 20035 9699 20035 9703 20036 9700 20036 9699 20036 9704 20037 9705 20037 9702 20037 9706 20038 9702 20038 9705 20038 9701 20039 9704 20039 9702 20039 9706 20040 9703 20040 9702 20040 9707 20041 9708 20041 9705 20041 9706 20042 9705 20042 9708 20042 9704 20043 9707 20043 9705 20043 9709 20044 9710 20044 9708 20044 9711 20045 9708 20045 9710 20045 9707 20046 9709 20046 9708 20046 9711 20047 9706 20047 9708 20047 9712 20048 9713 20048 9710 20048 9711 20049 9710 20049 9713 20049 9709 20050 9712 20050 9710 20050 9714 20051 9715 20051 9713 20051 9716 20052 9713 20052 9715 20052 9712 20053 9714 20053 9713 20053 9716 20054 9711 20054 9713 20054 9717 20055 9718 20055 9715 20055 9716 20056 9715 20056 9718 20056 9714 20057 9717 20057 9715 20057 9719 20058 9720 20058 9718 20058 9721 20059 9718 20059 9720 20059 9717 20060 9719 20060 9718 20060 9721 20061 9716 20061 9718 20061 9722 20062 9723 20062 9720 20062 9724 20063 9720 20063 9723 20063 9719 20064 9722 20064 9720 20064 9724 20065 9721 20065 9720 20065 9725 20066 9726 20066 9723 20066 9724 20067 9723 20067 9726 20067 9722 20068 9725 20068 9723 20068 9727 20069 9728 20069 9726 20069 9729 20070 9726 20070 9728 20070 9730 20071 9727 20071 9726 20071 9725 20072 9730 20072 9726 20072 9729 20073 9724 20073 9726 20073 9731 20074 9732 20074 9728 20074 9733 20075 9728 20075 9732 20075 9727 20076 9731 20076 9728 20076 9733 20077 9729 20077 9728 20077 9734 20078 9735 20078 9732 20078 9733 20079 9732 20079 9735 20079 9731 20080 9734 20080 9732 20080 9736 20081 9737 20081 9735 20081 9738 20082 9735 20082 9737 20082 9734 20083 9736 20083 9735 20083 9738 20084 9733 20084 9735 20084 9739 20085 9740 20085 9737 20085 9738 20086 9737 20086 9740 20086 9736 20087 9739 20087 9737 20087 9741 20088 9742 20088 9740 20088 9743 20089 9740 20089 9742 20089 9739 20090 9741 20090 9740 20090 9743 20091 9738 20091 9740 20091 9744 20092 9745 20092 9742 20092 9746 20093 9742 20093 9745 20093 9741 20094 9744 20094 9742 20094 9746 20095 9743 20095 9742 20095 9747 20096 9748 20096 9745 20096 9746 20097 9745 20097 9748 20097 9744 20098 9747 20098 9745 20098 9747 20099 9749 20099 9748 20099 9750 20100 9748 20100 9749 20100 9750 20101 9746 20101 9748 20101 9747 20102 9751 20102 9749 20102 9752 20103 9749 20103 9751 20103 9752 20104 9750 20104 9749 20104 9753 20105 9754 20105 9751 20105 9755 20106 9751 20106 9754 20106 9756 20107 9753 20107 9751 20107 9747 20108 9756 20108 9751 20108 9755 20109 9752 20109 9751 20109 9757 20110 9758 20110 9754 20110 9759 20111 9754 20111 9758 20111 9753 20112 9757 20112 9754 20112 9759 20113 9755 20113 9754 20113 9760 20114 9761 20114 9758 20114 9762 20115 9758 20115 9761 20115 9757 20116 9760 20116 9758 20116 9763 20117 9759 20117 9758 20117 9762 20118 9763 20118 9758 20118 9764 20119 9765 20119 9761 20119 9762 20120 9761 20120 9765 20120 9760 20121 9764 20121 9761 20121 9766 20122 9767 20122 9765 20122 9768 20123 9765 20123 9767 20123 9764 20124 9766 20124 9765 20124 9768 20125 9762 20125 9765 20125 9769 20126 9770 20126 9767 20126 9771 20127 9767 20127 9770 20127 9766 20128 9769 20128 9767 20128 9771 20129 9768 20129 9767 20129 9772 20130 9773 20130 9770 20130 9771 20131 9770 20131 9773 20131 9769 20132 9772 20132 9770 20132 9774 20133 9775 20133 9773 20133 9776 20134 9773 20134 9775 20134 9777 20135 9774 20135 9773 20135 9772 20136 9777 20136 9773 20136 9776 20137 9771 20137 9773 20137 9778 20138 9779 20138 9775 20138 9780 20139 9775 20139 9779 20139 9774 20140 9778 20140 9775 20140 9780 20141 9776 20141 9775 20141 9781 20142 9782 20142 9779 20142 9780 20143 9779 20143 9782 20143 9778 20144 9781 20144 9779 20144 9783 20145 9784 20145 9782 20145 9785 20146 9782 20146 9784 20146 9786 20147 9783 20147 9782 20147 9781 20148 9786 20148 9782 20148 9785 20149 9780 20149 9782 20149 9787 20150 9788 20150 9784 20150 9785 20151 9784 20151 9788 20151 9783 20152 9787 20152 9784 20152 9789 20153 9790 20153 9788 20153 9791 20154 9788 20154 9790 20154 9787 20155 9789 20155 9788 20155 9791 20156 9785 20156 9788 20156 9792 20157 9793 20157 9790 20157 9791 20158 9790 20158 9793 20158 9789 20159 9792 20159 9790 20159 9794 20160 9795 20160 9793 20160 9796 20161 9793 20161 9795 20161 9792 20162 9794 20162 9793 20162 9796 20163 9791 20163 9793 20163 9797 20164 9798 20164 9795 20164 9796 20165 9795 20165 9798 20165 9794 20166 9797 20166 9795 20166 9799 20167 9800 20167 9798 20167 9801 20168 9798 20168 9800 20168 9797 20169 9799 20169 9798 20169 9801 20170 9796 20170 9798 20170 9802 20171 9803 20171 9800 20171 9801 20172 9800 20172 9803 20172 9799 20173 9802 20173 9800 20173 9804 20174 9805 20174 9803 20174 9806 20175 9803 20175 9805 20175 9802 20176 9804 20176 9803 20176 9806 20177 9801 20177 9803 20177 9807 20178 9808 20178 9805 20178 9806 20179 9805 20179 9808 20179 9804 20180 9807 20180 9805 20180 9809 20181 9810 20181 9808 20181 9811 20182 9808 20182 9810 20182 9807 20183 9809 20183 9808 20183 9811 20184 9806 20184 9808 20184 9812 20185 9813 20185 9810 20185 9811 20186 9810 20186 9813 20186 9814 20187 9812 20187 9810 20187 9809 20188 9814 20188 9810 20188 9815 20189 9816 20189 9813 20189 9817 20190 9813 20190 9816 20190 9812 20191 9815 20191 9813 20191 9817 20192 9811 20192 9813 20192 9818 20193 9679 20193 9816 20193 9680 20194 9816 20194 9679 20194 9815 20195 9818 20195 9816 20195 9680 20196 9817 20196 9816 20196 9818 20197 9678 20197 9679 20197 9819 20198 9678 20198 9818 20198 9819 20199 9433 20199 9678 20199 9819 20200 9818 20200 9815 20200 9820 20201 9815 20201 9812 20201 9820 20202 9819 20202 9815 20202 9820 20203 9812 20203 9814 20203 9821 20204 9814 20204 9809 20204 9821 20205 9820 20205 9814 20205 9821 20206 9809 20206 9807 20206 9821 20207 9807 20207 9804 20207 9822 20208 9804 20208 9802 20208 9822 20209 9821 20209 9804 20209 9822 20210 9802 20210 9799 20210 9823 20211 9799 20211 9797 20211 9823 20212 9822 20212 9799 20212 9824 20213 9797 20213 9794 20213 9824 20214 9823 20214 9797 20214 9824 20215 9794 20215 9792 20215 9824 20216 9792 20216 9789 20216 9825 20217 9789 20217 9787 20217 9825 20218 9824 20218 9789 20218 9825 20219 9787 20219 9783 20219 9826 20220 9783 20220 9786 20220 9826 20221 9825 20221 9783 20221 9826 20222 9786 20222 9781 20222 9826 20223 9781 20223 9778 20223 9827 20224 9778 20224 9774 20224 9827 20225 9826 20225 9778 20225 9827 20226 9774 20226 9777 20226 9828 20227 9777 20227 9772 20227 9828 20228 9827 20228 9777 20228 9829 20229 9772 20229 9769 20229 9829 20230 9828 20230 9772 20230 9829 20231 9769 20231 9766 20231 9830 20232 9766 20232 9764 20232 9830 20233 9829 20233 9766 20233 9831 20234 9764 20234 9760 20234 9831 20235 9830 20235 9764 20235 9832 20236 9760 20236 9757 20236 9832 20237 9831 20237 9760 20237 9833 20238 9757 20238 9753 20238 9833 20239 9832 20239 9757 20239 9834 20240 9753 20240 9756 20240 9834 20241 9833 20241 9753 20241 9835 20242 9756 20242 9747 20242 9835 20243 9834 20243 9756 20243 9836 20244 9747 20244 9744 20244 9836 20245 9835 20245 9747 20245 9837 20246 9744 20246 9741 20246 9837 20247 9836 20247 9744 20247 9838 20248 9741 20248 9739 20248 9838 20249 9837 20249 9741 20249 9838 20250 9739 20250 9736 20250 9839 20251 9736 20251 9734 20251 9839 20252 9838 20252 9736 20252 9840 20253 9734 20253 9731 20253 9840 20254 9839 20254 9734 20254 9840 20255 9731 20255 9727 20255 9841 20256 9727 20256 9730 20256 9841 20257 9840 20257 9727 20257 9841 20258 9730 20258 9725 20258 9842 20259 9725 20259 9722 20259 9842 20260 9841 20260 9725 20260 9842 20261 9722 20261 9719 20261 9843 20262 9719 20262 9717 20262 9843 20263 9842 20263 9719 20263 9844 20264 9717 20264 9714 20264 9844 20265 9843 20265 9717 20265 9844 20266 9714 20266 9712 20266 9845 20267 9712 20267 9709 20267 9845 20268 9844 20268 9712 20268 9845 20269 9709 20269 9707 20269 9846 20270 9707 20270 9704 20270 9846 20271 9845 20271 9707 20271 9847 20272 9704 20272 9701 20272 9847 20273 9846 20273 9704 20273 9847 20274 9701 20274 9698 20274 9848 20275 9698 20275 9696 20275 9848 20276 9847 20276 9698 20276 9848 20277 9696 20277 9691 20277 9849 20278 9691 20278 9687 20278 9849 20279 9848 20279 9691 20279 9850 20280 9687 20280 9681 20280 9851 20281 9849 20281 9687 20281 9850 20282 9851 20282 9687 20282 9852 20283 9681 20283 9685 20283 9852 20284 9850 20284 9681 20284 9853 20285 9685 20285 9686 20285 9640 20286 9685 20286 9853 20286 9854 20287 9685 20287 9640 20287 9852 20288 9685 20288 9854 20288 9855 20289 9853 20289 9686 20289 9552 20290 9855 20290 9686 20290 9552 20291 9686 20291 9550 20291 9856 20292 9550 20292 9686 20292 9857 20293 9856 20293 9686 20293 9858 20294 9859 20294 9860 20294 9684 20295 9857 20295 9686 20295 9861 20296 9853 20296 9855 20296 9640 20297 9853 20297 9861 20297 9862 20298 9863 20298 9864 20298 9554 20299 9864 20299 9863 20299 9865 20300 9862 20300 9864 20300 9866 20301 9865 20301 9864 20301 9555 20302 9866 20302 9864 20302 9555 20303 9864 20303 9554 20303 9861 20304 9855 20304 9863 20304 9553 20305 9863 20305 9855 20305 9862 20306 9861 20306 9863 20306 9553 20307 9554 20307 9863 20307 9553 20308 9855 20308 9552 20308 9637 20309 9861 20309 9862 20309 9640 20310 9861 20310 9637 20310 9635 20311 9862 20311 9865 20311 9637 20312 9862 20312 9635 20312 9867 20313 9865 20313 9866 20313 9633 20314 9865 20314 9867 20314 9635 20315 9865 20315 9633 20315 9868 20316 9869 20316 9453 20316 9454 20317 9453 20317 9869 20317 9452 20318 9868 20318 9453 20318 9870 20319 9871 20319 9869 20319 9450 20320 9869 20320 9871 20320 9868 20321 9870 20321 9869 20321 9458 20322 9869 20322 9457 20322 9450 20323 9457 20323 9869 20323 9459 20324 9869 20324 9458 20324 9460 20325 9869 20325 9459 20325 9454 20326 9869 20326 9460 20326 9872 20327 9873 20327 9871 20327 9563 20328 9871 20328 9873 20328 9870 20329 9872 20329 9871 20329 9450 20330 9871 20330 9563 20330 9874 20331 9875 20331 9873 20331 9562 20332 9873 20332 9875 20332 9872 20333 9874 20333 9873 20333 9563 20334 9873 20334 9562 20334 9874 20335 9876 20335 9875 20335 9562 20336 9875 20336 9876 20336 9877 20337 9878 20337 9876 20337 9561 20338 9876 20338 9878 20338 9874 20339 9877 20339 9876 20339 9562 20340 9876 20340 9561 20340 9879 20341 9880 20341 9878 20341 9560 20342 9878 20342 9880 20342 9877 20343 9879 20343 9878 20343 9561 20344 9878 20344 9560 20344 9881 20345 9882 20345 9880 20345 9560 20346 9880 20346 9882 20346 9879 20347 9881 20347 9880 20347 9881 20348 9883 20348 9882 20348 9559 20349 9882 20349 9883 20349 9560 20350 9882 20350 9559 20350 9884 20351 9885 20351 9883 20351 9559 20352 9883 20352 9885 20352 9881 20353 9884 20353 9883 20353 9886 20354 9887 20354 9885 20354 9558 20355 9885 20355 9887 20355 9884 20356 9886 20356 9885 20356 9559 20357 9885 20357 9558 20357 9886 20358 9888 20358 9887 20358 9558 20359 9887 20359 9888 20359 9889 20360 9890 20360 9888 20360 9557 20361 9888 20361 9890 20361 9886 20362 9889 20362 9888 20362 9558 20363 9888 20363 9557 20363 9891 20364 9892 20364 9890 20364 9557 20365 9890 20365 9892 20365 9889 20366 9891 20366 9890 20366 9893 20367 9894 20367 9892 20367 9557 20368 9892 20368 9894 20368 9891 20369 9893 20369 9892 20369 9893 20370 9895 20370 9894 20370 9556 20371 9894 20371 9895 20371 9557 20372 9894 20372 9556 20372 9896 20373 9897 20373 9895 20373 9556 20374 9895 20374 9897 20374 9893 20375 9896 20375 9895 20375 9898 20376 9899 20376 9897 20376 9555 20377 9897 20377 9899 20377 9896 20378 9898 20378 9897 20378 9556 20379 9897 20379 9555 20379 9867 20380 9866 20380 9899 20380 9555 20381 9899 20381 9866 20381 9898 20382 9867 20382 9899 20382 9628 20383 9867 20383 9898 20383 9628 20384 9633 20384 9867 20384 9628 20385 9898 20385 9896 20385 9622 20386 9896 20386 9893 20386 9622 20387 9628 20387 9896 20387 9622 20388 9893 20388 9891 20388 9620 20389 9891 20389 9889 20389 9620 20390 9622 20390 9891 20390 9620 20391 9889 20391 9886 20391 9615 20392 9886 20392 9884 20392 9615 20393 9620 20393 9886 20393 9610 20394 9884 20394 9881 20394 9610 20395 9615 20395 9884 20395 9610 20396 9881 20396 9879 20396 9606 20397 9879 20397 9877 20397 9606 20398 9610 20398 9879 20398 9602 20399 9877 20399 9874 20399 9602 20400 9606 20400 9877 20400 9596 20401 9874 20401 9872 20401 9596 20402 9602 20402 9874 20402 9588 20403 9872 20403 9870 20403 9588 20404 9596 20404 9872 20404 9577 20405 9870 20405 9868 20405 9577 20406 9588 20406 9870 20406 9572 20407 9868 20407 9452 20407 9577 20408 9868 20408 9572 20408 9570 20409 9452 20409 9451 20409 9571 20410 9452 20410 9570 20410 9572 20411 9452 20411 9571 20411 9574 20412 9572 20412 9573 20412 9568 20413 9572 20413 9574 20413 9450 20414 9443 20414 9455 20414 9450 20415 9455 20415 9456 20415 9450 20416 9456 20416 9457 20416 9900 20417 9422 20417 9421 20417 9901 20418 9420 20418 9422 20418 9902 20419 9901 20419 9422 20419 9903 20420 9902 20420 9422 20420 9904 20421 9903 20421 9422 20421 9905 20422 9904 20422 9422 20422 9906 20423 9905 20423 9422 20423 9906 20424 9422 20424 9900 20424 9907 20425 9421 20425 9428 20425 9908 20426 9909 20426 9421 20426 9910 20427 9421 20427 9909 20427 9911 20428 9908 20428 9421 20428 9912 20429 9911 20429 9421 20429 9907 20430 9912 20430 9421 20430 9913 20431 9900 20431 9421 20431 9914 20432 9913 20432 9421 20432 9915 20433 9914 20433 9421 20433 9916 20434 9915 20434 9421 20434 9917 20435 9916 20435 9421 20435 9918 20436 9917 20436 9421 20436 9910 20437 9918 20437 9421 20437 9418 20438 9420 20438 9901 20438 9919 20439 9901 20439 9902 20439 9919 20440 9418 20440 9901 20440 9920 20441 9902 20441 9903 20441 9919 20442 9902 20442 9920 20442 9920 20443 9903 20443 9904 20443 9905 20444 9921 20444 9904 20444 9922 20445 9904 20445 9921 20445 9920 20446 9904 20446 9922 20446 9905 20447 9923 20447 9921 20447 9922 20448 9921 20448 9923 20448 9924 20449 9925 20449 9923 20449 9926 20450 9923 20450 9925 20450 9905 20451 9924 20451 9923 20451 9922 20452 9923 20452 9926 20452 9924 20453 9927 20453 9925 20453 9926 20454 9925 20454 9927 20454 9924 20455 9928 20455 9927 20455 9929 20456 9927 20456 9928 20456 9926 20457 9927 20457 9929 20457 9924 20458 9930 20458 9928 20458 9929 20459 9928 20459 9930 20459 9924 20460 9931 20460 9930 20460 9929 20461 9930 20461 9931 20461 9932 20462 9933 20462 9931 20462 9934 20463 9931 20463 9933 20463 9924 20464 9932 20464 9931 20464 9929 20465 9931 20465 9934 20465 9932 20466 9935 20466 9933 20466 9934 20467 9933 20467 9935 20467 9932 20468 9936 20468 9935 20468 9937 20469 9935 20469 9936 20469 9934 20470 9935 20470 9937 20470 9932 20471 9938 20471 9936 20471 9939 20472 9936 20472 9938 20472 9937 20473 9936 20473 9939 20473 9940 20474 9941 20474 9938 20474 9939 20475 9938 20475 9941 20475 9932 20476 9940 20476 9938 20476 9940 20477 9942 20477 9941 20477 9943 20478 9941 20478 9942 20478 9939 20479 9941 20479 9943 20479 9940 20480 9944 20480 9942 20480 9945 20481 9942 20481 9944 20481 9943 20482 9942 20482 9945 20482 9946 20483 9947 20483 9944 20483 9948 20484 9944 20484 9947 20484 9940 20485 9946 20485 9944 20485 9945 20486 9944 20486 9948 20486 9946 20487 9949 20487 9947 20487 9950 20488 9947 20488 9949 20488 9948 20489 9947 20489 9950 20489 9951 20490 9952 20490 9949 20490 9953 20491 9949 20491 9952 20491 9946 20492 9951 20492 9949 20492 9950 20493 9949 20493 9953 20493 9951 20494 9954 20494 9952 20494 9955 20495 9952 20495 9954 20495 9953 20496 9952 20496 9955 20496 9956 20497 9957 20497 9954 20497 9958 20498 9954 20498 9957 20498 9951 20499 9956 20499 9954 20499 9955 20500 9954 20500 9958 20500 9959 20501 9960 20501 9957 20501 9961 20502 9957 20502 9960 20502 9956 20503 9959 20503 9957 20503 9958 20504 9957 20504 9961 20504 9962 20505 9963 20505 9960 20505 9964 20506 9960 20506 9963 20506 9959 20507 9962 20507 9960 20507 9961 20508 9960 20508 9964 20508 9965 20509 9966 20509 9963 20509 9967 20510 9963 20510 9966 20510 9962 20511 9965 20511 9963 20511 9968 20512 9963 20512 9967 20512 9964 20513 9963 20513 9968 20513 9969 20514 9970 20514 9966 20514 9971 20515 9966 20515 9970 20515 9972 20516 9969 20516 9966 20516 9965 20517 9972 20517 9966 20517 9973 20518 9966 20518 9971 20518 9967 20519 9966 20519 9973 20519 9974 20520 9975 20520 9970 20520 9976 20521 9970 20521 9975 20521 9977 20522 9974 20522 9970 20522 9969 20523 9977 20523 9970 20523 9971 20524 9970 20524 9976 20524 9978 20525 9979 20525 9975 20525 9980 20526 9975 20526 9979 20526 9981 20527 9978 20527 9975 20527 9982 20528 9981 20528 9975 20528 9974 20529 9982 20529 9975 20529 9983 20530 9975 20530 9980 20530 9976 20531 9975 20531 9983 20531 9984 20532 9985 20532 9979 20532 9986 20533 9979 20533 9985 20533 9987 20534 9984 20534 9979 20534 9988 20535 9987 20535 9979 20535 9989 20536 9988 20536 9979 20536 9978 20537 9989 20537 9979 20537 9990 20538 9979 20538 9986 20538 9991 20539 9979 20539 9990 20539 9980 20540 9979 20540 9991 20540 9992 20541 9993 20541 9985 20541 9994 20542 9985 20542 9993 20542 9995 20543 9992 20543 9985 20543 9996 20544 9995 20544 9985 20544 9997 20545 9996 20545 9985 20545 9984 20546 9997 20546 9985 20546 9998 20547 9985 20547 9994 20547 9986 20548 9985 20548 9998 20548 9999 20549 10000 20549 9993 20549 10001 20550 9993 20550 10000 20550 10002 20551 9999 20551 9993 20551 10003 20552 10002 20552 9993 20552 10004 20553 10003 20553 9993 20553 10005 20554 10004 20554 9993 20554 10006 20555 10005 20555 9993 20555 10007 20556 10006 20556 9993 20556 10008 20557 10007 20557 9993 20557 9992 20558 10008 20558 9993 20558 10009 20559 9993 20559 10001 20559 10010 20560 9993 20560 10009 20560 9994 20561 9993 20561 10010 20561 10011 20562 10000 20562 9999 20562 10012 20563 10000 20563 10011 20563 10013 20564 10000 20564 10012 20564 10001 20565 10000 20565 10013 20565 10011 20566 9999 20566 10002 20566 10014 20567 10002 20567 10003 20567 10014 20568 10011 20568 10002 20568 10015 20569 10003 20569 10004 20569 10015 20570 10014 20570 10003 20570 10015 20571 10004 20571 10005 20571 10016 20572 10005 20572 10006 20572 10015 20573 10005 20573 10016 20573 10016 20574 10006 20574 10007 20574 10016 20575 10007 20575 10008 20575 10017 20576 10008 20576 9992 20576 10017 20577 10016 20577 10008 20577 10017 20578 9992 20578 9995 20578 10017 20579 9995 20579 9996 20579 10017 20580 9996 20580 9997 20580 10018 20581 9997 20581 9984 20581 10018 20582 10017 20582 9997 20582 10018 20583 9984 20583 9987 20583 10018 20584 9987 20584 9988 20584 10018 20585 9988 20585 9989 20585 10019 20586 9989 20586 9978 20586 10019 20587 10018 20587 9989 20587 10019 20588 9978 20588 9981 20588 10019 20589 9981 20589 9982 20589 10020 20590 9982 20590 9974 20590 10020 20591 10019 20591 9982 20591 10020 20592 9974 20592 9977 20592 10020 20593 9977 20593 9969 20593 10021 20594 9969 20594 9972 20594 10021 20595 10020 20595 9969 20595 10021 20596 9972 20596 9965 20596 10022 20597 9965 20597 9962 20597 10022 20598 10021 20598 9965 20598 10022 20599 9962 20599 9959 20599 10023 20600 9959 20600 9956 20600 10023 20601 10022 20601 9959 20601 10024 20602 9956 20602 9951 20602 10024 20603 10023 20603 9956 20603 10025 20604 9951 20604 9946 20604 10025 20605 10024 20605 9951 20605 10025 20606 9946 20606 9940 20606 10026 20607 9940 20607 9932 20607 10026 20608 10025 20608 9940 20608 10027 20609 9932 20609 9924 20609 10027 20610 10026 20610 9932 20610 9906 20611 9924 20611 9905 20611 9906 20612 10027 20612 9924 20612 10028 20613 10029 20613 10030 20613 10031 20614 10030 20614 10029 20614 10032 20615 10028 20615 10030 20615 10033 20616 10032 20616 10030 20616 10034 20617 10033 20617 10030 20617 10031 20618 10034 20618 10030 20618 10028 20619 10035 20619 10029 20619 10036 20620 10029 20620 10035 20620 10037 20621 10031 20621 10029 20621 10036 20622 10037 20622 10029 20622 10028 20623 10038 20623 10035 20623 10039 20624 10035 20624 10038 20624 10039 20625 10036 20625 10035 20625 10028 20626 10040 20626 10038 20626 10039 20627 10038 20627 10040 20627 10041 20628 10040 20628 10028 20628 10042 20629 10039 20629 10040 20629 10043 20630 10042 20630 10040 20630 10041 20631 10043 20631 10040 20631 10044 20632 10028 20632 10032 20632 10044 20633 10041 20633 10028 20633 10033 20634 10045 20634 10032 20634 10044 20635 10032 20635 10045 20635 10046 20636 10047 20636 10045 20636 10048 20637 10045 20637 10047 20637 10033 20638 10046 20638 10045 20638 10048 20639 10044 20639 10045 20639 10049 20640 10050 20640 10047 20640 10051 20641 10047 20641 10050 20641 10046 20642 10049 20642 10047 20642 10051 20643 10048 20643 10047 20643 10052 20644 10053 20644 10050 20644 10054 20645 10050 20645 10053 20645 10055 20646 10052 20646 10050 20646 10049 20647 10055 20647 10050 20647 10054 20648 10051 20648 10050 20648 10056 20649 10057 20649 10053 20649 10058 20650 10053 20650 10057 20650 10052 20651 10056 20651 10053 20651 10058 20652 10054 20652 10053 20652 10059 20653 10060 20653 10057 20653 10061 20654 10057 20654 10060 20654 10056 20655 10059 20655 10057 20655 10061 20656 10058 20656 10057 20656 10062 20657 10063 20657 10060 20657 10064 20658 10060 20658 10063 20658 10059 20659 10062 20659 10060 20659 10064 20660 10061 20660 10060 20660 10065 20661 10066 20661 10063 20661 10067 20662 10063 20662 10066 20662 10068 20663 10065 20663 10063 20663 10062 20664 10068 20664 10063 20664 10067 20665 10064 20665 10063 20665 10069 20666 10070 20666 10066 20666 10071 20667 10066 20667 10070 20667 10065 20668 10069 20668 10066 20668 10071 20669 10067 20669 10066 20669 10072 20670 10073 20670 10070 20670 10074 20671 10070 20671 10073 20671 10069 20672 10072 20672 10070 20672 10074 20673 10071 20673 10070 20673 10072 20674 10075 20674 10073 20674 10076 20675 10073 20675 10075 20675 10076 20676 10074 20676 10073 20676 10077 20677 10078 20677 10075 20677 10076 20678 10075 20678 10078 20678 10072 20679 10077 20679 10075 20679 10079 20680 10080 20680 10078 20680 10081 20681 10078 20681 10080 20681 10082 20682 10079 20682 10078 20682 10077 20683 10082 20683 10078 20683 10081 20684 10076 20684 10078 20684 10083 20685 10084 20685 10080 20685 10085 20686 10080 20686 10084 20686 10079 20687 10083 20687 10080 20687 10086 20688 10081 20688 10080 20688 10087 20689 10086 20689 10080 20689 10085 20690 10087 20690 10080 20690 10088 20691 10089 20691 10084 20691 10090 20692 10084 20692 10089 20692 10083 20693 10088 20693 10084 20693 10091 20694 10085 20694 10084 20694 10090 20695 10091 20695 10084 20695 10092 20696 10093 20696 10089 20696 10094 20697 10089 20697 10093 20697 10088 20698 10092 20698 10089 20698 10095 20699 10090 20699 10089 20699 10094 20700 10095 20700 10089 20700 10096 20701 10097 20701 10093 20701 10098 20702 10093 20702 10097 20702 10092 20703 10096 20703 10093 20703 10098 20704 10094 20704 10093 20704 10099 20705 10100 20705 10097 20705 10101 20706 10097 20706 10100 20706 10096 20707 10099 20707 10097 20707 10102 20708 10098 20708 10097 20708 10101 20709 10102 20709 10097 20709 10099 20710 10103 20710 10100 20710 10104 20711 10100 20711 10103 20711 10104 20712 10101 20712 10100 20712 10099 20713 10105 20713 10103 20713 10104 20714 10103 20714 10105 20714 10106 20715 10107 20715 10105 20715 10108 20716 10105 20716 10107 20716 10099 20717 10106 20717 10105 20717 10108 20718 10104 20718 10105 20718 10106 20719 10109 20719 10107 20719 10110 20720 10107 20720 10109 20720 10110 20721 10108 20721 10107 20721 10106 20722 10111 20722 10109 20722 10110 20723 10109 20723 10111 20723 10112 20724 10113 20724 10111 20724 10114 20725 10111 20725 10113 20725 10106 20726 10112 20726 10111 20726 10114 20727 10110 20727 10111 20727 10112 20728 10115 20728 10113 20728 10114 20729 10113 20729 10115 20729 10112 20730 10116 20730 10115 20730 10117 20731 10115 20731 10116 20731 10117 20732 10114 20732 10115 20732 10112 20733 10118 20733 10116 20733 10119 20734 10116 20734 10118 20734 10119 20735 10117 20735 10116 20735 10120 20736 10121 20736 10118 20736 10122 20737 10118 20737 10121 20737 10112 20738 10120 20738 10118 20738 10122 20739 10119 20739 10118 20739 10120 20740 10123 20740 10121 20740 10122 20741 10121 20741 10123 20741 10120 20742 10124 20742 10123 20742 10125 20743 10123 20743 10124 20743 10125 20744 10122 20744 10123 20744 10126 20745 10127 20745 10124 20745 10125 20746 10124 20746 10127 20746 10120 20747 10126 20747 10124 20747 10126 20748 10128 20748 10127 20748 10129 20749 10127 20749 10128 20749 10129 20750 10125 20750 10127 20750 10126 20751 10130 20751 10128 20751 10131 20752 10128 20752 10130 20752 10131 20753 10129 20753 10128 20753 9428 20754 10132 20754 10130 20754 10133 20755 10130 20755 10132 20755 10126 20756 9428 20756 10130 20756 10133 20757 10131 20757 10130 20757 9428 20758 9408 20758 10132 20758 10133 20759 10132 20759 9408 20759 10133 20760 9408 20760 9410 20760 10134 20761 9428 20761 10126 20761 10135 20762 9907 20762 9428 20762 10136 20763 10135 20763 9428 20763 10137 20764 10136 20764 9428 20764 10138 20765 10137 20765 9428 20765 10134 20766 10138 20766 9428 20766 10138 20767 10126 20767 10120 20767 10134 20768 10126 20768 10138 20768 10139 20769 10120 20769 10112 20769 10139 20770 10138 20770 10120 20770 10140 20771 10112 20771 10106 20771 10140 20772 10139 20772 10112 20772 10141 20773 10106 20773 10099 20773 10141 20774 10140 20774 10106 20774 10142 20775 10099 20775 10096 20775 10142 20776 10141 20776 10099 20776 10143 20777 10096 20777 10092 20777 10143 20778 10142 20778 10096 20778 10144 20779 10092 20779 10088 20779 10144 20780 10143 20780 10092 20780 10144 20781 10088 20781 10083 20781 10145 20782 10083 20782 10079 20782 10145 20783 10144 20783 10083 20783 10145 20784 10079 20784 10082 20784 10146 20785 10082 20785 10077 20785 10146 20786 10145 20786 10082 20786 10146 20787 10077 20787 10072 20787 10147 20788 10072 20788 10069 20788 10147 20789 10146 20789 10072 20789 10147 20790 10069 20790 10065 20790 10148 20791 10065 20791 10068 20791 10148 20792 10147 20792 10065 20792 10148 20793 10068 20793 10062 20793 10148 20794 10062 20794 10059 20794 10148 20795 10059 20795 10056 20795 10149 20796 10056 20796 10052 20796 10149 20797 10148 20797 10056 20797 10149 20798 10052 20798 10055 20798 10149 20799 10055 20799 10049 20799 10034 20800 10049 20800 10046 20800 10034 20801 10149 20801 10049 20801 10034 20802 10046 20802 10033 20802 9412 20803 9411 20803 9414 20803 9417 20804 9414 20804 9413 20804 10150 20805 9414 20805 9417 20805 9412 20806 9414 20806 10150 20806 9417 20807 9413 20807 9416 20807 10151 20808 10150 20808 9417 20808 10152 20809 10151 20809 9417 20809 10152 20810 9417 20810 9415 20810 10153 20811 10150 20811 10151 20811 9412 20812 10150 20812 10153 20812 10154 20813 10155 20813 10156 20813 10157 20814 10156 20814 10155 20814 10158 20815 10154 20815 10156 20815 10159 20816 10158 20816 10156 20816 10157 20817 10159 20817 10156 20817 10154 20818 10160 20818 10155 20818 10161 20819 10155 20819 10160 20819 10161 20820 10157 20820 10155 20820 10162 20821 10163 20821 10160 20821 10161 20822 10160 20822 10163 20822 10154 20823 10162 20823 10160 20823 10164 20824 10165 20824 10163 20824 10166 20825 10163 20825 10165 20825 10162 20826 10164 20826 10163 20826 10166 20827 10161 20827 10163 20827 10167 20828 10168 20828 10165 20828 10166 20829 10165 20829 10168 20829 10164 20830 10167 20830 10165 20830 10169 20831 10170 20831 10168 20831 10171 20832 10168 20832 10170 20832 10167 20833 10169 20833 10168 20833 10171 20834 10166 20834 10168 20834 10172 20835 10173 20835 10170 20835 10174 20836 10170 20836 10173 20836 10169 20837 10172 20837 10170 20837 10174 20838 10171 20838 10170 20838 10175 20839 10176 20839 10173 20839 10177 20840 10173 20840 10176 20840 10172 20841 10175 20841 10173 20841 10177 20842 10174 20842 10173 20842 10178 20843 10179 20843 10176 20843 10177 20844 10176 20844 10179 20844 10175 20845 10178 20845 10176 20845 10180 20846 10181 20846 10179 20846 10182 20847 10179 20847 10181 20847 10178 20848 10180 20848 10179 20848 10182 20849 10177 20849 10179 20849 10183 20850 10184 20850 10181 20850 10182 20851 10181 20851 10184 20851 10180 20852 10183 20852 10181 20852 10185 20853 10186 20853 10184 20853 10187 20854 10184 20854 10186 20854 10183 20855 10185 20855 10184 20855 10187 20856 10182 20856 10184 20856 10188 20857 10189 20857 10186 20857 10190 20858 10186 20858 10189 20858 10185 20859 10188 20859 10186 20859 10190 20860 10187 20860 10186 20860 10191 20861 10192 20861 10189 20861 10190 20862 10189 20862 10192 20862 10188 20863 10191 20863 10189 20863 10193 20864 10194 20864 10192 20864 10195 20865 10192 20865 10194 20865 10191 20866 10193 20866 10192 20866 10195 20867 10190 20867 10192 20867 10196 20868 10197 20868 10194 20868 10195 20869 10194 20869 10197 20869 10193 20870 10196 20870 10194 20870 10198 20871 10199 20871 10197 20871 10200 20872 10197 20872 10199 20872 10196 20873 10198 20873 10197 20873 10200 20874 10195 20874 10197 20874 10201 20875 10202 20875 10199 20875 10203 20876 10199 20876 10202 20876 10198 20877 10201 20877 10199 20877 10203 20878 10200 20878 10199 20878 10204 20879 10205 20879 10202 20879 10203 20880 10202 20880 10205 20880 10201 20881 10204 20881 10202 20881 10206 20882 10207 20882 10205 20882 10208 20883 10205 20883 10207 20883 10204 20884 10206 20884 10205 20884 10208 20885 10203 20885 10205 20885 10209 20886 10210 20886 10207 20886 10211 20887 10207 20887 10210 20887 10206 20888 10209 20888 10207 20888 10211 20889 10208 20889 10207 20889 10212 20890 10213 20890 10210 20890 10211 20891 10210 20891 10213 20891 10209 20892 10212 20892 10210 20892 10214 20893 10215 20893 10213 20893 10216 20894 10213 20894 10215 20894 10212 20895 10214 20895 10213 20895 10216 20896 10211 20896 10213 20896 10217 20897 10218 20897 10215 20897 10216 20898 10215 20898 10218 20898 10214 20899 10217 20899 10215 20899 10217 20900 10219 20900 10218 20900 10220 20901 10218 20901 10219 20901 10220 20902 10216 20902 10218 20902 10221 20903 10222 20903 10219 20903 10220 20904 10219 20904 10222 20904 10217 20905 10221 20905 10219 20905 10223 20906 10224 20906 10222 20906 10225 20907 10222 20907 10224 20907 10226 20908 10223 20908 10222 20908 10221 20909 10226 20909 10222 20909 10225 20910 10220 20910 10222 20910 10227 20911 10228 20911 10224 20911 10229 20912 10224 20912 10228 20912 10230 20913 10227 20913 10224 20913 10223 20914 10230 20914 10224 20914 10231 20915 10225 20915 10224 20915 10229 20916 10231 20916 10224 20916 10232 20917 10233 20917 10228 20917 10234 20918 10228 20918 10233 20918 10227 20919 10232 20919 10228 20919 10234 20920 10229 20920 10228 20920 10235 20921 10236 20921 10233 20921 10237 20922 10233 20922 10236 20922 10232 20923 10235 20923 10233 20923 10238 20924 10234 20924 10233 20924 10237 20925 10238 20925 10233 20925 10239 20926 10240 20926 10236 20926 10241 20927 10236 20927 10240 20927 10235 20928 10239 20928 10236 20928 10241 20929 10237 20929 10236 20929 10242 20930 10243 20930 10240 20930 10244 20931 10240 20931 10243 20931 10239 20932 10242 20932 10240 20932 10244 20933 10241 20933 10240 20933 10245 20934 10246 20934 10243 20934 10247 20935 10243 20935 10246 20935 10242 20936 10245 20936 10243 20936 10247 20937 10244 20937 10243 20937 10248 20938 10249 20938 10246 20938 10247 20939 10246 20939 10249 20939 10245 20940 10248 20940 10246 20940 10250 20941 10251 20941 10249 20941 10252 20942 10249 20942 10251 20942 10248 20943 10250 20943 10249 20943 10252 20944 10247 20944 10249 20944 10253 20945 10254 20945 10251 20945 10255 20946 10251 20946 10254 20946 10256 20947 10253 20947 10251 20947 10250 20948 10256 20948 10251 20948 10255 20949 10252 20949 10251 20949 10257 20950 10258 20950 10254 20950 10255 20951 10254 20951 10258 20951 10253 20952 10257 20952 10254 20952 10259 20953 10260 20953 10258 20953 10261 20954 10258 20954 10260 20954 10257 20955 10259 20955 10258 20955 10261 20956 10255 20956 10258 20956 10262 20957 10263 20957 10260 20957 10261 20958 10260 20958 10263 20958 10259 20959 10262 20959 10260 20959 10264 20960 10265 20960 10263 20960 10266 20961 10263 20961 10265 20961 10262 20962 10264 20962 10263 20962 10266 20963 10261 20963 10263 20963 10264 20964 10267 20964 10265 20964 10266 20965 10265 20965 10267 20965 10268 20966 10269 20966 10267 20966 10270 20967 10267 20967 10269 20967 10264 20968 10268 20968 10267 20968 10270 20969 10266 20969 10267 20969 10268 20970 10271 20970 10269 20970 10270 20971 10269 20971 10271 20971 10272 20972 10273 20972 10271 20972 10274 20973 10271 20973 10273 20973 10268 20974 10272 20974 10271 20974 10274 20975 10270 20975 10271 20975 10275 20976 10276 20976 10273 20976 10274 20977 10273 20977 10276 20977 10272 20978 10275 20978 10273 20978 10277 20979 10278 20979 10276 20979 10279 20980 10276 20980 10278 20980 10275 20981 10277 20981 10276 20981 10279 20982 10274 20982 10276 20982 10280 20983 10281 20983 10278 20983 10279 20984 10278 20984 10281 20984 10277 20985 10280 20985 10278 20985 10282 20986 10283 20986 10281 20986 10284 20987 10281 20987 10283 20987 10280 20988 10282 20988 10281 20988 10284 20989 10279 20989 10281 20989 10153 20990 10151 20990 10283 20990 10152 20991 10283 20991 10151 20991 10282 20992 10153 20992 10283 20992 10152 20993 10284 20993 10283 20993 10285 20994 10153 20994 10282 20994 10285 20995 9412 20995 10153 20995 10286 20996 10282 20996 10280 20996 10286 20997 10285 20997 10282 20997 10286 20998 10280 20998 10277 20998 10287 20999 10277 20999 10275 20999 10287 21000 10286 21000 10277 21000 10287 21001 10275 21001 10272 21001 10288 21002 10272 21002 10268 21002 10288 21003 10287 21003 10272 21003 10289 21004 10268 21004 10264 21004 10289 21005 10288 21005 10268 21005 10290 21006 10264 21006 10262 21006 10290 21007 10289 21007 10264 21007 10290 21008 10262 21008 10259 21008 10291 21009 10259 21009 10257 21009 10291 21010 10290 21010 10259 21010 10291 21011 10257 21011 10253 21011 10292 21012 10253 21012 10256 21012 10292 21013 10291 21013 10253 21013 10292 21014 10256 21014 10250 21014 10293 21015 10250 21015 10248 21015 10293 21016 10292 21016 10250 21016 10294 21017 10248 21017 10245 21017 10294 21018 10293 21018 10248 21018 10295 21019 10245 21019 10242 21019 10295 21020 10294 21020 10245 21020 10296 21021 10242 21021 10239 21021 10296 21022 10295 21022 10242 21022 10297 21023 10239 21023 10235 21023 10297 21024 10296 21024 10239 21024 10298 21025 10235 21025 10232 21025 10298 21026 10297 21026 10235 21026 10299 21027 10232 21027 10227 21027 10299 21028 10298 21028 10232 21028 10300 21029 10227 21029 10230 21029 10300 21030 10299 21030 10227 21030 10301 21031 10230 21031 10223 21031 10301 21032 10300 21032 10230 21032 10301 21033 10223 21033 10226 21033 10302 21034 10226 21034 10221 21034 10302 21035 10301 21035 10226 21035 10303 21036 10221 21036 10217 21036 10303 21037 10302 21037 10221 21037 10303 21038 10217 21038 10214 21038 10304 21039 10214 21039 10212 21039 10304 21040 10303 21040 10214 21040 10305 21041 10212 21041 10209 21041 10305 21042 10304 21042 10212 21042 10305 21043 10209 21043 10206 21043 10306 21044 10206 21044 10204 21044 10306 21045 10305 21045 10206 21045 10307 21046 10204 21046 10201 21046 10307 21047 10306 21047 10204 21047 10307 21048 10201 21048 10198 21048 10308 21049 10198 21049 10196 21049 10308 21050 10307 21050 10198 21050 10309 21051 10196 21051 10193 21051 10309 21052 10308 21052 10196 21052 10309 21053 10193 21053 10191 21053 10310 21054 10191 21054 10188 21054 10310 21055 10309 21055 10191 21055 10310 21056 10188 21056 10185 21056 10311 21057 10185 21057 10183 21057 10311 21058 10310 21058 10185 21058 10312 21059 10183 21059 10180 21059 10312 21060 10311 21060 10183 21060 10312 21061 10180 21061 10178 21061 10313 21062 10178 21062 10175 21062 10313 21063 10312 21063 10178 21063 10314 21064 10175 21064 10172 21064 10314 21065 10313 21065 10175 21065 10314 21066 10172 21066 10169 21066 10315 21067 10169 21067 10167 21067 10315 21068 10314 21068 10169 21068 10316 21069 10167 21069 10164 21069 10316 21070 10315 21070 10167 21070 10316 21071 10164 21071 10162 21071 10317 21072 10162 21072 10154 21072 10317 21073 10316 21073 10162 21073 10318 21074 10154 21074 10158 21074 10317 21075 10154 21075 10318 21075 10319 21076 10158 21076 10159 21076 10042 21077 10158 21077 10319 21077 10318 21078 10158 21078 10042 21078 10320 21079 10319 21079 10159 21079 10014 21080 10320 21080 10159 21080 10014 21081 10159 21081 10011 21081 10321 21082 10011 21082 10159 21082 10322 21083 10321 21083 10159 21083 10157 21084 10322 21084 10159 21084 10323 21085 10319 21085 10320 21085 10042 21086 10319 21086 10323 21086 10324 21087 10325 21087 10326 21087 10327 21088 10326 21088 10325 21088 10328 21089 10324 21089 10326 21089 10329 21090 10328 21090 10326 21090 10330 21091 10329 21091 10326 21091 10330 21092 10326 21092 10327 21092 10323 21093 10320 21093 10325 21093 10015 21094 10325 21094 10320 21094 10324 21095 10323 21095 10325 21095 10327 21096 10325 21096 10331 21096 10015 21097 10331 21097 10325 21097 10015 21098 10320 21098 10014 21098 10039 21099 10323 21099 10324 21099 10042 21100 10323 21100 10039 21100 10036 21101 10324 21101 10328 21101 10039 21102 10324 21102 10036 21102 10332 21103 10328 21103 10329 21103 10333 21104 10328 21104 10332 21104 10036 21105 10328 21105 10333 21105 10334 21106 10335 21106 9909 21106 9910 21107 9909 21107 10335 21107 9908 21108 10334 21108 9909 21108 10334 21109 10336 21109 10335 21109 10337 21110 10335 21110 10336 21110 9910 21111 10335 21111 9918 21111 10337 21112 9918 21112 10335 21112 10338 21113 10339 21113 10336 21113 10337 21114 10336 21114 10339 21114 10334 21115 10338 21115 10336 21115 10340 21116 10341 21116 10339 21116 10342 21117 10339 21117 10341 21117 10338 21118 10340 21118 10339 21118 10337 21119 10339 21119 10342 21119 10343 21120 10344 21120 10341 21120 10345 21121 10341 21121 10344 21121 10340 21122 10343 21122 10341 21122 10342 21123 10341 21123 10345 21123 10346 21124 10347 21124 10344 21124 10348 21125 10344 21125 10347 21125 10343 21126 10346 21126 10344 21126 10345 21127 10344 21127 10348 21127 10349 21128 10350 21128 10347 21128 10348 21129 10347 21129 10350 21129 10346 21130 10349 21130 10347 21130 10351 21131 10352 21131 10350 21131 10353 21132 10350 21132 10352 21132 10349 21133 10351 21133 10350 21133 10348 21134 10350 21134 10353 21134 10351 21135 10354 21135 10352 21135 10355 21136 10352 21136 10354 21136 10353 21137 10352 21137 10355 21137 10356 21138 10357 21138 10354 21138 10355 21139 10354 21139 10357 21139 10351 21140 10356 21140 10354 21140 10358 21141 10359 21141 10357 21141 10360 21142 10357 21142 10359 21142 10356 21143 10358 21143 10357 21143 10355 21144 10357 21144 10360 21144 10361 21145 10362 21145 10359 21145 10360 21146 10359 21146 10362 21146 10358 21147 10361 21147 10359 21147 10363 21148 10364 21148 10362 21148 10365 21149 10362 21149 10364 21149 10361 21150 10363 21150 10362 21150 10360 21151 10362 21151 10365 21151 10366 21152 10367 21152 10364 21152 10365 21153 10364 21153 10367 21153 10363 21154 10366 21154 10364 21154 10366 21155 10368 21155 10367 21155 10365 21156 10367 21156 10368 21156 10369 21157 10370 21157 10368 21157 10371 21158 10368 21158 10370 21158 10366 21159 10369 21159 10368 21159 10365 21160 10368 21160 10371 21160 10372 21161 10373 21161 10370 21161 10371 21162 10370 21162 10373 21162 10369 21163 10372 21163 10370 21163 10374 21164 10375 21164 10373 21164 10371 21165 10373 21165 10375 21165 10372 21166 10374 21166 10373 21166 10376 21167 10377 21167 10375 21167 10378 21168 10375 21168 10377 21168 10374 21169 10376 21169 10375 21169 10371 21170 10375 21170 10378 21170 10379 21171 10380 21171 10377 21171 10378 21172 10377 21172 10380 21172 10376 21173 10379 21173 10377 21173 10379 21174 10381 21174 10380 21174 10378 21175 10380 21175 10381 21175 10382 21176 10383 21176 10381 21176 10378 21177 10381 21177 10383 21177 10379 21178 10382 21178 10381 21178 10384 21179 10385 21179 10383 21179 10386 21180 10383 21180 10385 21180 10382 21181 10384 21181 10383 21181 10378 21182 10383 21182 10386 21182 10387 21183 10388 21183 10385 21183 10386 21184 10385 21184 10388 21184 10384 21185 10387 21185 10385 21185 10389 21186 10390 21186 10388 21186 10386 21187 10388 21187 10390 21187 10387 21188 10389 21188 10388 21188 10391 21189 10392 21189 10390 21189 10386 21190 10390 21190 10392 21190 10389 21191 10391 21191 10390 21191 10391 21192 10393 21192 10392 21192 10330 21193 10392 21193 10393 21193 10386 21194 10392 21194 10330 21194 10394 21195 10395 21195 10393 21195 10330 21196 10393 21196 10395 21196 10391 21197 10394 21197 10393 21197 10332 21198 10329 21198 10395 21198 10330 21199 10395 21199 10329 21199 10394 21200 10332 21200 10395 21200 10333 21201 10332 21201 10394 21201 10396 21202 10394 21202 10391 21202 10396 21203 10333 21203 10394 21203 10396 21204 10391 21204 10389 21204 10396 21205 10389 21205 10387 21205 10396 21206 10387 21206 10384 21206 10397 21207 10384 21207 10382 21207 10397 21208 10396 21208 10384 21208 10397 21209 10382 21209 10379 21209 10397 21210 10379 21210 10376 21210 10398 21211 10376 21211 10374 21211 10398 21212 10397 21212 10376 21212 10398 21213 10374 21213 10372 21213 10398 21214 10372 21214 10369 21214 10399 21215 10369 21215 10366 21215 10399 21216 10398 21216 10369 21216 10399 21217 10366 21217 10363 21217 10400 21218 10363 21218 10361 21218 10400 21219 10399 21219 10363 21219 10401 21220 10361 21220 10358 21220 10401 21221 10400 21221 10361 21221 10401 21222 10358 21222 10356 21222 10402 21223 10356 21223 10351 21223 10402 21224 10401 21224 10356 21224 10403 21225 10351 21225 10349 21225 10403 21226 10402 21226 10351 21226 10404 21227 10349 21227 10346 21227 10404 21228 10403 21228 10349 21228 10405 21229 10346 21229 10343 21229 10405 21230 10404 21230 10346 21230 10405 21231 10343 21231 10340 21231 10406 21232 10340 21232 10338 21232 10406 21233 10405 21233 10340 21233 10407 21234 10338 21234 10334 21234 10407 21235 10406 21235 10338 21235 9912 21236 10334 21236 9908 21236 10407 21237 10334 21237 9912 21237 9912 21238 9908 21238 9911 21238 10135 21239 9912 21239 9907 21239 10407 21240 9912 21240 10135 21240 10137 21241 10135 21241 10136 21241 10138 21242 10135 21242 10137 21242 10408 21243 10135 21243 10138 21243 10408 21244 10407 21244 10135 21244 10408 21245 10138 21245 10139 21245 9906 21246 9900 21246 9913 21246 10409 21247 9913 21247 9914 21247 10409 21248 9906 21248 9913 21248 10409 21249 9914 21249 9915 21249 10409 21250 9915 21250 9916 21250 10337 21251 9916 21251 9917 21251 10337 21252 10409 21252 9916 21252 10337 21253 9917 21253 9918 21253 10331 21254 10016 21254 10017 21254 10015 21255 10016 21255 10331 21255 10410 21256 10017 21256 10018 21256 10410 21257 10331 21257 10017 21257 10411 21258 10018 21258 10019 21258 10411 21259 10410 21259 10018 21259 10412 21260 10019 21260 10020 21260 10412 21261 10411 21261 10019 21261 10413 21262 10020 21262 10021 21262 10413 21263 10412 21263 10020 21263 10414 21264 10021 21264 10022 21264 10414 21265 10413 21265 10021 21265 10415 21266 10022 21266 10023 21266 10415 21267 10414 21267 10022 21267 10416 21268 10023 21268 10024 21268 10416 21269 10415 21269 10023 21269 10417 21270 10024 21270 10025 21270 10417 21271 10416 21271 10024 21271 10418 21272 10025 21272 10026 21272 10418 21273 10417 21273 10025 21273 10419 21274 10026 21274 10027 21274 10419 21275 10418 21275 10026 21275 10420 21276 10027 21276 9906 21276 10420 21277 10419 21277 10027 21277 10409 21278 10420 21278 9906 21278 10327 21279 10331 21279 10410 21279 10330 21280 10410 21280 10411 21280 10330 21281 10327 21281 10410 21281 10386 21282 10411 21282 10412 21282 10386 21283 10330 21283 10411 21283 10378 21284 10412 21284 10413 21284 10378 21285 10386 21285 10412 21285 10371 21286 10413 21286 10414 21286 10371 21287 10378 21287 10413 21287 10365 21288 10414 21288 10415 21288 10365 21289 10371 21289 10414 21289 10360 21290 10415 21290 10416 21290 10360 21291 10365 21291 10415 21291 10355 21292 10416 21292 10417 21292 10355 21293 10360 21293 10416 21293 10353 21294 10417 21294 10418 21294 10353 21295 10355 21295 10417 21295 10348 21296 10418 21296 10419 21296 10348 21297 10353 21297 10418 21297 10345 21298 10419 21298 10420 21298 10345 21299 10348 21299 10419 21299 10342 21300 10420 21300 10409 21300 10342 21301 10345 21301 10420 21301 10337 21302 10342 21302 10409 21302 10421 21303 10012 21303 10011 21303 10321 21304 10421 21304 10011 21304 10422 21305 10012 21305 10421 21305 10013 21306 10012 21306 10422 21306 10422 21307 10421 21307 10321 21307 10161 21308 10321 21308 10322 21308 10422 21309 10321 21309 10161 21309 10161 21310 10322 21310 10157 21310 10423 21311 9415 21311 9419 21311 10423 21312 10152 21312 9415 21312 9919 21313 9419 21313 9418 21313 9919 21314 10423 21314 9419 21314 10422 21315 10161 21315 10166 21315 10424 21316 10166 21316 10171 21316 10424 21317 10422 21317 10166 21317 10425 21318 10171 21318 10174 21318 10425 21319 10424 21319 10171 21319 10426 21320 10174 21320 10177 21320 10426 21321 10425 21321 10174 21321 10427 21322 10177 21322 10182 21322 10427 21323 10426 21323 10177 21323 10428 21324 10182 21324 10187 21324 10428 21325 10427 21325 10182 21325 10429 21326 10187 21326 10190 21326 10429 21327 10428 21327 10187 21327 10430 21328 10190 21328 10195 21328 10430 21329 10429 21329 10190 21329 10431 21330 10195 21330 10200 21330 10431 21331 10430 21331 10195 21331 10432 21332 10200 21332 10203 21332 10432 21333 10431 21333 10200 21333 10433 21334 10203 21334 10208 21334 10433 21335 10432 21335 10203 21335 10434 21336 10208 21336 10211 21336 10434 21337 10433 21337 10208 21337 10435 21338 10211 21338 10216 21338 10435 21339 10434 21339 10211 21339 10436 21340 10216 21340 10220 21340 10436 21341 10435 21341 10216 21341 10437 21342 10220 21342 10225 21342 10437 21343 10436 21343 10220 21343 10438 21344 10225 21344 10231 21344 10438 21345 10437 21345 10225 21345 10439 21346 10231 21346 10229 21346 10439 21347 10438 21347 10231 21347 10440 21348 10229 21348 10234 21348 10440 21349 10439 21349 10229 21349 10441 21350 10234 21350 10238 21350 10441 21351 10440 21351 10234 21351 10442 21352 10238 21352 10237 21352 10442 21353 10441 21353 10238 21353 10443 21354 10237 21354 10241 21354 10443 21355 10442 21355 10237 21355 10444 21356 10241 21356 10244 21356 10444 21357 10443 21357 10241 21357 10445 21358 10244 21358 10247 21358 10445 21359 10444 21359 10244 21359 10446 21360 10247 21360 10252 21360 10446 21361 10445 21361 10247 21361 10447 21362 10252 21362 10255 21362 10447 21363 10446 21363 10252 21363 10448 21364 10255 21364 10261 21364 10448 21365 10447 21365 10255 21365 10449 21366 10261 21366 10266 21366 10449 21367 10448 21367 10261 21367 10450 21368 10266 21368 10270 21368 10450 21369 10449 21369 10266 21369 10451 21370 10270 21370 10274 21370 10451 21371 10450 21371 10270 21371 10452 21372 10274 21372 10279 21372 10452 21373 10451 21373 10274 21373 10453 21374 10279 21374 10284 21374 10453 21375 10452 21375 10279 21375 10454 21376 10284 21376 10152 21376 10454 21377 10453 21377 10284 21377 10423 21378 10454 21378 10152 21378 10013 21379 10422 21379 10424 21379 10001 21380 10424 21380 10425 21380 10001 21381 10013 21381 10424 21381 10009 21382 10425 21382 10426 21382 10009 21383 10001 21383 10425 21383 10010 21384 10426 21384 10427 21384 10010 21385 10009 21385 10426 21385 9994 21386 10427 21386 10428 21386 9994 21387 10010 21387 10427 21387 9998 21388 10428 21388 10429 21388 9998 21389 9994 21389 10428 21389 9986 21390 10429 21390 10430 21390 9986 21391 9998 21391 10429 21391 9990 21392 10430 21392 10431 21392 9990 21393 9986 21393 10430 21393 9991 21394 10431 21394 10432 21394 9991 21395 9990 21395 10431 21395 9980 21396 10432 21396 10433 21396 9980 21397 9991 21397 10432 21397 9983 21398 10433 21398 10434 21398 9983 21399 9980 21399 10433 21399 9976 21400 10434 21400 10435 21400 9976 21401 9983 21401 10434 21401 9971 21402 10435 21402 10436 21402 9971 21403 9976 21403 10435 21403 9973 21404 10436 21404 10437 21404 9973 21405 9971 21405 10436 21405 9967 21406 10437 21406 10438 21406 9967 21407 9973 21407 10437 21407 9968 21408 10438 21408 10439 21408 9968 21409 9967 21409 10438 21409 9964 21410 10439 21410 10440 21410 9964 21411 9968 21411 10439 21411 9961 21412 10440 21412 10441 21412 9961 21413 9964 21413 10440 21413 9958 21414 10441 21414 10442 21414 9958 21415 9961 21415 10441 21415 9955 21416 10442 21416 10443 21416 9955 21417 9958 21417 10442 21417 9953 21418 10443 21418 10444 21418 9953 21419 9955 21419 10443 21419 9950 21420 10444 21420 10445 21420 9950 21421 9953 21421 10444 21421 9948 21422 10445 21422 10446 21422 9948 21423 9950 21423 10445 21423 9945 21424 10446 21424 10447 21424 9945 21425 9948 21425 10446 21425 9943 21426 10447 21426 10448 21426 9943 21427 9945 21427 10447 21427 9939 21428 10448 21428 10449 21428 9939 21429 9943 21429 10448 21429 9937 21430 10449 21430 10450 21430 9937 21431 9939 21431 10449 21431 9934 21432 10450 21432 10451 21432 9934 21433 9937 21433 10450 21433 9929 21434 10451 21434 10452 21434 9929 21435 9934 21435 10451 21435 9926 21436 10452 21436 10453 21436 9926 21437 9929 21437 10452 21437 9922 21438 10453 21438 10454 21438 9922 21439 9926 21439 10453 21439 9920 21440 10454 21440 10423 21440 9920 21441 9922 21441 10454 21441 9919 21442 9920 21442 10423 21442 10037 21443 10333 21443 10396 21443 10036 21444 10333 21444 10037 21444 10455 21445 10396 21445 10397 21445 10456 21446 10037 21446 10396 21446 10456 21447 10396 21447 10455 21447 10457 21448 10397 21448 10398 21448 10455 21449 10397 21449 10457 21449 10458 21450 10398 21450 10399 21450 10457 21451 10398 21451 10458 21451 10459 21452 10399 21452 10400 21452 10458 21453 10399 21453 10459 21453 10460 21454 10400 21454 10401 21454 10459 21455 10400 21455 10460 21455 10461 21456 10401 21456 10402 21456 10460 21457 10401 21457 10461 21457 10462 21458 10402 21458 10403 21458 10461 21459 10402 21459 10462 21459 10463 21460 10403 21460 10404 21460 10462 21461 10403 21461 10463 21461 10464 21462 10404 21462 10405 21462 10463 21463 10404 21463 10464 21463 10465 21464 10405 21464 10406 21464 10464 21465 10405 21465 10465 21465 10408 21466 10406 21466 10407 21466 10465 21467 10406 21467 10408 21467 10465 21468 10139 21468 10140 21468 10465 21469 10408 21469 10139 21469 10464 21470 10140 21470 10141 21470 10464 21471 10465 21471 10140 21471 10463 21472 10141 21472 10142 21472 10463 21473 10464 21473 10141 21473 10462 21474 10142 21474 10143 21474 10462 21475 10463 21475 10142 21475 10461 21476 10143 21476 10144 21476 10461 21477 10462 21477 10143 21477 10460 21478 10144 21478 10145 21478 10460 21479 10461 21479 10144 21479 10459 21480 10145 21480 10146 21480 10459 21481 10460 21481 10145 21481 10458 21482 10146 21482 10147 21482 10458 21483 10459 21483 10146 21483 10457 21484 10147 21484 10148 21484 10457 21485 10458 21485 10147 21485 10455 21486 10148 21486 10149 21486 10455 21487 10457 21487 10148 21487 10456 21488 10149 21488 10034 21488 10456 21489 10455 21489 10149 21489 10456 21490 10034 21490 10031 21490 10456 21491 10031 21491 10037 21491 10466 21492 10318 21492 10042 21492 10467 21493 10466 21493 10042 21493 10043 21494 10467 21494 10042 21494 10467 21495 10318 21495 10466 21495 10317 21496 10318 21496 10467 21496 10041 21497 10467 21497 10043 21497 10468 21498 10467 21498 10041 21498 10468 21499 10317 21499 10467 21499 10468 21500 10041 21500 10044 21500 10469 21501 9410 21501 9409 21501 10469 21502 10133 21502 9410 21502 10285 21503 9409 21503 9412 21503 10469 21504 9409 21504 10285 21504 10470 21505 10044 21505 10048 21505 10468 21506 10044 21506 10470 21506 10471 21507 10048 21507 10051 21507 10470 21508 10048 21508 10471 21508 10472 21509 10051 21509 10054 21509 10471 21510 10051 21510 10472 21510 10473 21511 10054 21511 10058 21511 10472 21512 10054 21512 10473 21512 10474 21513 10058 21513 10061 21513 10473 21514 10058 21514 10474 21514 10475 21515 10061 21515 10064 21515 10474 21516 10061 21516 10475 21516 10476 21517 10064 21517 10067 21517 10475 21518 10064 21518 10476 21518 10477 21519 10067 21519 10071 21519 10476 21520 10067 21520 10477 21520 10478 21521 10071 21521 10074 21521 10477 21522 10071 21522 10478 21522 10479 21523 10074 21523 10076 21523 10478 21524 10074 21524 10479 21524 10480 21525 10076 21525 10081 21525 10479 21526 10076 21526 10480 21526 10481 21527 10081 21527 10086 21527 10480 21528 10081 21528 10481 21528 10482 21529 10086 21529 10087 21529 10481 21530 10086 21530 10482 21530 10483 21531 10087 21531 10085 21531 10482 21532 10087 21532 10483 21532 10484 21533 10085 21533 10091 21533 10483 21534 10085 21534 10484 21534 10485 21535 10091 21535 10090 21535 10484 21536 10091 21536 10485 21536 10486 21537 10090 21537 10095 21537 10485 21538 10090 21538 10486 21538 10487 21539 10095 21539 10094 21539 10486 21540 10095 21540 10487 21540 10488 21541 10094 21541 10098 21541 10487 21542 10094 21542 10488 21542 10489 21543 10098 21543 10102 21543 10488 21544 10098 21544 10489 21544 10490 21545 10102 21545 10101 21545 10489 21546 10102 21546 10490 21546 10491 21547 10101 21547 10104 21547 10490 21548 10101 21548 10491 21548 10492 21549 10104 21549 10108 21549 10491 21550 10104 21550 10492 21550 10493 21551 10108 21551 10110 21551 10492 21552 10108 21552 10493 21552 10494 21553 10110 21553 10114 21553 10493 21554 10110 21554 10494 21554 10495 21555 10114 21555 10117 21555 10494 21556 10114 21556 10495 21556 10496 21557 10117 21557 10119 21557 10495 21558 10117 21558 10496 21558 10497 21559 10119 21559 10122 21559 10496 21560 10119 21560 10497 21560 10498 21561 10122 21561 10125 21561 10497 21562 10122 21562 10498 21562 10499 21563 10125 21563 10129 21563 10498 21564 10125 21564 10499 21564 10500 21565 10129 21565 10131 21565 10499 21566 10129 21566 10500 21566 10469 21567 10131 21567 10133 21567 10500 21568 10131 21568 10469 21568 10500 21569 10285 21569 10286 21569 10500 21570 10469 21570 10285 21570 10499 21571 10286 21571 10287 21571 10499 21572 10500 21572 10286 21572 10498 21573 10287 21573 10288 21573 10498 21574 10499 21574 10287 21574 10497 21575 10288 21575 10289 21575 10497 21576 10498 21576 10288 21576 10496 21577 10289 21577 10290 21577 10496 21578 10497 21578 10289 21578 10495 21579 10290 21579 10291 21579 10495 21580 10496 21580 10290 21580 10494 21581 10291 21581 10292 21581 10494 21582 10495 21582 10291 21582 10493 21583 10292 21583 10293 21583 10493 21584 10494 21584 10292 21584 10492 21585 10293 21585 10294 21585 10492 21586 10493 21586 10293 21586 10491 21587 10294 21587 10295 21587 10491 21588 10492 21588 10294 21588 10490 21589 10295 21589 10296 21589 10490 21590 10491 21590 10295 21590 10489 21591 10296 21591 10297 21591 10489 21592 10490 21592 10296 21592 10488 21593 10297 21593 10298 21593 10488 21594 10489 21594 10297 21594 10487 21595 10298 21595 10299 21595 10487 21596 10488 21596 10298 21596 10486 21597 10299 21597 10300 21597 10486 21598 10487 21598 10299 21598 10485 21599 10300 21599 10301 21599 10485 21600 10486 21600 10300 21600 10484 21601 10301 21601 10302 21601 10484 21602 10485 21602 10301 21602 10483 21603 10302 21603 10303 21603 10483 21604 10484 21604 10302 21604 10482 21605 10303 21605 10304 21605 10482 21606 10483 21606 10303 21606 10481 21607 10304 21607 10305 21607 10481 21608 10482 21608 10304 21608 10480 21609 10305 21609 10306 21609 10480 21610 10481 21610 10305 21610 10479 21611 10306 21611 10307 21611 10479 21612 10480 21612 10306 21612 10478 21613 10307 21613 10308 21613 10478 21614 10479 21614 10307 21614 10477 21615 10308 21615 10309 21615 10477 21616 10478 21616 10308 21616 10476 21617 10309 21617 10310 21617 10476 21618 10477 21618 10309 21618 10475 21619 10310 21619 10311 21619 10475 21620 10476 21620 10310 21620 10474 21621 10311 21621 10312 21621 10474 21622 10475 21622 10311 21622 10473 21623 10312 21623 10313 21623 10473 21624 10474 21624 10312 21624 10472 21625 10313 21625 10314 21625 10472 21626 10473 21626 10313 21626 10471 21627 10314 21627 10315 21627 10471 21628 10472 21628 10314 21628 10470 21629 10315 21629 10316 21629 10470 21630 10471 21630 10315 21630 10468 21631 10316 21631 10317 21631 10468 21632 10470 21632 10316 21632 10501 21633 9551 21633 9550 21633 10502 21634 10501 21634 9550 21634 9856 21635 10502 21635 9550 21635 10503 21636 9551 21636 10501 21636 9545 21637 9551 21637 10503 21637 10504 21638 10501 21638 10502 21638 10503 21639 10501 21639 10504 21639 10504 21640 10502 21640 9856 21640 10505 21641 9856 21641 9857 21641 10504 21642 9856 21642 10505 21642 9858 21643 10506 21643 9859 21643 10505 21644 9857 21644 9690 21644 9690 21645 9857 21645 9684 21645 10507 21646 9439 21646 9437 21646 10507 21647 9680 21647 9439 21647 10508 21648 9437 21648 9441 21648 10508 21649 10507 21649 9437 21649 10509 21650 9441 21650 9440 21650 10509 21651 10508 21651 9441 21651 9461 21652 9440 21652 9442 21652 9461 21653 10509 21653 9440 21653 10505 21654 9690 21654 9689 21654 10510 21655 9689 21655 9693 21655 10510 21656 10505 21656 9689 21656 10511 21657 9693 21657 9695 21657 10511 21658 10510 21658 9693 21658 10512 21659 9695 21659 9700 21659 10512 21660 10511 21660 9695 21660 10513 21661 9700 21661 9703 21661 10513 21662 10512 21662 9700 21662 10514 21663 9703 21663 9706 21663 10514 21664 10513 21664 9703 21664 10515 21665 9706 21665 9711 21665 10515 21666 10514 21666 9706 21666 10516 21667 9711 21667 9716 21667 10516 21668 10515 21668 9711 21668 10517 21669 9716 21669 9721 21669 10517 21670 10516 21670 9716 21670 10518 21671 9721 21671 9724 21671 10518 21672 10517 21672 9721 21672 10519 21673 9724 21673 9729 21673 10519 21674 10518 21674 9724 21674 10520 21675 9729 21675 9733 21675 10520 21676 10519 21676 9729 21676 10521 21677 9733 21677 9738 21677 10521 21678 10520 21678 9733 21678 10522 21679 9738 21679 9743 21679 10522 21680 10521 21680 9738 21680 10523 21681 9743 21681 9746 21681 10523 21682 10522 21682 9743 21682 10524 21683 9746 21683 9750 21683 10524 21684 10523 21684 9746 21684 10525 21685 9750 21685 9752 21685 10525 21686 10524 21686 9750 21686 10526 21687 9752 21687 9755 21687 10526 21688 10525 21688 9752 21688 10527 21689 9755 21689 9759 21689 10527 21690 10526 21690 9755 21690 10528 21691 9759 21691 9763 21691 10528 21692 10527 21692 9759 21692 10529 21693 9763 21693 9762 21693 10529 21694 10528 21694 9763 21694 10530 21695 9762 21695 9768 21695 10530 21696 10529 21696 9762 21696 10531 21697 9768 21697 9771 21697 10531 21698 10530 21698 9768 21698 10532 21699 9771 21699 9776 21699 10532 21700 10531 21700 9771 21700 10533 21701 9776 21701 9780 21701 10533 21702 10532 21702 9776 21702 10534 21703 9780 21703 9785 21703 10534 21704 10533 21704 9780 21704 10535 21705 9785 21705 9791 21705 10535 21706 10534 21706 9785 21706 10536 21707 9791 21707 9796 21707 10536 21708 10535 21708 9791 21708 10537 21709 9796 21709 9801 21709 10537 21710 10536 21710 9796 21710 10538 21711 9801 21711 9806 21711 10538 21712 10537 21712 9801 21712 10539 21713 9806 21713 9811 21713 10539 21714 10538 21714 9806 21714 10540 21715 9811 21715 9817 21715 10540 21716 10539 21716 9811 21716 10541 21717 9817 21717 9680 21717 10541 21718 10540 21718 9817 21718 10507 21719 10541 21719 9680 21719 10504 21720 10505 21720 10510 21720 10542 21721 10510 21721 10511 21721 10542 21722 10504 21722 10510 21722 10543 21723 10511 21723 10512 21723 10543 21724 10542 21724 10511 21724 10544 21725 10512 21725 10513 21725 10544 21726 10543 21726 10512 21726 10545 21727 10513 21727 10514 21727 10545 21728 10544 21728 10513 21728 10546 21729 10514 21729 10515 21729 10546 21730 10545 21730 10514 21730 10547 21731 10515 21731 10516 21731 10547 21732 10546 21732 10515 21732 10548 21733 10516 21733 10517 21733 10548 21734 10547 21734 10516 21734 10549 21735 10517 21735 10518 21735 10549 21736 10548 21736 10517 21736 10550 21737 10518 21737 10519 21737 10550 21738 10549 21738 10518 21738 10551 21739 10519 21739 10520 21739 10551 21740 10550 21740 10519 21740 10552 21741 10520 21741 10521 21741 10552 21742 10551 21742 10520 21742 10553 21743 10521 21743 10522 21743 10553 21744 10552 21744 10521 21744 10554 21745 10522 21745 10523 21745 10554 21746 10553 21746 10522 21746 10555 21747 10523 21747 10524 21747 10555 21748 10554 21748 10523 21748 10556 21749 10524 21749 10525 21749 10556 21750 10555 21750 10524 21750 10557 21751 10525 21751 10526 21751 10557 21752 10556 21752 10525 21752 10558 21753 10526 21753 10527 21753 10558 21754 10557 21754 10526 21754 10559 21755 10527 21755 10528 21755 10559 21756 10558 21756 10527 21756 10560 21757 10528 21757 10529 21757 10560 21758 10559 21758 10528 21758 10561 21759 10529 21759 10530 21759 10561 21760 10560 21760 10529 21760 10562 21761 10530 21761 10531 21761 10562 21762 10561 21762 10530 21762 10563 21763 10531 21763 10532 21763 10563 21764 10562 21764 10531 21764 10564 21765 10532 21765 10533 21765 10564 21766 10563 21766 10532 21766 10565 21767 10533 21767 10534 21767 10565 21768 10564 21768 10533 21768 10566 21769 10534 21769 10535 21769 10566 21770 10565 21770 10534 21770 10567 21771 10535 21771 10536 21771 10567 21772 10566 21772 10535 21772 10568 21773 10536 21773 10537 21773 10568 21774 10567 21774 10536 21774 10569 21775 10537 21775 10538 21775 10569 21776 10568 21776 10537 21776 10570 21777 10538 21777 10539 21777 10570 21778 10569 21778 10538 21778 10571 21779 10539 21779 10540 21779 10571 21780 10570 21780 10539 21780 10572 21781 10540 21781 10541 21781 10572 21782 10571 21782 10540 21782 10573 21783 10541 21783 10507 21783 10573 21784 10572 21784 10541 21784 10508 21785 10573 21785 10507 21785 10503 21786 10504 21786 10542 21786 10574 21787 10542 21787 10543 21787 10574 21788 10503 21788 10542 21788 10575 21789 10543 21789 10544 21789 10575 21790 10574 21790 10543 21790 10576 21791 10544 21791 10545 21791 10576 21792 10575 21792 10544 21792 10577 21793 10545 21793 10546 21793 10577 21794 10576 21794 10545 21794 10578 21795 10546 21795 10547 21795 10578 21796 10577 21796 10546 21796 10579 21797 10547 21797 10548 21797 10579 21798 10578 21798 10547 21798 10580 21799 10548 21799 10549 21799 10580 21800 10579 21800 10548 21800 10581 21801 10549 21801 10550 21801 10581 21802 10580 21802 10549 21802 10582 21803 10550 21803 10551 21803 10582 21804 10581 21804 10550 21804 10583 21805 10551 21805 10552 21805 10583 21806 10582 21806 10551 21806 10584 21807 10552 21807 10553 21807 10584 21808 10583 21808 10552 21808 10585 21809 10553 21809 10554 21809 10585 21810 10584 21810 10553 21810 10586 21811 10554 21811 10555 21811 10586 21812 10585 21812 10554 21812 10587 21813 10555 21813 10556 21813 10587 21814 10586 21814 10555 21814 10588 21815 10556 21815 10557 21815 10588 21816 10587 21816 10556 21816 10589 21817 10557 21817 10558 21817 10589 21818 10588 21818 10557 21818 10590 21819 10558 21819 10559 21819 10590 21820 10589 21820 10558 21820 10591 21821 10559 21821 10560 21821 10591 21822 10590 21822 10559 21822 10592 21823 10560 21823 10561 21823 10592 21824 10591 21824 10560 21824 10593 21825 10561 21825 10562 21825 10593 21826 10592 21826 10561 21826 10594 21827 10562 21827 10563 21827 10594 21828 10593 21828 10562 21828 10595 21829 10563 21829 10564 21829 10595 21830 10594 21830 10563 21830 10596 21831 10564 21831 10565 21831 10596 21832 10595 21832 10564 21832 10597 21833 10565 21833 10566 21833 10597 21834 10596 21834 10565 21834 10598 21835 10566 21835 10567 21835 10598 21836 10597 21836 10566 21836 10599 21837 10567 21837 10568 21837 10599 21838 10598 21838 10567 21838 10600 21839 10568 21839 10569 21839 10600 21840 10599 21840 10568 21840 10601 21841 10569 21841 10570 21841 10601 21842 10600 21842 10569 21842 10602 21843 10570 21843 10571 21843 10602 21844 10601 21844 10570 21844 10603 21845 10571 21845 10572 21845 10603 21846 10602 21846 10571 21846 10604 21847 10572 21847 10573 21847 10604 21848 10603 21848 10572 21848 10605 21849 10573 21849 10508 21849 10605 21850 10604 21850 10573 21850 10509 21851 10605 21851 10508 21851 9545 21852 10503 21852 10574 21852 9541 21853 10574 21853 10575 21853 9541 21854 9545 21854 10574 21854 9542 21855 10575 21855 10576 21855 9542 21856 9541 21856 10575 21856 9536 21857 10576 21857 10577 21857 9536 21858 9542 21858 10576 21858 9538 21859 10577 21859 10578 21859 9538 21860 9536 21860 10577 21860 9531 21861 10578 21861 10579 21861 9531 21862 9538 21862 10578 21862 9533 21863 10579 21863 10580 21863 9533 21864 9531 21864 10579 21864 9526 21865 10580 21865 10581 21865 9526 21866 9533 21866 10580 21866 9527 21867 10581 21867 10582 21867 9527 21868 9526 21868 10581 21868 9528 21869 10582 21869 10583 21869 9528 21870 9527 21870 10582 21870 9521 21871 10583 21871 10584 21871 9521 21872 9528 21872 10583 21872 9523 21873 10584 21873 10585 21873 9523 21874 9521 21874 10584 21874 9517 21875 10585 21875 10586 21875 9517 21876 9523 21876 10585 21876 9513 21877 10586 21877 10587 21877 9513 21878 9517 21878 10586 21878 9514 21879 10587 21879 10588 21879 9514 21880 9513 21880 10587 21880 9510 21881 10588 21881 10589 21881 9510 21882 9514 21882 10588 21882 9506 21883 10589 21883 10590 21883 9506 21884 9510 21884 10589 21884 9507 21885 10590 21885 10591 21885 9507 21886 9506 21886 10590 21886 9503 21887 10591 21887 10592 21887 9503 21888 9507 21888 10591 21888 9501 21889 10592 21889 10593 21889 9501 21890 9503 21890 10592 21890 9498 21891 10593 21891 10594 21891 9498 21892 9501 21892 10593 21892 9496 21893 10594 21893 10595 21893 9496 21894 9498 21894 10594 21894 9493 21895 10595 21895 10596 21895 9493 21896 9496 21896 10595 21896 9490 21897 10596 21897 10597 21897 9490 21898 9493 21898 10596 21898 9486 21899 10597 21899 10598 21899 9486 21900 9490 21900 10597 21900 9484 21901 10598 21901 10599 21901 9484 21902 9486 21902 10598 21902 9480 21903 10599 21903 10600 21903 9480 21904 9484 21904 10599 21904 9477 21905 10600 21905 10601 21905 9477 21906 9480 21906 10600 21906 9474 21907 10601 21907 10602 21907 9474 21908 9477 21908 10601 21908 9469 21909 10602 21909 10603 21909 9469 21910 9474 21910 10602 21910 9466 21911 10603 21911 10604 21911 9466 21912 9469 21912 10603 21912 9463 21913 10604 21913 10605 21913 9463 21914 9466 21914 10604 21914 9462 21915 10605 21915 10509 21915 9462 21916 9463 21916 10605 21916 9461 21917 9462 21917 10509 21917 10606 21918 9854 21918 9640 21918 10506 21919 10607 21919 9859 21919 10608 21920 10606 21920 9640 21920 9641 21921 10608 21921 9640 21921 10506 21922 10609 21922 10607 21922 9852 21923 9854 21923 10606 21923 10610 21924 10606 21924 10608 21924 10610 21925 9852 21925 10606 21925 9642 21926 10608 21926 9641 21926 10611 21927 10608 21927 9642 21927 10610 21928 10608 21928 10611 21928 10612 21929 9642 21929 9639 21929 10611 21930 9642 21930 10612 21930 10612 21931 9639 21931 9643 21931 10613 21932 9430 21932 9431 21932 10613 21933 9565 21933 9430 21933 9860 21934 9431 21934 9429 21934 9860 21935 10613 21935 9431 21935 9858 21936 9429 21936 9434 21936 9858 21937 9860 21937 9429 21937 9819 21938 9434 21938 9433 21938 9858 21939 9434 21939 9819 21939 10506 21940 9819 21940 9820 21940 9858 21941 9819 21941 10506 21941 10609 21942 9820 21942 9821 21942 10506 21943 9820 21943 10609 21943 10614 21944 9821 21944 9822 21944 10609 21945 9821 21945 10614 21945 10615 21946 9822 21946 9823 21946 10614 21947 9822 21947 10615 21947 10616 21948 9823 21948 9824 21948 10615 21949 9823 21949 10616 21949 10617 21950 9824 21950 9825 21950 10616 21951 9824 21951 10617 21951 10618 21952 9825 21952 9826 21952 10617 21953 9825 21953 10618 21953 10619 21954 9826 21954 9827 21954 10618 21955 9826 21955 10619 21955 10620 21956 9827 21956 9828 21956 10619 21957 9827 21957 10620 21957 10621 21958 9828 21958 9829 21958 10620 21959 9828 21959 10621 21959 10622 21960 9829 21960 9830 21960 10621 21961 9829 21961 10622 21961 10623 21962 9830 21962 9831 21962 10622 21963 9830 21963 10623 21963 10624 21964 9831 21964 9832 21964 10623 21965 9831 21965 10624 21965 10625 21966 9832 21966 9833 21966 10624 21967 9832 21967 10625 21967 10626 21968 9833 21968 9834 21968 10625 21969 9833 21969 10626 21969 10627 21970 9834 21970 9835 21970 10626 21971 9834 21971 10627 21971 10628 21972 9835 21972 9836 21972 10627 21973 9835 21973 10628 21973 10629 21974 9836 21974 9837 21974 10628 21975 9836 21975 10629 21975 10630 21976 9837 21976 9838 21976 10629 21977 9837 21977 10630 21977 10631 21978 9838 21978 9839 21978 10630 21979 9838 21979 10631 21979 10632 21980 9839 21980 9840 21980 10631 21981 9839 21981 10632 21981 10633 21982 9840 21982 9841 21982 10632 21983 9840 21983 10633 21983 10634 21984 9841 21984 9842 21984 10633 21985 9841 21985 10634 21985 10635 21986 9842 21986 9843 21986 10634 21987 9842 21987 10635 21987 10636 21988 9843 21988 9844 21988 10635 21989 9843 21989 10636 21989 10637 21990 9844 21990 9845 21990 10636 21991 9844 21991 10637 21991 10638 21992 9845 21992 9846 21992 10637 21993 9845 21993 10638 21993 10639 21994 9846 21994 9847 21994 10638 21995 9846 21995 10639 21995 10640 21996 9847 21996 9848 21996 10639 21997 9847 21997 10640 21997 10641 21998 9848 21998 9849 21998 10640 21999 9848 21999 10641 21999 10642 22000 9849 22000 9851 22000 10641 22001 9849 22001 10642 22001 10643 22002 9851 22002 9850 22002 10642 22003 9851 22003 10643 22003 10610 22004 9850 22004 9852 22004 10643 22005 9850 22005 10610 22005 10644 22006 9643 22006 9644 22006 10644 22007 10612 22007 9643 22007 10645 22008 9644 22008 9646 22008 10645 22009 10644 22009 9644 22009 10646 22010 9646 22010 9645 22010 10646 22011 10645 22011 9646 22011 10647 22012 9645 22012 9647 22012 10647 22013 10646 22013 9645 22013 10648 22014 9647 22014 9649 22014 10648 22015 10647 22015 9647 22015 10649 22016 9649 22016 9650 22016 10649 22017 10648 22017 9649 22017 10650 22018 9650 22018 9648 22018 10650 22019 10649 22019 9650 22019 10651 22020 9648 22020 9652 22020 10651 22021 10650 22021 9648 22021 10652 22022 9652 22022 9651 22022 10652 22023 10651 22023 9652 22023 10653 22024 9651 22024 9654 22024 10653 22025 10652 22025 9651 22025 10654 22026 9654 22026 9655 22026 10654 22027 10653 22027 9654 22027 10655 22028 9655 22028 9653 22028 10655 22029 10654 22029 9655 22029 10656 22030 9653 22030 9657 22030 10656 22031 10655 22031 9653 22031 10657 22032 9657 22032 9656 22032 10657 22033 10656 22033 9657 22033 10658 22034 9656 22034 9659 22034 10658 22035 10657 22035 9656 22035 10659 22036 9659 22036 9658 22036 10659 22037 10658 22037 9659 22037 10660 22038 9658 22038 9660 22038 10660 22039 10659 22039 9658 22039 10661 22040 9660 22040 9662 22040 10661 22041 10660 22041 9660 22041 10662 22042 9662 22042 9661 22042 10662 22043 10661 22043 9662 22043 10663 22044 9661 22044 9663 22044 10663 22045 10662 22045 9661 22045 10664 22046 9663 22046 9664 22046 10664 22047 10663 22047 9663 22047 10665 22048 9664 22048 9665 22048 10665 22049 10664 22049 9664 22049 10666 22050 9665 22050 9666 22050 10666 22051 10665 22051 9665 22051 10667 22052 9666 22052 9667 22052 10667 22053 10666 22053 9666 22053 10668 22054 9667 22054 9668 22054 10668 22055 10667 22055 9667 22055 10669 22056 9668 22056 9669 22056 10669 22057 10668 22057 9668 22057 10670 22058 9669 22058 9670 22058 10670 22059 10669 22059 9669 22059 10671 22060 9670 22060 9671 22060 10671 22061 10670 22061 9670 22061 10672 22062 9671 22062 9672 22062 10672 22063 10671 22063 9671 22063 10673 22064 9672 22064 9673 22064 10673 22065 10672 22065 9672 22065 10674 22066 9673 22066 9674 22066 10674 22067 10673 22067 9673 22067 10675 22068 9674 22068 9675 22068 10675 22069 10674 22069 9674 22069 10613 22070 9675 22070 9565 22070 10613 22071 10675 22071 9675 22071 10676 22072 10612 22072 10644 22072 10676 22073 10611 22073 10612 22073 10677 22074 10644 22074 10645 22074 10677 22075 10676 22075 10644 22075 10678 22076 10645 22076 10646 22076 10678 22077 10677 22077 10645 22077 10679 22078 10646 22078 10647 22078 10679 22079 10678 22079 10646 22079 10680 22080 10647 22080 10648 22080 10680 22081 10679 22081 10647 22081 10681 22082 10648 22082 10649 22082 10681 22083 10680 22083 10648 22083 10682 22084 10649 22084 10650 22084 10682 22085 10681 22085 10649 22085 10683 22086 10650 22086 10651 22086 10683 22087 10682 22087 10650 22087 10684 22088 10651 22088 10652 22088 10684 22089 10683 22089 10651 22089 10685 22090 10652 22090 10653 22090 10685 22091 10684 22091 10652 22091 10686 22092 10653 22092 10654 22092 10686 22093 10685 22093 10653 22093 10687 22094 10654 22094 10655 22094 10687 22095 10686 22095 10654 22095 10688 22096 10655 22096 10656 22096 10688 22097 10687 22097 10655 22097 10689 22098 10656 22098 10657 22098 10689 22099 10688 22099 10656 22099 10690 22100 10657 22100 10658 22100 10690 22101 10689 22101 10657 22101 10691 22102 10658 22102 10659 22102 10691 22103 10690 22103 10658 22103 10692 22104 10659 22104 10660 22104 10692 22105 10691 22105 10659 22105 10693 22106 10660 22106 10661 22106 10693 22107 10692 22107 10660 22107 10694 22108 10661 22108 10662 22108 10694 22109 10693 22109 10661 22109 10695 22110 10662 22110 10663 22110 10695 22111 10694 22111 10662 22111 10696 22112 10663 22112 10664 22112 10696 22113 10695 22113 10663 22113 10697 22114 10664 22114 10665 22114 10697 22115 10696 22115 10664 22115 10698 22116 10665 22116 10666 22116 10698 22117 10697 22117 10665 22117 10699 22118 10666 22118 10667 22118 10699 22119 10698 22119 10666 22119 10700 22120 10667 22120 10668 22120 10700 22121 10699 22121 10667 22121 10701 22122 10668 22122 10669 22122 10701 22123 10700 22123 10668 22123 10702 22124 10669 22124 10670 22124 10702 22125 10701 22125 10669 22125 10703 22126 10670 22126 10671 22126 10703 22127 10702 22127 10670 22127 10704 22128 10671 22128 10672 22128 10704 22129 10703 22129 10671 22129 10705 22130 10672 22130 10673 22130 10705 22131 10704 22131 10672 22131 10607 22132 10673 22132 10674 22132 10607 22133 10705 22133 10673 22133 9859 22134 10674 22134 10675 22134 9859 22135 10607 22135 10674 22135 9860 22136 10675 22136 10613 22136 9860 22137 9859 22137 10675 22137 10643 22138 10611 22138 10676 22138 10643 22139 10610 22139 10611 22139 10642 22140 10676 22140 10677 22140 10642 22141 10643 22141 10676 22141 10641 22142 10677 22142 10678 22142 10641 22143 10642 22143 10677 22143 10640 22144 10678 22144 10679 22144 10640 22145 10641 22145 10678 22145 10639 22146 10679 22146 10680 22146 10639 22147 10640 22147 10679 22147 10638 22148 10680 22148 10681 22148 10638 22149 10639 22149 10680 22149 10637 22150 10681 22150 10682 22150 10637 22151 10638 22151 10681 22151 10636 22152 10682 22152 10683 22152 10636 22153 10637 22153 10682 22153 10635 22154 10683 22154 10684 22154 10635 22155 10636 22155 10683 22155 10634 22156 10684 22156 10685 22156 10634 22157 10635 22157 10684 22157 10633 22158 10685 22158 10686 22158 10633 22159 10634 22159 10685 22159 10632 22160 10686 22160 10687 22160 10632 22161 10633 22161 10686 22161 10631 22162 10687 22162 10688 22162 10631 22163 10632 22163 10687 22163 10630 22164 10688 22164 10689 22164 10630 22165 10631 22165 10688 22165 10629 22166 10689 22166 10690 22166 10629 22167 10630 22167 10689 22167 10628 22168 10690 22168 10691 22168 10628 22169 10629 22169 10690 22169 10627 22170 10691 22170 10692 22170 10627 22171 10628 22171 10691 22171 10626 22172 10692 22172 10693 22172 10626 22173 10627 22173 10692 22173 10625 22174 10693 22174 10694 22174 10625 22175 10626 22175 10693 22175 10624 22176 10694 22176 10695 22176 10624 22177 10625 22177 10694 22177 10623 22178 10695 22178 10696 22178 10623 22179 10624 22179 10695 22179 10622 22180 10696 22180 10697 22180 10622 22181 10623 22181 10696 22181 10621 22182 10697 22182 10698 22182 10621 22183 10622 22183 10697 22183 10620 22184 10698 22184 10699 22184 10620 22185 10621 22185 10698 22185 10619 22186 10699 22186 10700 22186 10619 22187 10620 22187 10699 22187 10618 22188 10700 22188 10701 22188 10618 22189 10619 22189 10700 22189 10617 22190 10701 22190 10702 22190 10617 22191 10618 22191 10701 22191 10616 22192 10702 22192 10703 22192 10616 22193 10617 22193 10702 22193 10615 22194 10703 22194 10704 22194 10615 22195 10616 22195 10703 22195 10614 22196 10704 22196 10705 22196 10614 22197 10615 22197 10704 22197 10609 22198 10705 22198 10607 22198 10609 22199 10614 22199 10705 22199 10706 22200 10707 22200 10708 22200 10709 22201 10708 22201 10707 22201 10710 22202 10708 22202 10711 22202 10712 22203 10711 22203 10708 22203 10706 22204 10708 22204 10710 22204 10713 22205 10708 22205 10709 22205 10714 22206 10712 22206 10708 22206 10715 22207 10714 22207 10708 22207 10713 22208 10715 22208 10708 22208 10716 22209 10717 22209 10707 22209 10718 22210 10707 22210 10717 22210 10719 22211 10716 22211 10707 22211 10720 22212 10719 22212 10707 22212 10706 22213 10720 22213 10707 22213 10721 22214 10707 22214 10718 22214 10722 22215 10723 22215 10707 22215 10724 22216 10707 22216 10723 22216 10721 22217 10722 22217 10707 22217 10724 22218 10709 22218 10707 22218 10725 22219 10726 22219 10717 22219 10727 22220 10717 22220 10726 22220 10716 22221 10725 22221 10717 22221 10718 22222 10717 22222 10727 22222 10728 22223 10729 22223 10726 22223 10730 22224 10726 22224 10729 22224 10725 22225 10728 22225 10726 22225 10727 22226 10726 22226 10730 22226 10731 22227 10729 22227 10728 22227 10730 22228 10729 22228 10731 22228 10732 22229 10728 22229 10725 22229 10731 22230 10728 22230 10732 22230 10733 22231 10725 22231 10716 22231 10732 22232 10725 22232 10733 22232 10734 22233 10735 22233 10716 22233 10736 22234 10716 22234 10735 22234 10719 22235 10734 22235 10716 22235 10733 22236 10716 22236 10736 22236 10737 22237 10738 22237 10735 22237 10739 22238 10735 22238 10738 22238 10740 22239 10737 22239 10735 22239 10734 22240 10740 22240 10735 22240 10736 22241 10735 22241 10741 22241 10739 22242 10741 22242 10735 22242 10742 22243 10743 22243 10738 22243 10744 22244 10738 22244 10743 22244 10737 22245 10742 22245 10738 22245 10745 22246 10739 22246 10738 22246 10746 22247 10745 22247 10738 22247 10747 22248 10746 22248 10738 22248 10744 22249 10747 22249 10738 22249 10748 22250 10749 22250 10743 22250 10750 22251 10743 22251 10749 22251 10751 22252 10748 22252 10743 22252 10752 22253 10751 22253 10743 22253 10742 22254 10752 22254 10743 22254 10753 22255 10743 22255 10750 22255 10754 22256 10744 22256 10743 22256 10755 22257 10756 22257 10743 22257 10754 22258 10743 22258 10756 22258 10753 22259 10755 22259 10743 22259 10757 22260 10758 22260 10749 22260 10759 22261 10749 22261 10758 22261 10748 22262 10757 22262 10749 22262 10750 22263 10749 22263 10759 22263 10760 22264 10761 22264 10758 22264 10762 22265 10758 22265 10761 22265 10757 22266 10760 22266 10758 22266 10759 22267 10758 22267 10762 22267 10763 22268 10761 22268 10760 22268 10762 22269 10761 22269 10763 22269 10764 22270 10760 22270 10757 22270 10763 22271 10760 22271 10764 22271 10765 22272 10757 22272 10748 22272 10764 22273 10757 22273 10765 22273 10766 22274 10711 22274 10748 22274 10767 22275 10748 22275 10711 22275 10751 22276 10766 22276 10748 22276 10765 22277 10748 22277 10767 22277 10768 22278 10710 22278 10711 22278 10766 22279 10768 22279 10711 22279 10767 22280 10711 22280 10769 22280 10712 22281 10769 22281 10711 22281 10770 22282 10710 22282 10768 22282 10771 22283 10706 22283 10710 22283 10771 22284 10710 22284 10770 22284 10772 22285 10768 22285 10766 22285 10772 22286 10770 22286 10768 22286 10773 22287 10766 22287 10751 22287 10772 22288 10766 22288 10773 22288 10774 22289 10751 22289 10752 22289 10773 22290 10751 22290 10774 22290 10775 22291 10752 22291 10742 22291 10774 22292 10752 22292 10775 22292 10776 22293 10742 22293 10737 22293 10775 22294 10742 22294 10776 22294 10777 22295 10737 22295 10740 22295 10776 22296 10737 22296 10777 22296 10778 22297 10740 22297 10734 22297 10777 22298 10740 22298 10778 22298 10779 22299 10734 22299 10719 22299 10778 22300 10734 22300 10779 22300 10780 22301 10719 22301 10720 22301 10779 22302 10719 22302 10780 22302 10720 22303 10706 22303 10781 22303 10780 22304 10720 22304 10781 22304 10781 22305 10706 22305 10771 22305 10772 22306 10769 22306 10782 22306 10783 22307 10782 22307 10769 22307 10770 22308 10782 22308 10718 22308 10721 22309 10718 22309 10782 22309 10772 22310 10782 22310 10770 22310 10784 22311 10721 22311 10782 22311 10785 22312 10784 22312 10782 22312 10786 22313 10785 22313 10782 22313 10787 22314 10786 22314 10782 22314 10788 22315 10787 22315 10782 22315 10783 22316 10788 22316 10782 22316 10759 22317 10767 22317 10769 22317 10774 22318 10759 22318 10769 22318 10773 22319 10774 22319 10769 22319 10772 22320 10773 22320 10769 22320 10789 22321 10783 22321 10769 22321 10712 22322 10789 22322 10769 22322 10762 22323 10765 22323 10767 22323 10759 22324 10762 22324 10767 22324 10763 22325 10764 22325 10765 22325 10762 22326 10763 22326 10765 22326 10775 22327 10750 22327 10759 22327 10774 22328 10775 22328 10759 22328 10777 22329 10790 22329 10750 22329 10753 22330 10750 22330 10790 22330 10776 22331 10777 22331 10750 22331 10775 22332 10776 22332 10750 22332 10778 22333 10741 22333 10790 22333 10791 22334 10790 22334 10741 22334 10777 22335 10778 22335 10790 22335 10792 22336 10790 22336 10791 22336 10793 22337 10753 22337 10790 22337 10794 22338 10793 22338 10790 22338 10795 22339 10794 22339 10790 22339 10796 22340 10795 22340 10790 22340 10792 22341 10796 22341 10790 22341 10727 22342 10736 22342 10741 22342 10780 22343 10727 22343 10741 22343 10779 22344 10780 22344 10741 22344 10778 22345 10779 22345 10741 22345 10797 22346 10791 22346 10741 22346 10739 22347 10797 22347 10741 22347 10730 22348 10733 22348 10736 22348 10727 22349 10730 22349 10736 22349 10731 22350 10732 22350 10733 22350 10730 22351 10731 22351 10733 22351 10781 22352 10718 22352 10727 22352 10780 22353 10781 22353 10727 22353 10771 22354 10770 22354 10718 22354 10781 22355 10771 22355 10718 22355 10798 22356 10723 22356 10722 22356 10798 22357 10724 22357 10723 22357 10799 22358 10722 22358 10721 22358 10800 22359 10798 22359 10722 22359 10799 22360 10800 22360 10722 22360 10801 22361 10721 22361 10784 22361 10802 22362 10721 22362 10801 22362 10802 22363 10799 22363 10721 22363 10803 22364 10784 22364 10785 22364 10804 22365 10801 22365 10784 22365 10803 22366 10804 22366 10784 22366 10805 22367 10785 22367 10786 22367 10806 22368 10803 22368 10785 22368 10807 22369 10806 22369 10785 22369 10805 22370 10807 22370 10785 22370 10808 22371 10786 22371 10787 22371 10809 22372 10805 22372 10786 22372 10808 22373 10809 22373 10786 22373 10810 22374 10787 22374 10788 22374 10808 22375 10787 22375 10810 22375 10810 22376 10788 22376 10783 22376 10811 22377 10783 22377 10789 22377 10811 22378 10812 22378 10783 22378 10810 22379 10783 22379 10812 22379 10813 22380 10791 22380 10797 22380 10814 22381 10792 22381 10791 22381 10813 22382 10815 22382 10791 22382 10814 22383 10791 22383 10815 22383 10813 22384 10797 22384 10739 22384 10813 22385 10739 22385 10745 22385 10813 22386 10745 22386 10746 22386 10816 22387 10746 22387 10747 22387 10816 22388 10813 22388 10746 22388 10816 22389 10747 22389 10744 22389 10817 22390 10744 22390 10754 22390 10816 22391 10744 22391 10817 22391 10798 22392 10709 22392 10724 22392 10818 22393 10713 22393 10709 22393 10818 22394 10709 22394 10798 22394 10817 22395 10756 22395 10755 22395 10817 22396 10754 22396 10756 22396 10819 22397 10755 22397 10753 22397 10820 22398 10817 22398 10755 22398 10821 22399 10820 22399 10755 22399 10819 22400 10821 22400 10755 22400 10822 22401 10753 22401 10793 22401 10823 22402 10753 22402 10822 22402 10824 22403 10819 22403 10753 22403 10823 22404 10824 22404 10753 22404 10825 22405 10793 22405 10794 22405 10826 22406 10822 22406 10793 22406 10825 22407 10826 22407 10793 22407 10827 22408 10794 22408 10795 22408 10828 22409 10825 22409 10794 22409 10829 22410 10828 22410 10794 22410 10827 22411 10829 22411 10794 22411 10830 22412 10795 22412 10796 22412 10831 22413 10827 22413 10795 22413 10830 22414 10831 22414 10795 22414 10814 22415 10796 22415 10792 22415 10832 22416 10796 22416 10814 22416 10832 22417 10830 22417 10796 22417 10811 22418 10789 22418 10712 22418 10811 22419 10712 22419 10714 22419 10811 22420 10714 22420 10715 22420 10818 22421 10715 22421 10713 22421 10818 22422 10811 22422 10715 22422 10833 22423 10815 22423 10813 22423 10834 22424 10814 22424 10815 22424 10835 22425 10834 22425 10815 22425 10836 22426 10835 22426 10815 22426 10837 22427 10836 22427 10815 22427 10838 22428 10837 22428 10815 22428 10839 22429 10838 22429 10815 22429 10840 22430 10839 22430 10815 22430 10840 22431 10815 22431 10833 22431 10841 22432 10813 22432 10816 22432 10842 22433 10843 22433 10813 22433 10844 22434 10813 22434 10843 22434 10841 22435 10842 22435 10813 22435 10845 22436 10833 22436 10813 22436 10846 22437 10845 22437 10813 22437 10847 22438 10846 22438 10813 22438 10848 22439 10847 22439 10813 22439 10849 22440 10848 22440 10813 22440 10850 22441 10849 22441 10813 22441 10844 22442 10850 22442 10813 22442 10832 22443 10814 22443 10834 22443 10851 22444 10834 22444 10835 22444 10851 22445 10832 22445 10834 22445 10852 22446 10835 22446 10836 22446 10851 22447 10835 22447 10852 22447 10852 22448 10836 22448 10837 22448 10853 22449 10837 22449 10838 22449 10852 22450 10837 22450 10853 22450 10839 22451 10854 22451 10838 22451 10853 22452 10838 22452 10854 22452 10839 22453 10855 22453 10854 22453 10856 22454 10854 22454 10855 22454 10853 22455 10854 22455 10856 22455 10839 22456 10857 22456 10855 22456 10856 22457 10855 22457 10857 22457 10839 22458 10858 22458 10857 22458 10859 22459 10857 22459 10858 22459 10856 22460 10857 22460 10859 22460 10839 22461 10860 22461 10858 22461 10859 22462 10858 22462 10860 22462 10839 22463 10861 22463 10860 22463 10859 22464 10860 22464 10861 22464 10862 22465 10863 22465 10861 22465 10864 22466 10861 22466 10863 22466 10839 22467 10862 22467 10861 22467 10859 22468 10861 22468 10864 22468 10862 22469 10865 22469 10863 22469 10864 22470 10863 22470 10865 22470 10862 22471 10866 22471 10865 22471 10867 22472 10865 22472 10866 22472 10864 22473 10865 22473 10867 22473 10862 22474 10868 22474 10866 22474 10867 22475 10866 22475 10868 22475 10862 22476 10869 22476 10868 22476 10870 22477 10868 22477 10869 22477 10867 22478 10868 22478 10870 22478 10862 22479 10871 22479 10869 22479 10870 22480 10869 22480 10871 22480 10872 22481 10873 22481 10871 22481 10874 22482 10871 22482 10873 22482 10862 22483 10872 22483 10871 22483 10870 22484 10871 22484 10874 22484 10872 22485 10875 22485 10873 22485 10876 22486 10873 22486 10875 22486 10874 22487 10873 22487 10876 22487 10872 22488 10877 22488 10875 22488 10876 22489 10875 22489 10877 22489 10878 22490 10879 22490 10877 22490 10880 22491 10877 22491 10879 22491 10872 22492 10878 22492 10877 22492 10876 22493 10877 22493 10880 22493 10878 22494 10881 22494 10879 22494 10880 22495 10879 22495 10881 22495 10878 22496 10882 22496 10881 22496 10883 22497 10881 22497 10882 22497 10880 22498 10881 22498 10883 22498 10884 22499 10885 22499 10882 22499 10886 22500 10882 22500 10885 22500 10878 22501 10884 22501 10882 22501 10883 22502 10882 22502 10886 22502 10884 22503 10887 22503 10885 22503 10888 22504 10885 22504 10887 22504 10886 22505 10885 22505 10888 22505 10889 22506 10890 22506 10887 22506 10891 22507 10887 22507 10890 22507 10884 22508 10889 22508 10887 22508 10888 22509 10887 22509 10891 22509 10889 22510 10892 22510 10890 22510 10893 22511 10890 22511 10892 22511 10891 22512 10890 22512 10893 22512 10894 22513 10895 22513 10892 22513 10896 22514 10892 22514 10895 22514 10889 22515 10894 22515 10892 22515 10897 22516 10892 22516 10896 22516 10893 22517 10892 22517 10897 22517 10898 22518 10899 22518 10895 22518 10900 22519 10895 22519 10899 22519 10894 22520 10898 22520 10895 22520 10896 22521 10895 22521 10900 22521 10901 22522 10902 22522 10899 22522 10903 22523 10899 22523 10902 22523 10898 22524 10901 22524 10899 22524 10904 22525 10899 22525 10903 22525 10900 22526 10899 22526 10904 22526 10905 22527 10906 22527 10902 22527 10907 22528 10902 22528 10906 22528 10908 22529 10905 22529 10902 22529 10901 22530 10908 22530 10902 22530 10903 22531 10902 22531 10907 22531 10909 22532 10910 22532 10906 22532 10911 22533 10906 22533 10910 22533 10912 22534 10909 22534 10906 22534 10905 22535 10912 22535 10906 22535 10913 22536 10906 22536 10911 22536 10907 22537 10906 22537 10913 22537 10914 22538 10915 22538 10910 22538 10916 22539 10910 22539 10915 22539 10909 22540 10914 22540 10910 22540 10917 22541 10910 22541 10916 22541 10918 22542 10910 22542 10917 22542 10911 22543 10910 22543 10918 22543 10919 22544 10920 22544 10915 22544 10921 22545 10915 22545 10920 22545 10922 22546 10919 22546 10915 22546 10914 22547 10922 22547 10915 22547 10923 22548 10915 22548 10921 22548 10916 22549 10915 22549 10923 22549 10924 22550 10925 22550 10920 22550 10926 22551 10920 22551 10925 22551 10927 22552 10924 22552 10920 22552 10919 22553 10927 22553 10920 22553 10928 22554 10920 22554 10926 22554 10921 22555 10920 22555 10928 22555 10929 22556 10930 22556 10925 22556 10931 22557 10925 22557 10930 22557 10924 22558 10929 22558 10925 22558 10932 22559 10925 22559 10931 22559 10926 22560 10925 22560 10932 22560 10933 22561 10934 22561 10930 22561 10935 22562 10930 22562 10934 22562 10936 22563 10933 22563 10930 22563 10937 22564 10936 22564 10930 22564 10938 22565 10937 22565 10930 22565 10939 22566 10938 22566 10930 22566 10929 22567 10939 22567 10930 22567 10931 22568 10930 22568 10935 22568 10940 22569 10934 22569 10933 22569 10941 22570 10934 22570 10940 22570 10935 22571 10934 22571 10941 22571 10940 22572 10933 22572 10936 22572 10942 22573 10936 22573 10937 22573 10942 22574 10940 22574 10936 22574 10943 22575 10937 22575 10938 22575 10943 22576 10942 22576 10937 22576 10943 22577 10938 22577 10939 22577 10944 22578 10939 22578 10929 22578 10943 22579 10939 22579 10944 22579 10944 22580 10929 22580 10924 22580 10945 22581 10924 22581 10927 22581 10945 22582 10944 22582 10924 22582 10945 22583 10927 22583 10919 22583 10946 22584 10919 22584 10922 22584 10946 22585 10945 22585 10919 22585 10946 22586 10922 22586 10914 22586 10946 22587 10914 22587 10909 22587 10947 22588 10909 22588 10912 22588 10947 22589 10946 22589 10909 22589 10947 22590 10912 22590 10905 22590 10948 22591 10905 22591 10908 22591 10948 22592 10947 22592 10905 22592 10948 22593 10908 22593 10901 22593 10949 22594 10901 22594 10898 22594 10949 22595 10948 22595 10901 22595 10949 22596 10898 22596 10894 22596 10950 22597 10894 22597 10889 22597 10950 22598 10949 22598 10894 22598 10950 22599 10889 22599 10884 22599 10951 22600 10884 22600 10878 22600 10951 22601 10950 22601 10884 22601 10952 22602 10878 22602 10872 22602 10952 22603 10951 22603 10878 22603 10952 22604 10872 22604 10862 22604 10953 22605 10862 22605 10839 22605 10953 22606 10952 22606 10862 22606 10840 22607 10953 22607 10839 22607 10954 22608 10816 22608 10817 22608 10955 22609 10954 22609 10817 22609 10955 22610 10817 22610 10820 22610 10956 22611 10957 22611 10816 22611 10958 22612 10816 22612 10957 22612 10959 22613 10956 22613 10816 22613 10954 22614 10959 22614 10816 22614 10960 22615 10841 22615 10816 22615 10961 22616 10960 22616 10816 22616 10962 22617 10961 22617 10816 22617 10963 22618 10962 22618 10816 22618 10964 22619 10963 22619 10816 22619 10958 22620 10964 22620 10816 22620 10965 22621 10966 22621 10957 22621 10967 22622 10957 22622 10966 22622 10968 22623 10965 22623 10957 22623 10969 22624 10968 22624 10957 22624 10970 22625 10969 22625 10957 22625 10971 22626 10970 22626 10957 22626 10972 22627 10971 22627 10957 22627 10973 22628 10972 22628 10957 22628 10974 22629 10973 22629 10957 22629 10975 22630 10974 22630 10957 22630 10956 22631 10975 22631 10957 22631 10958 22632 10957 22632 10962 22632 10967 22633 10962 22633 10957 22633 10976 22634 10977 22634 10966 22634 10978 22635 10966 22635 10977 22635 10979 22636 10976 22636 10966 22636 10980 22637 10979 22637 10966 22637 10981 22638 10980 22638 10966 22638 10982 22639 10981 22639 10966 22639 10983 22640 10982 22640 10966 22640 10965 22641 10983 22641 10966 22641 10967 22642 10966 22642 10978 22642 10984 22643 10985 22643 10977 22643 10986 22644 10977 22644 10985 22644 10987 22645 10984 22645 10977 22645 10988 22646 10987 22646 10977 22646 10989 22647 10988 22647 10977 22647 10976 22648 10989 22648 10977 22648 10978 22649 10977 22649 10986 22649 10990 22650 10991 22650 10985 22650 10992 22651 10985 22651 10991 22651 10993 22652 10990 22652 10985 22652 10984 22653 10993 22653 10985 22653 10986 22654 10985 22654 10992 22654 10994 22655 10995 22655 10991 22655 10996 22656 10991 22656 10995 22656 10997 22657 10994 22657 10991 22657 10990 22658 10997 22658 10991 22658 10992 22659 10991 22659 10996 22659 10998 22660 10999 22660 10995 22660 11000 22661 10995 22661 10999 22661 10994 22662 10998 22662 10995 22662 10996 22663 10995 22663 11000 22663 11001 22664 11002 22664 10999 22664 11000 22665 10999 22665 11002 22665 10998 22666 11001 22666 10999 22666 11003 22667 11004 22667 11002 22667 11005 22668 11002 22668 11004 22668 11001 22669 11003 22669 11002 22669 11000 22670 11002 22670 11005 22670 11006 22671 11007 22671 11004 22671 11005 22672 11004 22672 11007 22672 11003 22673 11006 22673 11004 22673 11008 22674 11009 22674 11007 22674 11010 22675 11007 22675 11009 22675 11006 22676 11008 22676 11007 22676 11005 22677 11007 22677 11010 22677 11008 22678 11011 22678 11009 22678 11012 22679 11009 22679 11011 22679 11010 22680 11009 22680 11012 22680 11013 22681 11014 22681 11011 22681 11012 22682 11011 22682 11014 22682 11008 22683 11013 22683 11011 22683 11013 22684 11015 22684 11014 22684 11012 22685 11014 22685 11015 22685 11016 22686 11017 22686 11015 22686 11018 22687 11015 22687 11017 22687 11013 22688 11016 22688 11015 22688 11012 22689 11015 22689 11018 22689 11019 22690 11020 22690 11017 22690 11018 22691 11017 22691 11020 22691 11016 22692 11019 22692 11017 22692 11021 22693 11022 22693 11020 22693 11023 22694 11020 22694 11022 22694 11019 22695 11021 22695 11020 22695 11018 22696 11020 22696 11023 22696 11021 22697 11024 22697 11022 22697 11025 22698 11022 22698 11024 22698 11025 22699 11023 22699 11022 22699 11021 22700 11026 22700 11024 22700 11027 22701 11024 22701 11026 22701 11027 22702 11025 22702 11024 22702 11021 22703 11028 22703 11026 22703 11027 22704 11026 22704 11028 22704 11029 22705 11028 22705 11021 22705 11030 22706 11027 22706 11028 22706 11031 22707 11030 22707 11028 22707 11032 22708 11031 22708 11028 22708 11029 22709 11032 22709 11028 22709 11033 22710 11021 22710 11019 22710 11033 22711 11029 22711 11021 22711 11034 22712 11019 22712 11016 22712 11034 22713 11033 22713 11019 22713 11035 22714 11016 22714 11013 22714 11036 22715 11034 22715 11016 22715 11035 22716 11036 22716 11016 22716 11037 22717 11013 22717 11008 22717 11037 22718 11035 22718 11013 22718 11038 22719 11008 22719 11006 22719 11039 22720 11037 22720 11008 22720 11040 22721 11039 22721 11008 22721 11038 22722 11040 22722 11008 22722 11041 22723 11006 22723 11003 22723 11042 22724 11038 22724 11006 22724 11041 22725 11042 22725 11006 22725 11043 22726 11003 22726 11001 22726 11044 22727 11041 22727 11003 22727 11045 22728 11044 22728 11003 22728 11043 22729 11045 22729 11003 22729 11046 22730 11001 22730 10998 22730 11047 22731 11043 22731 11001 22731 11046 22732 11047 22732 11001 22732 11048 22733 10998 22733 10994 22733 11049 22734 11046 22734 10998 22734 11048 22735 11049 22735 10998 22735 11050 22736 10994 22736 10997 22736 11050 22737 11048 22737 10994 22737 11051 22738 10997 22738 10990 22738 11052 22739 11050 22739 10997 22739 11051 22740 11052 22740 10997 22740 11053 22741 10990 22741 10993 22741 11053 22742 11051 22742 10990 22742 11054 22743 10993 22743 10984 22743 11054 22744 11053 22744 10993 22744 11055 22745 10984 22745 10987 22745 11055 22746 11054 22746 10984 22746 11056 22747 10987 22747 10988 22747 11056 22748 11055 22748 10987 22748 11056 22749 10988 22749 10989 22749 11057 22750 10989 22750 10976 22750 11057 22751 11056 22751 10989 22751 11057 22752 10976 22752 10979 22752 11058 22753 10979 22753 10980 22753 11058 22754 11057 22754 10979 22754 11058 22755 10980 22755 10981 22755 11059 22756 10981 22756 10982 22756 11059 22757 11058 22757 10981 22757 11059 22758 10982 22758 10983 22758 11060 22759 10983 22759 10965 22759 11060 22760 11059 22760 10983 22760 11060 22761 10965 22761 10968 22761 11061 22762 10968 22762 10969 22762 11061 22763 11060 22763 10968 22763 11061 22764 10969 22764 10970 22764 11062 22765 10970 22765 10971 22765 11062 22766 11061 22766 10970 22766 11063 22767 10971 22767 10972 22767 11063 22768 11062 22768 10971 22768 11063 22769 10972 22769 10973 22769 11063 22770 10973 22770 10974 22770 11064 22771 10974 22771 10975 22771 11064 22772 11063 22772 10974 22772 11064 22773 10975 22773 10956 22773 11065 22774 10956 22774 10959 22774 11065 22775 11064 22775 10956 22775 10955 22776 10959 22776 10954 22776 10955 22777 11065 22777 10959 22777 10823 22778 10822 22778 10826 22778 11066 22779 10826 22779 10825 22779 11067 22780 10826 22780 11066 22780 10823 22781 10826 22781 11067 22781 11066 22782 10825 22782 10828 22782 10829 22783 11066 22783 10828 22783 11068 22784 11067 22784 11066 22784 11068 22785 11066 22785 11069 22785 11070 22786 11069 22786 11066 22786 11070 22787 11066 22787 10829 22787 10823 22788 11067 22788 11068 22788 11071 22789 11072 22789 11073 22789 11074 22790 11073 22790 11072 22790 11075 22791 11071 22791 11073 22791 11076 22792 11075 22792 11073 22792 11074 22793 11076 22793 11073 22793 11077 22794 11078 22794 11072 22794 11079 22795 11072 22795 11078 22795 11071 22796 11077 22796 11072 22796 11080 22797 11074 22797 11072 22797 11079 22798 11080 22798 11072 22798 11081 22799 11082 22799 11078 22799 11083 22800 11078 22800 11082 22800 11077 22801 11081 22801 11078 22801 11083 22802 11079 22802 11078 22802 11081 22803 11084 22803 11082 22803 11085 22804 11082 22804 11084 22804 11085 22805 11083 22805 11082 22805 11086 22806 11087 22806 11084 22806 11085 22807 11084 22807 11087 22807 11081 22808 11086 22808 11084 22808 11088 22809 11089 22809 11087 22809 11090 22810 11087 22810 11089 22810 11086 22811 11088 22811 11087 22811 11090 22812 11085 22812 11087 22812 11091 22813 11092 22813 11089 22813 11093 22814 11089 22814 11092 22814 11088 22815 11091 22815 11089 22815 11093 22816 11090 22816 11089 22816 11094 22817 11095 22817 11092 22817 11096 22818 11092 22818 11095 22818 11091 22819 11094 22819 11092 22819 11096 22820 11093 22820 11092 22820 11097 22821 11098 22821 11095 22821 11096 22822 11095 22822 11098 22822 11094 22823 11097 22823 11095 22823 11099 22824 11100 22824 11098 22824 11101 22825 11098 22825 11100 22825 11097 22826 11099 22826 11098 22826 11101 22827 11096 22827 11098 22827 11102 22828 11103 22828 11100 22828 11101 22829 11100 22829 11103 22829 11099 22830 11102 22830 11100 22830 11104 22831 11105 22831 11103 22831 11106 22832 11103 22832 11105 22832 11102 22833 11104 22833 11103 22833 11106 22834 11101 22834 11103 22834 11107 22835 11108 22835 11105 22835 11106 22836 11105 22836 11108 22836 11104 22837 11107 22837 11105 22837 11109 22838 11110 22838 11108 22838 11111 22839 11108 22839 11110 22839 11107 22840 11109 22840 11108 22840 11111 22841 11106 22841 11108 22841 11112 22842 11113 22842 11110 22842 11114 22843 11110 22843 11113 22843 11109 22844 11112 22844 11110 22844 11114 22845 11111 22845 11110 22845 11115 22846 11116 22846 11113 22846 11114 22847 11113 22847 11116 22847 11112 22848 11115 22848 11113 22848 11117 22849 11118 22849 11116 22849 11119 22850 11116 22850 11118 22850 11120 22851 11117 22851 11116 22851 11115 22852 11120 22852 11116 22852 11119 22853 11114 22853 11116 22853 11121 22854 11122 22854 11118 22854 11123 22855 11118 22855 11122 22855 11117 22856 11121 22856 11118 22856 11123 22857 11119 22857 11118 22857 11124 22858 11125 22858 11122 22858 11123 22859 11122 22859 11125 22859 11121 22860 11124 22860 11122 22860 11126 22861 11127 22861 11125 22861 11128 22862 11125 22862 11127 22862 11124 22863 11126 22863 11125 22863 11128 22864 11123 22864 11125 22864 11129 22865 11130 22865 11127 22865 11128 22866 11127 22866 11130 22866 11126 22867 11129 22867 11127 22867 11131 22868 11132 22868 11130 22868 11133 22869 11130 22869 11132 22869 11129 22870 11131 22870 11130 22870 11133 22871 11128 22871 11130 22871 11134 22872 11135 22872 11132 22872 11136 22873 11132 22873 11135 22873 11131 22874 11134 22874 11132 22874 11136 22875 11133 22875 11132 22875 11137 22876 11138 22876 11135 22876 11136 22877 11135 22877 11138 22877 11134 22878 11137 22878 11135 22878 11137 22879 11139 22879 11138 22879 11140 22880 11138 22880 11139 22880 11140 22881 11136 22881 11138 22881 11137 22882 11141 22882 11139 22882 11142 22883 11139 22883 11141 22883 11142 22884 11140 22884 11139 22884 11143 22885 11144 22885 11141 22885 11145 22886 11141 22886 11144 22886 11146 22887 11143 22887 11141 22887 11137 22888 11146 22888 11141 22888 11145 22889 11142 22889 11141 22889 11147 22890 11148 22890 11144 22890 11149 22891 11144 22891 11148 22891 11143 22892 11147 22892 11144 22892 11149 22893 11145 22893 11144 22893 11150 22894 11151 22894 11148 22894 11152 22895 11148 22895 11151 22895 11147 22896 11150 22896 11148 22896 11153 22897 11149 22897 11148 22897 11152 22898 11153 22898 11148 22898 11154 22899 11155 22899 11151 22899 11152 22900 11151 22900 11155 22900 11150 22901 11154 22901 11151 22901 11156 22902 11157 22902 11155 22902 11158 22903 11155 22903 11157 22903 11154 22904 11156 22904 11155 22904 11158 22905 11152 22905 11155 22905 11159 22906 11160 22906 11157 22906 11161 22907 11157 22907 11160 22907 11156 22908 11159 22908 11157 22908 11161 22909 11158 22909 11157 22909 11162 22910 11163 22910 11160 22910 11161 22911 11160 22911 11163 22911 11159 22912 11162 22912 11160 22912 11164 22913 11165 22913 11163 22913 11166 22914 11163 22914 11165 22914 11167 22915 11164 22915 11163 22915 11162 22916 11167 22916 11163 22916 11166 22917 11161 22917 11163 22917 11168 22918 11169 22918 11165 22918 11170 22919 11165 22919 11169 22919 11164 22920 11168 22920 11165 22920 11170 22921 11166 22921 11165 22921 11171 22922 11172 22922 11169 22922 11170 22923 11169 22923 11172 22923 11168 22924 11171 22924 11169 22924 11173 22925 11174 22925 11172 22925 11175 22926 11172 22926 11174 22926 11176 22927 11173 22927 11172 22927 11171 22928 11176 22928 11172 22928 11175 22929 11170 22929 11172 22929 11177 22930 11178 22930 11174 22930 11175 22931 11174 22931 11178 22931 11173 22932 11177 22932 11174 22932 11179 22933 11180 22933 11178 22933 11181 22934 11178 22934 11180 22934 11177 22935 11179 22935 11178 22935 11181 22936 11175 22936 11178 22936 11182 22937 11183 22937 11180 22937 11181 22938 11180 22938 11183 22938 11179 22939 11182 22939 11180 22939 11184 22940 11185 22940 11183 22940 11186 22941 11183 22941 11185 22941 11182 22942 11184 22942 11183 22942 11186 22943 11181 22943 11183 22943 11187 22944 11188 22944 11185 22944 11186 22945 11185 22945 11188 22945 11184 22946 11187 22946 11185 22946 11189 22947 11190 22947 11188 22947 11191 22948 11188 22948 11190 22948 11187 22949 11189 22949 11188 22949 11191 22950 11186 22950 11188 22950 11192 22951 11193 22951 11190 22951 11191 22952 11190 22952 11193 22952 11189 22953 11192 22953 11190 22953 11194 22954 11195 22954 11193 22954 11196 22955 11193 22955 11195 22955 11192 22956 11194 22956 11193 22956 11196 22957 11191 22957 11193 22957 11197 22958 11198 22958 11195 22958 11196 22959 11195 22959 11198 22959 11194 22960 11197 22960 11195 22960 11199 22961 11200 22961 11198 22961 11201 22962 11198 22962 11200 22962 11197 22963 11199 22963 11198 22963 11201 22964 11196 22964 11198 22964 11202 22965 11203 22965 11200 22965 11201 22966 11200 22966 11203 22966 11204 22967 11202 22967 11200 22967 11199 22968 11204 22968 11200 22968 11205 22969 11206 22969 11203 22969 11207 22970 11203 22970 11206 22970 11202 22971 11205 22971 11203 22971 11207 22972 11201 22972 11203 22972 11208 22973 11069 22973 11206 22973 11070 22974 11206 22974 11069 22974 11205 22975 11208 22975 11206 22975 11070 22976 11207 22976 11206 22976 11208 22977 11068 22977 11069 22977 11209 22978 11068 22978 11208 22978 11209 22979 10823 22979 11068 22979 11209 22980 11208 22980 11205 22980 11210 22981 11205 22981 11202 22981 11210 22982 11209 22982 11205 22982 11210 22983 11202 22983 11204 22983 11211 22984 11204 22984 11199 22984 11211 22985 11210 22985 11204 22985 11211 22986 11199 22986 11197 22986 11211 22987 11197 22987 11194 22987 11212 22988 11194 22988 11192 22988 11212 22989 11211 22989 11194 22989 11212 22990 11192 22990 11189 22990 11213 22991 11189 22991 11187 22991 11213 22992 11212 22992 11189 22992 11214 22993 11187 22993 11184 22993 11214 22994 11213 22994 11187 22994 11214 22995 11184 22995 11182 22995 11214 22996 11182 22996 11179 22996 11215 22997 11179 22997 11177 22997 11215 22998 11214 22998 11179 22998 11215 22999 11177 22999 11173 22999 11216 23000 11173 23000 11176 23000 11216 23001 11215 23001 11173 23001 11216 23002 11176 23002 11171 23002 11216 23003 11171 23003 11168 23003 11217 23004 11168 23004 11164 23004 11217 23005 11216 23005 11168 23005 11217 23006 11164 23006 11167 23006 11218 23007 11167 23007 11162 23007 11218 23008 11217 23008 11167 23008 11219 23009 11162 23009 11159 23009 11219 23010 11218 23010 11162 23010 11219 23011 11159 23011 11156 23011 11220 23012 11156 23012 11154 23012 11220 23013 11219 23013 11156 23013 11221 23014 11154 23014 11150 23014 11221 23015 11220 23015 11154 23015 11222 23016 11150 23016 11147 23016 11222 23017 11221 23017 11150 23017 11223 23018 11147 23018 11143 23018 11223 23019 11222 23019 11147 23019 11224 23020 11143 23020 11146 23020 11224 23021 11223 23021 11143 23021 11225 23022 11146 23022 11137 23022 11225 23023 11224 23023 11146 23023 11226 23024 11137 23024 11134 23024 11226 23025 11225 23025 11137 23025 11227 23026 11134 23026 11131 23026 11227 23027 11226 23027 11134 23027 11228 23028 11131 23028 11129 23028 11228 23029 11227 23029 11131 23029 11228 23030 11129 23030 11126 23030 11229 23031 11126 23031 11124 23031 11229 23032 11228 23032 11126 23032 11230 23033 11124 23033 11121 23033 11230 23034 11229 23034 11124 23034 11230 23035 11121 23035 11117 23035 11231 23036 11117 23036 11120 23036 11231 23037 11230 23037 11117 23037 11231 23038 11120 23038 11115 23038 11232 23039 11115 23039 11112 23039 11232 23040 11231 23040 11115 23040 11232 23041 11112 23041 11109 23041 11233 23042 11109 23042 11107 23042 11233 23043 11232 23043 11109 23043 11234 23044 11107 23044 11104 23044 11234 23045 11233 23045 11107 23045 11234 23046 11104 23046 11102 23046 11235 23047 11102 23047 11099 23047 11235 23048 11234 23048 11102 23048 11235 23049 11099 23049 11097 23049 11236 23050 11097 23050 11094 23050 11236 23051 11235 23051 11097 23051 11237 23052 11094 23052 11091 23052 11237 23053 11236 23053 11094 23053 11237 23054 11091 23054 11088 23054 11238 23055 11088 23055 11086 23055 11238 23056 11237 23056 11088 23056 11238 23057 11086 23057 11081 23057 11239 23058 11081 23058 11077 23058 11239 23059 11238 23059 11081 23059 11240 23060 11077 23060 11071 23060 11241 23061 11239 23061 11077 23061 11240 23062 11241 23062 11077 23062 11242 23063 11071 23063 11075 23063 11242 23064 11240 23064 11071 23064 11243 23065 11075 23065 11076 23065 11030 23066 11075 23066 11243 23066 11244 23067 11075 23067 11030 23067 11242 23068 11075 23068 11244 23068 11245 23069 11243 23069 11076 23069 10942 23070 11245 23070 11076 23070 10942 23071 11076 23071 10940 23071 11246 23072 10940 23072 11076 23072 11247 23073 11246 23073 11076 23073 11248 23074 11249 23074 11250 23074 11074 23075 11247 23075 11076 23075 11251 23076 11243 23076 11245 23076 11030 23077 11243 23077 11251 23077 11252 23078 11253 23078 11254 23078 10944 23079 11254 23079 11253 23079 11255 23080 11252 23080 11254 23080 11256 23081 11255 23081 11254 23081 10945 23082 11256 23082 11254 23082 10945 23083 11254 23083 10944 23083 11251 23084 11245 23084 11253 23084 10943 23085 11253 23085 11245 23085 11252 23086 11251 23086 11253 23086 10943 23087 10944 23087 11253 23087 10943 23088 11245 23088 10942 23088 11027 23089 11251 23089 11252 23089 11030 23090 11251 23090 11027 23090 11025 23091 11252 23091 11255 23091 11027 23092 11252 23092 11025 23092 11257 23093 11255 23093 11256 23093 11023 23094 11255 23094 11257 23094 11025 23095 11255 23095 11023 23095 11258 23096 11259 23096 10843 23096 10844 23097 10843 23097 11259 23097 10842 23098 11258 23098 10843 23098 11260 23099 11261 23099 11259 23099 10840 23100 11259 23100 11261 23100 11258 23101 11260 23101 11259 23101 10848 23102 11259 23102 10847 23102 10840 23103 10847 23103 11259 23103 10849 23104 11259 23104 10848 23104 10850 23105 11259 23105 10849 23105 10844 23106 11259 23106 10850 23106 11262 23107 11263 23107 11261 23107 10953 23108 11261 23108 11263 23108 11260 23109 11262 23109 11261 23109 10840 23110 11261 23110 10953 23110 11264 23111 11265 23111 11263 23111 10952 23112 11263 23112 11265 23112 11262 23113 11264 23113 11263 23113 10953 23114 11263 23114 10952 23114 11264 23115 11266 23115 11265 23115 10952 23116 11265 23116 11266 23116 11267 23117 11268 23117 11266 23117 10951 23118 11266 23118 11268 23118 11264 23119 11267 23119 11266 23119 10952 23120 11266 23120 10951 23120 11269 23121 11270 23121 11268 23121 10950 23122 11268 23122 11270 23122 11267 23123 11269 23123 11268 23123 10951 23124 11268 23124 10950 23124 11271 23125 11272 23125 11270 23125 10950 23126 11270 23126 11272 23126 11269 23127 11271 23127 11270 23127 11271 23128 11273 23128 11272 23128 10949 23129 11272 23129 11273 23129 10950 23130 11272 23130 10949 23130 11274 23131 11275 23131 11273 23131 10949 23132 11273 23132 11275 23132 11271 23133 11274 23133 11273 23133 11276 23134 11277 23134 11275 23134 10948 23135 11275 23135 11277 23135 11274 23136 11276 23136 11275 23136 10949 23137 11275 23137 10948 23137 11276 23138 11278 23138 11277 23138 10948 23139 11277 23139 11278 23139 11279 23140 11280 23140 11278 23140 10947 23141 11278 23141 11280 23141 11276 23142 11279 23142 11278 23142 10948 23143 11278 23143 10947 23143 11281 23144 11282 23144 11280 23144 10947 23145 11280 23145 11282 23145 11279 23146 11281 23146 11280 23146 11283 23147 11284 23147 11282 23147 10947 23148 11282 23148 11284 23148 11281 23149 11283 23149 11282 23149 11283 23150 11285 23150 11284 23150 10946 23151 11284 23151 11285 23151 10947 23152 11284 23152 10946 23152 11286 23153 11287 23153 11285 23153 10946 23154 11285 23154 11287 23154 11283 23155 11286 23155 11285 23155 11288 23156 11289 23156 11287 23156 10945 23157 11287 23157 11289 23157 11286 23158 11288 23158 11287 23158 10946 23159 11287 23159 10945 23159 11257 23160 11256 23160 11289 23160 10945 23161 11289 23161 11256 23161 11288 23162 11257 23162 11289 23162 11018 23163 11257 23163 11288 23163 11018 23164 11023 23164 11257 23164 11018 23165 11288 23165 11286 23165 11012 23166 11286 23166 11283 23166 11012 23167 11018 23167 11286 23167 11012 23168 11283 23168 11281 23168 11010 23169 11281 23169 11279 23169 11010 23170 11012 23170 11281 23170 11010 23171 11279 23171 11276 23171 11005 23172 11276 23172 11274 23172 11005 23173 11010 23173 11276 23173 11000 23174 11274 23174 11271 23174 11000 23175 11005 23175 11274 23175 11000 23176 11271 23176 11269 23176 10996 23177 11269 23177 11267 23177 10996 23178 11000 23178 11269 23178 10992 23179 11267 23179 11264 23179 10992 23180 10996 23180 11267 23180 10986 23181 11264 23181 11262 23181 10986 23182 10992 23182 11264 23182 10978 23183 11262 23183 11260 23183 10978 23184 10986 23184 11262 23184 10967 23185 11260 23185 11258 23185 10967 23186 10978 23186 11260 23186 10962 23187 11258 23187 10842 23187 10967 23188 11258 23188 10962 23188 10960 23189 10842 23189 10841 23189 10961 23190 10842 23190 10960 23190 10962 23191 10842 23191 10961 23191 10964 23192 10962 23192 10963 23192 10958 23193 10962 23193 10964 23193 10840 23194 10833 23194 10845 23194 10840 23195 10845 23195 10846 23195 10840 23196 10846 23196 10847 23196 11290 23197 10812 23197 10811 23197 11291 23198 10810 23198 10812 23198 11292 23199 11291 23199 10812 23199 11293 23200 11292 23200 10812 23200 11294 23201 11293 23201 10812 23201 11295 23202 11294 23202 10812 23202 11296 23203 11295 23203 10812 23203 11296 23204 10812 23204 11290 23204 11297 23205 10811 23205 10818 23205 11298 23206 11299 23206 10811 23206 11300 23207 10811 23207 11299 23207 11301 23208 11298 23208 10811 23208 11302 23209 11301 23209 10811 23209 11297 23210 11302 23210 10811 23210 11303 23211 11290 23211 10811 23211 11304 23212 11303 23212 10811 23212 11305 23213 11304 23213 10811 23213 11306 23214 11305 23214 10811 23214 11307 23215 11306 23215 10811 23215 11308 23216 11307 23216 10811 23216 11300 23217 11308 23217 10811 23217 10808 23218 10810 23218 11291 23218 11309 23219 11291 23219 11292 23219 11309 23220 10808 23220 11291 23220 11310 23221 11292 23221 11293 23221 11309 23222 11292 23222 11310 23222 11310 23223 11293 23223 11294 23223 11295 23224 11311 23224 11294 23224 11312 23225 11294 23225 11311 23225 11310 23226 11294 23226 11312 23226 11295 23227 11313 23227 11311 23227 11312 23228 11311 23228 11313 23228 11314 23229 11315 23229 11313 23229 11316 23230 11313 23230 11315 23230 11295 23231 11314 23231 11313 23231 11312 23232 11313 23232 11316 23232 11314 23233 11317 23233 11315 23233 11316 23234 11315 23234 11317 23234 11314 23235 11318 23235 11317 23235 11319 23236 11317 23236 11318 23236 11316 23237 11317 23237 11319 23237 11314 23238 11320 23238 11318 23238 11319 23239 11318 23239 11320 23239 11314 23240 11321 23240 11320 23240 11319 23241 11320 23241 11321 23241 11322 23242 11323 23242 11321 23242 11324 23243 11321 23243 11323 23243 11314 23244 11322 23244 11321 23244 11319 23245 11321 23245 11324 23245 11322 23246 11325 23246 11323 23246 11324 23247 11323 23247 11325 23247 11322 23248 11326 23248 11325 23248 11327 23249 11325 23249 11326 23249 11324 23250 11325 23250 11327 23250 11322 23251 11328 23251 11326 23251 11329 23252 11326 23252 11328 23252 11327 23253 11326 23253 11329 23253 11330 23254 11331 23254 11328 23254 11329 23255 11328 23255 11331 23255 11322 23256 11330 23256 11328 23256 11330 23257 11332 23257 11331 23257 11333 23258 11331 23258 11332 23258 11329 23259 11331 23259 11333 23259 11330 23260 11334 23260 11332 23260 11335 23261 11332 23261 11334 23261 11333 23262 11332 23262 11335 23262 11336 23263 11337 23263 11334 23263 11338 23264 11334 23264 11337 23264 11330 23265 11336 23265 11334 23265 11335 23266 11334 23266 11338 23266 11336 23267 11339 23267 11337 23267 11340 23268 11337 23268 11339 23268 11338 23269 11337 23269 11340 23269 11341 23270 11342 23270 11339 23270 11343 23271 11339 23271 11342 23271 11336 23272 11341 23272 11339 23272 11340 23273 11339 23273 11343 23273 11341 23274 11344 23274 11342 23274 11345 23275 11342 23275 11344 23275 11343 23276 11342 23276 11345 23276 11346 23277 11347 23277 11344 23277 11348 23278 11344 23278 11347 23278 11341 23279 11346 23279 11344 23279 11345 23280 11344 23280 11348 23280 11349 23281 11350 23281 11347 23281 11351 23282 11347 23282 11350 23282 11346 23283 11349 23283 11347 23283 11348 23284 11347 23284 11351 23284 11352 23285 11353 23285 11350 23285 11354 23286 11350 23286 11353 23286 11349 23287 11352 23287 11350 23287 11351 23288 11350 23288 11354 23288 11355 23289 11356 23289 11353 23289 11357 23290 11353 23290 11356 23290 11352 23291 11355 23291 11353 23291 11358 23292 11353 23292 11357 23292 11354 23293 11353 23293 11358 23293 11359 23294 11360 23294 11356 23294 11361 23295 11356 23295 11360 23295 11362 23296 11359 23296 11356 23296 11355 23297 11362 23297 11356 23297 11363 23298 11356 23298 11361 23298 11357 23299 11356 23299 11363 23299 11364 23300 11365 23300 11360 23300 11366 23301 11360 23301 11365 23301 11367 23302 11364 23302 11360 23302 11359 23303 11367 23303 11360 23303 11361 23304 11360 23304 11366 23304 11368 23305 11369 23305 11365 23305 11370 23306 11365 23306 11369 23306 11371 23307 11368 23307 11365 23307 11372 23308 11371 23308 11365 23308 11364 23309 11372 23309 11365 23309 11373 23310 11365 23310 11370 23310 11366 23311 11365 23311 11373 23311 11374 23312 11375 23312 11369 23312 11376 23313 11369 23313 11375 23313 11377 23314 11374 23314 11369 23314 11378 23315 11377 23315 11369 23315 11379 23316 11378 23316 11369 23316 11368 23317 11379 23317 11369 23317 11380 23318 11369 23318 11376 23318 11381 23319 11369 23319 11380 23319 11370 23320 11369 23320 11381 23320 11382 23321 11383 23321 11375 23321 11384 23322 11375 23322 11383 23322 11385 23323 11382 23323 11375 23323 11386 23324 11385 23324 11375 23324 11387 23325 11386 23325 11375 23325 11374 23326 11387 23326 11375 23326 11388 23327 11375 23327 11384 23327 11376 23328 11375 23328 11388 23328 11389 23329 11390 23329 11383 23329 11391 23330 11383 23330 11390 23330 11392 23331 11389 23331 11383 23331 11393 23332 11392 23332 11383 23332 11394 23333 11393 23333 11383 23333 11395 23334 11394 23334 11383 23334 11396 23335 11395 23335 11383 23335 11397 23336 11396 23336 11383 23336 11398 23337 11397 23337 11383 23337 11382 23338 11398 23338 11383 23338 11399 23339 11383 23339 11391 23339 11400 23340 11383 23340 11399 23340 11384 23341 11383 23341 11400 23341 11401 23342 11390 23342 11389 23342 11402 23343 11390 23343 11401 23343 11403 23344 11390 23344 11402 23344 11391 23345 11390 23345 11403 23345 11401 23346 11389 23346 11392 23346 11404 23347 11392 23347 11393 23347 11404 23348 11401 23348 11392 23348 11405 23349 11393 23349 11394 23349 11405 23350 11404 23350 11393 23350 11405 23351 11394 23351 11395 23351 11406 23352 11395 23352 11396 23352 11405 23353 11395 23353 11406 23353 11406 23354 11396 23354 11397 23354 11406 23355 11397 23355 11398 23355 11407 23356 11398 23356 11382 23356 11407 23357 11406 23357 11398 23357 11407 23358 11382 23358 11385 23358 11407 23359 11385 23359 11386 23359 11407 23360 11386 23360 11387 23360 11408 23361 11387 23361 11374 23361 11408 23362 11407 23362 11387 23362 11408 23363 11374 23363 11377 23363 11408 23364 11377 23364 11378 23364 11408 23365 11378 23365 11379 23365 11409 23366 11379 23366 11368 23366 11409 23367 11408 23367 11379 23367 11409 23368 11368 23368 11371 23368 11409 23369 11371 23369 11372 23369 11410 23370 11372 23370 11364 23370 11410 23371 11409 23371 11372 23371 11410 23372 11364 23372 11367 23372 11410 23373 11367 23373 11359 23373 11411 23374 11359 23374 11362 23374 11411 23375 11410 23375 11359 23375 11411 23376 11362 23376 11355 23376 11412 23377 11355 23377 11352 23377 11412 23378 11411 23378 11355 23378 11412 23379 11352 23379 11349 23379 11413 23380 11349 23380 11346 23380 11413 23381 11412 23381 11349 23381 11414 23382 11346 23382 11341 23382 11414 23383 11413 23383 11346 23383 11415 23384 11341 23384 11336 23384 11415 23385 11414 23385 11341 23385 11415 23386 11336 23386 11330 23386 11416 23387 11330 23387 11322 23387 11416 23388 11415 23388 11330 23388 11417 23389 11322 23389 11314 23389 11417 23390 11416 23390 11322 23390 11296 23391 11314 23391 11295 23391 11296 23392 11417 23392 11314 23392 11418 23393 11419 23393 11420 23393 11421 23394 11420 23394 11419 23394 11422 23395 11418 23395 11420 23395 11423 23396 11422 23396 11420 23396 11424 23397 11423 23397 11420 23397 11421 23398 11424 23398 11420 23398 11418 23399 11425 23399 11419 23399 11426 23400 11419 23400 11425 23400 11427 23401 11421 23401 11419 23401 11426 23402 11427 23402 11419 23402 11418 23403 11428 23403 11425 23403 11429 23404 11425 23404 11428 23404 11429 23405 11426 23405 11425 23405 11418 23406 11430 23406 11428 23406 11429 23407 11428 23407 11430 23407 11431 23408 11430 23408 11418 23408 11432 23409 11429 23409 11430 23409 11433 23410 11432 23410 11430 23410 11431 23411 11433 23411 11430 23411 11434 23412 11418 23412 11422 23412 11434 23413 11431 23413 11418 23413 11423 23414 11435 23414 11422 23414 11434 23415 11422 23415 11435 23415 11436 23416 11437 23416 11435 23416 11438 23417 11435 23417 11437 23417 11423 23418 11436 23418 11435 23418 11438 23419 11434 23419 11435 23419 11439 23420 11440 23420 11437 23420 11441 23421 11437 23421 11440 23421 11436 23422 11439 23422 11437 23422 11441 23423 11438 23423 11437 23423 11442 23424 11443 23424 11440 23424 11444 23425 11440 23425 11443 23425 11445 23426 11442 23426 11440 23426 11439 23427 11445 23427 11440 23427 11444 23428 11441 23428 11440 23428 11446 23429 11447 23429 11443 23429 11448 23430 11443 23430 11447 23430 11442 23431 11446 23431 11443 23431 11448 23432 11444 23432 11443 23432 11449 23433 11450 23433 11447 23433 11451 23434 11447 23434 11450 23434 11446 23435 11449 23435 11447 23435 11451 23436 11448 23436 11447 23436 11452 23437 11453 23437 11450 23437 11454 23438 11450 23438 11453 23438 11449 23439 11452 23439 11450 23439 11454 23440 11451 23440 11450 23440 11455 23441 11456 23441 11453 23441 11457 23442 11453 23442 11456 23442 11458 23443 11455 23443 11453 23443 11452 23444 11458 23444 11453 23444 11457 23445 11454 23445 11453 23445 11459 23446 11460 23446 11456 23446 11461 23447 11456 23447 11460 23447 11455 23448 11459 23448 11456 23448 11461 23449 11457 23449 11456 23449 11462 23450 11463 23450 11460 23450 11464 23451 11460 23451 11463 23451 11459 23452 11462 23452 11460 23452 11464 23453 11461 23453 11460 23453 11462 23454 11465 23454 11463 23454 11466 23455 11463 23455 11465 23455 11466 23456 11464 23456 11463 23456 11467 23457 11468 23457 11465 23457 11466 23458 11465 23458 11468 23458 11462 23459 11467 23459 11465 23459 11469 23460 11470 23460 11468 23460 11471 23461 11468 23461 11470 23461 11472 23462 11469 23462 11468 23462 11467 23463 11472 23463 11468 23463 11471 23464 11466 23464 11468 23464 11473 23465 11474 23465 11470 23465 11475 23466 11470 23466 11474 23466 11469 23467 11473 23467 11470 23467 11476 23468 11471 23468 11470 23468 11477 23469 11476 23469 11470 23469 11475 23470 11477 23470 11470 23470 11478 23471 11479 23471 11474 23471 11480 23472 11474 23472 11479 23472 11473 23473 11478 23473 11474 23473 11481 23474 11475 23474 11474 23474 11480 23475 11481 23475 11474 23475 11482 23476 11483 23476 11479 23476 11484 23477 11479 23477 11483 23477 11478 23478 11482 23478 11479 23478 11485 23479 11480 23479 11479 23479 11484 23480 11485 23480 11479 23480 11486 23481 11487 23481 11483 23481 11488 23482 11483 23482 11487 23482 11482 23483 11486 23483 11483 23483 11488 23484 11484 23484 11483 23484 11489 23485 11490 23485 11487 23485 11491 23486 11487 23486 11490 23486 11486 23487 11489 23487 11487 23487 11492 23488 11488 23488 11487 23488 11491 23489 11492 23489 11487 23489 11489 23490 11493 23490 11490 23490 11494 23491 11490 23491 11493 23491 11494 23492 11491 23492 11490 23492 11489 23493 11495 23493 11493 23493 11494 23494 11493 23494 11495 23494 11496 23495 11497 23495 11495 23495 11498 23496 11495 23496 11497 23496 11489 23497 11496 23497 11495 23497 11498 23498 11494 23498 11495 23498 11496 23499 11499 23499 11497 23499 11500 23500 11497 23500 11499 23500 11500 23501 11498 23501 11497 23501 11496 23502 11501 23502 11499 23502 11500 23503 11499 23503 11501 23503 11502 23504 11503 23504 11501 23504 11504 23505 11501 23505 11503 23505 11496 23506 11502 23506 11501 23506 11504 23507 11500 23507 11501 23507 11502 23508 11505 23508 11503 23508 11504 23509 11503 23509 11505 23509 11502 23510 11506 23510 11505 23510 11507 23511 11505 23511 11506 23511 11507 23512 11504 23512 11505 23512 11502 23513 11508 23513 11506 23513 11509 23514 11506 23514 11508 23514 11509 23515 11507 23515 11506 23515 11510 23516 11511 23516 11508 23516 11512 23517 11508 23517 11511 23517 11502 23518 11510 23518 11508 23518 11512 23519 11509 23519 11508 23519 11510 23520 11513 23520 11511 23520 11512 23521 11511 23521 11513 23521 11510 23522 11514 23522 11513 23522 11515 23523 11513 23523 11514 23523 11515 23524 11512 23524 11513 23524 11516 23525 11517 23525 11514 23525 11515 23526 11514 23526 11517 23526 11510 23527 11516 23527 11514 23527 11516 23528 11518 23528 11517 23528 11519 23529 11517 23529 11518 23529 11519 23530 11515 23530 11517 23530 11516 23531 11520 23531 11518 23531 11521 23532 11518 23532 11520 23532 11521 23533 11519 23533 11518 23533 10818 23534 11522 23534 11520 23534 11523 23535 11520 23535 11522 23535 11516 23536 10818 23536 11520 23536 11523 23537 11521 23537 11520 23537 10818 23538 10798 23538 11522 23538 11523 23539 11522 23539 10798 23539 11523 23540 10798 23540 10800 23540 11524 23541 10818 23541 11516 23541 11525 23542 11297 23542 10818 23542 11526 23543 11525 23543 10818 23543 11527 23544 11526 23544 10818 23544 11528 23545 11527 23545 10818 23545 11524 23546 11528 23546 10818 23546 11528 23547 11516 23547 11510 23547 11524 23548 11516 23548 11528 23548 11529 23549 11510 23549 11502 23549 11529 23550 11528 23550 11510 23550 11530 23551 11502 23551 11496 23551 11530 23552 11529 23552 11502 23552 11531 23553 11496 23553 11489 23553 11531 23554 11530 23554 11496 23554 11532 23555 11489 23555 11486 23555 11532 23556 11531 23556 11489 23556 11533 23557 11486 23557 11482 23557 11533 23558 11532 23558 11486 23558 11534 23559 11482 23559 11478 23559 11534 23560 11533 23560 11482 23560 11534 23561 11478 23561 11473 23561 11535 23562 11473 23562 11469 23562 11535 23563 11534 23563 11473 23563 11535 23564 11469 23564 11472 23564 11536 23565 11472 23565 11467 23565 11536 23566 11535 23566 11472 23566 11536 23567 11467 23567 11462 23567 11537 23568 11462 23568 11459 23568 11537 23569 11536 23569 11462 23569 11537 23570 11459 23570 11455 23570 11538 23571 11455 23571 11458 23571 11538 23572 11537 23572 11455 23572 11538 23573 11458 23573 11452 23573 11538 23574 11452 23574 11449 23574 11538 23575 11449 23575 11446 23575 11539 23576 11446 23576 11442 23576 11539 23577 11538 23577 11446 23577 11539 23578 11442 23578 11445 23578 11539 23579 11445 23579 11439 23579 11424 23580 11439 23580 11436 23580 11424 23581 11539 23581 11439 23581 11424 23582 11436 23582 11423 23582 10802 23583 10801 23583 10804 23583 10807 23584 10804 23584 10803 23584 11540 23585 10804 23585 10807 23585 10802 23586 10804 23586 11540 23586 10807 23587 10803 23587 10806 23587 11541 23588 11540 23588 10807 23588 11542 23589 11541 23589 10807 23589 11542 23590 10807 23590 10805 23590 11543 23591 11540 23591 11541 23591 10802 23592 11540 23592 11543 23592 11544 23593 11545 23593 11546 23593 11547 23594 11546 23594 11545 23594 11548 23595 11544 23595 11546 23595 11549 23596 11548 23596 11546 23596 11547 23597 11549 23597 11546 23597 11544 23598 11550 23598 11545 23598 11551 23599 11545 23599 11550 23599 11551 23600 11547 23600 11545 23600 11552 23601 11553 23601 11550 23601 11551 23602 11550 23602 11553 23602 11544 23603 11552 23603 11550 23603 11554 23604 11555 23604 11553 23604 11556 23605 11553 23605 11555 23605 11552 23606 11554 23606 11553 23606 11556 23607 11551 23607 11553 23607 11557 23608 11558 23608 11555 23608 11556 23609 11555 23609 11558 23609 11554 23610 11557 23610 11555 23610 11559 23611 11560 23611 11558 23611 11561 23612 11558 23612 11560 23612 11557 23613 11559 23613 11558 23613 11561 23614 11556 23614 11558 23614 11562 23615 11563 23615 11560 23615 11564 23616 11560 23616 11563 23616 11559 23617 11562 23617 11560 23617 11564 23618 11561 23618 11560 23618 11565 23619 11566 23619 11563 23619 11567 23620 11563 23620 11566 23620 11562 23621 11565 23621 11563 23621 11567 23622 11564 23622 11563 23622 11568 23623 11569 23623 11566 23623 11567 23624 11566 23624 11569 23624 11565 23625 11568 23625 11566 23625 11570 23626 11571 23626 11569 23626 11572 23627 11569 23627 11571 23627 11568 23628 11570 23628 11569 23628 11572 23629 11567 23629 11569 23629 11573 23630 11574 23630 11571 23630 11572 23631 11571 23631 11574 23631 11570 23632 11573 23632 11571 23632 11575 23633 11576 23633 11574 23633 11577 23634 11574 23634 11576 23634 11573 23635 11575 23635 11574 23635 11577 23636 11572 23636 11574 23636 11578 23637 11579 23637 11576 23637 11580 23638 11576 23638 11579 23638 11575 23639 11578 23639 11576 23639 11580 23640 11577 23640 11576 23640 11581 23641 11582 23641 11579 23641 11580 23642 11579 23642 11582 23642 11578 23643 11581 23643 11579 23643 11583 23644 11584 23644 11582 23644 11585 23645 11582 23645 11584 23645 11581 23646 11583 23646 11582 23646 11585 23647 11580 23647 11582 23647 11586 23648 11587 23648 11584 23648 11585 23649 11584 23649 11587 23649 11583 23650 11586 23650 11584 23650 11588 23651 11589 23651 11587 23651 11590 23652 11587 23652 11589 23652 11586 23653 11588 23653 11587 23653 11590 23654 11585 23654 11587 23654 11591 23655 11592 23655 11589 23655 11593 23656 11589 23656 11592 23656 11588 23657 11591 23657 11589 23657 11593 23658 11590 23658 11589 23658 11594 23659 11595 23659 11592 23659 11593 23660 11592 23660 11595 23660 11591 23661 11594 23661 11592 23661 11596 23662 11597 23662 11595 23662 11598 23663 11595 23663 11597 23663 11594 23664 11596 23664 11595 23664 11598 23665 11593 23665 11595 23665 11599 23666 11600 23666 11597 23666 11601 23667 11597 23667 11600 23667 11596 23668 11599 23668 11597 23668 11601 23669 11598 23669 11597 23669 11602 23670 11603 23670 11600 23670 11601 23671 11600 23671 11603 23671 11599 23672 11602 23672 11600 23672 11604 23673 11605 23673 11603 23673 11606 23674 11603 23674 11605 23674 11602 23675 11604 23675 11603 23675 11606 23676 11601 23676 11603 23676 11607 23677 11608 23677 11605 23677 11606 23678 11605 23678 11608 23678 11604 23679 11607 23679 11605 23679 11607 23680 11609 23680 11608 23680 11610 23681 11608 23681 11609 23681 11610 23682 11606 23682 11608 23682 11611 23683 11612 23683 11609 23683 11610 23684 11609 23684 11612 23684 11607 23685 11611 23685 11609 23685 11613 23686 11614 23686 11612 23686 11615 23687 11612 23687 11614 23687 11616 23688 11613 23688 11612 23688 11611 23689 11616 23689 11612 23689 11615 23690 11610 23690 11612 23690 11617 23691 11618 23691 11614 23691 11619 23692 11614 23692 11618 23692 11620 23693 11617 23693 11614 23693 11613 23694 11620 23694 11614 23694 11621 23695 11615 23695 11614 23695 11619 23696 11621 23696 11614 23696 11622 23697 11623 23697 11618 23697 11624 23698 11618 23698 11623 23698 11617 23699 11622 23699 11618 23699 11624 23700 11619 23700 11618 23700 11625 23701 11626 23701 11623 23701 11627 23702 11623 23702 11626 23702 11622 23703 11625 23703 11623 23703 11628 23704 11624 23704 11623 23704 11627 23705 11628 23705 11623 23705 11629 23706 11630 23706 11626 23706 11631 23707 11626 23707 11630 23707 11625 23708 11629 23708 11626 23708 11631 23709 11627 23709 11626 23709 11632 23710 11633 23710 11630 23710 11634 23711 11630 23711 11633 23711 11629 23712 11632 23712 11630 23712 11634 23713 11631 23713 11630 23713 11635 23714 11636 23714 11633 23714 11637 23715 11633 23715 11636 23715 11632 23716 11635 23716 11633 23716 11637 23717 11634 23717 11633 23717 11638 23718 11639 23718 11636 23718 11637 23719 11636 23719 11639 23719 11635 23720 11638 23720 11636 23720 11640 23721 11641 23721 11639 23721 11642 23722 11639 23722 11641 23722 11638 23723 11640 23723 11639 23723 11642 23724 11637 23724 11639 23724 11643 23725 11644 23725 11641 23725 11645 23726 11641 23726 11644 23726 11646 23727 11643 23727 11641 23727 11640 23728 11646 23728 11641 23728 11645 23729 11642 23729 11641 23729 11647 23730 11648 23730 11644 23730 11645 23731 11644 23731 11648 23731 11643 23732 11647 23732 11644 23732 11649 23733 11650 23733 11648 23733 11651 23734 11648 23734 11650 23734 11647 23735 11649 23735 11648 23735 11651 23736 11645 23736 11648 23736 11652 23737 11653 23737 11650 23737 11651 23738 11650 23738 11653 23738 11649 23739 11652 23739 11650 23739 11654 23740 11655 23740 11653 23740 11656 23741 11653 23741 11655 23741 11652 23742 11654 23742 11653 23742 11656 23743 11651 23743 11653 23743 11654 23744 11657 23744 11655 23744 11656 23745 11655 23745 11657 23745 11658 23746 11659 23746 11657 23746 11660 23747 11657 23747 11659 23747 11654 23748 11658 23748 11657 23748 11660 23749 11656 23749 11657 23749 11658 23750 11661 23750 11659 23750 11660 23751 11659 23751 11661 23751 11662 23752 11663 23752 11661 23752 11664 23753 11661 23753 11663 23753 11658 23754 11662 23754 11661 23754 11664 23755 11660 23755 11661 23755 11665 23756 11666 23756 11663 23756 11664 23757 11663 23757 11666 23757 11662 23758 11665 23758 11663 23758 11667 23759 11668 23759 11666 23759 11669 23760 11666 23760 11668 23760 11665 23761 11667 23761 11666 23761 11669 23762 11664 23762 11666 23762 11670 23763 11671 23763 11668 23763 11669 23764 11668 23764 11671 23764 11667 23765 11670 23765 11668 23765 11672 23766 11673 23766 11671 23766 11674 23767 11671 23767 11673 23767 11670 23768 11672 23768 11671 23768 11674 23769 11669 23769 11671 23769 11543 23770 11541 23770 11673 23770 11542 23771 11673 23771 11541 23771 11672 23772 11543 23772 11673 23772 11542 23773 11674 23773 11673 23773 11675 23774 11543 23774 11672 23774 11675 23775 10802 23775 11543 23775 11676 23776 11672 23776 11670 23776 11676 23777 11675 23777 11672 23777 11676 23778 11670 23778 11667 23778 11677 23779 11667 23779 11665 23779 11677 23780 11676 23780 11667 23780 11677 23781 11665 23781 11662 23781 11678 23782 11662 23782 11658 23782 11678 23783 11677 23783 11662 23783 11679 23784 11658 23784 11654 23784 11679 23785 11678 23785 11658 23785 11680 23786 11654 23786 11652 23786 11680 23787 11679 23787 11654 23787 11680 23788 11652 23788 11649 23788 11681 23789 11649 23789 11647 23789 11681 23790 11680 23790 11649 23790 11681 23791 11647 23791 11643 23791 11682 23792 11643 23792 11646 23792 11682 23793 11681 23793 11643 23793 11682 23794 11646 23794 11640 23794 11683 23795 11640 23795 11638 23795 11683 23796 11682 23796 11640 23796 11684 23797 11638 23797 11635 23797 11684 23798 11683 23798 11638 23798 11685 23799 11635 23799 11632 23799 11685 23800 11684 23800 11635 23800 11686 23801 11632 23801 11629 23801 11686 23802 11685 23802 11632 23802 11687 23803 11629 23803 11625 23803 11687 23804 11686 23804 11629 23804 11688 23805 11625 23805 11622 23805 11688 23806 11687 23806 11625 23806 11689 23807 11622 23807 11617 23807 11689 23808 11688 23808 11622 23808 11690 23809 11617 23809 11620 23809 11690 23810 11689 23810 11617 23810 11691 23811 11620 23811 11613 23811 11691 23812 11690 23812 11620 23812 11691 23813 11613 23813 11616 23813 11692 23814 11616 23814 11611 23814 11692 23815 11691 23815 11616 23815 11693 23816 11611 23816 11607 23816 11693 23817 11692 23817 11611 23817 11693 23818 11607 23818 11604 23818 11694 23819 11604 23819 11602 23819 11694 23820 11693 23820 11604 23820 11695 23821 11602 23821 11599 23821 11695 23822 11694 23822 11602 23822 11695 23823 11599 23823 11596 23823 11696 23824 11596 23824 11594 23824 11696 23825 11695 23825 11596 23825 11697 23826 11594 23826 11591 23826 11697 23827 11696 23827 11594 23827 11697 23828 11591 23828 11588 23828 11698 23829 11588 23829 11586 23829 11698 23830 11697 23830 11588 23830 11699 23831 11586 23831 11583 23831 11699 23832 11698 23832 11586 23832 11699 23833 11583 23833 11581 23833 11700 23834 11581 23834 11578 23834 11700 23835 11699 23835 11581 23835 11700 23836 11578 23836 11575 23836 11701 23837 11575 23837 11573 23837 11701 23838 11700 23838 11575 23838 11702 23839 11573 23839 11570 23839 11702 23840 11701 23840 11573 23840 11702 23841 11570 23841 11568 23841 11703 23842 11568 23842 11565 23842 11703 23843 11702 23843 11568 23843 11704 23844 11565 23844 11562 23844 11704 23845 11703 23845 11565 23845 11704 23846 11562 23846 11559 23846 11705 23847 11559 23847 11557 23847 11705 23848 11704 23848 11559 23848 11706 23849 11557 23849 11554 23849 11706 23850 11705 23850 11557 23850 11706 23851 11554 23851 11552 23851 11707 23852 11552 23852 11544 23852 11707 23853 11706 23853 11552 23853 11708 23854 11544 23854 11548 23854 11707 23855 11544 23855 11708 23855 11709 23856 11548 23856 11549 23856 11432 23857 11548 23857 11709 23857 11708 23858 11548 23858 11432 23858 11710 23859 11709 23859 11549 23859 11404 23860 11710 23860 11549 23860 11404 23861 11549 23861 11401 23861 11711 23862 11401 23862 11549 23862 11712 23863 11711 23863 11549 23863 11547 23864 11712 23864 11549 23864 11713 23865 11709 23865 11710 23865 11432 23866 11709 23866 11713 23866 11714 23867 11715 23867 11716 23867 11717 23868 11716 23868 11715 23868 11718 23869 11714 23869 11716 23869 11719 23870 11718 23870 11716 23870 11720 23871 11719 23871 11716 23871 11720 23872 11716 23872 11717 23872 11713 23873 11710 23873 11715 23873 11405 23874 11715 23874 11710 23874 11714 23875 11713 23875 11715 23875 11717 23876 11715 23876 11721 23876 11405 23877 11721 23877 11715 23877 11405 23878 11710 23878 11404 23878 11429 23879 11713 23879 11714 23879 11432 23880 11713 23880 11429 23880 11426 23881 11714 23881 11718 23881 11429 23882 11714 23882 11426 23882 11722 23883 11718 23883 11719 23883 11723 23884 11718 23884 11722 23884 11426 23885 11718 23885 11723 23885 11724 23886 11725 23886 11299 23886 11300 23887 11299 23887 11725 23887 11298 23888 11724 23888 11299 23888 11724 23889 11726 23889 11725 23889 11727 23890 11725 23890 11726 23890 11300 23891 11725 23891 11308 23891 11727 23892 11308 23892 11725 23892 11728 23893 11729 23893 11726 23893 11727 23894 11726 23894 11729 23894 11724 23895 11728 23895 11726 23895 11730 23896 11731 23896 11729 23896 11732 23897 11729 23897 11731 23897 11728 23898 11730 23898 11729 23898 11727 23899 11729 23899 11732 23899 11733 23900 11734 23900 11731 23900 11735 23901 11731 23901 11734 23901 11730 23902 11733 23902 11731 23902 11732 23903 11731 23903 11735 23903 11736 23904 11737 23904 11734 23904 11738 23905 11734 23905 11737 23905 11733 23906 11736 23906 11734 23906 11735 23907 11734 23907 11738 23907 11739 23908 11740 23908 11737 23908 11738 23909 11737 23909 11740 23909 11736 23910 11739 23910 11737 23910 11741 23911 11742 23911 11740 23911 11743 23912 11740 23912 11742 23912 11739 23913 11741 23913 11740 23913 11738 23914 11740 23914 11743 23914 11741 23915 11744 23915 11742 23915 11745 23916 11742 23916 11744 23916 11743 23917 11742 23917 11745 23917 11746 23918 11747 23918 11744 23918 11745 23919 11744 23919 11747 23919 11741 23920 11746 23920 11744 23920 11748 23921 11749 23921 11747 23921 11750 23922 11747 23922 11749 23922 11746 23923 11748 23923 11747 23923 11745 23924 11747 23924 11750 23924 11751 23925 11752 23925 11749 23925 11750 23926 11749 23926 11752 23926 11748 23927 11751 23927 11749 23927 11753 23928 11754 23928 11752 23928 11755 23929 11752 23929 11754 23929 11751 23930 11753 23930 11752 23930 11750 23931 11752 23931 11755 23931 11756 23932 11757 23932 11754 23932 11755 23933 11754 23933 11757 23933 11753 23934 11756 23934 11754 23934 11756 23935 11758 23935 11757 23935 11755 23936 11757 23936 11758 23936 11759 23937 11760 23937 11758 23937 11761 23938 11758 23938 11760 23938 11756 23939 11759 23939 11758 23939 11755 23940 11758 23940 11761 23940 11762 23941 11763 23941 11760 23941 11761 23942 11760 23942 11763 23942 11759 23943 11762 23943 11760 23943 11764 23944 11765 23944 11763 23944 11761 23945 11763 23945 11765 23945 11762 23946 11764 23946 11763 23946 11766 23947 11767 23947 11765 23947 11768 23948 11765 23948 11767 23948 11764 23949 11766 23949 11765 23949 11761 23950 11765 23950 11768 23950 11769 23951 11770 23951 11767 23951 11768 23952 11767 23952 11770 23952 11766 23953 11769 23953 11767 23953 11769 23954 11771 23954 11770 23954 11768 23955 11770 23955 11771 23955 11772 23956 11773 23956 11771 23956 11768 23957 11771 23957 11773 23957 11769 23958 11772 23958 11771 23958 11774 23959 11775 23959 11773 23959 11776 23960 11773 23960 11775 23960 11772 23961 11774 23961 11773 23961 11768 23962 11773 23962 11776 23962 11777 23963 11778 23963 11775 23963 11776 23964 11775 23964 11778 23964 11774 23965 11777 23965 11775 23965 11779 23966 11780 23966 11778 23966 11776 23967 11778 23967 11780 23967 11777 23968 11779 23968 11778 23968 11781 23969 11782 23969 11780 23969 11776 23970 11780 23970 11782 23970 11779 23971 11781 23971 11780 23971 11781 23972 11783 23972 11782 23972 11720 23973 11782 23973 11783 23973 11776 23974 11782 23974 11720 23974 11784 23975 11785 23975 11783 23975 11720 23976 11783 23976 11785 23976 11781 23977 11784 23977 11783 23977 11722 23978 11719 23978 11785 23978 11720 23979 11785 23979 11719 23979 11784 23980 11722 23980 11785 23980 11723 23981 11722 23981 11784 23981 11786 23982 11784 23982 11781 23982 11786 23983 11723 23983 11784 23983 11786 23984 11781 23984 11779 23984 11786 23985 11779 23985 11777 23985 11786 23986 11777 23986 11774 23986 11787 23987 11774 23987 11772 23987 11787 23988 11786 23988 11774 23988 11787 23989 11772 23989 11769 23989 11787 23990 11769 23990 11766 23990 11788 23991 11766 23991 11764 23991 11788 23992 11787 23992 11766 23992 11788 23993 11764 23993 11762 23993 11788 23994 11762 23994 11759 23994 11789 23995 11759 23995 11756 23995 11789 23996 11788 23996 11759 23996 11789 23997 11756 23997 11753 23997 11790 23998 11753 23998 11751 23998 11790 23999 11789 23999 11753 23999 11791 24000 11751 24000 11748 24000 11791 24001 11790 24001 11751 24001 11791 24002 11748 24002 11746 24002 11792 24003 11746 24003 11741 24003 11792 24004 11791 24004 11746 24004 11793 24005 11741 24005 11739 24005 11793 24006 11792 24006 11741 24006 11794 24007 11739 24007 11736 24007 11794 24008 11793 24008 11739 24008 11795 24009 11736 24009 11733 24009 11795 24010 11794 24010 11736 24010 11795 24011 11733 24011 11730 24011 11796 24012 11730 24012 11728 24012 11796 24013 11795 24013 11730 24013 11797 24014 11728 24014 11724 24014 11797 24015 11796 24015 11728 24015 11302 24016 11724 24016 11298 24016 11797 24017 11724 24017 11302 24017 11302 24018 11298 24018 11301 24018 11525 24019 11302 24019 11297 24019 11797 24020 11302 24020 11525 24020 11527 24021 11525 24021 11526 24021 11528 24022 11525 24022 11527 24022 11798 24023 11525 24023 11528 24023 11798 24024 11797 24024 11525 24024 11798 24025 11528 24025 11529 24025 11296 24026 11290 24026 11303 24026 11799 24027 11303 24027 11304 24027 11799 24028 11296 24028 11303 24028 11799 24029 11304 24029 11305 24029 11799 24030 11305 24030 11306 24030 11727 24031 11306 24031 11307 24031 11727 24032 11799 24032 11306 24032 11727 24033 11307 24033 11308 24033 11721 24034 11406 24034 11407 24034 11405 24035 11406 24035 11721 24035 11800 24036 11407 24036 11408 24036 11800 24037 11721 24037 11407 24037 11801 24038 11408 24038 11409 24038 11801 24039 11800 24039 11408 24039 11802 24040 11409 24040 11410 24040 11802 24041 11801 24041 11409 24041 11803 24042 11410 24042 11411 24042 11803 24043 11802 24043 11410 24043 11804 24044 11411 24044 11412 24044 11804 24045 11803 24045 11411 24045 11805 24046 11412 24046 11413 24046 11805 24047 11804 24047 11412 24047 11806 24048 11413 24048 11414 24048 11806 24049 11805 24049 11413 24049 11807 24050 11414 24050 11415 24050 11807 24051 11806 24051 11414 24051 11808 24052 11415 24052 11416 24052 11808 24053 11807 24053 11415 24053 11809 24054 11416 24054 11417 24054 11809 24055 11808 24055 11416 24055 11810 24056 11417 24056 11296 24056 11810 24057 11809 24057 11417 24057 11799 24058 11810 24058 11296 24058 11717 24059 11721 24059 11800 24059 11720 24060 11800 24060 11801 24060 11720 24061 11717 24061 11800 24061 11776 24062 11801 24062 11802 24062 11776 24063 11720 24063 11801 24063 11768 24064 11802 24064 11803 24064 11768 24065 11776 24065 11802 24065 11761 24066 11803 24066 11804 24066 11761 24067 11768 24067 11803 24067 11755 24068 11804 24068 11805 24068 11755 24069 11761 24069 11804 24069 11750 24070 11805 24070 11806 24070 11750 24071 11755 24071 11805 24071 11745 24072 11806 24072 11807 24072 11745 24073 11750 24073 11806 24073 11743 24074 11807 24074 11808 24074 11743 24075 11745 24075 11807 24075 11738 24076 11808 24076 11809 24076 11738 24077 11743 24077 11808 24077 11735 24078 11809 24078 11810 24078 11735 24079 11738 24079 11809 24079 11732 24080 11810 24080 11799 24080 11732 24081 11735 24081 11810 24081 11727 24082 11732 24082 11799 24082 11811 24083 11402 24083 11401 24083 11711 24084 11811 24084 11401 24084 11812 24085 11402 24085 11811 24085 11403 24086 11402 24086 11812 24086 11812 24087 11811 24087 11711 24087 11551 24088 11711 24088 11712 24088 11812 24089 11711 24089 11551 24089 11551 24090 11712 24090 11547 24090 11813 24091 10805 24091 10809 24091 11813 24092 11542 24092 10805 24092 11309 24093 10809 24093 10808 24093 11309 24094 11813 24094 10809 24094 11812 24095 11551 24095 11556 24095 11814 24096 11556 24096 11561 24096 11814 24097 11812 24097 11556 24097 11815 24098 11561 24098 11564 24098 11815 24099 11814 24099 11561 24099 11816 24100 11564 24100 11567 24100 11816 24101 11815 24101 11564 24101 11817 24102 11567 24102 11572 24102 11817 24103 11816 24103 11567 24103 11818 24104 11572 24104 11577 24104 11818 24105 11817 24105 11572 24105 11819 24106 11577 24106 11580 24106 11819 24107 11818 24107 11577 24107 11820 24108 11580 24108 11585 24108 11820 24109 11819 24109 11580 24109 11821 24110 11585 24110 11590 24110 11821 24111 11820 24111 11585 24111 11822 24112 11590 24112 11593 24112 11822 24113 11821 24113 11590 24113 11823 24114 11593 24114 11598 24114 11823 24115 11822 24115 11593 24115 11824 24116 11598 24116 11601 24116 11824 24117 11823 24117 11598 24117 11825 24118 11601 24118 11606 24118 11825 24119 11824 24119 11601 24119 11826 24120 11606 24120 11610 24120 11826 24121 11825 24121 11606 24121 11827 24122 11610 24122 11615 24122 11827 24123 11826 24123 11610 24123 11828 24124 11615 24124 11621 24124 11828 24125 11827 24125 11615 24125 11829 24126 11621 24126 11619 24126 11829 24127 11828 24127 11621 24127 11830 24128 11619 24128 11624 24128 11830 24129 11829 24129 11619 24129 11831 24130 11624 24130 11628 24130 11831 24131 11830 24131 11624 24131 11832 24132 11628 24132 11627 24132 11832 24133 11831 24133 11628 24133 11833 24134 11627 24134 11631 24134 11833 24135 11832 24135 11627 24135 11834 24136 11631 24136 11634 24136 11834 24137 11833 24137 11631 24137 11835 24138 11634 24138 11637 24138 11835 24139 11834 24139 11634 24139 11836 24140 11637 24140 11642 24140 11836 24141 11835 24141 11637 24141 11837 24142 11642 24142 11645 24142 11837 24143 11836 24143 11642 24143 11838 24144 11645 24144 11651 24144 11838 24145 11837 24145 11645 24145 11839 24146 11651 24146 11656 24146 11839 24147 11838 24147 11651 24147 11840 24148 11656 24148 11660 24148 11840 24149 11839 24149 11656 24149 11841 24150 11660 24150 11664 24150 11841 24151 11840 24151 11660 24151 11842 24152 11664 24152 11669 24152 11842 24153 11841 24153 11664 24153 11843 24154 11669 24154 11674 24154 11843 24155 11842 24155 11669 24155 11844 24156 11674 24156 11542 24156 11844 24157 11843 24157 11674 24157 11813 24158 11844 24158 11542 24158 11403 24159 11812 24159 11814 24159 11391 24160 11814 24160 11815 24160 11391 24161 11403 24161 11814 24161 11399 24162 11815 24162 11816 24162 11399 24163 11391 24163 11815 24163 11400 24164 11816 24164 11817 24164 11400 24165 11399 24165 11816 24165 11384 24166 11817 24166 11818 24166 11384 24167 11400 24167 11817 24167 11388 24168 11818 24168 11819 24168 11388 24169 11384 24169 11818 24169 11376 24170 11819 24170 11820 24170 11376 24171 11388 24171 11819 24171 11380 24172 11820 24172 11821 24172 11380 24173 11376 24173 11820 24173 11381 24174 11821 24174 11822 24174 11381 24175 11380 24175 11821 24175 11370 24176 11822 24176 11823 24176 11370 24177 11381 24177 11822 24177 11373 24178 11823 24178 11824 24178 11373 24179 11370 24179 11823 24179 11366 24180 11824 24180 11825 24180 11366 24181 11373 24181 11824 24181 11361 24182 11825 24182 11826 24182 11361 24183 11366 24183 11825 24183 11363 24184 11826 24184 11827 24184 11363 24185 11361 24185 11826 24185 11357 24186 11827 24186 11828 24186 11357 24187 11363 24187 11827 24187 11358 24188 11828 24188 11829 24188 11358 24189 11357 24189 11828 24189 11354 24190 11829 24190 11830 24190 11354 24191 11358 24191 11829 24191 11351 24192 11830 24192 11831 24192 11351 24193 11354 24193 11830 24193 11348 24194 11831 24194 11832 24194 11348 24195 11351 24195 11831 24195 11345 24196 11832 24196 11833 24196 11345 24197 11348 24197 11832 24197 11343 24198 11833 24198 11834 24198 11343 24199 11345 24199 11833 24199 11340 24200 11834 24200 11835 24200 11340 24201 11343 24201 11834 24201 11338 24202 11835 24202 11836 24202 11338 24203 11340 24203 11835 24203 11335 24204 11836 24204 11837 24204 11335 24205 11338 24205 11836 24205 11333 24206 11837 24206 11838 24206 11333 24207 11335 24207 11837 24207 11329 24208 11838 24208 11839 24208 11329 24209 11333 24209 11838 24209 11327 24210 11839 24210 11840 24210 11327 24211 11329 24211 11839 24211 11324 24212 11840 24212 11841 24212 11324 24213 11327 24213 11840 24213 11319 24214 11841 24214 11842 24214 11319 24215 11324 24215 11841 24215 11316 24216 11842 24216 11843 24216 11316 24217 11319 24217 11842 24217 11312 24218 11843 24218 11844 24218 11312 24219 11316 24219 11843 24219 11310 24220 11844 24220 11813 24220 11310 24221 11312 24221 11844 24221 11309 24222 11310 24222 11813 24222 11427 24223 11723 24223 11786 24223 11426 24224 11723 24224 11427 24224 11845 24225 11786 24225 11787 24225 11846 24226 11427 24226 11786 24226 11846 24227 11786 24227 11845 24227 11847 24228 11787 24228 11788 24228 11845 24229 11787 24229 11847 24229 11848 24230 11788 24230 11789 24230 11847 24231 11788 24231 11848 24231 11849 24232 11789 24232 11790 24232 11848 24233 11789 24233 11849 24233 11850 24234 11790 24234 11791 24234 11849 24235 11790 24235 11850 24235 11851 24236 11791 24236 11792 24236 11850 24237 11791 24237 11851 24237 11852 24238 11792 24238 11793 24238 11851 24239 11792 24239 11852 24239 11853 24240 11793 24240 11794 24240 11852 24241 11793 24241 11853 24241 11854 24242 11794 24242 11795 24242 11853 24243 11794 24243 11854 24243 11855 24244 11795 24244 11796 24244 11854 24245 11795 24245 11855 24245 11798 24246 11796 24246 11797 24246 11855 24247 11796 24247 11798 24247 11855 24248 11529 24248 11530 24248 11855 24249 11798 24249 11529 24249 11854 24250 11530 24250 11531 24250 11854 24251 11855 24251 11530 24251 11853 24252 11531 24252 11532 24252 11853 24253 11854 24253 11531 24253 11852 24254 11532 24254 11533 24254 11852 24255 11853 24255 11532 24255 11851 24256 11533 24256 11534 24256 11851 24257 11852 24257 11533 24257 11850 24258 11534 24258 11535 24258 11850 24259 11851 24259 11534 24259 11849 24260 11535 24260 11536 24260 11849 24261 11850 24261 11535 24261 11848 24262 11536 24262 11537 24262 11848 24263 11849 24263 11536 24263 11847 24264 11537 24264 11538 24264 11847 24265 11848 24265 11537 24265 11845 24266 11538 24266 11539 24266 11845 24267 11847 24267 11538 24267 11846 24268 11539 24268 11424 24268 11846 24269 11845 24269 11539 24269 11846 24270 11424 24270 11421 24270 11846 24271 11421 24271 11427 24271 11856 24272 11708 24272 11432 24272 11857 24273 11856 24273 11432 24273 11433 24274 11857 24274 11432 24274 11857 24275 11708 24275 11856 24275 11707 24276 11708 24276 11857 24276 11431 24277 11857 24277 11433 24277 11858 24278 11857 24278 11431 24278 11858 24279 11707 24279 11857 24279 11858 24280 11431 24280 11434 24280 11859 24281 10800 24281 10799 24281 11859 24282 11523 24282 10800 24282 11675 24283 10799 24283 10802 24283 11859 24284 10799 24284 11675 24284 11860 24285 11434 24285 11438 24285 11858 24286 11434 24286 11860 24286 11861 24287 11438 24287 11441 24287 11860 24288 11438 24288 11861 24288 11862 24289 11441 24289 11444 24289 11861 24290 11441 24290 11862 24290 11863 24291 11444 24291 11448 24291 11862 24292 11444 24292 11863 24292 11864 24293 11448 24293 11451 24293 11863 24294 11448 24294 11864 24294 11865 24295 11451 24295 11454 24295 11864 24296 11451 24296 11865 24296 11866 24297 11454 24297 11457 24297 11865 24298 11454 24298 11866 24298 11867 24299 11457 24299 11461 24299 11866 24300 11457 24300 11867 24300 11868 24301 11461 24301 11464 24301 11867 24302 11461 24302 11868 24302 11869 24303 11464 24303 11466 24303 11868 24304 11464 24304 11869 24304 11870 24305 11466 24305 11471 24305 11869 24306 11466 24306 11870 24306 11871 24307 11471 24307 11476 24307 11870 24308 11471 24308 11871 24308 11872 24309 11476 24309 11477 24309 11871 24310 11476 24310 11872 24310 11873 24311 11477 24311 11475 24311 11872 24312 11477 24312 11873 24312 11874 24313 11475 24313 11481 24313 11873 24314 11475 24314 11874 24314 11875 24315 11481 24315 11480 24315 11874 24316 11481 24316 11875 24316 11876 24317 11480 24317 11485 24317 11875 24318 11480 24318 11876 24318 11877 24319 11485 24319 11484 24319 11876 24320 11485 24320 11877 24320 11878 24321 11484 24321 11488 24321 11877 24322 11484 24322 11878 24322 11879 24323 11488 24323 11492 24323 11878 24324 11488 24324 11879 24324 11880 24325 11492 24325 11491 24325 11879 24326 11492 24326 11880 24326 11881 24327 11491 24327 11494 24327 11880 24328 11491 24328 11881 24328 11882 24329 11494 24329 11498 24329 11881 24330 11494 24330 11882 24330 11883 24331 11498 24331 11500 24331 11882 24332 11498 24332 11883 24332 11884 24333 11500 24333 11504 24333 11883 24334 11500 24334 11884 24334 11885 24335 11504 24335 11507 24335 11884 24336 11504 24336 11885 24336 11886 24337 11507 24337 11509 24337 11885 24338 11507 24338 11886 24338 11887 24339 11509 24339 11512 24339 11886 24340 11509 24340 11887 24340 11888 24341 11512 24341 11515 24341 11887 24342 11512 24342 11888 24342 11889 24343 11515 24343 11519 24343 11888 24344 11515 24344 11889 24344 11890 24345 11519 24345 11521 24345 11889 24346 11519 24346 11890 24346 11859 24347 11521 24347 11523 24347 11890 24348 11521 24348 11859 24348 11890 24349 11675 24349 11676 24349 11890 24350 11859 24350 11675 24350 11889 24351 11676 24351 11677 24351 11889 24352 11890 24352 11676 24352 11888 24353 11677 24353 11678 24353 11888 24354 11889 24354 11677 24354 11887 24355 11678 24355 11679 24355 11887 24356 11888 24356 11678 24356 11886 24357 11679 24357 11680 24357 11886 24358 11887 24358 11679 24358 11885 24359 11680 24359 11681 24359 11885 24360 11886 24360 11680 24360 11884 24361 11681 24361 11682 24361 11884 24362 11885 24362 11681 24362 11883 24363 11682 24363 11683 24363 11883 24364 11884 24364 11682 24364 11882 24365 11683 24365 11684 24365 11882 24366 11883 24366 11683 24366 11881 24367 11684 24367 11685 24367 11881 24368 11882 24368 11684 24368 11880 24369 11685 24369 11686 24369 11880 24370 11881 24370 11685 24370 11879 24371 11686 24371 11687 24371 11879 24372 11880 24372 11686 24372 11878 24373 11687 24373 11688 24373 11878 24374 11879 24374 11687 24374 11877 24375 11688 24375 11689 24375 11877 24376 11878 24376 11688 24376 11876 24377 11689 24377 11690 24377 11876 24378 11877 24378 11689 24378 11875 24379 11690 24379 11691 24379 11875 24380 11876 24380 11690 24380 11874 24381 11691 24381 11692 24381 11874 24382 11875 24382 11691 24382 11873 24383 11692 24383 11693 24383 11873 24384 11874 24384 11692 24384 11872 24385 11693 24385 11694 24385 11872 24386 11873 24386 11693 24386 11871 24387 11694 24387 11695 24387 11871 24388 11872 24388 11694 24388 11870 24389 11695 24389 11696 24389 11870 24390 11871 24390 11695 24390 11869 24391 11696 24391 11697 24391 11869 24392 11870 24392 11696 24392 11868 24393 11697 24393 11698 24393 11868 24394 11869 24394 11697 24394 11867 24395 11698 24395 11699 24395 11867 24396 11868 24396 11698 24396 11866 24397 11699 24397 11700 24397 11866 24398 11867 24398 11699 24398 11865 24399 11700 24399 11701 24399 11865 24400 11866 24400 11700 24400 11864 24401 11701 24401 11702 24401 11864 24402 11865 24402 11701 24402 11863 24403 11702 24403 11703 24403 11863 24404 11864 24404 11702 24404 11862 24405 11703 24405 11704 24405 11862 24406 11863 24406 11703 24406 11861 24407 11704 24407 11705 24407 11861 24408 11862 24408 11704 24408 11860 24409 11705 24409 11706 24409 11860 24410 11861 24410 11705 24410 11858 24411 11706 24411 11707 24411 11858 24412 11860 24412 11706 24412 11891 24413 10941 24413 10940 24413 11892 24414 11891 24414 10940 24414 11246 24415 11892 24415 10940 24415 11893 24416 10941 24416 11891 24416 10935 24417 10941 24417 11893 24417 11894 24418 11891 24418 11892 24418 11893 24419 11891 24419 11894 24419 11894 24420 11892 24420 11246 24420 11895 24421 11246 24421 11247 24421 11894 24422 11246 24422 11895 24422 11248 24423 11896 24423 11249 24423 11895 24424 11247 24424 11080 24424 11080 24425 11247 24425 11074 24425 11897 24426 10829 24426 10827 24426 11897 24427 11070 24427 10829 24427 11898 24428 10827 24428 10831 24428 11898 24429 11897 24429 10827 24429 11899 24430 10831 24430 10830 24430 11899 24431 11898 24431 10831 24431 10851 24432 10830 24432 10832 24432 10851 24433 11899 24433 10830 24433 11895 24434 11080 24434 11079 24434 11900 24435 11079 24435 11083 24435 11900 24436 11895 24436 11079 24436 11901 24437 11083 24437 11085 24437 11901 24438 11900 24438 11083 24438 11902 24439 11085 24439 11090 24439 11902 24440 11901 24440 11085 24440 11903 24441 11090 24441 11093 24441 11903 24442 11902 24442 11090 24442 11904 24443 11093 24443 11096 24443 11904 24444 11903 24444 11093 24444 11905 24445 11096 24445 11101 24445 11905 24446 11904 24446 11096 24446 11906 24447 11101 24447 11106 24447 11906 24448 11905 24448 11101 24448 11907 24449 11106 24449 11111 24449 11907 24450 11906 24450 11106 24450 11908 24451 11111 24451 11114 24451 11908 24452 11907 24452 11111 24452 11909 24453 11114 24453 11119 24453 11909 24454 11908 24454 11114 24454 11910 24455 11119 24455 11123 24455 11910 24456 11909 24456 11119 24456 11911 24457 11123 24457 11128 24457 11911 24458 11910 24458 11123 24458 11912 24459 11128 24459 11133 24459 11912 24460 11911 24460 11128 24460 11913 24461 11133 24461 11136 24461 11913 24462 11912 24462 11133 24462 11914 24463 11136 24463 11140 24463 11914 24464 11913 24464 11136 24464 11915 24465 11140 24465 11142 24465 11915 24466 11914 24466 11140 24466 11916 24467 11142 24467 11145 24467 11916 24468 11915 24468 11142 24468 11917 24469 11145 24469 11149 24469 11917 24470 11916 24470 11145 24470 11918 24471 11149 24471 11153 24471 11918 24472 11917 24472 11149 24472 11919 24473 11153 24473 11152 24473 11919 24474 11918 24474 11153 24474 11920 24475 11152 24475 11158 24475 11920 24476 11919 24476 11152 24476 11921 24477 11158 24477 11161 24477 11921 24478 11920 24478 11158 24478 11922 24479 11161 24479 11166 24479 11922 24480 11921 24480 11161 24480 11923 24481 11166 24481 11170 24481 11923 24482 11922 24482 11166 24482 11924 24483 11170 24483 11175 24483 11924 24484 11923 24484 11170 24484 11925 24485 11175 24485 11181 24485 11925 24486 11924 24486 11175 24486 11926 24487 11181 24487 11186 24487 11926 24488 11925 24488 11181 24488 11927 24489 11186 24489 11191 24489 11927 24490 11926 24490 11186 24490 11928 24491 11191 24491 11196 24491 11928 24492 11927 24492 11191 24492 11929 24493 11196 24493 11201 24493 11929 24494 11928 24494 11196 24494 11930 24495 11201 24495 11207 24495 11930 24496 11929 24496 11201 24496 11931 24497 11207 24497 11070 24497 11931 24498 11930 24498 11207 24498 11897 24499 11931 24499 11070 24499 11894 24500 11895 24500 11900 24500 11932 24501 11900 24501 11901 24501 11932 24502 11894 24502 11900 24502 11933 24503 11901 24503 11902 24503 11933 24504 11932 24504 11901 24504 11934 24505 11902 24505 11903 24505 11934 24506 11933 24506 11902 24506 11935 24507 11903 24507 11904 24507 11935 24508 11934 24508 11903 24508 11936 24509 11904 24509 11905 24509 11936 24510 11935 24510 11904 24510 11937 24511 11905 24511 11906 24511 11937 24512 11936 24512 11905 24512 11938 24513 11906 24513 11907 24513 11938 24514 11937 24514 11906 24514 11939 24515 11907 24515 11908 24515 11939 24516 11938 24516 11907 24516 11940 24517 11908 24517 11909 24517 11940 24518 11939 24518 11908 24518 11941 24519 11909 24519 11910 24519 11941 24520 11940 24520 11909 24520 11942 24521 11910 24521 11911 24521 11942 24522 11941 24522 11910 24522 11943 24523 11911 24523 11912 24523 11943 24524 11942 24524 11911 24524 11944 24525 11912 24525 11913 24525 11944 24526 11943 24526 11912 24526 11945 24527 11913 24527 11914 24527 11945 24528 11944 24528 11913 24528 11946 24529 11914 24529 11915 24529 11946 24530 11945 24530 11914 24530 11947 24531 11915 24531 11916 24531 11947 24532 11946 24532 11915 24532 11948 24533 11916 24533 11917 24533 11948 24534 11947 24534 11916 24534 11949 24535 11917 24535 11918 24535 11949 24536 11948 24536 11917 24536 11950 24537 11918 24537 11919 24537 11950 24538 11949 24538 11918 24538 11951 24539 11919 24539 11920 24539 11951 24540 11950 24540 11919 24540 11952 24541 11920 24541 11921 24541 11952 24542 11951 24542 11920 24542 11953 24543 11921 24543 11922 24543 11953 24544 11952 24544 11921 24544 11954 24545 11922 24545 11923 24545 11954 24546 11953 24546 11922 24546 11955 24547 11923 24547 11924 24547 11955 24548 11954 24548 11923 24548 11956 24549 11924 24549 11925 24549 11956 24550 11955 24550 11924 24550 11957 24551 11925 24551 11926 24551 11957 24552 11956 24552 11925 24552 11958 24553 11926 24553 11927 24553 11958 24554 11957 24554 11926 24554 11959 24555 11927 24555 11928 24555 11959 24556 11958 24556 11927 24556 11960 24557 11928 24557 11929 24557 11960 24558 11959 24558 11928 24558 11961 24559 11929 24559 11930 24559 11961 24560 11960 24560 11929 24560 11962 24561 11930 24561 11931 24561 11962 24562 11961 24562 11930 24562 11963 24563 11931 24563 11897 24563 11963 24564 11962 24564 11931 24564 11898 24565 11963 24565 11897 24565 11893 24566 11894 24566 11932 24566 11964 24567 11932 24567 11933 24567 11964 24568 11893 24568 11932 24568 11965 24569 11933 24569 11934 24569 11965 24570 11964 24570 11933 24570 11966 24571 11934 24571 11935 24571 11966 24572 11965 24572 11934 24572 11967 24573 11935 24573 11936 24573 11967 24574 11966 24574 11935 24574 11968 24575 11936 24575 11937 24575 11968 24576 11967 24576 11936 24576 11969 24577 11937 24577 11938 24577 11969 24578 11968 24578 11937 24578 11970 24579 11938 24579 11939 24579 11970 24580 11969 24580 11938 24580 11971 24581 11939 24581 11940 24581 11971 24582 11970 24582 11939 24582 11972 24583 11940 24583 11941 24583 11972 24584 11971 24584 11940 24584 11973 24585 11941 24585 11942 24585 11973 24586 11972 24586 11941 24586 11974 24587 11942 24587 11943 24587 11974 24588 11973 24588 11942 24588 11975 24589 11943 24589 11944 24589 11975 24590 11974 24590 11943 24590 11976 24591 11944 24591 11945 24591 11976 24592 11975 24592 11944 24592 11977 24593 11945 24593 11946 24593 11977 24594 11976 24594 11945 24594 11978 24595 11946 24595 11947 24595 11978 24596 11977 24596 11946 24596 11979 24597 11947 24597 11948 24597 11979 24598 11978 24598 11947 24598 11980 24599 11948 24599 11949 24599 11980 24600 11979 24600 11948 24600 11981 24601 11949 24601 11950 24601 11981 24602 11980 24602 11949 24602 11982 24603 11950 24603 11951 24603 11982 24604 11981 24604 11950 24604 11983 24605 11951 24605 11952 24605 11983 24606 11982 24606 11951 24606 11984 24607 11952 24607 11953 24607 11984 24608 11983 24608 11952 24608 11985 24609 11953 24609 11954 24609 11985 24610 11984 24610 11953 24610 11986 24611 11954 24611 11955 24611 11986 24612 11985 24612 11954 24612 11987 24613 11955 24613 11956 24613 11987 24614 11986 24614 11955 24614 11988 24615 11956 24615 11957 24615 11988 24616 11987 24616 11956 24616 11989 24617 11957 24617 11958 24617 11989 24618 11988 24618 11957 24618 11990 24619 11958 24619 11959 24619 11990 24620 11989 24620 11958 24620 11991 24621 11959 24621 11960 24621 11991 24622 11990 24622 11959 24622 11992 24623 11960 24623 11961 24623 11992 24624 11991 24624 11960 24624 11993 24625 11961 24625 11962 24625 11993 24626 11992 24626 11961 24626 11994 24627 11962 24627 11963 24627 11994 24628 11993 24628 11962 24628 11995 24629 11963 24629 11898 24629 11995 24630 11994 24630 11963 24630 11899 24631 11995 24631 11898 24631 10935 24632 11893 24632 11964 24632 10931 24633 11964 24633 11965 24633 10931 24634 10935 24634 11964 24634 10932 24635 11965 24635 11966 24635 10932 24636 10931 24636 11965 24636 10926 24637 11966 24637 11967 24637 10926 24638 10932 24638 11966 24638 10928 24639 11967 24639 11968 24639 10928 24640 10926 24640 11967 24640 10921 24641 11968 24641 11969 24641 10921 24642 10928 24642 11968 24642 10923 24643 11969 24643 11970 24643 10923 24644 10921 24644 11969 24644 10916 24645 11970 24645 11971 24645 10916 24646 10923 24646 11970 24646 10917 24647 11971 24647 11972 24647 10917 24648 10916 24648 11971 24648 10918 24649 11972 24649 11973 24649 10918 24650 10917 24650 11972 24650 10911 24651 11973 24651 11974 24651 10911 24652 10918 24652 11973 24652 10913 24653 11974 24653 11975 24653 10913 24654 10911 24654 11974 24654 10907 24655 11975 24655 11976 24655 10907 24656 10913 24656 11975 24656 10903 24657 11976 24657 11977 24657 10903 24658 10907 24658 11976 24658 10904 24659 11977 24659 11978 24659 10904 24660 10903 24660 11977 24660 10900 24661 11978 24661 11979 24661 10900 24662 10904 24662 11978 24662 10896 24663 11979 24663 11980 24663 10896 24664 10900 24664 11979 24664 10897 24665 11980 24665 11981 24665 10897 24666 10896 24666 11980 24666 10893 24667 11981 24667 11982 24667 10893 24668 10897 24668 11981 24668 10891 24669 11982 24669 11983 24669 10891 24670 10893 24670 11982 24670 10888 24671 11983 24671 11984 24671 10888 24672 10891 24672 11983 24672 10886 24673 11984 24673 11985 24673 10886 24674 10888 24674 11984 24674 10883 24675 11985 24675 11986 24675 10883 24676 10886 24676 11985 24676 10880 24677 11986 24677 11987 24677 10880 24678 10883 24678 11986 24678 10876 24679 11987 24679 11988 24679 10876 24680 10880 24680 11987 24680 10874 24681 11988 24681 11989 24681 10874 24682 10876 24682 11988 24682 10870 24683 11989 24683 11990 24683 10870 24684 10874 24684 11989 24684 10867 24685 11990 24685 11991 24685 10867 24686 10870 24686 11990 24686 10864 24687 11991 24687 11992 24687 10864 24688 10867 24688 11991 24688 10859 24689 11992 24689 11993 24689 10859 24690 10864 24690 11992 24690 10856 24691 11993 24691 11994 24691 10856 24692 10859 24692 11993 24692 10853 24693 11994 24693 11995 24693 10853 24694 10856 24694 11994 24694 10852 24695 11995 24695 11899 24695 10852 24696 10853 24696 11995 24696 10851 24697 10852 24697 11899 24697 11996 24698 11244 24698 11030 24698 11896 24699 11997 24699 11249 24699 11998 24700 11996 24700 11030 24700 11031 24701 11998 24701 11030 24701 11896 24702 11999 24702 11997 24702 11242 24703 11244 24703 11996 24703 12000 24704 11996 24704 11998 24704 12000 24705 11242 24705 11996 24705 11032 24706 11998 24706 11031 24706 12001 24707 11998 24707 11032 24707 12000 24708 11998 24708 12001 24708 12002 24709 11032 24709 11029 24709 12001 24710 11032 24710 12002 24710 12002 24711 11029 24711 11033 24711 12003 24712 10820 24712 10821 24712 12003 24713 10955 24713 10820 24713 11250 24714 10821 24714 10819 24714 11250 24715 12003 24715 10821 24715 11248 24716 10819 24716 10824 24716 11248 24717 11250 24717 10819 24717 11209 24718 10824 24718 10823 24718 11248 24719 10824 24719 11209 24719 11896 24720 11209 24720 11210 24720 11248 24721 11209 24721 11896 24721 11999 24722 11210 24722 11211 24722 11896 24723 11210 24723 11999 24723 12004 24724 11211 24724 11212 24724 11999 24725 11211 24725 12004 24725 12005 24726 11212 24726 11213 24726 12004 24727 11212 24727 12005 24727 12006 24728 11213 24728 11214 24728 12005 24729 11213 24729 12006 24729 12007 24730 11214 24730 11215 24730 12006 24731 11214 24731 12007 24731 12008 24732 11215 24732 11216 24732 12007 24733 11215 24733 12008 24733 12009 24734 11216 24734 11217 24734 12008 24735 11216 24735 12009 24735 12010 24736 11217 24736 11218 24736 12009 24737 11217 24737 12010 24737 12011 24738 11218 24738 11219 24738 12010 24739 11218 24739 12011 24739 12012 24740 11219 24740 11220 24740 12011 24741 11219 24741 12012 24741 12013 24742 11220 24742 11221 24742 12012 24743 11220 24743 12013 24743 12014 24744 11221 24744 11222 24744 12013 24745 11221 24745 12014 24745 12015 24746 11222 24746 11223 24746 12014 24747 11222 24747 12015 24747 12016 24748 11223 24748 11224 24748 12015 24749 11223 24749 12016 24749 12017 24750 11224 24750 11225 24750 12016 24751 11224 24751 12017 24751 12018 24752 11225 24752 11226 24752 12017 24753 11225 24753 12018 24753 12019 24754 11226 24754 11227 24754 12018 24755 11226 24755 12019 24755 12020 24756 11227 24756 11228 24756 12019 24757 11227 24757 12020 24757 12021 24758 11228 24758 11229 24758 12020 24759 11228 24759 12021 24759 12022 24760 11229 24760 11230 24760 12021 24761 11229 24761 12022 24761 12023 24762 11230 24762 11231 24762 12022 24763 11230 24763 12023 24763 12024 24764 11231 24764 11232 24764 12023 24765 11231 24765 12024 24765 12025 24766 11232 24766 11233 24766 12024 24767 11232 24767 12025 24767 12026 24768 11233 24768 11234 24768 12025 24769 11233 24769 12026 24769 12027 24770 11234 24770 11235 24770 12026 24771 11234 24771 12027 24771 12028 24772 11235 24772 11236 24772 12027 24773 11235 24773 12028 24773 12029 24774 11236 24774 11237 24774 12028 24775 11236 24775 12029 24775 12030 24776 11237 24776 11238 24776 12029 24777 11237 24777 12030 24777 12031 24778 11238 24778 11239 24778 12030 24779 11238 24779 12031 24779 12032 24780 11239 24780 11241 24780 12031 24781 11239 24781 12032 24781 12033 24782 11241 24782 11240 24782 12032 24783 11241 24783 12033 24783 12000 24784 11240 24784 11242 24784 12033 24785 11240 24785 12000 24785 12034 24786 11033 24786 11034 24786 12034 24787 12002 24787 11033 24787 12035 24788 11034 24788 11036 24788 12035 24789 12034 24789 11034 24789 12036 24790 11036 24790 11035 24790 12036 24791 12035 24791 11036 24791 12037 24792 11035 24792 11037 24792 12037 24793 12036 24793 11035 24793 12038 24794 11037 24794 11039 24794 12038 24795 12037 24795 11037 24795 12039 24796 11039 24796 11040 24796 12039 24797 12038 24797 11039 24797 12040 24798 11040 24798 11038 24798 12040 24799 12039 24799 11040 24799 12041 24800 11038 24800 11042 24800 12041 24801 12040 24801 11038 24801 12042 24802 11042 24802 11041 24802 12042 24803 12041 24803 11042 24803 12043 24804 11041 24804 11044 24804 12043 24805 12042 24805 11041 24805 12044 24806 11044 24806 11045 24806 12044 24807 12043 24807 11044 24807 12045 24808 11045 24808 11043 24808 12045 24809 12044 24809 11045 24809 12046 24810 11043 24810 11047 24810 12046 24811 12045 24811 11043 24811 12047 24812 11047 24812 11046 24812 12047 24813 12046 24813 11047 24813 12048 24814 11046 24814 11049 24814 12048 24815 12047 24815 11046 24815 12049 24816 11049 24816 11048 24816 12049 24817 12048 24817 11049 24817 12050 24818 11048 24818 11050 24818 12050 24819 12049 24819 11048 24819 12051 24820 11050 24820 11052 24820 12051 24821 12050 24821 11050 24821 12052 24822 11052 24822 11051 24822 12052 24823 12051 24823 11052 24823 12053 24824 11051 24824 11053 24824 12053 24825 12052 24825 11051 24825 12054 24826 11053 24826 11054 24826 12054 24827 12053 24827 11053 24827 12055 24828 11054 24828 11055 24828 12055 24829 12054 24829 11054 24829 12056 24830 11055 24830 11056 24830 12056 24831 12055 24831 11055 24831 12057 24832 11056 24832 11057 24832 12057 24833 12056 24833 11056 24833 12058 24834 11057 24834 11058 24834 12058 24835 12057 24835 11057 24835 12059 24836 11058 24836 11059 24836 12059 24837 12058 24837 11058 24837 12060 24838 11059 24838 11060 24838 12060 24839 12059 24839 11059 24839 12061 24840 11060 24840 11061 24840 12061 24841 12060 24841 11060 24841 12062 24842 11061 24842 11062 24842 12062 24843 12061 24843 11061 24843 12063 24844 11062 24844 11063 24844 12063 24845 12062 24845 11062 24845 12064 24846 11063 24846 11064 24846 12064 24847 12063 24847 11063 24847 12065 24848 11064 24848 11065 24848 12065 24849 12064 24849 11064 24849 12003 24850 11065 24850 10955 24850 12003 24851 12065 24851 11065 24851 12066 24852 12002 24852 12034 24852 12066 24853 12001 24853 12002 24853 12067 24854 12034 24854 12035 24854 12067 24855 12066 24855 12034 24855 12068 24856 12035 24856 12036 24856 12068 24857 12067 24857 12035 24857 12069 24858 12036 24858 12037 24858 12069 24859 12068 24859 12036 24859 12070 24860 12037 24860 12038 24860 12070 24861 12069 24861 12037 24861 12071 24862 12038 24862 12039 24862 12071 24863 12070 24863 12038 24863 12072 24864 12039 24864 12040 24864 12072 24865 12071 24865 12039 24865 12073 24866 12040 24866 12041 24866 12073 24867 12072 24867 12040 24867 12074 24868 12041 24868 12042 24868 12074 24869 12073 24869 12041 24869 12075 24870 12042 24870 12043 24870 12075 24871 12074 24871 12042 24871 12076 24872 12043 24872 12044 24872 12076 24873 12075 24873 12043 24873 12077 24874 12044 24874 12045 24874 12077 24875 12076 24875 12044 24875 12078 24876 12045 24876 12046 24876 12078 24877 12077 24877 12045 24877 12079 24878 12046 24878 12047 24878 12079 24879 12078 24879 12046 24879 12080 24880 12047 24880 12048 24880 12080 24881 12079 24881 12047 24881 12081 24882 12048 24882 12049 24882 12081 24883 12080 24883 12048 24883 12082 24884 12049 24884 12050 24884 12082 24885 12081 24885 12049 24885 12083 24886 12050 24886 12051 24886 12083 24887 12082 24887 12050 24887 12084 24888 12051 24888 12052 24888 12084 24889 12083 24889 12051 24889 12085 24890 12052 24890 12053 24890 12085 24891 12084 24891 12052 24891 12086 24892 12053 24892 12054 24892 12086 24893 12085 24893 12053 24893 12087 24894 12054 24894 12055 24894 12087 24895 12086 24895 12054 24895 12088 24896 12055 24896 12056 24896 12088 24897 12087 24897 12055 24897 12089 24898 12056 24898 12057 24898 12089 24899 12088 24899 12056 24899 12090 24900 12057 24900 12058 24900 12090 24901 12089 24901 12057 24901 12091 24902 12058 24902 12059 24902 12091 24903 12090 24903 12058 24903 12092 24904 12059 24904 12060 24904 12092 24905 12091 24905 12059 24905 12093 24906 12060 24906 12061 24906 12093 24907 12092 24907 12060 24907 12094 24908 12061 24908 12062 24908 12094 24909 12093 24909 12061 24909 12095 24910 12062 24910 12063 24910 12095 24911 12094 24911 12062 24911 11997 24912 12063 24912 12064 24912 11997 24913 12095 24913 12063 24913 11249 24914 12064 24914 12065 24914 11249 24915 11997 24915 12064 24915 11250 24916 12065 24916 12003 24916 11250 24917 11249 24917 12065 24917 12033 24918 12001 24918 12066 24918 12033 24919 12000 24919 12001 24919 12032 24920 12066 24920 12067 24920 12032 24921 12033 24921 12066 24921 12031 24922 12067 24922 12068 24922 12031 24923 12032 24923 12067 24923 12030 24924 12068 24924 12069 24924 12030 24925 12031 24925 12068 24925 12029 24926 12069 24926 12070 24926 12029 24927 12030 24927 12069 24927 12028 24928 12070 24928 12071 24928 12028 24929 12029 24929 12070 24929 12027 24930 12071 24930 12072 24930 12027 24931 12028 24931 12071 24931 12026 24932 12072 24932 12073 24932 12026 24933 12027 24933 12072 24933 12025 24934 12073 24934 12074 24934 12025 24935 12026 24935 12073 24935 12024 24936 12074 24936 12075 24936 12024 24937 12025 24937 12074 24937 12023 24938 12075 24938 12076 24938 12023 24939 12024 24939 12075 24939 12022 24940 12076 24940 12077 24940 12022 24941 12023 24941 12076 24941 12021 24942 12077 24942 12078 24942 12021 24943 12022 24943 12077 24943 12020 24944 12078 24944 12079 24944 12020 24945 12021 24945 12078 24945 12019 24946 12079 24946 12080 24946 12019 24947 12020 24947 12079 24947 12018 24948 12080 24948 12081 24948 12018 24949 12019 24949 12080 24949 12017 24950 12081 24950 12082 24950 12017 24951 12018 24951 12081 24951 12016 24952 12082 24952 12083 24952 12016 24953 12017 24953 12082 24953 12015 24954 12083 24954 12084 24954 12015 24955 12016 24955 12083 24955 12014 24956 12084 24956 12085 24956 12014 24957 12015 24957 12084 24957 12013 24958 12085 24958 12086 24958 12013 24959 12014 24959 12085 24959 12012 24960 12086 24960 12087 24960 12012 24961 12013 24961 12086 24961 12011 24962 12087 24962 12088 24962 12011 24963 12012 24963 12087 24963 12010 24964 12088 24964 12089 24964 12010 24965 12011 24965 12088 24965 12009 24966 12089 24966 12090 24966 12009 24967 12010 24967 12089 24967 12008 24968 12090 24968 12091 24968 12008 24969 12009 24969 12090 24969 12007 24970 12091 24970 12092 24970 12007 24971 12008 24971 12091 24971 12006 24972 12092 24972 12093 24972 12006 24973 12007 24973 12092 24973 12005 24974 12093 24974 12094 24974 12005 24975 12006 24975 12093 24975 12004 24976 12094 24976 12095 24976 12004 24977 12005 24977 12094 24977 11999 24978 12095 24978 11997 24978 11999 24979 12004 24979 12095 24979 12480 25184 12481 25184 12483 25184 12482 25185 12483 25185 12484 25185 12484 25186 12485 25186 12486 25186 12486 25187 12487 25187 12488 25187 12488 25188 12489 25188 12490 25188 12490 25189 12491 25189 12492 25189 12492 25190 12493 25190 12494 25190 12494 25191 12495 25191 12496 25191 12496 25192 12497 25192 12499 25192 12498 25193 12499 25193 12501 25193 12500 25194 12501 25194 12503 25194 12502 25195 12503 25195 12505 25195 12504 25196 12505 25196 12507 25196 12506 25197 12507 25197 12509 25197 12508 25198 12509 25198 12511 25198 12510 25199 12511 25199 12513 25199 12512 25200 12513 25200 12515 25200 12514 25201 12515 25201 12517 25201 12516 25202 12517 25202 12519 25202 12518 25203 12519 25203 12520 25203 12520 25204 12521 25204 12522 25204 12522 25205 12523 25205 12524 25205 12524 25206 12525 25206 12526 25206 12526 25207 12527 25207 12528 25207 12528 25208 12529 25208 12531 25208 12530 25209 12531 25209 12533 25209 12532 25210 12533 25210 12535 25210 12534 25211 12535 25211 12537 25211 12536 25212 12537 25212 12539 25212 12538 25213 12539 25213 12541 25213 12537 25214 12541 25214 12539 25214 12542 25215 12543 25215 12481 25215 12540 25216 12541 25216 12543 25216 12480 25217 12482 25217 12542 25217 12544 25218 12545 25218 12546 25218 12546 25219 12547 25219 12549 25219 12548 25220 12549 25220 12550 25220 12550 25221 12551 25221 12552 25221 12552 25222 12553 25222 12554 25222 12554 25223 12555 25223 12556 25223 12556 25224 12557 25224 12558 25224 12558 25225 12559 25225 12560 25225 12560 25226 12561 25226 12563 25226 12562 25227 12563 25227 12565 25227 12564 25228 12565 25228 12567 25228 12566 25229 12567 25229 12569 25229 12568 25230 12569 25230 12571 25230 12570 25231 12571 25231 12573 25231 12572 25232 12573 25232 12575 25232 12574 25233 12575 25233 12577 25233 12576 25234 12577 25234 12579 25234 12578 25235 12579 25235 12581 25235 12580 25236 12581 25236 12583 25236 12582 25237 12583 25237 12584 25237 12584 25238 12585 25238 12586 25238 12586 25239 12587 25239 12588 25239 12588 25240 12589 25240 12590 25240 12590 25241 12591 25241 12592 25241 12592 25242 12593 25242 12595 25242 12594 25243 12595 25243 12597 25243 12596 25244 12597 25244 12599 25244 12598 25245 12599 25245 12601 25245 12600 25246 12601 25246 12603 25246 12602 25247 12603 25247 12605 25247 12547 25248 12545 25248 12549 25248 12606 25249 12607 25249 12545 25249 12604 25250 12605 25250 12607 25250 12544 25251 12546 25251 12606 25251 12482 25822 12480 25822 12483 25822 12483 25823 12485 25823 12484 25823 12485 25824 12487 25824 12486 25824 12487 25825 12489 25825 12488 25825 12489 25826 12491 25826 12490 25826 12491 25827 12493 25827 12492 25827 12493 25828 12495 25828 12494 25828 12495 25829 12497 25829 12496 25829 12498 25830 12496 25830 12499 25830 12500 25831 12498 25831 12501 25831 12502 25832 12500 25832 12503 25832 12504 25833 12502 25833 12505 25833 12506 25834 12504 25834 12507 25834 12508 25835 12506 25835 12509 25835 12510 25836 12508 25836 12511 25836 12512 25837 12510 25837 12513 25837 12514 25838 12512 25838 12515 25838 12516 25839 12514 25839 12517 25839 12518 25840 12516 25840 12519 25840 12519 25841 12521 25841 12520 25841 12521 25842 12523 25842 12522 25842 12523 25843 12525 25843 12524 25843 12525 25844 12527 25844 12526 25844 12527 25845 12529 25845 12528 25845 12530 25846 12528 25846 12531 25846 12532 25847 12530 25847 12533 25847 12534 25848 12532 25848 12535 25848 12536 25849 12534 25849 12537 25849 12538 25850 12536 25850 12539 25850 12540 25851 12538 25851 12541 25851 12505 25852 12509 25852 12507 25852 12483 25853 12481 25853 12485 25853 12481 25854 12543 25854 12485 25854 12543 25855 12541 25855 12485 25855 12541 25856 12537 25856 12485 25856 12537 25857 12535 25857 12485 25857 12535 25858 12533 25858 12485 25858 12533 25859 12531 25859 12485 25859 12531 25860 12529 25860 12485 25860 12529 25861 12527 25861 12485 25861 12527 25862 12525 25862 12485 25862 12525 25863 12523 25863 12485 25863 12523 25864 12521 25864 12485 25864 12521 25865 12519 25865 12485 25865 12519 25866 12517 25866 12485 25866 12517 25867 12515 25867 12485 25867 12515 25868 12513 25868 12485 25868 12513 25869 12511 25869 12485 25869 12511 25870 12509 25870 12485 25870 12509 25871 12505 25871 12485 25871 12505 25872 12503 25872 12485 25872 12503 25873 12501 25873 12485 25873 12501 25874 12499 25874 12485 25874 12499 25875 12497 25875 12485 25875 12497 25876 12495 25876 12485 25876 12495 25877 12493 25877 12485 25877 12493 25878 12491 25878 12485 25878 12491 25879 12489 25879 12485 25879 12489 25880 12487 25880 12485 25880 12480 25881 12542 25881 12481 25881 12542 25882 12540 25882 12543 25882 12482 25883 12484 25883 12542 25883 12484 25884 12486 25884 12542 25884 12486 25885 12488 25885 12542 25885 12488 25886 12490 25886 12542 25886 12490 25887 12492 25887 12542 25887 12492 25888 12494 25888 12542 25888 12494 25889 12496 25889 12542 25889 12496 25890 12498 25890 12542 25890 12498 25891 12500 25891 12542 25891 12500 25892 12502 25892 12542 25892 12502 25893 12504 25893 12542 25893 12522 25894 12518 25894 12520 25894 12532 25895 12528 25895 12530 25895 12536 25896 12532 25896 12534 25896 12536 25897 12528 25897 12532 25897 12542 25898 12504 25898 12540 25898 12504 25899 12506 25899 12540 25899 12540 25900 12506 25900 12538 25900 12508 25901 12510 25901 12512 25901 12506 25902 12508 25902 12512 25902 12538 25903 12506 25903 12512 25903 12536 25904 12538 25904 12512 25904 12526 25905 12522 25905 12524 25905 12526 25906 12518 25906 12522 25906 12528 25907 12536 25907 12512 25907 12528 25908 12512 25908 12514 25908 12526 25909 12528 25909 12518 25909 12528 25910 12514 25910 12516 25910 12518 25911 12528 25911 12516 25911 12545 25912 12547 25912 12546 25912 12548 25913 12546 25913 12549 25913 12549 25914 12551 25914 12550 25914 12551 25915 12553 25915 12552 25915 12553 25916 12555 25916 12554 25916 12555 25917 12557 25917 12556 25917 12557 25918 12559 25918 12558 25918 12559 25919 12561 25919 12560 25919 12562 25920 12560 25920 12563 25920 12564 25921 12562 25921 12565 25921 12566 25922 12564 25922 12567 25922 12568 25923 12566 25923 12569 25923 12570 25924 12568 25924 12571 25924 12572 25925 12570 25925 12573 25925 12574 25926 12572 25926 12575 25926 12576 25927 12574 25927 12577 25927 12578 25928 12576 25928 12579 25928 12580 25929 12578 25929 12581 25929 12582 25930 12580 25930 12583 25930 12583 25931 12585 25931 12584 25931 12585 25932 12587 25932 12586 25932 12587 25933 12589 25933 12588 25933 12589 25934 12591 25934 12590 25934 12591 25935 12593 25935 12592 25935 12594 25936 12592 25936 12595 25936 12596 25937 12594 25937 12597 25937 12598 25938 12596 25938 12599 25938 12600 25939 12598 25939 12601 25939 12602 25940 12600 25940 12603 25940 12604 25941 12602 25941 12605 25941 12601 25942 12605 25942 12603 25942 12579 25943 12583 25943 12581 25943 12571 25944 12575 25944 12573 25944 12563 25945 12567 25945 12565 25945 12549 25946 12553 25946 12551 25946 12545 25947 12607 25947 12549 25947 12607 25948 12605 25948 12549 25948 12605 25949 12601 25949 12549 25949 12601 25950 12599 25950 12549 25950 12599 25951 12597 25951 12549 25951 12597 25952 12595 25952 12549 25952 12595 25953 12593 25953 12549 25953 12593 25954 12591 25954 12549 25954 12591 25955 12589 25955 12549 25955 12589 25956 12587 25956 12549 25956 12587 25957 12585 25957 12549 25957 12585 25958 12583 25958 12549 25958 12583 25959 12579 25959 12549 25959 12579 25960 12577 25960 12549 25960 12577 25961 12575 25961 12549 25961 12575 25962 12571 25962 12549 25962 12571 25963 12569 25963 12549 25963 12569 25964 12567 25964 12549 25964 12567 25965 12563 25965 12549 25965 12563 25966 12561 25966 12549 25966 12561 25967 12559 25967 12549 25967 12559 25968 12557 25968 12549 25968 12557 25969 12555 25969 12553 25969 12549 25970 12557 25970 12553 25970 12544 25971 12606 25971 12545 25971 12606 25972 12604 25972 12607 25972 12546 25973 12548 25973 12550 25973 12606 25974 12546 25974 12604 25974 12546 25975 12550 25975 12604 25975 12550 25976 12552 25976 12604 25976 12552 25977 12554 25977 12604 25977 12554 25978 12556 25978 12604 25978 12556 25979 12558 25979 12604 25979 12558 25980 12560 25980 12604 25980 12560 25981 12562 25981 12604 25981 12562 25982 12564 25982 12604 25982 12564 25983 12566 25983 12604 25983 12588 25984 12584 25984 12586 25984 12566 25985 12568 25985 12570 25985 12604 25986 12566 25986 12570 25986 12576 25987 12572 25987 12574 25987 12578 25988 12572 25988 12576 25988 12588 25989 12582 25989 12584 25989 12602 25990 12604 25990 12570 25990 12602 25991 12570 25991 12572 25991 12602 25992 12572 25992 12578 25992 12600 25993 12602 25993 12578 25993 12596 25994 12592 25994 12594 25994 12596 25995 12590 25995 12592 25995 12596 25996 12598 25996 12590 25996 12590 25997 12598 25997 12588 25997 12588 25998 12598 25998 12582 25998 12598 25999 12600 25999 12582 25999 12600 26000 12578 26000 12580 26000 12582 26001 12600 26001 12580 26001</p> + </polylist> + <polylist material="mat_battery-material" count="12"> + <input semantic="VERTEX" source="#battery_001-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#battery_001-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>12609 25252 12608 25252 12613 25252 12613 25253 12614 25253 12610 25253 12614 25254 12615 25254 12611 25254 12608 25255 12611 25255 12615 25255 12608 25256 12609 25256 12610 25256 12615 25257 12614 25257 12613 25257 12608 26002 12612 26002 12613 26002 12609 26003 12613 26003 12610 26003 12610 26004 12614 26004 12611 26004 12612 26005 12608 26005 12615 26005 12611 26006 12608 26006 12610 26006 12612 26007 12615 26007 12613 26007</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="battery_001" name="battery_001" type="NODE"> + <matrix sid="transform">-1.89742e-8 0.025 7.1795e-10 0 -0.025 -1.89742e-8 1.61886e-9 0 8.09432e-9 -3.58974e-9 0.005 0 0 0 0 1</matrix> + <instance_geometry url="#battery_001-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="mat_pc_embed-material" target="#mat_pc_embed-material"/> + <instance_material symbol="mat_kinton_struct-material" target="#mat_kinton_struct-material"/> + <instance_material symbol="mat_marker-material" target="#mat_marker-material"/> + <instance_material symbol="mat_helix_front-material" target="#mat_helix_front-material"/> + <instance_material symbol="mat_helix_back-material" target="#mat_helix_back-material"/> + <instance_material symbol="mat_battery-material" target="#mat_battery-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/kinton/kinton2.stl b/kinton_description/meshes/kinton/kinton2.stl new file mode 100644 index 0000000000000000000000000000000000000000..0d292c3d03c3a9875f504626b4bf1dceee6081ce Binary files /dev/null and b/kinton_description/meshes/kinton/kinton2.stl differ diff --git a/kinton_description/meshes/lidarlite_sensor/lidarlite.dae b/kinton_description/meshes/lidarlite_sensor/lidarlite.dae new file mode 100644 index 0000000000000000000000000000000000000000..aa5a54f59ef05fadafa3ba74043c2f1855587d1a --- /dev/null +++ b/kinton_description/meshes/lidarlite_sensor/lidarlite.dae @@ -0,0 +1,199 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Blender User</author> + <authoring_tool>Blender 2.78.0</authoring_tool> + </contributor> + <created>2016-11-30T17:41:47</created> + <modified>2016-11-30T17:41:47</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera-camera" name="Camera"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + <extra> + <technique profile="blender"> + <YF_dofdist>0</YF_dofdist> + <shiftx>0</shiftx> + <shifty>0</shifty> + </technique> + </extra> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp-light" name="Lamp"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>0.000999987</adapt_thresh> + <area_shape>1</area_shape> + <area_size>0.1</area_size> + <area_sizey>0.1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_images/> + <library_effects> + <effect id="Material_001-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0 0 0 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.01507886 0.01507886 0.01507886 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + </profile_COMMON> + </effect> + </library_effects> + <library_materials> + <material id="Material_001-material" name="Material_001"> + <instance_effect url="#Material_001-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="lidarlite-mesh" name="lidarlite"> + <mesh> + <source id="lidarlite-mesh-positions"> + <float_array id="lidarlite-mesh-positions-array" count="3519">-8.382994 -11.33508 9.792975 -23.88299 0.6649218 9.792975 -20.38299 -11.33508 9.792975 -23.88299 -13.83508 9.792975 -20.38299 -13.83508 9.792975 -8.382994 -13.83508 9.792975 8.617007 -13.83508 9.792975 8.617007 -11.33508 9.792975 20.61701 -13.83508 9.792975 24.11701 -13.83508 9.792975 20.61701 -11.33508 9.792975 24.11701 0.6649218 9.792975 -2.882994 -0.8350782 9.792975 -2.882994 -6.335078 9.792975 7.117006 -6.335078 9.792975 7.117006 -0.8350782 9.792975 -3.466516 0.6649218 4.434051 -3.466516 23.16492 4.434051 -4.066137 23.16492 4.477913 -4.066137 0.6649218 4.477913 -4.779968 23.16492 4.642874 -4.779968 0.6649218 4.642874 -5.430109 23.16492 4.911468 -5.430109 0.6649218 4.911468 -6.103205 23.16492 5.323057 -6.103205 0.6649218 5.323057 -6.919403 23.16492 6.030352 -6.919403 0.6649218 6.030352 2.989181 23.16492 4.434051 2.989181 0.6649218 4.434051 6.44207 0.6649218 6.030352 6.44207 23.16492 6.030352 5.62587 23.16492 5.323057 5.62587 0.6649218 5.323057 4.952774 23.16492 4.911468 4.952774 0.6649218 4.911468 4.302633 23.16492 4.642874 4.302633 0.6649218 4.642874 3.588804 23.16492 4.477913 3.588804 0.6649218 4.477913 2.989181 0.6649218 -5.065949 2.989181 23.16492 -5.065949 3.588804 23.16492 -5.109811 3.588804 0.6649218 -5.109811 4.302633 23.16492 -5.274774 4.302633 0.6649218 -5.274774 4.952774 23.16492 -5.543367 4.952774 0.6649218 -5.543367 5.62587 23.16492 -5.954955 5.62587 0.6649218 -5.954955 6.44207 23.16492 -6.66225 6.44207 0.6649218 -6.66225 -3.466516 0.6649218 -5.065949 -3.466516 23.16492 -5.065949 -6.919403 0.6649218 -6.66225 -6.919403 23.16492 -6.66225 -6.103205 23.16492 -5.954955 -6.103205 0.6649218 -5.954955 -5.430109 23.16492 -5.543367 -5.430109 0.6649218 -5.543367 -4.779968 23.16492 -5.274774 -4.779968 0.6649218 -5.274774 -4.066137 23.16492 -5.109811 -4.066137 0.6649218 -5.109811 -10.06884 26.16492 -6.115518 -8.668907 26.16492 -8.186791 -11.10536 26.16492 -6.69455 -10.07561 26.16492 -8.97262 -12.22482 26.16492 -7.09008 -11.59488 26.16492 -9.509413 -13.39503 26.16492 -7.290731 -13.18301 26.16492 -9.781726 -14.58231 26.16492 -7.290731 -14.79432 26.16492 -9.781726 -15.75251 26.16492 -7.09008 -16.38246 26.16492 -9.509413 -16.87198 26.16492 -6.69455 -17.90173 26.16492 -8.97262 -17.90849 26.16492 -6.115518 -19.30843 26.16492 -8.186791 -18.83224 26.16492 -5.369642 -20.56209 26.16492 -7.174533 -19.61665 26.16492 -4.478382 -21.62664 26.16492 -5.964965 -20.23915 26.16492 -3.467376 -22.47146 26.16492 -4.592885 -20.68184 26.16492 -2.36571 -23.07225 26.16492 -3.097766 -20.93197 26.16492 -1.205076 -23.41172 26.16492 -1.522619 -20.98236 26.16492 -0.01886177 -23.48011 26.16492 0.08724021 -20.83156 26.16492 1.158806 -23.27544 26.16492 1.685505 -20.48389 26.16492 2.294044 -22.80361 26.16492 3.226187 -19.94937 26.16492 3.3542 -22.07819 26.16492 4.664968 -19.24337 26.16492 4.308773 -21.12005 26.16492 5.960461 -18.38621 26.16492 5.1303 -19.95676 26.16492 7.07539 -17.40253 26.16492 5.795149 -18.62177 26.16492 7.977686 -16.32065 26.16492 6.284193 -17.1535 26.16492 8.641386 -15.17167 26.16492 6.583363 -15.59418 26.16492 9.047402 -13.98867 26.16492 6.68405 -13.98867 26.16492 9.184052 -12.80566 26.16492 6.583363 -12.38316 26.16492 9.047402 -11.65669 26.16492 6.284193 -10.82384 26.16492 8.641386 -10.5748 26.16492 5.795149 -9.355566 26.16492 7.977686 -9.591128 26.16492 5.1303 -8.020578 26.16492 7.07539 -8.733962 26.16492 4.308773 -6.857281 26.16492 5.960461 -8.027963 26.16492 3.3542 -5.899139 26.16492 4.664968 -7.493443 26.16492 2.294044 -5.173721 26.16492 3.226187 -7.145781 26.16492 1.158806 -4.701893 26.16492 1.685505 -6.994974 26.16492 -0.01886177 -4.497227 26.16492 0.08724021 -7.045362 26.16492 -1.205076 -4.565613 26.16492 -1.522619 -7.2955 26.16492 -2.36571 -4.905083 26.16492 -3.097766 -7.738186 26.16492 -3.467376 -5.505873 26.16492 -4.592885 -8.360688 26.16492 -4.478382 -6.350693 26.16492 -5.964965 -9.145095 26.16492 -5.369642 -7.415247 26.16492 -7.174533 19.76182 26.16492 -3.467376 21.99413 26.16492 -4.592885 19.13931 26.16492 -4.478382 21.14931 26.16492 -5.964965 18.35491 26.16492 -5.369642 20.08475 26.16492 -7.174533 17.43116 26.16492 -6.115518 18.83109 26.16492 -8.186791 16.39464 26.16492 -6.69455 17.4244 26.16492 -8.97262 15.27518 26.16492 -7.09008 15.90513 26.16492 -9.509413 14.10497 26.16492 -7.290731 14.31699 26.16492 -9.781726 12.91769 26.16492 -7.290731 12.70567 26.16492 -9.781726 11.74748 26.16492 -7.09008 11.11754 26.16492 -9.509413 10.62802 26.16492 -6.69455 9.598273 26.16492 -8.97262 9.591509 26.16492 -6.115518 8.191573 26.16492 -8.186791 8.667761 26.16492 -5.369642 6.937914 26.16492 -7.174533 7.883354 26.16492 -4.478382 5.87336 26.16492 -5.964965 7.260853 26.16492 -3.467376 5.028538 26.16492 -4.592885 6.818165 26.16492 -2.36571 4.427748 26.16492 -3.097766 6.568029 26.16492 -1.205076 4.08828 26.16492 -1.522619 6.517641 26.16492 -0.01886177 4.019892 26.16492 0.08724021 6.668446 26.16492 1.158806 4.224558 26.16492 1.685505 7.016109 26.16492 2.294044 4.696386 26.16492 3.226187 7.550629 26.16492 3.3542 5.421806 26.16492 4.664968 8.256628 26.16492 4.308773 6.379946 26.16492 5.960461 9.113791 26.16492 5.1303 7.543241 26.16492 7.07539 10.09747 26.16492 5.795149 8.87823 26.16492 7.977686 11.17935 26.16492 6.284193 10.34651 26.16492 8.641386 12.32833 26.16492 6.583363 11.90582 26.16492 9.047402 13.51133 26.16492 6.68405 13.51133 26.16492 9.184052 14.69434 26.16492 6.583363 15.11684 26.16492 9.047402 15.84331 26.16492 6.284193 16.67616 26.16492 8.641386 16.9252 26.16492 5.795149 18.14443 26.16492 7.977686 17.90887 26.16492 5.1303 19.47942 26.16492 7.07539 18.76604 26.16492 4.308773 20.64272 26.16492 5.960461 19.47204 26.16492 3.3542 21.60086 26.16492 4.664968 20.00656 26.16492 2.294044 22.32628 26.16492 3.226187 20.35422 26.16492 1.158806 22.79811 26.16492 1.685505 20.50503 26.16492 -0.01886177 23.00277 26.16492 0.08724021 20.45464 26.16492 -1.205076 22.93439 26.16492 -1.522619 20.2045 26.16492 -2.36571 22.59492 26.16492 -3.097766 24.11701 -13.83508 -10.20703 20.61701 -13.83508 -10.20703 20.61701 -11.33508 -10.20703 8.617007 -11.33508 -10.20703 -23.88299 0.6649218 -10.20703 24.11701 0.6649218 -10.20703 -20.38299 -13.83508 -10.20703 -23.88299 -13.83508 -10.20703 -20.38299 -11.33508 -10.20703 -8.382994 -11.33508 -10.20703 -8.382994 -13.83508 -10.20703 8.617007 -13.83508 -10.20703 -23.88299 0.6649218 9.792975 16.32006 -13.83508 12.49436 12.70467 -13.83508 -13.37138 16.47278 -13.83508 12.79726 16.57212 -13.83508 13.12162 14.61701 -13.83508 11.54297 12.63321 -13.83508 -13.70299 13.23313 -13.83508 14.98689 13.49706 -13.83508 15.19999 12.63851 -13.83508 17.02838 15.59239 -13.83508 11.79695 15.28328 -13.83508 11.65722 14.95501 -13.83508 11.57174 18.99897 -13.83508 -11.03145 19.2028 -13.83508 -10.79281 16.11835 -13.83508 12.22162 15.87345 -13.83508 11.9869 10.61701 -13.83508 11.79297 13.11566 -13.83508 12.22162 12.91395 -13.83508 12.49436 16.52934 -13.83508 -13.37138 18.64163 -13.83508 -11.89416 18.71489 -13.83508 -11.58899 18.83499 -13.83508 -11.29904 13.95073 -13.83508 11.65722 13.64162 -13.83508 11.79695 12.76122 -13.83508 12.79726 12.66189 -13.83508 13.12162 10.61701 -13.83508 13.79297 13.23917 -13.83508 17.30649 13.7932 -13.83508 15.36543 13.87741 -13.83508 17.48195 14.11305 -13.83508 15.47844 14.53584 -13.83508 17.54996 16.00088 -13.83508 -12.51311 16.225 -13.83508 -12.76776 10.03122 -13.83508 -10.79281 14.279 -13.83508 11.57174 9.792578 -13.83508 -10.58899 9.524989 -13.83508 -10.42501 -12.39919 -13.83508 -13.70299 -12.3848 -13.83508 -14.04191 -10.38299 -13.83508 -14.20703 12.61881 -13.83508 13.45809 12.63321 -13.83508 13.79701 10.71271 -13.83508 14.44794 12.70467 -13.83508 14.12862 10.91491 -13.83508 15.07823 12.83116 -13.83508 14.44338 11.2181 -13.83508 15.66663 13.00901 -13.83508 14.73224 11.614 -13.83508 16.19711 12.09181 -13.83508 16.65519 16.40286 -13.83508 -13.05662 19.44144 -13.83508 -10.58899 19.70903 -13.83508 -10.42501 19.99898 -13.83508 -10.30491 20.30414 -13.83508 -10.23165 10.23504 -13.83508 -11.03145 10.39902 -13.83508 -11.29904 10.51912 -13.83508 -11.58899 10.59238 -13.83508 -11.89416 10.61701 -13.83508 -12.20703 12.61881 -13.83508 -14.04191 10.61701 -13.83508 -14.20703 12.66189 -13.83508 -14.37838 10.71271 -13.83508 -14.86199 12.76122 -13.83508 -14.70274 10.91491 -13.83508 -15.49228 12.91395 -13.83508 -15.00564 11.2181 -13.83508 -16.08069 13.11566 -13.83508 -15.27837 11.614 -13.83508 -16.61116 13.36057 -13.83508 -15.5131 12.09181 -13.83508 -17.06924 13.64162 -13.83508 -15.70305 12.63851 -13.83508 -17.44243 13.95073 -13.83508 -15.84278 13.23917 -13.83508 -17.72054 14.279 -13.83508 -15.92826 13.87741 -13.83508 -17.896 14.61701 -13.83508 -15.95703 14.53584 -13.83508 -17.96401 14.95501 -13.83508 -15.92826 15.19647 -13.83508 -17.92272 15.28328 -13.83508 -15.84278 15.8413 -13.83508 -17.77326 15.59239 -13.83508 -15.70305 16.45273 -13.83508 -17.5197 15.87345 -13.83508 -15.5131 17.01409 -13.83508 -17.16896 16.11835 -13.83508 -15.27837 17.51006 -13.83508 -16.7306 16.32006 -13.83508 -15.00564 17.92712 -13.83508 -16.21659 16.47278 -13.83508 -14.70274 18.25389 -13.83508 -15.64095 16.57212 -13.83508 -14.37838 18.48145 -13.83508 -15.01937 16.6152 -13.83508 -14.04191 18.6036 -13.83508 -14.36881 16.60081 -13.83508 -13.70299 18.61701 -13.83508 -13.70703 18.61701 -13.83508 -12.20703 -9.290975 -13.83508 -10.42501 -9.001029 -13.83508 -10.30491 -8.695863 -13.83508 -10.23165 12.83116 -13.83508 -13.05662 13.00901 -13.83508 -12.76776 13.23313 -13.83508 -12.51311 15.12096 -13.83508 -12.02156 15.44081 -13.83508 -12.13457 15.73696 -13.83508 -12.30001 8.929873 -13.83508 -10.23165 9.235041 -13.83508 -10.30491 13.49706 -13.83508 -12.30001 13.7932 -13.83508 -12.13457 14.11305 -13.83508 -12.02156 -15.04927 -13.83508 11.65722 -15.35838 -13.83508 11.79695 -15.63943 -13.83508 11.9869 -15.88434 -13.83508 12.22162 -16.08605 -13.83508 12.49436 -16.23877 -13.83508 12.79726 -16.3381 -13.83508 13.12162 -10.38299 -13.83508 11.79297 -10.38299 -13.83508 13.79297 -12.3848 -13.83508 13.45809 -14.38299 -13.83508 11.54297 -16.3668 -13.83508 -13.70299 -16.29533 -13.83508 -13.37138 -16.16885 -13.83508 -13.05662 -15.99099 -13.83508 -12.76776 -15.76687 -13.83508 -12.51311 -19.20742 -13.83508 -10.58899 -18.96878 -13.83508 -10.79281 -14.72099 -13.83508 11.57174 -15.50294 -13.83508 -12.30001 -15.2068 -13.83508 -12.13457 -14.88695 -13.83508 -12.02156 10.51912 -13.83508 11.17494 10.39902 -13.83508 10.88499 13.36057 -13.83508 11.9869 19.44144 -13.83508 10.17494 19.2028 -13.83508 10.37876 -10.4787 -13.83508 -14.86199 -12.42788 -13.83508 -14.37838 -10.6809 -13.83508 -15.49228 -12.52722 -13.83508 -14.70274 -10.98409 -13.83508 -16.08069 -12.67994 -13.83508 -15.00564 -11.37998 -13.83508 -16.61116 -12.88165 -13.83508 -15.27837 -11.8578 -13.83508 -17.06924 -13.12655 -13.83508 -15.5131 -12.40449 -13.83508 -17.44243 -13.4076 -13.83508 -15.70305 -13.00516 -13.83508 -17.72054 -13.71671 -13.83508 -15.84278 -13.6434 -13.83508 -17.896 -14.04499 -13.83508 -15.92826 -14.30182 -13.83508 -17.96401 -14.38299 -13.83508 -15.95703 -14.96246 -13.83508 -17.92272 -14.72099 -13.83508 -15.92826 -15.60729 -13.83508 -17.77326 -15.04927 -13.83508 -15.84278 -16.21872 -13.83508 -17.5197 -15.35838 -13.83508 -15.70305 -16.78008 -13.83508 -17.16896 -15.63943 -13.83508 -15.5131 -17.27605 -13.83508 -16.7306 -15.88434 -13.83508 -15.27837 -17.69311 -13.83508 -16.21659 -16.08605 -13.83508 -15.00564 -18.01988 -13.83508 -15.64095 -16.23877 -13.83508 -14.70274 -18.24744 -13.83508 -15.01937 -16.3381 -13.83508 -14.37838 -18.36959 -13.83508 -14.36881 -16.38119 -13.83508 -14.04191 -18.38299 -13.83508 -13.70703 -18.38299 -13.83508 -12.20703 -19.47501 -13.83508 -10.42501 -18.76496 -13.83508 -11.03145 -18.60098 -13.83508 -11.29904 -18.48088 -13.83508 -11.58899 -18.40762 -13.83508 -11.89416 -18.38299 -13.83508 11.79297 -18.40762 -13.83508 11.48011 -13.71671 -13.83508 11.65722 -14.04499 -13.83508 11.57174 -13.87904 -13.83508 -12.02156 -13.55919 -13.83508 -12.13457 -12.775 -13.83508 14.73224 -12.59714 -13.83508 14.44338 -10.6809 -13.83508 15.07823 -10.4787 -13.83508 14.44794 -12.47066 -13.83508 14.12862 -12.39919 -13.83508 13.79701 -12.42788 -13.83508 13.12162 -12.52722 -13.83508 12.79726 -10.35837 -13.83508 11.48011 -12.67994 -13.83508 12.49436 -10.28511 -13.83508 11.17494 -12.88165 -13.83508 12.22162 -10.00103 -13.83508 10.6174 -10.16501 -13.83508 10.88499 10.59238 -13.83508 11.48011 18.99897 -13.83508 10.6174 18.83499 -13.83508 10.88499 18.71489 -13.83508 11.17494 14.44739 -13.83508 15.53577 14.61701 -13.83508 15.54297 15.19647 -13.83508 17.50867 14.78662 -13.83508 15.53577 15.8413 -13.83508 17.3592 15.12096 -13.83508 15.47844 16.45273 -13.83508 17.10565 15.44081 -13.83508 15.36543 17.01409 -13.83508 16.7549 15.73696 -13.83508 15.19999 17.51006 -13.83508 16.31655 16.00088 -13.83508 14.98689 17.92712 -13.83508 15.80254 16.225 -13.83508 14.73224 18.25389 -13.83508 15.2269 16.40286 -13.83508 14.44338 18.48145 -13.83508 14.60532 16.52934 -13.83508 14.12862 18.6036 -13.83508 13.95476 16.60081 -13.83508 13.79701 18.61701 -13.83508 13.29297 16.6152 -13.83508 13.45809 18.61701 -13.83508 11.79297 18.64163 -13.83508 11.48011 -20.07013 -13.83508 -10.23165 -19.76496 -13.83508 -10.30491 -18.96878 -13.83508 10.37876 -19.20742 -13.83508 10.17494 -19.47501 -13.83508 10.01096 -10.98409 -13.83508 15.66663 -11.37998 -13.83508 16.19711 -12.99912 -13.83508 14.98689 -11.8578 -13.83508 16.65519 -13.26304 -13.83508 15.19999 -12.40449 -13.83508 17.02838 -13.55919 -13.83508 15.36543 -13.00516 -13.83508 17.30649 -13.87904 -13.83508 15.47844 -13.6434 -13.83508 17.48195 -14.21338 -13.83508 15.53577 -14.30182 -13.83508 17.54996 9.524989 -13.83508 10.01096 9.235041 -13.83508 9.890862 -9.797207 -13.83508 -10.79281 8.929873 -13.83508 9.817599 -10.16501 -13.83508 -11.29904 -10.00103 -13.83508 -11.03145 -12.775 -13.83508 -12.76776 -12.99912 -13.83508 -12.51311 -13.26304 -13.83508 -12.30001 -12.47066 -13.83508 -13.37138 -10.38299 -13.83508 -12.20703 -12.59714 -13.83508 -13.05662 -10.35837 -13.83508 -11.89416 -10.28511 -13.83508 -11.58899 -18.48088 -13.83508 11.17494 -18.60098 -13.83508 10.88499 -18.76496 -13.83508 10.6174 -19.76496 -13.83508 9.890862 -20.07013 -13.83508 9.817599 -18.38299 -13.83508 13.29297 -16.38119 -13.83508 13.45809 -18.36959 -13.83508 13.95476 -16.3668 -13.83508 13.79701 -18.24744 -13.83508 14.60532 -16.29533 -13.83508 14.12862 -18.01988 -13.83508 15.2269 -16.16885 -13.83508 14.44338 -17.69311 -13.83508 15.80254 -15.99099 -13.83508 14.73224 -17.27605 -13.83508 16.31655 -15.76687 -13.83508 14.98689 -16.78008 -13.83508 16.7549 -15.50294 -13.83508 15.19999 -16.21872 -13.83508 17.10565 -15.2068 -13.83508 15.36543 -15.60729 -13.83508 17.3592 -14.88695 -13.83508 15.47844 -14.96246 -13.83508 17.50867 -14.55261 -13.83508 15.53577 -14.38299 -13.83508 15.54297 14.44739 -13.83508 -11.96423 19.99898 -13.83508 9.890862 19.70903 -13.83508 10.01096 -14.55261 -13.83508 -11.96423 -14.38299 -13.83508 -11.95703 -14.21338 -13.83508 -11.96423 10.23504 -13.83508 10.6174 10.03122 -13.83508 10.37876 9.792578 -13.83508 10.17494 -9.558565 -13.83508 -10.58899 20.30414 -13.83508 9.817599 14.78662 -13.83508 -11.96423 14.61701 -13.83508 -11.95703 -8.695863 -13.83508 9.817599 -9.001029 -13.83508 9.890862 -9.290975 -13.83508 10.01096 -13.4076 -13.83508 11.79695 -13.12655 -13.83508 11.9869 -9.558565 -13.83508 10.17494 -9.797207 -13.83508 10.37876 -18.38299 -11.33508 11.79297 -18.38299 -11.33508 13.29297 -18.36959 -11.33508 13.95476 -18.24744 -11.33508 14.60532 -18.01988 -11.33508 15.2269 -17.69311 -11.33508 15.80254 -17.27605 -11.33508 16.31655 -16.78008 -11.33508 16.7549 -16.21872 -11.33508 17.10565 -15.60729 -11.33508 17.3592 -14.96246 -11.33508 17.50867 -14.30182 -11.33508 17.54996 -13.6434 -11.33508 17.48195 -13.00516 -11.33508 17.30649 -12.40449 -11.33508 17.02838 -11.8578 -11.33508 16.65519 -11.37998 -11.33508 16.19711 -10.98409 -11.33508 15.66663 -10.6809 -11.33508 15.07823 -10.4787 -11.33508 14.44794 -10.38299 -11.33508 13.79297 -10.38299 -11.33508 11.79297 -14.55261 -11.33508 15.53577 -14.38299 -11.33508 15.54297 -14.88695 -11.33508 15.47844 -15.2068 -11.33508 15.36543 -15.50294 -11.33508 15.19999 -15.76687 -11.33508 14.98689 -15.99099 -11.33508 14.73224 -16.16885 -11.33508 14.44338 -16.29533 -11.33508 14.12862 -16.3668 -11.33508 13.79701 -16.38119 -11.33508 13.45809 -16.3381 -11.33508 13.12162 -16.23877 -11.33508 12.79726 -16.08605 -11.33508 12.49436 -15.88434 -11.33508 12.22162 -15.63943 -11.33508 11.9869 -15.35838 -11.33508 11.79695 -15.04927 -11.33508 11.65722 -14.72099 -11.33508 11.57174 -14.38299 -11.33508 11.54297 -14.04499 -11.33508 11.57174 -13.71671 -11.33508 11.65722 -13.4076 -11.33508 11.79695 -13.12655 -11.33508 11.9869 -12.88165 -11.33508 12.22162 -12.67994 -11.33508 12.49436 -12.52722 -11.33508 12.79726 -12.42788 -11.33508 13.12162 -12.3848 -11.33508 13.45809 -12.39919 -11.33508 13.79701 -12.47066 -11.33508 14.12862 -12.59714 -11.33508 14.44338 -12.775 -11.33508 14.73224 -12.99912 -11.33508 14.98689 -13.26304 -11.33508 15.19999 -13.55919 -11.33508 15.36543 -13.87904 -11.33508 15.47844 -14.21338 -11.33508 15.53577 -10.28511 -11.33508 11.17494 -10.16501 -11.33508 10.88499 -19.20742 -11.33508 10.17494 -19.47501 -11.33508 10.01096 -9.290975 -11.33508 10.01096 -9.558565 -11.33508 10.17494 -9.797207 -11.33508 10.37876 -19.76496 -11.33508 9.890862 -9.001029 -11.33508 9.890862 -20.07013 -11.33508 9.817599 -8.695863 -11.33508 9.817599 -18.40762 -11.33508 11.48011 -18.48088 -11.33508 11.17494 -18.96878 -11.33508 10.37876 -18.76496 -11.33508 10.6174 -18.60098 -11.33508 10.88499 -10.00103 -11.33508 10.6174 -10.35837 -11.33508 11.48011 10.61701 -11.33508 13.79297 10.71271 -11.33508 14.44794 10.91491 -11.33508 15.07823 11.2181 -11.33508 15.66663 11.614 -11.33508 16.19711 12.09181 -11.33508 16.65519 12.63851 -11.33508 17.02838 13.23917 -11.33508 17.30649 13.87741 -11.33508 17.48195 14.53584 -11.33508 17.54996 15.19647 -11.33508 17.50867 15.8413 -11.33508 17.3592 16.45273 -11.33508 17.10565 17.01409 -11.33508 16.7549 17.51006 -11.33508 16.31655 17.92712 -11.33508 15.80254 18.25389 -11.33508 15.2269 18.48145 -11.33508 14.60532 18.6036 -11.33508 13.95476 18.61701 -11.33508 13.29297 18.61701 -11.33508 11.79297 10.61701 -11.33508 11.79297 14.44739 -11.33508 15.53577 14.61701 -11.33508 15.54297 14.11305 -11.33508 15.47844 13.7932 -11.33508 15.36543 13.49706 -11.33508 15.19999 13.23313 -11.33508 14.98689 13.00901 -11.33508 14.73224 12.83116 -11.33508 14.44338 12.70467 -11.33508 14.12862 12.63321 -11.33508 13.79701 12.61881 -11.33508 13.45809 12.66189 -11.33508 13.12162 12.76122 -11.33508 12.79726 12.91395 -11.33508 12.49436 13.11566 -11.33508 12.22162 13.36057 -11.33508 11.9869 13.64162 -11.33508 11.79695 13.95073 -11.33508 11.65722 14.279 -11.33508 11.57174 14.61701 -11.33508 11.54297 14.95501 -11.33508 11.57174 15.28328 -11.33508 11.65722 15.59239 -11.33508 11.79695 15.87345 -11.33508 11.9869 16.11835 -11.33508 12.22162 16.32006 -11.33508 12.49436 16.47278 -11.33508 12.79726 16.57212 -11.33508 13.12162 16.6152 -11.33508 13.45809 16.60081 -11.33508 13.79701 16.52934 -11.33508 14.12862 16.40286 -11.33508 14.44338 16.225 -11.33508 14.73224 16.00088 -11.33508 14.98689 15.73696 -11.33508 15.19999 15.44081 -11.33508 15.36543 15.12096 -11.33508 15.47844 14.78662 -11.33508 15.53577 9.792578 -11.33508 10.17494 9.524989 -11.33508 10.01096 10.59238 -11.33508 11.48011 10.51912 -11.33508 11.17494 9.235041 -11.33508 9.890862 10.03122 -11.33508 10.37876 10.23504 -11.33508 10.6174 10.39902 -11.33508 10.88499 19.99898 -11.33508 9.890862 19.70903 -11.33508 10.01096 19.44144 -11.33508 10.17494 18.71489 -11.33508 11.17494 18.83499 -11.33508 10.88499 8.929873 -11.33508 9.817599 20.30414 -11.33508 9.817599 18.99897 -11.33508 10.6174 19.2028 -11.33508 10.37876 18.64163 -11.33508 11.48011 -10.38299 -11.33508 -14.20703 -10.4787 -11.33508 -14.86199 -10.6809 -11.33508 -15.49228 -10.98409 -11.33508 -16.08069 -11.37998 -11.33508 -16.61116 -11.8578 -11.33508 -17.06924 -12.40449 -11.33508 -17.44243 -13.00516 -11.33508 -17.72054 -13.6434 -11.33508 -17.896 -14.30182 -11.33508 -17.96401 -14.96246 -11.33508 -17.92272 -15.60729 -11.33508 -17.77326 -16.21872 -11.33508 -17.5197 -16.78008 -11.33508 -17.16896 -17.27605 -11.33508 -16.7306 -17.69311 -11.33508 -16.21659 -18.01988 -11.33508 -15.64095 -18.24744 -11.33508 -15.01937 -18.36959 -11.33508 -14.36881 -18.38299 -11.33508 -13.70703 -18.38299 -11.33508 -12.20703 -10.38299 -11.33508 -12.20703 -14.55261 -11.33508 -11.96423 -14.38299 -11.33508 -11.95703 -14.88695 -11.33508 -12.02156 -15.2068 -11.33508 -12.13457 -15.50294 -11.33508 -12.30001 -15.76687 -11.33508 -12.51311 -15.99099 -11.33508 -12.76776 -16.16885 -11.33508 -13.05662 -16.29533 -11.33508 -13.37138 -16.3668 -11.33508 -13.70299 -16.38119 -11.33508 -14.04191 -16.3381 -11.33508 -14.37838 -16.23877 -11.33508 -14.70274 -16.08605 -11.33508 -15.00564 -15.88434 -11.33508 -15.27837 -15.63943 -11.33508 -15.5131 -15.35838 -11.33508 -15.70305 -15.04927 -11.33508 -15.84278 -14.72099 -11.33508 -15.92826 -14.38299 -11.33508 -15.95703 -14.04499 -11.33508 -15.92826 -13.71671 -11.33508 -15.84278 -13.4076 -11.33508 -15.70305 -13.12655 -11.33508 -15.5131 -12.88165 -11.33508 -15.27837 -12.67994 -11.33508 -15.00564 -12.52722 -11.33508 -14.70274 -12.42788 -11.33508 -14.37838 -12.3848 -11.33508 -14.04191 -12.39919 -11.33508 -13.70299 -12.47066 -11.33508 -13.37138 -12.59714 -11.33508 -13.05662 -12.775 -11.33508 -12.76776 -12.99912 -11.33508 -12.51311 -13.26304 -11.33508 -12.30001 -13.55919 -11.33508 -12.13457 -13.87904 -11.33508 -12.02156 -14.21338 -11.33508 -11.96423 -19.47501 -11.33508 -10.42501 -19.76496 -11.33508 -10.30491 -9.001029 -11.33508 -10.30491 -9.290975 -11.33508 -10.42501 -18.60098 -11.33508 -11.29904 -18.76496 -11.33508 -11.03145 -19.20742 -11.33508 -10.58899 -18.96878 -11.33508 -10.79281 -8.695863 -11.33508 -10.23165 -20.07013 -11.33508 -10.23165 -18.40762 -11.33508 -11.89416 -18.48088 -11.33508 -11.58899 -9.558565 -11.33508 -10.58899 -9.797207 -11.33508 -10.79281 -10.00103 -11.33508 -11.03145 -10.35837 -11.33508 -11.89416 -10.28511 -11.33508 -11.58899 -10.16501 -11.33508 -11.29904 18.61701 -11.33508 -12.20703 18.61701 -11.33508 -13.70703 18.6036 -11.33508 -14.36881 18.48145 -11.33508 -15.01937 18.25389 -11.33508 -15.64095 17.92712 -11.33508 -16.21659 17.51006 -11.33508 -16.7306 17.01409 -11.33508 -17.16896 16.45273 -11.33508 -17.5197 15.8413 -11.33508 -17.77326 15.19647 -11.33508 -17.92272 14.53584 -11.33508 -17.96401 13.87741 -11.33508 -17.896 13.23917 -11.33508 -17.72054 12.63851 -11.33508 -17.44243 12.09181 -11.33508 -17.06924 11.614 -11.33508 -16.61116 11.2181 -11.33508 -16.08069 10.91491 -11.33508 -15.49228 10.71271 -11.33508 -14.86199 10.61701 -11.33508 -14.20703 10.61701 -11.33508 -12.20703 14.44739 -11.33508 -11.96423 14.61701 -11.33508 -11.95703 14.11305 -11.33508 -12.02156 13.7932 -11.33508 -12.13457 13.49706 -11.33508 -12.30001 13.23313 -11.33508 -12.51311 13.00901 -11.33508 -12.76776 12.83116 -11.33508 -13.05662 12.70467 -11.33508 -13.37138 12.63321 -11.33508 -13.70299 12.61881 -11.33508 -14.04191 12.66189 -11.33508 -14.37838 12.76122 -11.33508 -14.70274 12.91395 -11.33508 -15.00564 13.11566 -11.33508 -15.27837 13.36057 -11.33508 -15.5131 13.64162 -11.33508 -15.70305 13.95073 -11.33508 -15.84278 14.279 -11.33508 -15.92826 14.61701 -11.33508 -15.95703 14.95501 -11.33508 -15.92826 15.28328 -11.33508 -15.84278 15.59239 -11.33508 -15.70305 15.87345 -11.33508 -15.5131 16.11835 -11.33508 -15.27837 16.32006 -11.33508 -15.00564 16.47278 -11.33508 -14.70274 16.57212 -11.33508 -14.37838 16.6152 -11.33508 -14.04191 16.60081 -11.33508 -13.70299 16.52934 -11.33508 -13.37138 16.40286 -11.33508 -13.05662 16.225 -11.33508 -12.76776 16.00088 -11.33508 -12.51311 15.73696 -11.33508 -12.30001 15.44081 -11.33508 -12.13457 15.12096 -11.33508 -12.02156 14.78662 -11.33508 -11.96423 9.524989 -11.33508 -10.42501 9.235041 -11.33508 -10.30491 19.70903 -11.33508 -10.42501 19.99898 -11.33508 -10.30491 9.792578 -11.33508 -10.58899 19.44144 -11.33508 -10.58899 19.2028 -11.33508 -10.79281 18.99897 -11.33508 -11.03145 10.59238 -11.33508 -11.89416 10.51912 -11.33508 -11.58899 10.39902 -11.33508 -11.29904 10.23504 -11.33508 -11.03145 10.03122 -11.33508 -10.79281 20.30414 -11.33508 -10.23165 8.929873 -11.33508 -10.23165 18.83499 -11.33508 -11.29904 18.71489 -11.33508 -11.58899 18.64163 -11.33508 -11.89416 6.937914 0.6649218 -7.174533 6.379946 23.16492 5.960461 5.421806 23.16492 4.664968 4.696386 23.16492 3.226187 4.224558 23.16492 1.685505 4.019892 23.16492 0.08724021 4.08828 23.16492 -1.522619 4.427748 23.16492 -3.097766 5.028538 23.16492 -4.592885 5.87336 23.16492 -5.964965 8.191573 0.6649218 -8.186791 9.598273 0.6649218 -8.97262 11.11754 0.6649218 -9.509413 12.70567 0.6649218 -9.781726 14.31699 0.6649218 -9.781726 15.90513 0.6649218 -9.509413 17.4244 0.6649218 -8.97262 18.83109 0.6649218 -8.186791 20.08475 0.6649218 -7.174533 21.14931 0.6649218 -5.964965 21.99413 0.6649218 -4.592885 22.59492 0.6649218 -3.097766 22.93439 0.6649218 -1.522619 23.00277 0.6649218 0.08724021 22.79811 0.6649218 1.685505 22.32628 0.6649218 3.226187 21.60086 0.6649218 4.664968 20.64272 0.6649218 5.960461 19.47942 0.6649218 7.07539 18.14443 0.6649218 7.977686 16.67616 0.6649218 8.641386 15.11684 0.6649218 9.047402 13.51133 0.6649218 9.184052 11.90582 0.6649218 9.047402 10.34651 0.6649218 8.641386 8.87823 0.6649218 7.977686 7.543241 0.6649218 7.07539 -6.350693 23.16492 -5.964965 -5.505873 23.16492 -4.592885 -4.905083 23.16492 -3.097766 -4.565613 23.16492 -1.522619 -4.497227 23.16492 0.08724021 -4.701893 23.16492 1.685505 -5.173721 23.16492 3.226187 -5.899139 23.16492 4.664968 -6.857281 23.16492 5.960461 -8.020578 0.6649218 7.07539 -9.355566 0.6649218 7.977686 -10.82384 0.6649218 8.641386 -12.38316 0.6649218 9.047402 -13.98867 0.6649218 9.184052 -15.59418 0.6649218 9.047402 -17.1535 0.6649218 8.641386 -18.62177 0.6649218 7.977686 -19.95676 0.6649218 7.07539 -21.12005 0.6649218 5.960461 -22.07819 0.6649218 4.664968 -22.80361 0.6649218 3.226187 -23.27544 0.6649218 1.685505 -23.48011 0.6649218 0.08724021 -23.41172 0.6649218 -1.522619 -23.07225 0.6649218 -3.097766 -22.47146 0.6649218 -4.592885 -21.62664 0.6649218 -5.964965 -20.56209 0.6649218 -7.174533 -19.30843 0.6649218 -8.186791 -17.90173 0.6649218 -8.97262 -16.38246 0.6649218 -9.509413 -14.79432 0.6649218 -9.781726 -13.18301 0.6649218 -9.781726 -11.59488 0.6649218 -9.509413 -10.07561 0.6649218 -8.97262 -8.668907 0.6649218 -8.186791 -7.415247 0.6649218 -7.174533 -15.17167 23.16492 6.583363 -13.98867 23.16492 6.68405 -12.80566 23.16492 6.583363 -11.65669 23.16492 6.284193 -10.5748 23.16492 5.795149 -9.591128 23.16492 5.1303 -8.733962 23.16492 4.308773 -8.027963 23.16492 3.3542 -7.493443 23.16492 2.294044 -7.145781 23.16492 1.158806 -6.994974 23.16492 -0.01886177 -7.045362 23.16492 -1.205076 -7.2955 23.16492 -2.36571 -7.738186 23.16492 -3.467376 -8.360688 23.16492 -4.478382 -9.145095 23.16492 -5.369642 -10.06884 23.16492 -6.115518 -11.10536 23.16492 -6.69455 -12.22482 23.16492 -7.09008 -13.39503 23.16492 -7.290731 -14.58231 23.16492 -7.290731 -15.75251 23.16492 -7.09008 -16.87198 23.16492 -6.69455 -17.90849 23.16492 -6.115518 -18.83224 23.16492 -5.369642 -19.61665 23.16492 -4.478382 -20.23915 23.16492 -3.467376 -20.68184 23.16492 -2.36571 -20.93197 23.16492 -1.205076 -20.98236 23.16492 -0.01886177 -20.83156 23.16492 1.158806 -20.48389 23.16492 2.294044 -19.94937 23.16492 3.3542 -19.24337 23.16492 4.308773 -18.38621 23.16492 5.1303 -17.40253 23.16492 5.795149 -16.32065 23.16492 6.284193 12.32833 23.16492 6.583363 13.51133 23.16492 6.68405 14.69434 23.16492 6.583363 15.84331 23.16492 6.284193 16.9252 23.16492 5.795149 17.90887 23.16492 5.1303 18.76604 23.16492 4.308773 19.47204 23.16492 3.3542 20.00656 23.16492 2.294044 20.35422 23.16492 1.158806 20.50503 23.16492 -0.01886177 20.45464 23.16492 -1.205076 20.2045 23.16492 -2.36571 19.76182 23.16492 -3.467376 19.13931 23.16492 -4.478382 18.35491 23.16492 -5.369642 17.43116 23.16492 -6.115518 16.39464 23.16492 -6.69455 15.27518 23.16492 -7.09008 14.10497 23.16492 -7.290731 12.91769 23.16492 -7.290731 11.74748 23.16492 -7.09008 10.62802 23.16492 -6.69455 9.591509 23.16492 -6.115518 8.667761 23.16492 -5.369642 7.883354 23.16492 -4.478382 7.260853 23.16492 -3.467376 6.818165 23.16492 -2.36571 6.568029 23.16492 -1.205076 6.517641 23.16492 -0.01886177 6.668446 23.16492 1.158806 7.016109 23.16492 2.294044 7.550629 23.16492 3.3542 8.256628 23.16492 4.308773 9.113791 23.16492 5.1303 10.09747 23.16492 5.795149 11.17935 23.16492 6.284193 -2.882994 -6.335078 9.692975 -2.882994 -0.8350782 9.692975 7.117006 -0.8350782 9.692975 7.117006 -6.335078 9.692975 3.89135 -1.510107 9.692975 3.89135 -3.259362 9.692975 6.708752 -3.259362 9.692975 -2.53771 -3.259362 9.692975 0.08460807 -3.259362 9.692975 0.08460807 -1.510107 9.692975 6.708752 -5.805627 9.692975 -2.53771 -5.805627 9.692975 -2.53771 -3.259362 5.792976 0.08460807 -3.259362 5.792976 -2.53771 -5.805627 5.792976 6.708752 -5.805627 5.792976 6.708752 -3.259362 5.792976 3.89135 -3.259362 5.792976 3.89135 -1.510107 5.792976 0.08460807 -1.510107 5.792976 -2.180618 -4.354571 5.792976 6.176002 -4.354571 5.792976 -2.180618 -5.061084 5.792976 6.176002 -5.061084 5.792976 6.176002 -5.061084 9.692975 6.176002 -4.354571 9.692975 -2.180618 -5.061084 9.692975 -2.180618 -4.354571 9.692975 -12.22482 21.16492 -7.09008 -13.98867 21.16492 6.68405 -15.17167 21.16492 6.583363 -16.32065 21.16492 6.284193 -17.40253 21.16492 5.795149 -18.38621 21.16492 5.1303 -11.10536 21.16492 -6.69455 -10.06884 21.16492 -6.115518 -7.2955 21.16492 -2.36571 -19.24337 21.16492 4.308773 -19.94937 21.16492 3.3542 -20.48389 21.16492 2.294044 -7.045362 21.16492 -1.205076 -6.994974 21.16492 -0.01886177 -8.027963 21.16492 3.3542 -8.733962 21.16492 4.308773 -9.591128 21.16492 5.1303 -10.5748 21.16492 5.795149 -11.65669 21.16492 6.284193 -12.80566 21.16492 6.583363 -20.83156 21.16492 1.158806 -20.98236 21.16492 -0.01886177 -20.93197 21.16492 -1.205076 -20.68184 21.16492 -2.36571 -20.23915 21.16492 -3.467376 -19.61665 21.16492 -4.478382 -9.145095 21.16492 -5.369642 -8.360688 21.16492 -4.478382 -7.738186 21.16492 -3.467376 -7.145781 21.16492 1.158806 -7.493443 21.16492 2.294044 -18.83224 21.16492 -5.369642 -14.58231 21.16492 -7.290731 -13.39503 21.16492 -7.290731 -17.90849 21.16492 -6.115518 -16.87198 21.16492 -6.69455 -15.75251 21.16492 -7.09008 -17.40253 0.6649218 5.795149 -16.32065 0.6649218 6.284193 -12.22482 0.6649218 -7.09008 -13.39503 0.6649218 -7.290731 -14.58231 0.6649218 -7.290731 -20.68184 0.6649218 -2.36571 -15.17167 0.6649218 6.583363 -13.98867 0.6649218 6.68405 -12.80566 0.6649218 6.583363 -20.93197 0.6649218 -1.205076 -20.98236 0.6649218 -0.01886177 -20.83156 0.6649218 1.158806 -20.48389 0.6649218 2.294044 -19.94937 0.6649218 3.3542 -19.24337 0.6649218 4.308773 -18.38621 0.6649218 5.1303 -11.65669 0.6649218 6.284193 -10.5748 0.6649218 5.795149 -9.591128 0.6649218 5.1303 -8.733962 0.6649218 4.308773 -8.027963 0.6649218 3.3542 -7.493443 0.6649218 2.294044 -10.06884 0.6649218 -6.115518 -11.10536 0.6649218 -6.69455 -7.2955 0.6649218 -2.36571 -7.045362 0.6649218 -1.205076 -15.75251 0.6649218 -7.09008 -19.61665 0.6649218 -4.478382 -20.23915 0.6649218 -3.467376 -16.87198 0.6649218 -6.69455 -17.90849 0.6649218 -6.115518 -18.83224 0.6649218 -5.369642 -7.145781 0.6649218 1.158806 -6.994974 0.6649218 -0.01886177 -7.738186 0.6649218 -3.467376 -8.360688 0.6649218 -4.478382 -9.145095 0.6649218 -5.369642 18.76604 21.16492 4.308773 17.90887 21.16492 5.1303 7.883354 21.16492 -4.478382 16.9252 21.16492 5.795149 19.13931 21.16492 -4.478382 19.76182 21.16492 -3.467376 20.2045 21.16492 -2.36571 20.45464 21.16492 -1.205076 20.50503 21.16492 -0.01886177 20.35422 21.16492 1.158806 8.667761 21.16492 -5.369642 9.591509 21.16492 -6.115518 17.43116 21.16492 -6.115518 20.00656 21.16492 2.294044 19.47204 21.16492 3.3542 15.84331 21.16492 6.284193 14.69434 21.16492 6.583363 13.51133 21.16492 6.68405 12.32833 21.16492 6.583363 11.17935 21.16492 6.284193 10.09747 21.16492 5.795149 18.35491 21.16492 -5.369642 10.62802 21.16492 -6.69455 11.74748 21.16492 -7.09008 12.91769 21.16492 -7.290731 14.10497 21.16492 -7.290731 15.27518 21.16492 -7.09008 16.39464 21.16492 -6.69455 9.113791 21.16492 5.1303 8.256628 21.16492 4.308773 7.550629 21.16492 3.3542 6.818165 21.16492 -2.36571 6.668446 21.16492 1.158806 6.568029 21.16492 -1.205076 6.517641 21.16492 -0.01886177 7.016109 21.16492 2.294044 7.260853 21.16492 -3.467376 20.50503 0.6649218 -0.01886177 20.45464 0.6649218 -1.205076 7.883354 0.6649218 -4.478382 16.9252 0.6649218 5.795149 17.90887 0.6649218 5.1303 18.76604 0.6649218 4.308773 19.47204 0.6649218 3.3542 20.00656 0.6649218 2.294044 20.35422 0.6649218 1.158806 20.2045 0.6649218 -2.36571 19.76182 0.6649218 -3.467376 19.13931 0.6649218 -4.478382 18.35491 0.6649218 -5.369642 17.43116 0.6649218 -6.115518 8.667761 0.6649218 -5.369642 7.260853 0.6649218 -3.467376 6.818165 0.6649218 -2.36571 11.17935 0.6649218 6.284193 6.568029 0.6649218 -1.205076 12.32833 0.6649218 6.583363 13.51133 0.6649218 6.68405 14.69434 0.6649218 6.583363 15.84331 0.6649218 6.284193 9.591509 0.6649218 -6.115518 16.39464 0.6649218 -6.69455 15.27518 0.6649218 -7.09008 9.113791 0.6649218 5.1303 6.668446 0.6649218 1.158806 8.256628 0.6649218 4.308773 7.016109 0.6649218 2.294044 7.550629 0.6649218 3.3542 14.10497 0.6649218 -7.290731 12.91769 0.6649218 -7.290731 10.62802 0.6649218 -6.69455 11.74748 0.6649218 -7.09008 6.517641 0.6649218 -0.01886177 10.09747 0.6649218 5.795149</float_array> + <technique_common> + <accessor source="#lidarlite-mesh-positions-array" count="1173" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="lidarlite-mesh-normals"> + <float_array id="lidarlite-mesh-normals-array" count="4137">0 0 1 -6.01332e-7 0 1 6.01332e-7 0 1 0.07295334 0 0.9973354 0.07295334 0 0.9973354 0.2251586 0 0.9743221 0.3818309 0 0.9242323 0.381831 0 0.9242322 0.5216828 0 0.8531395 0.5216829 0 0.8531396 0.6548896 0 0.7557246 0.6548897 0 0.7557246 -0.6548886 0 0.7557255 -0.6548888 0 0.7557255 -0.5216828 0 0.8531395 -0.5216829 0 0.8531396 -0.3818309 0 0.9242323 -0.381831 0 0.9242322 -0.2251592 0 0.9743221 -0.2251592 0 0.9743221 -0.0729531 0 0.9973354 -0.0729531 0 0.9973354 -0.0729531 0 -0.9973354 -0.0729531 0 -0.9973354 -0.2251619 0 -0.9743214 -0.225161 0 -0.9743216 -0.3818301 0 -0.9242326 -0.3818302 0 -0.9242326 -0.5216816 0 -0.8531402 -0.5216829 0 -0.8531396 -0.6548886 0 -0.7557255 -0.6548888 0 -0.7557255 0 0 -1 0.6548896 0 -0.7557246 0.6548897 0 -0.7557246 0.5216828 0 -0.8531395 0.5216816 0 -0.8531403 0.3818301 0 -0.9242326 0.3818302 0 -0.9242326 0.2251604 0 -0.9743218 0.2251613 0 -0.9743216 0.07295334 0 -0.9973354 0.07295334 0 -0.9973354 0 1 0 0 1 -1.90081e-6 0 1 6.44915e-7 0 1 8.263e-7 0 1 1.9008e-6 0 1 -1.28983e-6 0 1 -1.28983e-6 0 1 2.57966e-6 0 1 -1.90081e-6 0 1 -4.75201e-7 0 1 -9.50402e-7 0 1 -1.0692e-6 0 1 5.15933e-6 0 1 -2.37601e-6 0 1 -9.50404e-7 0 1 -3.8016e-6 0 1 -2.57966e-6 0 1 2.57967e-6 0 1 1.9008e-6 0 1 3.22458e-7 0 1 -1.9008e-6 0 1 9.50403e-7 0 1 -1.28983e-6 0 1 2.57966e-6 0 1 -2.57967e-6 0 1 9.50404e-7 0 1 -7.12801e-7 0 1 1.0098e-6 0 1 4.75201e-7 0 1 -1.90081e-6 0 1 1.9008e-6 0 1 1.90081e-6 0 1 1.90081e-6 0 1 -2.41844e-7 0 1 1.9008e-6 0 1 2.57966e-6 0 1 -1.90081e-6 0 1 4.75202e-7 0 1 -7.12802e-7 0 1 -7.12801e-7 0 1 -9.50404e-7 0 1 -1.9008e-6 0 1 -3.80161e-6 0 1 -2.57966e-6 0 1 1.28983e-6 0 1 4.75202e-7 0 1 1.6632e-6 0 1 7.12803e-7 0 1 -4.75202e-7 -6.01332e-7 0 -1 6.01332e-7 0 -1 -1 0 0 1 0 0 0 -1 0 0 -1 -9.35899e-7 0 -1 0 0 -1 8.76935e-7 0 -1 2.48371e-6 0 -1 2.66698e-6 0 -1 -7.46068e-6 0 -1 -6.17825e-6 0 -1 -8.99418e-7 0 -1 -7.13287e-7 0 -1 5.3534e-7 0 -1 -7.14263e-7 0 -1 -2.15949e-6 0 -1 1.22998e-6 0 -1 9.59573e-7 0 -1 -1.56999e-6 0 -1 2.09305e-6 0 -1 2.09289e-6 0 -1 2.0928e-6 0 -1 4.04907e-7 0 -1 4.06919e-7 0 -1 -7.15322e-7 0 -1 9.27225e-7 0 -1 -1.3692e-6 0 -1 1.09537e-6 0 -1 -7.81422e-7 0 -1 -9.03149e-7 0 -1 -3.60438e-7 0 -1 1.08098e-6 0 -1 7.20412e-7 0 -1 7.20164e-7 0 -1 -5.62335e-6 0 -1 2.15885e-6 0 -1 2.81635e-6 0 -1 -1.43803e-6 0 -1 3.53016e-7 0 -1 -7.0675e-7 0 -1 -1.43374e-6 0 -1 5.67241e-6 0 -1 7.16465e-7 0 -1 -1.43209e-6 0 -1 1.43123e-6 0 -1 1.25155e-6 0 -1 1.71977e-6 0 -1 -5.70804e-6 0 -1 -8.59004e-7 0 -1 1.2376e-5 0 -1 -4.66158e-6 0 -1 -6.66839e-7 0 -1 1.07156e-6 0 -1 6.0137e-7 0 -1 -4.38224e-7 0 -1 0 0 -1 -2.73576e-7 0 -1 6.76792e-7 0 -1 -1.50965e-6 0 -1 6.79276e-7 0 -1 -3.05529e-7 0 -1 -1.55271e-6 0 -1 -5.72668e-7 0 -1 2.35189e-6 0 -1 -2.0796e-6 0 -1 1.49643e-6 0 -1 -7.41311e-7 0 -1 3.78521e-7 0 -1 -1.38701e-7 0 -1 1.27495e-7 0 -1 3.34713e-6 0 -1 -2.87613e-6 0 -1 -3.52019e-7 0 -1 7.03453e-7 0 -1 -2.81155e-6 0 -1 7.02353e-7 0 -1 -7.01857e-7 0 -1 7.2043e-7 0 -1 -7.20889e-7 0 -1 -1.44219e-6 0 -1 1.40024e-6 0 -1 -1.39952e-6 0 -1 -1.39886e-6 0 -1 -6.99118e-7 0 -1 -5.59075e-6 0 -1 2.79438e-6 0 -1 6.98375e-7 0 -1 -3.49089e-7 0 -1 3.31558e-6 0 -1 9.5958e-7 0 -1 1.09536e-6 0 -1 -6.0112e-7 0 -1 1.4589e-6 0 -1 -9.03155e-7 0 -1 -6.28378e-6 0 -1 -5.72401e-6 0 -1 3.21519e-6 0 -1 -3.03241e-6 0 -1 9.59574e-7 0 -1 5.11834e-6 0 -1 -2.99805e-7 0 -1 -5.90392e-6 0 -1 5.5569e-7 0 -1 1.63196e-5 0 -1 -9.78734e-6 0 -1 -3.84052e-6 0 -1 2.95211e-6 0 -1 -1.04492e-6 0 -1 0 0 -1 -1.84586e-6 0 -1 3.56721e-7 0 -1 -4.23755e-6 0 -1 1.43041e-6 0 -1 2.84273e-6 0 -1 1.41966e-6 0 -1 7.08996e-7 0 -1 -3.54099e-6 0 -1 2.86916e-6 0 -1 2.12229e-6 0 -1 -2.87065e-6 0 -1 2.12008e-6 0 -1 2.11798e-6 0 -1 -2.87352e-6 0 -1 2.8212e-6 0 -1 -2.07933e-6 0 -1 7.46102e-6 0 -1 8.20732e-7 0 -1 -2.00383e-6 0 -1 1.75964e-6 0 -1 -2.74486e-7 0 -1 3.9015e-6 0 -1 -2.03455e-6 0 -1 2.85301e-6 0 -1 5.58081e-6 0 -1 -1.44501e-6 0 -1 -7.22497e-7 0 -1 -2.79054e-6 0 -1 1.39554e-6 0 -1 -4.07252e-6 0 -1 -2.23001e-6 0 -1 1.70249e-5 0 -1 -6.35308e-6 0 -1 -8.91393e-7 0 -1 -6.03049e-6 0 -1 4.74235e-6 0 -1 -7.98493e-7 0 -1 -4.60219e-6 0 -1 -4.10807e-6 0 -1 7.46124e-6 0 -1 -3.69164e-6 0 -1 -4.24862e-7 0 -1 4.89603e-6 0 -1 -2.83917e-6 0 -1 4.90618e-7 0 -1 -9.27214e-7 0 -1 3.32758e-6 0 -1 -4.63843e-6 0 -1 2.88512e-6 0 -1 -3.49893e-6 0 -1 -1.74862e-6 0 -1 1.39828e-6 0 -1 -2.79545e-6 0 -1 1.44384e-6 0 -1 -2.79442e-6 0 -1 1.44407e-6 0 -1 1.39678e-6 0 -1 -7.22151e-7 0 -1 1.39638e-6 0 -1 -1.80561e-7 0 -1 3.61161e-7 0 -1 2.18333e-6 0 -1 -5.40287e-7 0 -1 8.39844e-7 0 -1 -1.19412e-7 0 -1 -1.24706e-5 0 -1 -1.02162e-6 0 -1 4.85219e-6 0 -1 -8.91394e-7 0 -1 -3.88099e-7 0 -1 2.14719e-5 0 -1 2.74029e-7 0 -1 1.35248e-6 0 -1 -2.70764e-7 0 -1 -1.37432e-7 0 -1 1.30698e-7 0 -1 0 0 -1 -1.90314e-5 0 -1 -7.57359e-6 0 -1 6.61423e-6 -0.9997949 0 0.02025425 -0.9828255 0 0.1845377 -0.9828253 0 0.1845385 -0.9390473 0 0.3437881 -0.8696535 0 0.4936626 -0.7765387 0 0.6300696 -0.7765406 0 0.6300673 -0.6622384 0 0.7492933 -0.662241 0 0.749291 -0.5298882 0 0.8480676 -0.5298849 0 0.8480697 -0.3830586 0 0.9237241 -0.3830589 0 0.923724 -0.2258009 0 0.9741735 -0.2258054 0 0.9741725 -0.06237918 0 0.9980526 -0.06237918 0 0.9980526 0.1027436 0 0.994708 0.1027437 0 0.994708 0.2650724 0 0.9642286 0.265072 0 0.9642286 0.4201545 0 0.9074526 0.5637952 0 0.8259146 0.5637921 0 0.8259168 0.6920441 0 0.7218552 0.6920418 0 0.7218576 0.8014204 0 0.5981014 0.8014189 0 0.5981037 0.8889328 0 0.4580377 0.9521993 0 0.3054778 0.9894927 0 0.1445834 0.04246014 0 -0.9990982 -0.04246014 0 -0.9990982 0.0424422 0 -0.9990989 0.1690044 0 -0.9856154 0.1690046 0 -0.9856153 0.3331331 0 -0.9428799 0.4876916 0 -0.8730161 0.62822 0 -0.7780358 0.6282255 0 -0.7780315 0.7506713 0 -0.660676 0.7506752 0 -0.6606715 0.8515274 0 -0.5243104 0.8515298 0 -0.5243063 0.9278917 0 -0.3728498 0.9278905 0 -0.3728529 0.9775543 0 -0.2106837 0.999099 0 -0.04243952 0.999099 0 -0.04243987 0.9919005 0 0.127017 0.9919006 0 0.127017 0.9561661 0 0.2928249 0.8929257 0 0.4502041 0.8039997 0 0.5946298 0.6919379 0 0.721957 0.6919356 0 0.7219592 0.5599783 0 0.8285073 0.5599814 0 0.8285052 0.4118999 0 0.9112292 0.2519769 0 0.9677334 0.2519727 0 0.9677343 0.08480817 0 0.9963973 0.0848037 0 0.9963977 -0.0848034 0 0.9963977 -0.08480793 0 0.9963973 -0.2519735 0 0.9677342 -0.2519776 0 0.967733 -0.4119011 0 0.9112286 -0.4119009 0 0.9112287 -0.5599814 0 0.8285052 -0.5599783 0 0.8285073 -0.6919342 0 0.7219606 -0.6919366 0 0.7219583 -0.8039997 0 0.5946298 -0.8929257 0 0.4502041 -0.9561661 0 0.2928249 -0.9919005 0 0.127017 -0.9919006 0 0.127017 -0.999099 0 -0.04243987 -0.999099 0 -0.04243952 -0.9775549 0 -0.210681 -0.9278886 0 -0.3728578 -0.9278898 0 -0.3728546 -0.851531 0 -0.5243042 -0.8515285 0 -0.5243083 -0.7506752 0 -0.6606715 -0.7506713 0 -0.660676 -0.6282255 0 -0.7780315 -0.62822 0 -0.7780358 -0.4876916 0 -0.8730161 -0.3331331 0 -0.9428799 -0.1690044 0 -0.9856154 -0.1690046 0 -0.9856153 -0.0424422 0 -0.9990989 0 1 7.11805e-6 0 1 7.61267e-5 0 1 -1.86084e-6 0 1 -2.09864e-6 0 1 -7.13289e-7 0 1 0 0 1 -7.1442e-7 0 1 7.14267e-7 0 1 -7.76184e-6 0 1 -8.79616e-6 0 1 1.06967e-5 0 1 -8.58326e-6 0 1 5.80945e-5 0 1 -3.88094e-6 0 1 3.80702e-6 0 1 -2.59971e-6 0 1 -3.56721e-7 0 1 -1.42313e-6 0 1 -1.41966e-6 0 1 1.41798e-6 0 1 1.41639e-6 0 1 -2.86917e-6 0 1 1.41486e-6 0 1 1.76673e-6 0 1 -2.11797e-6 0 1 2.36433e-6 0 1 -2.09863e-6 0 1 5.90392e-6 0 1 -2.77844e-6 0 1 -2.64564e-6 0 1 -3.439e-6 0 1 -5.82835e-6 0 1 6.22835e-6 0 1 7.51272e-6 0 1 -1.98427e-5 0 1 -7.6485e-7 0 1 -1.87982e-6 0 1 -9.59574e-7 0 1 1.56998e-6 0 1 -3.48842e-7 0 1 -1.445e-6 0 1 1.3952e-6 0 1 -7.12775e-7 -0.9894927 0 0.1445834 -0.9521996 0 0.3054765 -0.8889318 0 0.4580398 -0.8889316 0 0.4580401 -0.8014203 0 0.5981018 -0.8014219 0 0.5980996 -0.6920418 0 0.7218576 -0.6920441 0 0.7218552 -0.5637907 0 0.8259177 -0.5637939 0 0.8259156 -0.4201549 0 0.9074525 -0.4201551 0 0.9074523 -0.2650729 0 0.9642284 -0.2650731 0 0.9642284 -0.102743 0 0.994708 -0.102743 0 0.994708 0.06237936 0 0.9980525 0.0623793 0 0.9980525 0.2258063 0 0.9741722 0.2258021 0 0.9741733 0.3830562 0 0.9237251 0.5298874 0 0.848068 0.5298908 0 0.8480659 0.662241 0 0.749291 0.6622384 0 0.7492933 0.7765392 0 0.630069 0.7765374 0 0.6300713 0.8696523 0 0.4936648 0.8696524 0 0.4936646 0.9390473 0 0.3437881 0.9828264 0 0.1845329 0.9828266 0 0.1845321 0.9997949 0 0.02025717 0.0424599 0 -0.9990982 -0.0424599 0 -0.9990983 0.04244196 0 -0.999099 0.169005 0 -0.9856152 0.6282213 0 -0.7780347 0.6282268 0 -0.7780303 0.7506698 0 -0.6606776 0.7506737 0 -0.6606731 0.8515298 0 -0.5243062 0.8515323 0 -0.5243023 0.9278879 0 -0.3728595 0.9278866 0 -0.3728626 0.9775566 0 -0.2106729 0.9919021 0 0.127006 0.9561676 0 0.2928198 0.8929189 0 0.4502176 0.6919394 0 0.7219557 0.691937 0 0.7219579 0.5599757 0 0.828509 0.5599788 0 0.828507 0.411902 0 0.9112282 0.2519804 0 0.9677324 0.2519763 0 0.9677335 0.08480721 0 0.9963974 0.08480268 0 0.9963977 -0.0848037 0 0.9963977 -0.08480817 0 0.9963973 -0.411902 0 0.9112282 -0.5599788 0 0.828507 -0.5599757 0 0.828509 -0.691937 0 0.7219579 -0.6919394 0 0.7219557 -0.8929233 0 0.4502089 -0.8929234 0 0.4502087 -0.9561676 0 0.2928198 -0.9990996 0 -0.04242867 -0.9990996 0 -0.04242825 -0.9775543 0 -0.2106837 -0.9278866 0 -0.3728626 -0.9278879 0 -0.3728595 -0.8515323 0 -0.5243023 -0.8515298 0 -0.5243062 -0.7506737 0 -0.6606731 -0.7506698 0 -0.6606776 -0.6282268 0 -0.7780303 -0.6282213 0 -0.7780347 -0.169005 0 -0.9856152 -0.04244196 0 -0.999099 0 1 -1.44496e-6 0 1 1.39527e-6 0 1 -6.97603e-7 0 1 -2.0928e-6 0 1 7.61296e-5 0 1 -4.64129e-6 0 1 3.28376e-6 0 1 3.49723e-6 0 1 -2.09741e-6 0 1 1.44356e-6 0 1 6.98858e-7 0 1 -1.44384e-6 0 1 -6.98614e-7 0 1 1.39678e-6 0 1 -5.41684e-7 0 1 -7.01596e-7 0 1 -6.99186e-7 0 1 -2.1465e-6 0 1 -2.14346e-6 0 1 1.60539e-6 0 1 -9.59573e-7 0 1 8.99418e-7 0 1 1.66706e-6 0 1 -6.0154e-6 0 1 -5.27848e-5 0 1 6.76805e-6 0 1 -5.94216e-6 0 1 -9.26002e-6 0 1 3.497e-6 0 1 1.33465e-6 0 1 1.06967e-5 0 1 -4.45661e-6 0 1 -4.29022e-7 0 1 2.05998e-5 0 1 -1.08961e-4 0 1 4.51846e-5 0 1 -7.57312e-6 0 1 2.49197e-6 0 1 -6.95597e-7 0 1 1.83222e-6 0 1 1.04578e-6 0 1 -1.28956e-6 0.9894927 0 -0.1445834 0.9521996 0 -0.3054764 0.9521993 0 -0.3054778 0.8889337 0 -0.4580358 0.8889328 0 -0.4580377 0.8014189 0 -0.5981037 0.8014172 0 -0.5981059 0.6920441 0 -0.7218552 0.5637921 0 -0.8259168 0.5637889 0 -0.8259189 0.4201583 0 -0.9074509 0.4201621 0 -0.9074491 0.265068 0 -0.9642298 0.2650678 0 -0.9642299 0.1027527 0 -0.9947069 0.1027391 0 -0.9947084 -0.06237918 0 -0.9980526 -0.06237918 0 -0.9980526 -0.2257922 0 -0.9741755 -0.2258054 0 -0.9741725 -0.3830626 0 -0.9237225 -0.3830667 0 -0.9237207 -0.5298783 0 -0.8480738 -0.5298849 0 -0.8480697 -0.6622436 0 -0.7492887 -0.7765387 0 -0.6300696 -0.776537 0 -0.6300718 -0.8696547 0 -0.4936607 -0.9390473 0 -0.3437881 -0.9390468 0 -0.3437896 -0.9828253 0 -0.1845385 -0.9997949 0 -0.02025419 0.0424512 0 -0.9990986 -0.0424512 0 -0.9990986 0.0424332 0 -0.9990994 0.1690003 0 -0.985616 0.333137 0 -0.9428784 0.333141 0 -0.942877 0.4876984 0 -0.8730122 0.487695 0 -0.8730141 0.6282172 0 -0.778038 0.9775547 0 -0.2106818 0.9919007 0 0.1270158 0.9561669 0 0.2928224 0.8929248 0 0.450206 0.8929265 0 0.4502024 0.803998 0 0.594632 0.6919403 0 0.7219548 0.5599752 0 0.8285095 0.4118962 0 0.9112309 0.2519853 0 0.9677311 0.2519685 0 0.9677355 -0.08480787 0 0.9963974 -0.2519692 0 0.9677353 -0.251986 0 0.9677309 -0.4118974 0 0.9112303 -0.4118972 0 0.9112304 -0.5599752 0 0.8285095 -0.6919389 0 0.7219561 -0.803998 0 0.594632 -0.8929265 0 0.4502024 -0.8929248 0 0.450206 -0.9561669 0 0.2928224 -0.9919007 0 0.1270159 -0.9775553 0 -0.2106791 -0.6282172 0 -0.778038 -0.487695 0 -0.8730141 -0.4876984 0 -0.8730122 -0.333141 0 -0.942877 -0.333137 0 -0.9428784 -0.169 0 -0.9856161 -0.0424332 0 -0.9990994 0 1 -1.11724e-6 0 1 -3.66099e-4 0 1 6.29279e-6 0 1 -1.11724e-6 0 1 7.10988e-7 0 1 -1.54751e-4 0 1 3.64736e-6 0 1 5.72218e-7 0 1 -1.08961e-4 0 1 1.45236e-5 0 1 1.44032e-6 0 1 -1.43979e-6 0 1 5.62338e-6 0 1 -7.19618e-7 0 1 -2.81395e-6 0 1 7.19015e-7 0 1 -7.18691e-7 0 1 7.18355e-7 0 1 -5.29526e-7 0 1 -7.06742e-7 0 1 -7.17641e-7 0 1 -7.17263e-7 0 1 2.83301e-6 0 1 7.16466e-7 0 1 -5.67901e-6 0 1 2.14816e-6 0 1 1.43123e-6 0 1 -5.69304e-6 0 1 -1.78793e-7 0 1 5.70041e-6 0 1 -7.59381e-7 0 1 7.9849e-7 0 1 -4.4698e-6 0 1 1.77008e-6 0 1 8.21612e-7 0 1 -1.16056e-4 0 1 5.83579e-6 0 1 -1.75782e-5 0 1 -1.54771e-6 0 1 -9.69795e-7 0 1 1.38347e-6 0 1 -6.10847e-6 0 1 -2.79927e-7 0.9997949 0 -0.02025705 0.9828264 0 -0.1845329 0.9390468 0 -0.3437896 0.9390473 0 -0.3437881 0.8696534 0 -0.4936628 0.8696536 0 -0.4936627 0.7765355 0 -0.6300736 0.7765374 0 -0.6300713 0.6622436 0 -0.7492887 0.5298874 0 -0.848068 0.5298808 0 -0.8480721 0.383064 0 -0.9237219 0.3830601 0 -0.9237235 0.2258063 0 -0.9741722 0.2257933 0 -0.9741752 0.06237936 0 -0.9980525 0.0623793 0 -0.9980525 -0.1027384 0 -0.9947085 -0.1027521 0 -0.994707 -0.2650687 0 -0.9642297 -0.2650688 0 -0.9642295 -0.4201625 0 -0.907449 -0.420159 0 -0.9074506 -0.5637876 0 -0.8259198 -0.5637907 0 -0.8259177 -0.6920441 0 -0.7218552 -0.8014186 0 -0.598104 -0.8014203 0 -0.5981018 -0.8889318 0 -0.4580398 -0.8889327 0 -0.4580382 -0.9521996 0 -0.3054765 -0.9522001 0 -0.3054751 -0.9894927 0 -0.1445834 0.04245096 0 -0.9990985 -0.04245096 0 -0.9990986 0.04243296 0 -0.9990993 0.1690006 0 -0.985616 0.6282187 0 -0.7780369 0.977557 0 -0.2106711 0.9919021 0 0.1270049 0.9561684 0 0.2928173 0.892918 0 0.4502195 0.8929198 0 0.4502158 0.6919417 0 0.7219534 0.5599726 0 0.8285111 0.4118983 0 0.9112299 0.2519888 0 0.9677302 0.2519721 0 0.9677345 0.08480715 0 0.9963974 -0.4118983 0 0.9112299 -0.5599726 0 0.8285111 -0.6919417 0 0.7219534 -0.8929242 0 0.4502071 -0.8929225 0 0.4502105 -0.9561684 0 0.2928173 -0.9775547 0 -0.2106818 -0.6282187 0 -0.7780369 -0.1690006 0 -0.985616 -0.04243302 0 -0.9990994 0 1 -4.50653e-4 0 1 -7.86601e-7 0 1 -2.23448e-6 0 1 5.33242e-6 0 1 -1.0942e-6 0 1 -2.39169e-5 0 1 6.70341e-6 0 1 5.68789e-6 0 1 -1.16067e-4 0 1 1.05466e-5 0 1 1.08341e-5 0 1 7.98495e-7 0 1 3.71714e-6 0 1 -1.23243e-6 0 1 1.08341e-5 0 1 1.05465e-5 0 1 4.29022e-7 0 1 -1.43054e-5 0 1 1.08961e-4 0 1 -4.51846e-5 0 1 4.10678e-6 0 1 -2.19269e-6 0 1 8.59004e-7 0 1 4.91898e-6 0 1 1.15121e-6 0 1 -5.58413e-6 0 1 1.62506e-6 0 1 -5.58545e-6 0 1 1.44431e-6 0 1 1.08307e-6 0 1 -5.58875e-6 0 1 7.21923e-7 0 1 -5.59075e-6 0 1 1.44358e-6 0 1 7.21465e-7 0 1 7.21297e-7 0 1 1.40024e-6 0 1 7.00936e-7 0 1 7.20429e-7 0 1 -7.20178e-7 0 1 7.19636e-7 0 1 -5.62756e-6 0 1 1.79835e-6 0 1 -1.07855e-6 0 1 3.59356e-7 0.07846391 0 -0.9969171 0.2334409 0 -0.972371 0.2334456 0 -0.9723699 0.3826795 0 -0.9238812 0.3826756 0 -0.9238829 0.5225009 0 -0.8526388 0.5224938 0 -0.8526431 0.6494566 0 -0.7603986 0.6494539 0 -0.7604011 0.7604016 0 -0.6494533 0.8526403 0 -0.5224984 0.8526416 0 -0.5224963 0.9238762 0 -0.3826916 0.9238776 0 -0.3826882 0.9723719 0 -0.2334371 0.9723719 0 -0.233437 0.9969172 0 -0.07846111 -0.07846391 0 -0.9969171 -0.2334382 0 -0.9723717 -0.2334427 0 -0.9723706 -0.382684 0 -0.9238793 -0.3826799 0 -0.9238811 -0.5225009 0 -0.8526388 -0.5224938 0 -0.8526431 -0.6494566 0 -0.7603986 -0.6494539 0 -0.7604011 -0.7604016 0 -0.6494533 -0.8526403 0 -0.5224984 -0.8526416 0 -0.5224963 -0.9238762 0 -0.3826916 -0.9238776 0 -0.3826882 -0.9723719 0 -0.233437 -0.9723719 0 -0.2334371 -0.9969172 0 -0.07846111 0.07846319 0 -0.9969171 0.2334402 0 -0.9723712 0.2334449 0 -0.97237 0.3826853 0 -0.9238788 0.382681 0 -0.9238806 0.6494522 0 -0.7604026 0.6494494 0 -0.760405 0.7604061 0 -0.649448 0.852639 0 -0.5225006 0.8526403 0 -0.5224985 0.9238783 0 -0.3826864 0.9238798 0 -0.382683 0.9723706 0 -0.2334427 -0.07846343 0 -0.996917 -0.07846337 0 -0.9969171 -0.2334396 0 -0.9723713 -0.2334443 0 -0.9723702 -0.3826861 0 -0.9238784 -0.3826818 0 -0.9238802 -0.6494507 0 -0.7604038 -0.6494479 0 -0.7604063 -0.7604045 0 -0.6494497 -0.9238783 0 -0.3826864 -0.9238798 0 -0.382683 -0.9723706 0 -0.2334427 -0.9969173 0 0.07846075 -0.9969172 0 0.07846111 -0.9723717 0 0.2334381 -0.9723714 0 0.2334394 -0.9238783 0 0.3826864 -0.8526416 0 0.5224963 -0.7603996 0 0.6494557 -0.649451 0 0.7604035 -0.5225009 0 0.8526388 -0.382684 0 0.9238793 -0.2334428 0 0.9723705 -0.2334427 0 0.9723706 -0.07845908 0 0.9969174 0.9969173 0 0.07846075 0.9969172 0 0.07846111 0.9723717 0 0.2334383 0.9723714 0 0.2334392 0.9238783 0 0.3826864 0.8526416 0 0.5224963 0.7603996 0 0.6494557 0.649451 0 0.7604035 0.5225009 0 0.8526388 0.3826795 0 0.9238812 0.3826797 0 0.9238811 0.2334456 0 0.9723699 0.07845908 0 0.9969174 0.9723703 0 0.2334439 0.97237 0 0.2334449 0.9238805 0 0.3826813 0.8526403 0 0.5224985 0.7604039 0 0.6494504 0.6494465 0 0.7604073 0.3826853 0 0.9238788 0.3826851 0 0.9238789 0.2334448 0 0.9723701 0.2334449 0 0.97237 0.07845836 0 0.9969174 -0.9723703 0 0.2334439 -0.97237 0 0.2334449 -0.9238805 0 0.3826813 -0.7604026 0 0.6494522 -0.649445 0 0.7604085 -0.3826861 0 0.9238784 -0.382686 0 0.9238786 -0.2334442 0 0.9723703 -0.2334443 0 0.9723702 -0.0784586 0 0.9969175 -0.07845854 0 0.9969174 -0.7185418 0 -0.6954838 -0.7467211 0.04287964 0.6637536 -0.6919391 0 0.721956 -0.8039979 0 0.5946323 -0.8039975 0 0.5946328 -0.8929257 0 0.4502042 -0.8929253 0 0.4502048 -0.9561668 0 0.2928227 -0.9919004 0 0.127018 -0.9990989 0 -0.04244244 -0.9775555 0 -0.210678 -0.9278887 0 -0.3728574 -0.8515295 0 -0.5243068 -0.8515294 0 -0.524307 -0.7749348 0 -0.6320412 -0.7506241 0.01125389 -0.6606337 -0.7185423 0 -0.6954834 -0.6282196 0 -0.7780361 -0.6282197 0 -0.7780361 -0.4876951 0 -0.8730142 -0.4876945 0 -0.8730144 -0.3331401 0 -0.9428774 -0.3331395 0 -0.9428777 -0.1690009 0 -0.9856159 -0.1690016 0 -0.9856158 0.1690008 0 -0.9856159 0.1690001 0 -0.9856161 0.3331401 0 -0.9428774 0.3331409 0 -0.9428771 0.4876955 0 -0.8730139 0.4876961 0 -0.8730136 0.6282184 0 -0.7780371 0.6282185 0 -0.778037 0.7506729 0 -0.6606742 0.7506729 0 -0.6606741 0.8515295 0 -0.5243068 0.8515294 0 -0.5243069 0.9278891 0 -0.3728564 0.9278891 0 -0.3728564 0.9775549 0 -0.2106814 0.9990991 0 -0.04243886 0.9919008 0 0.1270157 0.9919008 0 0.1270157 0.9561661 0 0.2928249 0.9561661 0 0.2928249 0.892926 0 0.4502035 0.892926 0 0.4502035 0.8039971 0 0.5946332 0.8039969 0 0.5946335 0.6919391 0 0.721956 0.6919391 0 0.7219559 0.5599755 0 0.8285092 0.5599756 0 0.8285092 0.4119011 0 0.9112285 0.4119005 0 0.9112288 0.2519778 0 0.967733 0.08480626 0 0.9963975 0.08480697 0 0.9963974 -0.08480697 0 0.9963974 -0.08480626 0 0.9963974 -0.2519783 0 0.967733 -0.2519783 0 0.9677329 -0.4118996 0 0.9112293 -0.4119003 0 0.911229 -0.5599755 0 0.8285092 -0.5599756 0 0.8285092 -0.6883773 0 0.7253528 -0.6883774 0 0.7253528 0.7747764 0.02014994 -0.6319143 0.7506723 0 -0.6606748 0.8515301 0 -0.5243058 0.8515299 0 -0.5243062 0.9278887 0 -0.3728574 0.9775553 0 -0.2106792 0.999099 0 -0.04244124 0.9919004 0 0.127018 0.9561668 0 0.2928227 0.892926 0 0.4502035 0.803997 0 0.5946333 0.747422 0 0.6643495 0.6919361 0.002490937 0.7219545 0.6883765 0 0.7253537 0.6883763 0 0.7253538 0.2519779 0 0.967733 0.2519779 0 0.967733 0.0848062 0 0.9963975 0.08480697 0 0.9963975 -0.08480691 0 0.9963974 -0.0848062 0 0.9963975 -0.251978 0 0.967733 -0.2519781 0 0.967733 -0.4119005 0 0.9112288 -0.4119012 0 0.9112286 -0.6919385 0 0.7219565 -0.6919385 0 0.7219565 -0.8039975 0 0.5946328 -0.8039978 0 0.5946323 -0.8929255 0 0.4502044 -0.9561668 0 0.2928228 -0.9561668 0 0.2928227 -0.9919006 0 0.1270169 -0.9919006 0 0.1270168 -0.9990991 0 -0.04244005 -0.977555 0 -0.2106803 -0.977555 0 -0.2106803 -0.9278891 0 -0.3728564 -0.9278891 0 -0.3728564 -0.8515294 0 -0.5243069 -0.8515295 0 -0.5243068 -0.7506723 0 -0.6606748 -0.7506723 0 -0.6606748 -0.4876955 0 -0.8730138 -0.487695 0 -0.8730141 -0.1690006 0 -0.985616 -0.1690013 0 -0.9856159 0.1690012 0 -0.9856159 0.1690005 0 -0.985616 0.3331397 0 -0.9428776 0.3331403 0 -0.9428773 0.4876947 0 -0.8730143 0.4876953 0 -0.8730139 0.6282193 0 -0.7780364 0.6282194 0 -0.7780363 0.7185423 0 -0.6954834 0.7185418 0 -0.6954838 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 5.3969e-7 0 1 -2.04678e-7 0 1 2.10618e-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 -4.25326e-7 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 2.80493e-7 0 1 1.47952e-7 0 1 0 0 1 0 0 1 0 0 1 3.73989e-7 0 1 -1.82046e-7 0 1 4.25325e-7 0 1 3.02716e-7 0 1 -3.47909e-7 0 1 0 0 1 1.43957e-7 0 1 0 0 1 0 0 1 8.50653e-7 0 1 -4.25323e-7 0 1 -1.86996e-7 0 1 0 0 1 0 0 1 4.87892e-7 0 1 -1.47952e-7 0 1 -2.80496e-7 0 1 -1.04176e-5 0 1 2.39283e-6 0 1 -6.66348e-6 0 1 -1.04163e-5 0 1 1.95685e-6 0 1 1.14296e-5 0 1 -1.14442e-6 0 1 6.2897e-6 0 1 -1.54872e-6 0 1 9.28778e-7 0 1 -2.65673e-6 0 1 1.45528e-4 0 1 -2.40182e-6 0 1 8.30694e-7 0 1 -2.07594e-6 0 1 9.7948e-7 0 1 1.37368e-6 0 1 2.00537e-7 0 1 -2.50856e-7 0 1 -9.26297e-7 0 1 -1.77225e-6 0.08480411 0 -0.9963977 -0.08480399 0 -0.9963977 -0.08480507 0 -0.9963976 -0.2519778 0 -0.9677331 -0.2519791 0 -0.9677327 -0.4119022 0 -0.9112281 -0.5599741 0 -0.8285102 -0.5599746 0 -0.8285098 -0.6919389 0 -0.7219561 -0.803997 0 -0.5946335 -0.8929255 0 -0.4502045 -0.8929258 0 -0.4502041 -0.9561671 0 -0.2928221 -0.9919005 0 -0.127018 -0.999099 0 0.04243999 -0.977555 0 0.2106805 -0.9278889 0 0.3728568 -0.8515291 0 0.5243075 -0.8515292 0 0.5243072 -0.7506719 0 0.6606752 -0.7506725 0 0.6606746 -0.6282203 0 0.7780356 -0.6282209 0 0.778035 -0.4876945 0 0.8730145 -0.487694 0 0.8730147 -0.3331398 0 0.9428775 -0.3331394 0 0.9428776 -0.1689999 0 0.9856161 -0.1690009 0 0.9856159 0.1690008 0 0.985616 0.1689997 0 0.9856161 0.3331398 0 0.9428775 0.3331394 0 0.9428776 0.4876945 0 0.8730145 0.487694 0 0.8730147 0.6282209 0 0.778035 0.6282203 0 0.7780356 0.7506725 0 0.6606746 0.7506729 0 0.660674 0.8515292 0 0.5243072 0.8515291 0 0.5243075 0.9278883 0 0.3728582 0.9775554 0 0.210679 0.999099 0 0.0424416 0.9919005 0 -0.127018 0.9561666 0 -0.2928235 0.892926 0 -0.4502037 0.8039975 0 -0.5946328 0.6919389 0 -0.7219561 0.5599741 0 -0.8285102 0.4119018 0 -0.9112282 0.2519791 0 -0.9677327 0.251978 0 -0.967733 0.08480507 0 -0.9963976 0.08480399 0 -0.9963977 -0.2519773 0 -0.9677332 -0.2519783 0 -0.967733 -0.411903 0 -0.9112278 -0.8039975 0 -0.5946328 -0.892926 0 -0.4502037 -0.9561656 0 -0.2928264 -0.9919008 0 -0.1270148 -0.9775543 0 0.2106836 -0.9278906 0 0.3728527 -0.8515275 0 0.5243102 -0.8515278 0 0.5243096 -0.7506735 0 0.6606734 -0.4876936 0 0.8730149 0.1690004 0 0.9856161 0.1689993 0 0.9856162 0.4876949 0 0.8730141 0.999099 0 0.04243999 0.9919007 0 -0.1270164 0.8039965 0 -0.5946341 0.803997 0 -0.5946335 0.6919406 0 -0.7219545 0 1 5.21899e-6 0 1 -4.22366e-6 0 1 2.31963e-6 0 1 -2.25775e-6 0 1 -3.01831e-7 0 1 1.38496e-7 0 1 2.06937e-6 0 1 -4.91059e-7 0 1 -2.36683e-7 0 1 -1.22764e-7 0 1 -2.76991e-7 0 1 6.70431e-7 0 1 1.90126e-7 0 1 -6.68984e-6 0 1 -1.14245e-6 0 1 -1.14245e-6 0 1 -2.10089e-6 0 1 5.46789e-6 0 1 1.60132e-5 0 1 -1.76734e-6 0 1 -8.57927e-7 0 1 1.87558e-6 0 1 1.60128e-5 0 1 2.73394e-6 0 1 -4.13873e-6 0 1 -4.6316e-7 0 1 -6.89734e-7 0 1 3.70528e-6 0 1 -1.77513e-6 0 1 2.14838e-6 0 1 2.71648e-6 0 1 -8.38038e-7 0 1 -2.20917e-6 0 1 6.59947e-7 0 1 -1.00565e-6 0 1 -6.0366e-7 0 1 -2.58671e-7 0 1 -1.6807e-6 0 1 3.42735e-6 0 1 5.46793e-6 0 1 -5.38923e-6 0 1 8.00628e-6 0 1 -6.68989e-6 0 1 5.46788e-6 0 1 1.26052e-6 0 1 -4.56979e-6 0 1 3.34493e-6 -2.00873e-6 0 1 3.67427e-7 0 1 -5.05638e-7 0 1 1.69889e-6 0 1 2.09772e-6 0 1 0 -1 -2.31581e-7 0 -1 -4.6316e-7 0 -1 2.36683e-7 0 -1 1.81069e-6 0 -1 -1.24646e-6 0 -1 4.5698e-6 0 -1 -2.10089e-7 0 -1 -1.87558e-6 0 -1 -1.34086e-6 0 -1 2.58672e-7 0 -1 5.44723e-7 0 -1 -1.54478e-6 0 -1 1.31989e-6 0 -1 -1.95712e-6 0 -1 -5.46789e-6 0 -1 5.38927e-6 0 -1 -8.00641e-6 0 -1 9.50631e-7 0 -1 -6.85472e-6 0 -1 4.20176e-6 0 -1 1.60126e-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 -2.09058e-7 0 1 0 0 1 0 0 1 1.70871e-7 0 1 3.36822e-7 0 1 -5.00412e-7 0 1 0 0 1 0 0.08480346 0 -0.9963977 -0.0848034 0 -0.9963977 -0.08480465 0 -0.9963976 -0.2519791 0 -0.9677327 -0.251978 0 -0.967733 -0.4119021 0 -0.9112282 -0.4119021 0 -0.9112281 -0.5599747 0 -0.8285098 -0.6919388 0 -0.7219562 -0.6919389 0 -0.7219561 -0.8039971 0 -0.5946333 -0.8039971 0 -0.5946332 -0.8929256 0 -0.4502042 -0.8929256 0 -0.4502043 -0.956167 0 -0.292822 -0.9919005 0 -0.1270179 -0.999099 0 0.04243993 -0.977555 0 0.2106805 -0.977555 0 0.2106806 -0.9278889 0 0.3728568 -0.9278889 0 0.3728569 -0.8515293 0 0.5243073 -0.7506725 0 0.6606745 -0.7506722 0 0.6606748 -0.6282203 0 0.7780357 -0.6282207 0 0.7780352 -0.4876947 0 0.8730143 -0.4876943 0 0.8730146 -0.3331391 0 0.9428777 -0.3331402 0 0.9428773 -0.1690002 0 0.9856161 -0.1690002 0 0.9856161 0.169 0 0.9856161 0.3331402 0 0.9428773 0.3331391 0 0.9428777 0.4876943 0 0.8730145 0.4876947 0 0.8730142 0.6282206 0 0.7780352 0.7506726 0 0.6606744 0.7506729 0 0.6606741 0.8515293 0 0.5243073 0.9278883 0 0.3728583 0.9278884 0 0.3728581 0.9775553 0 0.210679 0.9775553 0 0.2106789 0.999099 0 0.04244154 0.9561666 0 -0.2928235 0.892926 0 -0.4502037 0.892926 0 -0.4502035 0.8039976 0 -0.5946327 0.6919388 0 -0.7219562 0.6919389 0 -0.7219561 0.5599742 0 -0.8285102 0.5599743 0 -0.8285101 0.4119018 0 -0.9112282 0.2519782 0 -0.967733 0.2519794 0 -0.9677327 0.08480471 0 -0.9963977 0 -1 2.36684e-7 0 -1 -3.01831e-7 0 -1 2.91005e-7 0 -1 -2.14838e-6 0 -1 3.78694e-6 0 -1 -1.04211e-6 0 -1 -2.29911e-7 0 -1 1.96424e-6 0 -1 -7.76012e-7 0 -1 -5.53982e-7 0 -1 1.20732e-6 0 -1 -3.35216e-7 0 -1 -4.22365e-6 0 -1 4.41834e-7 0 -1 7.60507e-7 0 -1 -3.42735e-6 0 -1 5.01741e-6 0 -1 5.38923e-6 0 -1 -1.60127e-5 0 -1 4.41833e-7 0 -1 -5.27958e-7 0 -1 -3.41741e-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 -1.42806e-7 0 1 1.70873e-7 0 1 -1.68413e-7 0 1 2.50196e-7 0 1 2.09059e-7 0 1 -2.56307e-7 0 1 3.36826e-7 0 1 -5.0039e-7 0 1 0 0 1 1.42806e-7 0 1 0 0.0848034 0 -0.9963977 -0.2519786 0 -0.9677329 -0.2519774 0 -0.9677332 -0.411903 0 -0.9112278 -0.411903 0 -0.9112278 -0.5599742 0 -0.8285102 -0.5599743 0 -0.8285101 -0.8039976 0 -0.5946327 -0.892926 0 -0.4502035 -0.892926 0 -0.4502037 -0.9561656 0 -0.2928264 -0.9919009 0 -0.1270148 -0.9919009 0 -0.1270148 -0.9775544 0 0.2106836 -0.9775543 0 0.2106836 -0.9278905 0 0.3728527 -0.9278906 0 0.3728528 -0.8515278 0 0.5243097 -0.8515278 0 0.5243096 -0.7506738 0 0.6606732 -0.7506734 0 0.6606735 -0.487694 0 0.8730146 -0.4876936 0 0.8730149 -0.3331394 0 0.9428777 -0.3331404 0 0.9428772 0.1689996 0 0.9856162 0.1689996 0 0.9856162 0.3331404 0 0.9428772 0.3331394 0 0.9428777 0.4876949 0 0.8730142 0.4876955 0 0.8730138 0.999099 0 0.04243999 0.999099 0 0.04243993 0.9919007 0 -0.1270164 0.8039968 0 -0.5946338 0.8039968 0 -0.5946338 0.6919405 0 -0.7219546 0.08480465 0 -0.9963976</float_array> + <technique_common> + <accessor source="#lidarlite-mesh-normals-array" count="1379" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="lidarlite-mesh-vertices"> + <input semantic="POSITION" source="#lidarlite-mesh-positions"/> + </vertices> + <polylist material="Material_001-material" count="2348"> + <input semantic="VERTEX" source="#lidarlite-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#lidarlite-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>0 0 1 0 2 0 2 1 1 1 3 1 2 0 3 0 4 0 5 0 6 0 0 0 0 0 6 0 7 0 8 0 9 0 10 0 10 2 9 2 11 2 11 0 1 0 12 0 12 0 1 0 0 0 12 0 0 0 13 0 13 0 0 0 7 0 13 0 7 0 14 0 14 0 7 0 10 0 14 0 10 0 15 0 15 0 10 0 11 0 15 0 11 0 12 0 16 3 17 3 18 3 16 4 18 4 19 4 19 5 18 5 20 5 19 5 20 5 21 5 21 6 20 6 22 6 21 7 22 7 23 7 23 8 22 8 24 8 23 9 24 9 25 9 25 10 24 10 26 10 25 11 26 11 27 11 17 0 16 0 28 0 28 0 16 0 29 0 30 12 31 12 32 12 30 13 32 13 33 13 33 14 32 14 34 14 33 15 34 15 35 15 35 16 34 16 36 16 35 17 36 17 37 17 37 18 36 18 38 18 37 19 38 19 39 19 39 20 38 20 28 20 39 21 28 21 29 21 40 22 41 22 42 22 40 23 42 23 43 23 43 24 42 24 44 24 43 25 44 25 45 25 45 26 44 26 46 26 45 27 46 27 47 27 47 28 46 28 48 28 47 29 48 29 49 29 49 30 48 30 50 30 49 31 50 31 51 31 40 32 52 32 41 32 41 32 52 32 53 32 54 33 55 33 56 33 54 34 56 34 57 34 57 35 56 35 58 35 57 36 58 36 59 36 59 37 58 37 60 37 59 38 60 38 61 38 61 39 60 39 62 39 61 40 62 40 63 40 63 41 62 41 53 41 63 42 53 42 52 42 64 43 65 43 66 43 66 43 65 43 67 43 66 43 67 43 68 43 68 43 67 43 69 43 68 43 69 43 70 43 70 43 69 43 71 43 70 43 71 43 72 43 72 43 71 43 73 43 72 43 73 43 74 43 74 44 73 44 75 44 74 45 75 45 76 45 76 43 75 43 77 43 76 46 77 46 78 46 78 47 77 47 79 47 78 48 79 48 80 48 80 43 79 43 81 43 80 49 81 49 82 49 82 43 81 43 83 43 82 50 83 50 84 50 84 51 83 51 85 51 84 43 85 43 86 43 86 52 85 52 87 52 86 43 87 43 88 43 88 53 87 53 89 53 88 43 89 43 90 43 90 54 89 54 91 54 90 55 91 55 92 55 92 56 91 56 93 56 92 43 93 43 94 43 94 57 93 57 95 57 94 43 95 43 96 43 96 43 95 43 97 43 96 43 97 43 98 43 98 43 97 43 99 43 98 43 99 43 100 43 100 43 99 43 101 43 100 55 101 55 102 55 102 58 101 58 103 58 102 59 103 59 104 59 104 43 103 43 105 43 104 43 105 43 106 43 106 43 105 43 107 43 106 60 107 60 108 60 108 43 107 43 109 43 108 43 109 43 110 43 110 61 109 61 111 61 110 43 111 43 112 43 112 43 111 43 113 43 112 43 113 43 114 43 114 43 113 43 115 43 114 62 115 62 116 62 116 63 115 63 117 63 116 43 117 43 118 43 118 64 117 64 119 64 118 65 119 65 120 65 120 43 119 43 121 43 120 66 121 66 122 66 122 43 121 43 123 43 122 67 123 67 124 67 124 68 123 68 125 68 124 43 125 43 126 43 126 69 125 69 127 69 126 43 127 43 128 43 128 70 127 70 129 70 128 43 129 43 130 43 130 71 129 71 131 71 130 43 131 43 132 43 132 43 131 43 133 43 132 43 133 43 134 43 134 72 133 72 135 72 134 43 135 43 136 43 136 43 135 43 137 43 136 43 137 43 64 43 64 51 137 51 65 51 138 43 139 43 140 43 140 43 139 43 141 43 140 43 141 43 142 43 142 43 141 43 143 43 142 43 143 43 144 43 144 73 143 73 145 73 144 43 145 43 146 43 146 43 145 43 147 43 146 43 147 43 148 43 148 74 147 74 149 74 148 43 149 43 150 43 150 43 149 43 151 43 150 43 151 43 152 43 152 43 151 43 153 43 152 43 153 43 154 43 154 43 153 43 155 43 154 43 155 43 156 43 156 75 155 75 157 75 156 76 157 76 158 76 158 77 157 77 159 77 158 65 159 65 160 65 160 43 159 43 161 43 160 48 161 48 162 48 162 43 161 43 163 43 162 78 163 78 164 78 164 79 163 79 165 79 164 43 165 43 166 43 166 43 165 43 167 43 166 43 167 43 168 43 168 80 167 80 169 80 168 43 169 43 170 43 170 81 169 81 171 81 170 43 171 43 172 43 172 82 171 82 173 82 172 43 173 43 174 43 174 83 173 83 175 83 174 43 175 43 176 43 176 43 175 43 177 43 176 43 177 43 178 43 178 84 177 84 179 84 178 43 179 43 180 43 180 44 179 44 181 44 180 55 181 55 182 55 182 85 181 85 183 85 182 86 183 86 184 86 184 43 183 43 185 43 184 43 185 43 186 43 186 43 185 43 187 43 186 43 187 43 188 43 188 43 187 43 189 43 188 43 189 43 190 43 190 43 189 43 191 43 190 43 191 43 192 43 192 43 191 43 193 43 192 43 193 43 194 43 194 43 193 43 195 43 194 43 195 43 196 43 196 43 195 43 197 43 196 48 197 48 198 48 198 53 197 53 199 53 198 87 199 87 200 87 200 53 199 53 201 53 200 60 201 60 202 60 202 43 201 43 203 43 202 43 203 43 204 43 204 88 203 88 205 88 204 43 205 43 206 43 206 89 205 89 207 89 206 43 207 43 208 43 208 90 207 90 209 90 208 43 209 43 210 43 210 53 209 53 211 53 210 43 211 43 138 43 138 91 211 91 139 91 212 32 213 32 214 32 215 32 216 32 214 32 214 32 216 32 217 32 214 92 217 92 212 92 218 32 219 32 220 32 220 93 219 93 216 93 220 32 216 32 221 32 221 32 216 32 215 32 221 32 215 32 222 32 222 32 215 32 223 32 219 94 3 94 216 94 216 94 3 94 224 94 11 95 9 95 217 95 217 95 9 95 212 95 225 96 226 96 227 96 227 96 226 96 228 96 229 97 230 97 226 97 231 96 232 96 233 96 234 96 235 96 226 96 226 96 235 96 236 96 226 98 236 98 229 98 237 96 238 96 9 96 225 96 239 96 226 96 226 96 239 96 240 96 226 99 240 99 234 99 241 100 242 100 243 100 244 101 245 101 246 101 237 102 9 102 247 102 248 103 249 103 222 103 243 96 250 96 241 96 241 104 250 104 251 104 241 96 251 96 252 96 233 105 232 105 253 105 253 96 232 96 254 96 253 106 254 106 255 106 255 96 254 96 256 96 255 107 256 107 257 107 258 108 259 108 9 108 260 109 261 109 262 109 262 96 261 96 263 96 264 96 265 96 266 96 251 96 267 96 252 96 252 110 267 110 268 110 252 96 268 96 269 96 269 111 268 111 270 111 269 96 270 96 271 96 271 112 270 112 272 112 271 96 272 96 273 96 273 113 272 113 274 113 273 96 274 96 275 96 275 114 274 114 231 114 275 96 231 96 276 96 276 96 231 96 233 96 246 96 247 96 244 96 244 115 247 115 9 115 244 96 9 96 277 96 277 96 9 96 259 96 238 96 278 96 9 96 9 116 278 116 279 116 9 117 279 117 280 117 280 96 281 96 9 96 9 118 281 118 213 118 9 96 213 96 212 96 260 119 282 119 261 119 261 120 282 120 283 120 261 96 283 96 229 96 229 121 283 121 284 121 229 96 284 96 230 96 284 96 285 96 230 96 230 122 285 122 286 122 230 96 286 96 287 96 287 96 286 96 288 96 287 96 288 96 289 96 289 123 288 123 290 123 289 96 290 96 291 96 291 124 290 124 292 124 291 96 292 96 293 96 293 125 292 125 294 125 293 96 294 96 295 96 295 126 294 126 296 126 295 96 296 96 297 96 297 96 296 96 298 96 297 127 298 127 299 127 299 128 298 128 300 128 299 96 300 96 301 96 301 96 300 96 302 96 301 129 302 129 303 129 303 130 302 130 304 130 303 96 304 96 305 96 305 96 304 96 306 96 305 96 306 96 307 96 307 96 306 96 308 96 307 131 308 131 309 131 309 96 308 96 310 96 309 132 310 132 311 132 311 96 310 96 312 96 311 96 312 96 313 96 313 96 312 96 314 96 313 96 314 96 315 96 315 133 314 133 316 133 315 134 316 134 317 134 317 135 316 135 318 135 317 96 318 96 319 96 319 136 318 136 320 136 319 96 320 96 321 96 321 137 320 137 322 137 321 96 322 96 323 96 323 138 322 138 324 138 323 96 324 96 325 96 325 139 324 139 326 139 325 140 326 140 244 140 244 96 326 96 327 96 244 141 327 141 245 141 328 96 329 96 249 96 249 142 329 142 330 142 249 143 330 143 222 143 4 96 3 96 219 96 226 96 331 96 228 96 228 144 331 144 332 144 228 145 332 145 333 145 334 96 335 96 9 96 9 146 335 146 336 146 9 147 336 147 258 147 222 148 223 148 248 148 248 149 223 149 337 149 248 96 337 96 261 96 261 150 337 150 338 150 261 151 338 151 263 151 333 96 339 96 228 96 228 152 339 152 340 152 228 96 340 96 341 96 342 96 343 96 219 96 219 153 343 153 344 153 219 154 344 154 345 154 345 96 346 96 219 96 219 155 346 155 347 155 219 156 347 156 348 156 349 96 350 96 351 96 352 157 353 157 354 157 354 158 355 158 352 158 352 159 355 159 356 159 352 160 356 160 357 160 358 96 359 96 360 96 357 96 361 96 352 96 352 161 361 161 362 161 352 162 362 162 363 162 364 96 365 96 366 96 367 96 368 96 341 96 266 96 265 96 369 96 369 163 265 163 370 163 369 164 370 164 371 164 371 165 370 165 372 165 371 96 372 96 373 96 373 166 372 166 374 166 373 96 374 96 375 96 375 167 374 167 376 167 375 96 376 96 377 96 377 168 376 168 378 168 377 96 378 96 379 96 379 169 378 169 380 169 379 170 380 170 381 170 381 96 380 96 382 96 381 96 382 96 383 96 383 96 382 96 384 96 383 171 384 171 385 171 385 96 384 96 386 96 385 172 386 172 387 172 387 173 386 173 388 173 387 96 388 96 389 96 389 174 388 174 390 174 389 96 390 96 391 96 391 175 390 175 392 175 391 96 392 96 393 96 393 176 392 176 394 176 393 96 394 96 395 96 395 177 394 177 396 177 395 96 396 96 397 96 397 178 396 178 398 178 397 96 398 96 399 96 399 179 398 179 400 179 399 96 400 96 401 96 401 180 400 180 402 180 401 96 402 96 403 96 403 181 402 181 404 181 403 96 404 96 405 96 405 182 404 182 353 182 405 96 353 96 406 96 358 96 360 96 407 96 359 96 408 96 360 96 360 183 408 183 409 183 360 96 409 96 352 96 352 184 409 184 410 184 352 96 410 96 353 96 353 185 410 185 411 185 353 186 411 186 406 186 412 187 413 187 348 187 414 96 415 96 416 96 5 96 416 96 417 96 418 188 419 188 420 188 420 96 419 96 421 96 421 189 419 189 422 189 421 96 422 96 350 96 350 190 422 190 423 190 350 191 423 191 351 191 351 192 424 192 349 192 349 193 424 193 425 193 349 194 425 194 426 194 426 195 425 195 427 195 426 96 427 96 428 96 429 96 430 96 427 96 427 196 430 196 431 196 427 197 431 197 428 197 5 96 417 96 6 96 242 96 241 96 366 96 366 198 241 198 432 198 366 199 432 199 364 199 368 96 433 96 341 96 341 200 433 200 434 200 341 201 434 201 228 201 228 202 434 202 435 202 256 203 436 203 257 203 257 96 436 96 437 96 257 96 437 96 438 96 438 204 437 204 439 204 438 205 439 205 440 205 440 96 439 96 441 96 440 96 441 96 442 96 442 206 441 206 443 206 442 96 443 96 444 96 444 207 443 207 445 207 444 96 445 96 446 96 446 208 445 208 447 208 446 96 447 96 448 96 448 209 447 209 449 209 448 210 449 210 450 210 450 211 449 211 451 211 450 212 451 212 452 212 452 213 451 213 453 213 452 96 453 96 454 96 454 214 453 214 455 214 454 215 455 215 456 215 456 216 455 216 457 216 456 96 457 96 458 96 458 217 457 217 228 217 458 96 228 96 459 96 459 218 228 218 435 218 219 96 218 96 342 96 342 219 218 219 460 219 342 220 460 220 360 220 360 221 460 221 461 221 360 222 461 222 407 222 462 223 463 223 219 223 219 224 463 224 464 224 420 225 465 225 418 225 418 96 465 96 466 96 418 226 466 226 467 226 467 227 466 227 468 227 467 96 468 96 469 96 469 228 468 228 470 228 469 229 470 229 471 229 471 96 470 96 472 96 471 96 472 96 473 96 473 96 472 96 474 96 473 230 474 230 475 230 475 96 474 96 476 96 477 96 478 96 479 96 479 231 478 231 480 231 479 232 480 232 6 232 481 96 482 96 483 96 483 233 482 233 479 233 483 234 479 234 484 234 484 235 479 235 6 235 484 96 6 96 485 96 485 96 6 96 417 96 264 236 266 236 486 236 486 96 266 96 487 96 486 237 487 237 488 237 488 238 487 238 489 238 488 96 489 96 483 96 483 239 489 239 490 239 483 240 490 240 481 240 413 241 491 241 348 241 348 242 491 242 492 242 348 243 492 243 219 243 219 244 492 244 493 244 219 245 493 245 462 245 464 96 494 96 219 96 219 246 494 246 495 246 219 247 495 247 4 247 412 96 348 96 496 96 496 248 348 248 497 248 496 96 497 96 498 96 498 249 497 249 499 249 498 250 499 250 500 250 500 251 499 251 501 251 500 96 501 96 502 96 502 252 501 252 503 252 502 96 503 96 504 96 504 253 503 253 505 253 504 96 505 96 506 96 506 254 505 254 507 254 506 255 507 255 508 255 508 256 507 256 509 256 508 257 509 257 510 257 510 258 509 258 511 258 510 259 511 259 512 259 512 260 511 260 513 260 512 261 513 261 514 261 514 96 513 96 515 96 514 262 515 262 476 262 476 96 515 96 516 96 476 96 516 96 475 96 517 263 518 263 341 263 341 264 518 264 519 264 341 265 519 265 367 265 363 96 520 96 352 96 352 96 520 96 521 96 352 96 521 96 415 96 415 266 521 266 522 266 415 96 522 96 416 96 365 267 523 267 366 267 366 268 523 268 524 268 366 269 524 269 525 269 328 96 249 96 526 96 526 270 249 270 366 270 526 96 366 96 479 96 479 271 366 271 525 271 479 272 525 272 477 272 9 96 8 96 334 96 334 273 8 273 527 273 334 96 527 96 528 96 528 274 527 274 518 274 528 96 518 96 529 96 529 96 518 96 517 96 5 96 530 96 416 96 416 275 530 275 531 275 416 276 531 276 532 276 414 277 416 277 533 277 533 278 416 278 532 278 533 96 532 96 534 96 534 279 532 279 535 279 534 96 535 96 429 96 429 280 535 280 536 280 429 281 536 281 430 281 412 94 496 94 537 94 537 94 496 94 538 94 538 282 496 282 498 282 538 282 498 282 539 282 539 283 498 283 500 283 539 284 500 284 540 284 540 285 500 285 502 285 540 285 502 285 541 285 541 286 502 286 504 286 541 286 504 286 542 286 542 287 504 287 506 287 542 288 506 288 543 288 543 289 506 289 508 289 543 290 508 290 544 290 544 291 508 291 510 291 544 292 510 292 545 292 545 293 510 293 512 293 545 294 512 294 546 294 546 295 512 295 514 295 546 296 514 296 547 296 547 297 514 297 476 297 547 298 476 298 548 298 548 299 476 299 474 299 548 300 474 300 549 300 549 301 474 301 472 301 549 302 472 302 550 302 550 303 472 303 470 303 550 303 470 303 551 303 551 304 470 304 468 304 551 305 468 305 552 305 552 306 468 306 466 306 552 307 466 307 553 307 553 308 466 308 465 308 553 309 465 309 554 309 554 310 465 310 420 310 554 310 420 310 555 310 555 311 420 311 421 311 555 311 421 311 556 311 556 312 421 312 350 312 556 312 350 312 557 312 558 95 557 95 349 95 349 95 557 95 350 95 559 313 560 313 516 313 516 314 560 314 475 314 516 315 515 315 559 315 559 316 515 316 513 316 559 317 513 317 561 317 561 318 513 318 511 318 561 318 511 318 562 318 562 319 511 319 509 319 562 319 509 319 563 319 563 320 509 320 507 320 563 321 507 321 564 321 564 322 507 322 505 322 564 323 505 323 565 323 565 324 505 324 503 324 565 325 503 325 566 325 566 326 503 326 501 326 566 327 501 327 567 327 567 328 501 328 499 328 567 328 499 328 568 328 568 329 499 329 497 329 568 330 497 330 569 330 569 331 497 331 348 331 569 332 348 332 570 332 570 333 348 333 347 333 570 333 347 333 571 333 571 334 347 334 346 334 571 334 346 334 572 334 572 335 346 335 345 335 572 335 345 335 573 335 573 336 345 336 344 336 573 337 344 337 574 337 574 338 344 338 343 338 574 339 343 339 575 339 575 340 343 340 342 340 575 340 342 340 576 340 576 341 342 341 360 341 576 342 360 342 577 342 577 343 360 343 352 343 577 344 352 344 578 344 578 345 352 345 415 345 578 346 415 346 579 346 579 347 415 347 414 347 579 348 414 348 580 348 580 349 414 349 533 349 580 350 533 350 581 350 581 351 533 351 534 351 581 352 534 352 582 352 582 353 534 353 429 353 582 354 429 354 583 354 583 355 429 355 427 355 583 355 427 355 584 355 584 356 427 356 425 356 584 356 425 356 585 356 585 357 425 357 424 357 585 357 424 357 586 357 586 358 424 358 351 358 586 359 351 359 587 359 587 360 351 360 423 360 587 361 423 361 588 361 588 362 423 362 422 362 588 362 422 362 589 362 589 363 422 363 419 363 589 364 419 364 590 364 590 365 419 365 418 365 590 366 418 366 591 366 591 367 418 367 467 367 591 368 467 368 592 368 592 369 467 369 469 369 592 370 469 370 593 370 593 371 469 371 471 371 593 371 471 371 594 371 594 372 471 372 473 372 594 372 473 372 595 372 595 373 473 373 475 373 595 374 475 374 596 374 596 375 475 375 560 375 597 376 598 376 584 376 573 43 574 43 599 43 599 377 574 377 600 377 601 377 582 377 602 377 602 378 582 378 583 378 602 43 583 43 603 43 558 379 585 379 586 379 592 43 593 43 551 43 551 380 593 380 550 380 550 43 593 43 594 43 550 381 594 381 549 381 549 382 594 382 595 382 549 383 595 383 548 383 577 384 604 384 576 384 576 385 604 385 600 385 576 43 600 43 575 43 575 43 600 43 574 43 577 386 578 386 604 386 604 43 578 43 605 43 604 43 605 43 606 43 606 387 605 387 607 387 606 43 607 43 2 43 2 388 607 388 0 388 578 43 579 43 605 43 605 389 579 389 580 389 605 43 580 43 601 43 601 390 580 390 581 390 601 391 581 391 582 391 558 43 586 43 557 43 595 392 596 392 548 392 548 43 596 43 560 43 548 43 560 43 547 43 547 43 560 43 559 43 547 43 559 43 546 43 546 393 559 393 561 393 546 43 561 43 545 43 545 43 561 43 562 43 545 43 562 43 544 43 544 394 562 394 563 394 544 43 563 43 543 43 543 395 563 395 564 395 543 43 564 43 542 43 542 396 564 396 565 396 542 397 565 397 541 397 541 398 565 398 566 398 541 43 566 43 540 43 540 399 566 399 567 399 540 43 567 43 539 43 539 400 567 400 568 400 539 43 568 43 538 43 568 43 569 43 538 43 538 401 569 401 570 401 538 43 570 43 537 43 537 402 570 402 571 402 537 403 571 403 608 403 608 404 571 404 572 404 608 43 572 43 609 43 599 43 610 43 573 43 573 405 610 405 611 405 573 406 611 406 572 406 572 407 611 407 612 407 572 408 612 408 609 408 584 43 598 43 583 43 583 409 598 409 613 409 583 410 613 410 603 410 585 43 558 43 584 43 584 411 558 411 614 411 584 412 614 412 597 412 586 43 587 43 557 43 557 413 587 413 588 413 557 43 588 43 556 43 556 414 588 414 589 414 556 43 589 43 555 43 555 415 589 415 590 415 555 43 590 43 554 43 554 43 590 43 591 43 554 416 591 416 553 416 553 417 591 417 592 417 553 43 592 43 552 43 552 418 592 418 551 418 615 419 252 419 269 419 615 419 269 419 616 419 616 420 269 420 271 420 616 420 271 420 617 420 617 421 271 421 273 421 617 422 273 422 618 422 618 423 273 423 275 423 618 424 275 424 619 424 619 425 275 425 276 425 619 426 276 426 620 426 620 427 276 427 233 427 620 428 233 428 621 428 621 429 233 429 253 429 621 430 253 430 622 430 622 431 253 431 255 431 622 432 255 432 623 432 623 433 255 433 257 433 623 434 257 434 624 434 624 435 257 435 438 435 624 436 438 436 625 436 625 437 438 437 440 437 625 438 440 438 626 438 626 439 440 439 442 439 626 439 442 439 627 439 627 440 442 440 444 440 627 441 444 441 628 441 628 442 444 442 446 442 628 443 446 443 629 443 629 444 446 444 448 444 629 445 448 445 630 445 630 446 448 446 450 446 630 447 450 447 631 447 631 448 450 448 452 448 631 448 452 448 632 448 632 449 452 449 454 449 632 450 454 450 633 450 633 451 454 451 456 451 633 451 456 451 634 451 635 95 634 95 458 95 458 95 634 95 456 95 241 94 252 94 636 94 636 94 252 94 615 94 637 452 638 452 437 452 437 453 638 453 439 453 437 454 436 454 637 454 637 455 436 455 256 455 637 455 256 455 639 455 639 318 256 318 254 318 639 318 254 318 640 318 640 319 254 319 232 319 640 319 232 319 641 319 641 456 232 456 231 456 641 457 231 457 642 457 642 458 231 458 274 458 642 459 274 459 643 459 643 460 274 460 272 460 643 461 272 461 644 461 644 462 272 462 270 462 644 463 270 463 645 463 645 464 270 464 268 464 645 464 268 464 646 464 646 329 268 329 267 329 646 330 267 330 647 330 647 465 267 465 251 465 647 465 251 465 648 465 648 466 251 466 250 466 648 466 250 466 649 466 649 467 250 467 243 467 649 467 243 467 650 467 650 335 243 335 242 335 650 335 242 335 651 335 651 468 242 468 366 468 651 469 366 469 652 469 652 470 366 470 249 470 652 471 249 471 653 471 653 472 249 472 248 472 653 472 248 472 654 472 654 473 248 473 261 473 654 474 261 474 655 474 655 475 261 475 229 475 655 476 229 476 656 476 656 477 229 477 236 477 656 478 236 478 657 478 657 347 236 347 235 347 657 348 235 348 658 348 658 479 235 479 234 479 658 479 234 479 659 479 659 480 234 480 240 480 659 481 240 481 660 481 660 482 240 482 239 482 660 483 239 483 661 483 661 355 239 355 225 355 661 355 225 355 662 355 662 484 225 484 227 484 662 485 227 485 663 485 663 486 227 486 228 486 663 486 228 486 664 486 664 358 228 358 457 358 664 359 457 359 665 359 665 487 457 487 455 487 665 488 455 488 666 488 666 489 455 489 453 489 666 489 453 489 667 489 667 490 453 490 451 490 667 491 451 491 668 491 668 492 451 492 449 492 668 493 449 493 669 493 669 494 449 494 447 494 669 495 447 495 670 495 670 496 447 496 445 496 670 497 445 497 671 497 671 371 445 371 443 371 671 371 443 371 672 371 672 372 443 372 441 372 672 372 441 372 673 372 673 498 441 498 439 498 673 498 439 498 674 498 674 499 439 499 638 499 624 43 637 43 623 43 623 43 637 43 639 43 623 43 639 43 622 43 622 43 639 43 640 43 622 500 640 500 621 500 621 501 640 501 641 501 621 43 641 43 620 43 620 502 641 502 642 502 620 43 642 43 619 43 619 503 642 503 643 503 619 43 643 43 618 43 651 43 652 43 675 43 675 504 652 504 676 504 636 43 615 43 647 43 663 43 664 43 631 43 631 505 664 505 665 505 631 506 665 506 666 506 666 43 667 43 631 43 631 507 667 507 668 507 631 43 668 43 630 43 630 508 668 508 669 508 630 509 669 509 629 509 629 510 669 510 670 510 629 511 670 511 628 511 628 512 670 512 671 512 628 43 671 43 627 43 627 513 671 513 672 513 627 43 672 43 626 43 626 43 672 43 673 43 626 514 673 514 625 514 625 43 673 43 674 43 625 43 674 43 624 43 624 515 674 515 638 515 624 516 638 516 637 516 618 43 643 43 617 43 617 517 643 517 644 517 617 43 644 43 616 43 616 518 644 518 645 518 616 43 645 43 615 43 615 519 645 519 646 519 615 520 646 520 647 520 647 43 648 43 636 43 636 521 648 521 649 521 636 43 649 43 677 43 677 522 649 522 650 522 677 523 650 523 678 523 655 43 679 43 654 43 654 524 679 524 676 524 654 525 676 525 653 525 653 526 676 526 652 526 675 43 680 43 651 43 651 527 680 527 681 527 651 43 681 43 650 43 650 528 681 528 682 528 650 529 682 529 678 529 656 530 657 530 683 530 683 389 657 389 658 389 683 43 658 43 684 43 658 525 659 525 684 525 684 531 659 531 660 531 684 504 660 504 685 504 685 43 660 43 661 43 686 43 687 43 661 43 655 43 656 43 679 43 679 532 656 532 683 532 679 43 683 43 688 43 688 533 683 533 689 533 688 534 689 534 7 534 7 535 689 535 10 535 687 43 690 43 661 43 661 527 690 527 691 527 661 536 691 536 685 536 633 537 634 537 662 537 662 43 634 43 635 43 662 43 635 43 661 43 661 538 635 538 692 538 661 539 692 539 686 539 663 43 631 43 662 43 662 540 631 540 632 540 662 541 632 541 633 541 693 542 266 542 369 542 693 542 369 542 694 542 694 543 369 543 371 543 694 544 371 544 695 544 695 545 371 545 373 545 695 546 373 546 696 546 696 547 373 547 375 547 696 548 375 548 697 548 697 549 375 549 377 549 697 549 377 549 698 549 698 550 377 550 379 550 698 551 379 551 699 551 699 552 379 552 381 552 699 553 381 553 700 553 700 554 381 554 383 554 700 555 383 555 701 555 701 556 383 556 385 556 701 557 385 557 702 557 702 558 385 558 387 558 702 559 387 559 703 559 703 560 387 560 389 560 703 561 389 561 704 561 704 562 389 562 391 562 704 563 391 563 705 563 705 564 391 564 393 564 705 565 393 565 706 565 706 566 393 566 395 566 706 566 395 566 707 566 707 567 395 567 397 567 707 568 397 568 708 568 708 569 397 569 399 569 708 569 399 569 709 569 709 570 399 570 401 570 709 571 401 571 710 571 710 572 401 572 403 572 710 572 403 572 711 572 711 573 403 573 405 573 711 573 405 573 712 573 713 94 712 94 406 94 406 94 712 94 405 94 487 95 266 95 714 95 714 95 266 95 693 95 715 574 716 574 521 574 521 575 716 575 522 575 521 576 520 576 715 576 715 316 520 316 363 316 715 577 363 577 717 577 717 578 363 578 362 578 717 579 362 579 718 579 718 580 362 580 361 580 718 581 361 581 719 581 719 582 361 582 357 582 719 320 357 320 720 320 720 322 357 322 356 322 720 323 356 323 721 323 721 324 356 324 355 324 721 324 355 324 722 324 722 327 355 327 354 327 722 326 354 326 723 326 723 328 354 328 353 328 723 583 353 583 724 583 724 330 353 330 404 330 724 330 404 330 725 330 725 331 404 331 402 331 725 584 402 584 726 584 726 333 402 333 400 333 726 585 400 585 727 585 727 586 400 586 398 586 727 587 398 587 728 587 728 588 398 588 396 588 728 588 396 588 729 588 729 589 396 589 394 589 729 589 394 589 730 589 730 590 394 590 392 590 730 590 392 590 731 590 731 591 392 591 390 591 731 591 390 591 732 591 732 592 390 592 388 592 732 593 388 593 733 593 733 343 388 343 386 343 733 343 386 343 734 343 734 594 386 594 384 594 734 346 384 346 735 346 735 595 384 595 382 595 735 596 382 596 736 596 736 597 382 597 380 597 736 598 380 598 737 598 737 599 380 599 378 599 737 599 378 599 738 599 738 600 378 600 376 600 738 600 376 600 739 600 739 601 376 601 374 601 739 601 374 601 740 601 740 602 374 602 372 602 740 603 372 603 741 603 741 604 372 604 370 604 741 357 370 357 742 357 742 605 370 605 265 605 742 359 265 359 743 359 743 360 265 360 264 360 743 360 264 360 744 360 744 606 264 606 486 606 744 362 486 362 745 362 745 364 486 364 488 364 745 363 488 363 746 363 746 366 488 366 483 366 746 366 483 366 747 366 747 367 483 367 484 367 747 368 484 368 748 368 748 370 484 370 485 370 748 607 485 607 749 607 749 608 485 608 417 608 749 609 417 609 750 609 750 610 417 610 416 610 750 611 416 611 751 611 751 612 416 612 522 612 751 374 522 374 752 374 752 613 522 613 716 613 753 43 754 43 718 43 755 614 751 614 752 614 751 43 755 43 750 43 750 615 755 615 756 615 750 616 756 616 749 616 716 43 715 43 754 43 754 617 715 617 717 617 754 43 717 43 718 43 757 43 758 43 721 43 718 43 719 43 753 43 753 618 719 618 720 618 753 619 720 619 759 619 759 620 720 620 721 620 759 43 721 43 760 43 760 43 721 43 758 43 693 43 694 43 742 43 752 43 716 43 755 43 755 43 716 43 754 43 755 43 754 43 761 43 761 621 754 621 762 621 761 622 762 622 221 622 221 623 762 623 220 623 742 43 694 43 741 43 741 43 694 43 695 43 741 43 695 43 740 43 740 43 695 43 696 43 740 43 696 43 739 43 739 624 696 624 697 624 739 43 697 43 738 43 738 625 697 625 698 625 738 626 698 626 737 626 737 627 698 627 699 627 737 628 699 628 736 628 736 43 699 43 700 43 736 43 700 43 735 43 735 629 700 629 701 629 735 43 701 43 734 43 734 630 701 630 702 630 734 43 702 43 733 43 733 631 702 631 703 631 733 632 703 632 732 632 732 43 703 43 704 43 732 633 704 633 731 633 731 634 704 634 705 634 731 43 705 43 730 43 730 635 705 635 706 635 730 636 706 636 729 636 729 43 706 43 707 43 729 43 707 43 728 43 728 637 707 637 708 637 728 638 708 638 727 638 727 639 708 639 709 639 727 43 709 43 726 43 726 640 709 640 710 640 726 641 710 641 725 641 725 642 710 642 711 642 725 643 711 643 724 643 724 644 711 644 712 644 724 43 712 43 723 43 723 43 712 43 713 43 723 43 713 43 722 43 722 645 713 645 763 645 722 646 763 646 721 646 721 647 763 647 764 647 721 648 764 648 757 648 749 43 756 43 748 43 748 649 756 649 765 649 748 650 765 650 747 650 747 651 765 651 766 651 747 652 766 652 767 652 742 43 743 43 693 43 693 653 743 653 744 653 693 43 744 43 714 43 714 654 744 654 745 654 714 655 745 655 768 655 768 656 745 656 746 656 768 43 746 43 769 43 769 43 746 43 747 43 769 43 747 43 770 43 770 43 747 43 767 43 327 95 326 95 771 95 771 95 326 95 772 95 772 657 326 657 324 657 772 657 324 657 773 657 773 658 324 658 322 658 773 658 322 658 774 658 774 659 322 659 320 659 774 660 320 660 775 660 775 661 320 661 318 661 775 662 318 662 776 662 776 663 318 663 316 663 776 664 316 664 777 664 777 665 316 665 314 665 777 665 314 665 778 665 778 666 314 666 312 666 778 667 312 667 779 667 779 668 312 668 310 668 779 669 310 669 780 669 780 670 310 670 308 670 780 671 308 671 781 671 781 672 308 672 306 672 781 673 306 673 782 673 782 674 306 674 304 674 782 675 304 675 783 675 783 676 304 676 302 676 783 677 302 677 784 677 784 678 302 678 300 678 784 679 300 679 785 679 785 680 300 680 298 680 785 681 298 681 786 681 786 682 298 682 296 682 786 682 296 682 787 682 787 683 296 683 294 683 787 684 294 684 788 684 788 685 294 685 292 685 788 686 292 686 789 686 789 687 292 687 290 687 789 688 290 688 790 688 790 689 290 689 288 689 790 689 288 689 791 689 792 94 791 94 286 94 286 94 791 94 288 94 793 690 794 690 529 690 529 691 794 691 528 691 529 692 517 692 793 692 793 455 517 455 341 455 793 693 341 693 795 693 795 578 341 578 340 578 795 579 340 579 796 579 796 580 340 580 339 580 796 581 339 581 797 581 797 694 339 694 333 694 797 456 333 456 798 456 798 458 333 458 332 458 798 459 332 459 799 459 799 460 332 460 331 460 799 460 331 460 800 460 800 463 331 463 226 463 800 462 226 462 801 462 801 464 226 464 230 464 801 695 230 695 802 695 802 330 230 330 287 330 802 330 287 330 803 330 803 465 287 465 289 465 803 696 289 696 804 696 804 466 289 466 291 466 804 697 291 697 805 697 805 698 291 698 293 698 805 699 293 699 806 699 806 588 293 588 295 588 806 588 295 588 807 588 807 700 295 700 297 700 807 700 297 700 808 700 808 701 297 701 299 701 808 701 299 701 809 701 809 702 299 702 301 702 809 702 301 702 810 702 810 703 301 703 303 703 810 704 303 704 811 704 811 475 303 475 305 475 811 705 305 705 812 705 812 478 305 478 307 478 812 478 307 478 813 478 813 595 307 595 309 595 813 596 309 596 814 596 814 706 309 706 311 706 814 706 311 706 815 706 815 707 311 707 313 707 815 707 313 707 816 707 816 708 313 708 315 708 816 708 315 708 817 708 817 601 315 601 317 601 817 601 317 601 818 601 818 709 317 709 319 709 818 710 319 710 819 710 819 711 319 711 321 711 819 486 321 486 820 486 820 605 321 605 323 605 820 359 323 359 821 359 821 487 323 487 325 487 821 487 325 487 822 487 822 712 325 712 244 712 822 489 244 489 823 489 823 491 244 491 277 491 823 490 277 490 824 490 824 493 277 493 259 493 824 493 259 493 825 493 825 494 259 494 258 494 825 495 258 495 826 495 826 497 258 497 336 497 826 713 336 713 827 713 827 608 336 608 335 608 827 609 335 609 828 609 828 610 335 610 334 610 828 611 334 611 829 611 829 714 334 714 528 714 829 498 528 498 830 498 830 715 528 715 794 715 831 716 832 716 796 716 833 717 827 717 828 717 833 43 828 43 834 43 834 43 828 43 829 43 834 718 829 718 830 718 796 43 797 43 831 43 831 719 797 719 798 719 831 619 798 619 835 619 835 720 798 720 799 720 791 43 792 43 801 43 794 721 793 721 832 721 832 722 793 722 795 722 832 43 795 43 796 43 827 723 833 723 826 723 826 724 833 724 836 724 826 43 836 43 825 43 825 725 836 725 837 725 825 726 837 726 838 726 801 43 792 43 800 43 800 727 792 727 839 727 800 43 839 43 799 43 799 728 839 728 840 728 799 729 840 729 841 729 841 43 842 43 799 43 799 730 842 730 843 730 799 731 843 731 835 731 830 721 794 721 834 721 834 732 794 732 832 732 834 43 832 43 844 43 844 733 832 733 845 733 844 734 845 734 214 734 214 735 845 735 215 735 838 43 846 43 825 43 825 729 846 729 847 729 825 736 847 736 824 736 824 737 847 737 848 737 824 43 848 43 823 43 823 738 848 738 771 738 823 739 771 739 822 739 822 43 771 43 772 43 822 43 772 43 821 43 821 740 772 740 773 740 821 741 773 741 820 741 820 742 773 742 774 742 820 743 774 743 819 743 819 744 774 744 775 744 819 43 775 43 818 43 818 745 775 745 776 745 818 746 776 746 817 746 817 747 776 747 777 747 817 748 777 748 816 748 816 749 777 749 778 749 816 43 778 43 815 43 815 43 778 43 779 43 815 43 779 43 814 43 814 750 779 750 780 750 814 43 780 43 813 43 813 751 780 751 781 751 813 752 781 752 812 752 812 43 781 43 782 43 812 43 782 43 811 43 811 43 782 43 783 43 811 753 783 753 810 753 810 43 783 43 784 43 810 43 784 43 809 43 809 754 784 754 785 754 809 43 785 43 808 43 808 755 785 755 786 755 808 43 786 43 807 43 807 43 786 43 787 43 807 43 787 43 806 43 806 756 787 756 788 756 806 757 788 757 805 757 805 758 788 758 789 758 805 43 789 43 804 43 804 759 789 759 790 759 804 43 790 43 803 43 803 760 790 760 791 760 803 43 791 43 802 43 802 43 791 43 801 43 214 761 213 761 281 761 214 761 281 761 844 761 844 762 281 762 280 762 844 763 280 763 834 763 834 764 280 764 279 764 834 765 279 765 833 765 833 766 279 766 278 766 833 767 278 767 836 767 836 768 278 768 238 768 836 769 238 769 837 769 837 770 238 770 237 770 837 770 237 770 838 770 838 771 237 771 247 771 838 772 247 772 846 772 846 773 247 773 246 773 846 774 246 774 847 774 847 775 246 775 245 775 847 776 245 776 848 776 848 777 245 777 327 777 848 777 327 777 771 777 223 778 215 778 845 778 223 778 845 778 337 778 337 779 845 779 832 779 337 780 832 780 338 780 338 781 832 781 831 781 338 782 831 782 263 782 263 783 831 783 835 783 263 784 835 784 262 784 262 785 835 785 843 785 262 786 843 786 260 786 260 787 843 787 842 787 260 787 842 787 282 787 282 788 842 788 841 788 282 789 841 789 283 789 283 790 841 790 840 790 283 791 840 791 284 791 284 792 840 792 839 792 284 793 839 793 285 793 285 794 839 794 792 794 285 794 792 794 286 794 221 795 222 795 330 795 221 795 330 795 761 795 761 796 330 796 329 796 761 797 329 797 755 797 755 798 329 798 328 798 755 799 328 799 756 799 756 766 328 766 526 766 756 767 526 767 765 767 765 800 526 800 479 800 765 801 479 801 766 801 766 802 479 802 482 802 766 802 482 802 767 802 767 803 482 803 481 803 767 804 481 804 770 804 770 805 481 805 490 805 770 806 490 806 769 806 769 807 490 807 489 807 769 807 489 807 768 807 768 777 489 777 487 777 768 777 487 777 714 777 218 808 220 808 762 808 218 809 762 809 460 809 460 810 762 810 754 810 460 811 754 811 461 811 461 812 754 812 753 812 461 813 753 813 407 813 407 783 753 783 759 783 407 784 759 784 358 784 358 814 759 814 760 814 358 815 760 815 359 815 359 816 760 816 758 816 359 816 758 816 408 816 408 788 758 788 757 788 408 789 757 789 409 789 409 817 757 817 764 817 409 818 764 818 410 818 410 819 764 819 763 819 410 819 763 819 411 819 411 794 763 794 713 794 411 794 713 794 406 794 241 820 636 820 677 820 241 821 677 821 432 821 432 822 677 822 678 822 432 823 678 823 364 823 364 824 678 824 682 824 364 824 682 824 365 824 365 825 682 825 681 825 365 825 681 825 523 825 523 826 681 826 680 826 523 826 680 826 524 826 524 827 680 827 675 827 524 827 675 827 525 827 525 828 675 828 676 828 525 828 676 828 477 828 477 829 676 829 679 829 477 829 679 829 478 829 478 830 679 830 688 830 478 831 688 831 480 831 480 832 688 832 7 832 480 832 7 832 6 832 635 833 458 833 459 833 635 834 459 834 692 834 692 835 459 835 435 835 692 836 435 836 686 836 686 837 435 837 434 837 686 837 434 837 687 837 687 838 434 838 433 838 687 838 433 838 690 838 690 839 433 839 368 839 690 839 368 839 691 839 691 840 368 840 367 840 691 840 367 840 685 840 685 841 367 841 519 841 685 841 519 841 684 841 684 842 519 842 518 842 684 843 518 843 683 843 683 844 518 844 527 844 683 844 527 844 689 844 689 845 527 845 8 845 689 845 8 845 10 845 558 833 349 833 426 833 558 834 426 834 614 834 614 846 426 846 428 846 614 847 428 847 597 847 597 848 428 848 431 848 597 848 431 848 598 848 598 849 431 849 430 849 598 849 430 849 613 849 613 850 430 850 536 850 613 850 536 850 603 850 603 851 536 851 535 851 603 851 535 851 602 851 602 841 535 841 532 841 602 841 532 841 601 841 601 852 532 852 531 852 601 853 531 853 605 853 605 854 531 854 530 854 605 855 530 855 607 855 607 856 530 856 5 856 607 856 5 856 0 856 412 820 537 820 608 820 412 821 608 821 413 821 413 857 608 857 609 857 413 858 609 858 491 858 491 859 609 859 612 859 491 859 612 859 492 859 492 825 612 825 611 825 492 825 611 825 493 825 493 860 611 860 610 860 493 860 610 860 462 860 462 861 610 861 599 861 462 861 599 861 463 861 463 828 599 828 600 828 463 828 600 828 464 828 464 862 600 862 604 862 464 863 604 863 494 863 494 864 604 864 606 864 494 865 606 865 495 865 495 866 606 866 2 866 495 867 2 867 4 867 849 868 51 868 50 868 850 869 31 869 181 869 181 870 179 870 850 870 850 871 179 871 177 871 850 872 177 872 851 872 851 873 177 873 175 873 851 874 175 874 852 874 852 875 175 875 173 875 852 875 173 875 853 875 853 876 173 876 171 876 853 876 171 876 854 876 854 877 171 877 169 877 854 877 169 877 855 877 855 878 169 878 167 878 855 878 167 878 856 878 856 879 167 879 165 879 856 879 165 879 857 879 857 880 165 880 163 880 857 881 163 881 858 881 858 882 163 882 50 882 50 883 163 883 161 883 50 884 161 884 849 884 849 885 161 885 159 885 849 886 159 886 859 886 859 887 159 887 157 887 859 888 157 888 860 888 860 889 157 889 155 889 860 890 155 890 861 890 861 891 155 891 153 891 861 892 153 892 862 892 862 32 153 32 151 32 862 32 151 32 863 32 863 893 151 893 149 893 863 894 149 894 864 894 864 895 149 895 147 895 864 896 147 896 865 896 865 897 147 897 145 897 865 898 145 898 866 898 866 899 145 899 143 899 866 900 143 900 867 900 867 901 143 901 141 901 867 902 141 902 868 902 868 903 141 903 139 903 868 904 139 904 869 904 869 905 139 905 211 905 869 906 211 906 870 906 870 907 211 907 209 907 870 907 209 907 871 907 871 908 209 908 207 908 871 908 207 908 872 908 872 909 207 909 205 909 872 910 205 910 873 910 873 911 205 911 203 911 873 912 203 912 874 912 874 913 203 913 201 913 874 914 201 914 875 914 875 915 201 915 199 915 875 916 199 916 876 916 876 917 199 917 197 917 876 918 197 918 877 918 877 919 197 919 195 919 877 920 195 920 878 920 878 921 195 921 193 921 878 922 193 922 879 922 879 923 193 923 191 923 879 923 191 923 880 923 880 924 191 924 189 924 880 925 189 925 881 925 881 926 189 926 187 926 881 927 187 927 882 927 882 928 187 928 185 928 882 929 185 929 883 929 883 930 185 930 183 930 883 931 183 931 884 931 884 932 183 932 181 932 884 933 181 933 885 933 885 934 181 934 31 934 885 935 31 935 30 935 886 936 55 936 137 936 137 937 135 937 886 937 886 938 135 938 133 938 886 939 133 939 887 939 887 940 133 940 131 940 887 940 131 940 888 940 888 941 131 941 129 941 888 941 129 941 889 941 889 942 129 942 127 942 889 942 127 942 890 942 890 943 127 943 125 943 890 943 125 943 891 943 891 944 125 944 123 944 891 944 123 944 892 944 892 945 123 945 121 945 892 945 121 945 893 945 893 946 121 946 119 946 893 946 119 946 894 946 894 947 119 947 26 947 26 948 119 948 117 948 26 949 117 949 27 949 27 950 117 950 895 950 895 919 117 919 115 919 895 920 115 920 896 920 896 921 115 921 113 921 896 922 113 922 897 922 897 951 113 951 111 951 897 952 111 952 898 952 898 953 111 953 109 953 898 954 109 954 899 954 899 955 109 955 107 955 899 956 107 956 900 956 900 957 107 957 105 957 900 958 105 958 901 958 901 959 105 959 103 959 901 960 103 960 902 960 902 932 103 932 101 932 902 933 101 933 903 933 903 961 101 961 99 961 903 962 99 962 904 962 904 963 99 963 97 963 904 964 97 964 905 964 905 965 97 965 95 965 905 965 95 965 906 965 906 966 95 966 93 966 906 967 93 967 907 967 907 968 93 968 91 968 907 969 91 969 908 969 908 970 91 970 89 970 908 970 89 970 909 970 909 971 89 971 87 971 909 972 87 972 910 972 910 973 87 973 85 973 910 974 85 974 911 974 911 975 85 975 83 975 911 976 83 976 912 976 912 977 83 977 81 977 912 978 81 978 913 978 913 885 81 885 79 885 913 886 79 886 914 886 914 979 79 979 77 979 914 980 77 980 915 980 915 889 77 889 75 889 915 890 75 890 916 890 916 981 75 981 73 981 916 982 73 982 917 982 917 32 73 32 71 32 917 32 71 32 918 32 918 983 71 983 69 983 918 984 69 984 919 984 919 985 69 985 67 985 919 986 67 986 920 986 920 987 67 987 65 987 920 988 65 988 921 988 921 989 65 989 137 989 921 990 137 990 922 990 922 991 137 991 55 991 922 992 55 992 54 992 874 43 875 43 11 43 882 43 897 43 881 43 881 43 897 43 11 43 875 43 876 43 11 43 11 43 876 43 877 43 11 993 877 993 878 993 878 43 879 43 11 43 11 994 879 994 880 994 11 995 880 995 881 995 870 43 871 43 217 43 217 996 871 996 872 996 217 43 872 43 11 43 11 43 872 43 873 43 11 43 873 43 874 43 882 43 883 43 897 43 897 997 883 997 884 997 897 43 884 43 896 43 896 998 884 998 885 998 897 43 898 43 11 43 11 999 898 999 899 999 11 43 899 43 1 43 1 1000 899 1000 900 1000 900 1001 901 1001 1 1001 1 1002 901 1002 902 1002 1 1003 902 1003 903 1003 903 1004 904 1004 1 1004 1 1005 904 1005 905 1005 1 43 905 43 906 43 30 43 27 43 885 43 885 1006 27 1006 895 1006 885 1007 895 1007 896 1007 906 43 907 43 1 43 1 1008 907 1008 908 1008 1 43 908 43 216 43 216 1009 908 1009 909 1009 216 1010 909 1010 910 1010 910 43 911 43 216 43 216 1011 911 1011 912 1011 216 1012 912 1012 913 1012 217 1013 863 1013 864 1013 867 1014 868 1014 217 1014 217 1015 868 1015 869 1015 217 1016 869 1016 870 1016 863 43 217 43 862 43 862 43 217 43 216 43 862 43 216 43 861 43 30 1017 33 1017 35 1017 30 1018 29 1018 27 1018 27 1019 29 1019 16 1019 27 1020 16 1020 19 1020 864 43 865 43 217 43 217 1021 865 1021 866 1021 217 1022 866 1022 867 1022 35 43 37 43 30 43 30 1023 37 1023 39 1023 30 1024 39 1024 29 1024 913 43 914 43 216 43 216 1025 914 1025 915 1025 216 1026 915 1026 916 1026 859 1027 919 1027 920 1027 19 1028 21 1028 27 1028 27 1029 21 1029 23 1029 27 1030 23 1030 25 1030 916 1031 917 1031 216 1031 216 1032 917 1032 918 1032 216 43 918 43 861 43 861 1033 918 1033 919 1033 861 43 919 43 860 43 860 43 919 43 859 43 920 1034 921 1034 859 1034 859 1035 921 1035 922 1035 859 43 922 43 849 43 52 1036 922 1036 54 1036 47 1037 49 1037 51 1037 54 1038 57 1038 59 1038 59 43 61 43 54 43 54 1039 61 1039 63 1039 54 1040 63 1040 52 1040 47 43 51 43 45 43 922 1041 52 1041 849 1041 849 43 52 43 40 43 849 1042 40 1042 51 1042 51 1043 40 1043 43 1043 51 1044 43 1044 45 1044 851 1045 32 1045 850 1045 850 43 32 43 31 43 852 1046 36 1046 851 1046 851 1047 36 1047 34 1047 851 43 34 43 32 43 852 1048 18 1048 17 1048 17 1049 28 1049 852 1049 852 43 28 43 38 43 852 43 38 43 36 43 46 43 857 43 48 43 48 43 857 43 858 43 48 1050 858 1050 50 1050 62 43 887 43 53 43 53 1051 887 1051 888 1051 46 43 44 43 857 43 857 1052 44 1052 42 1052 857 1053 42 1053 856 1053 856 43 42 43 41 43 20 1054 892 1054 22 1054 22 43 892 43 893 43 22 1055 893 1055 24 1055 24 43 893 43 894 43 24 1056 894 1056 26 1056 62 43 60 43 887 43 887 43 60 43 58 43 887 43 58 43 886 43 886 43 58 43 56 43 886 43 56 43 55 43 41 1057 53 1057 856 1057 856 1058 53 1058 888 1058 856 1059 888 1059 855 1059 855 1060 888 1060 889 1060 855 43 889 43 854 43 854 1061 889 1061 890 1061 854 43 890 43 853 43 853 1062 890 1062 891 1062 853 43 891 43 852 43 852 1063 891 1063 892 1063 852 1064 892 1064 18 1064 18 1065 892 1065 20 1065 923 1066 108 1066 924 1066 924 1067 108 1067 110 1067 924 1068 110 1068 925 1068 925 1069 110 1069 112 1069 925 1070 112 1070 926 1070 926 1071 112 1071 114 1071 926 1071 114 1071 927 1071 927 1072 114 1072 116 1072 927 1073 116 1073 928 1073 928 1074 116 1074 118 1074 928 1074 118 1074 929 1074 929 1075 118 1075 120 1075 929 1075 120 1075 930 1075 930 1076 120 1076 122 1076 930 1077 122 1077 931 1077 931 1078 122 1078 124 1078 931 1078 124 1078 932 1078 932 1079 124 1079 126 1079 932 1079 126 1079 933 1079 933 1080 126 1080 128 1080 933 1080 128 1080 934 1080 934 1081 128 1081 130 1081 934 1081 130 1081 935 1081 935 1082 130 1082 132 1082 935 1082 132 1082 936 1082 936 1083 132 1083 134 1083 936 1084 134 1084 937 1084 937 1085 134 1085 136 1085 937 1086 136 1086 938 1086 938 1087 136 1087 64 1087 938 1088 64 1088 939 1088 939 1089 64 1089 66 1089 939 1090 66 1090 940 1090 940 1091 66 1091 68 1091 940 1092 68 1092 941 1092 941 1093 68 1093 70 1093 941 1094 70 1094 942 1094 942 0 70 0 72 0 942 0 72 0 943 0 943 1095 72 1095 74 1095 943 1096 74 1096 944 1096 944 1097 74 1097 76 1097 944 1098 76 1098 945 1098 945 1099 76 1099 78 1099 945 1100 78 1100 946 1100 946 1101 78 1101 80 1101 946 1102 80 1102 947 1102 947 1103 80 1103 82 1103 947 1104 82 1104 948 1104 948 1105 82 1105 84 1105 948 1106 84 1106 949 1106 949 1107 84 1107 86 1107 949 1107 86 1107 950 1107 950 1108 86 1108 88 1108 950 1108 88 1108 951 1108 951 1109 88 1109 90 1109 951 1109 90 1109 952 1109 952 1110 90 1110 92 1110 952 1110 92 1110 953 1110 953 1111 92 1111 94 1111 953 1111 94 1111 954 1111 954 1112 94 1112 96 1112 954 1112 96 1112 955 1112 955 1113 96 1113 98 1113 955 1113 98 1113 956 1113 956 1114 98 1114 100 1114 956 1114 100 1114 957 1114 957 1115 100 1115 102 1115 957 1115 102 1115 958 1115 958 1116 102 1116 104 1116 958 1116 104 1116 959 1116 959 1117 104 1117 106 1117 959 1118 106 1118 923 1118 923 1119 106 1119 108 1119 960 1120 188 1120 961 1120 961 1067 188 1067 190 1067 961 1068 190 1068 962 1068 962 1121 190 1121 192 1121 962 1122 192 1122 963 1122 963 1123 192 1123 194 1123 963 1123 194 1123 964 1123 964 1072 194 1072 196 1072 964 1072 196 1072 965 1072 965 1074 196 1074 198 1074 965 1074 198 1074 966 1074 966 1124 198 1124 200 1124 966 1124 200 1124 967 1124 967 1125 200 1125 202 1125 967 1125 202 1125 968 1125 968 1126 202 1126 204 1126 968 1126 204 1126 969 1126 969 1127 204 1127 206 1127 969 1127 206 1127 970 1127 970 1080 206 1080 208 1080 970 1080 208 1080 971 1080 971 1128 208 1128 210 1128 971 1128 210 1128 972 1128 972 1129 210 1129 138 1129 972 1129 138 1129 973 1129 973 1130 138 1130 140 1130 973 1131 140 1131 974 1131 974 1132 140 1132 142 1132 974 1132 142 1132 975 1132 975 1087 142 1087 144 1087 975 1088 144 1088 976 1088 976 1133 144 1133 146 1133 976 1133 146 1133 977 1133 977 1091 146 1091 148 1091 977 1091 148 1091 978 1091 978 1093 148 1093 150 1093 978 1094 150 1094 979 1094 979 0 150 0 152 0 979 0 152 0 980 0 980 1134 152 1134 154 1134 980 1135 154 1135 981 1135 981 1097 154 1097 156 1097 981 1097 156 1097 982 1097 982 1136 156 1136 158 1136 982 1136 158 1136 983 1136 983 1101 158 1101 160 1101 983 1102 160 1102 984 1102 984 1103 160 1103 162 1103 984 1104 162 1104 985 1104 985 1105 162 1105 164 1105 985 1106 164 1106 986 1106 986 1107 164 1107 166 1107 986 1107 166 1107 987 1107 987 1108 166 1108 168 1108 987 1108 168 1108 988 1108 988 1137 168 1137 170 1137 988 1137 170 1137 989 1137 989 1138 170 1138 172 1138 989 1138 172 1138 990 1138 990 1111 172 1111 174 1111 990 1111 174 1111 991 1111 991 1112 174 1112 176 1112 991 1112 176 1112 992 1112 992 1139 176 1139 178 1139 992 1140 178 1140 993 1140 993 1141 178 1141 180 1141 993 1141 180 1141 994 1141 994 1115 180 1115 182 1115 994 1115 182 1115 995 1115 995 1116 182 1116 184 1116 995 1116 184 1116 996 1116 996 1117 184 1117 186 1117 996 1118 186 1118 960 1118 960 1119 186 1119 188 1119 958 43 959 43 941 43 942 1142 943 1142 950 1142 959 43 923 43 941 43 941 43 923 43 924 43 941 43 924 43 925 43 942 1143 950 1143 941 1143 941 1144 950 1144 951 1144 941 1145 951 1145 952 1145 952 43 953 43 941 43 941 1146 953 1146 954 1146 941 1147 954 1147 955 1147 955 1148 956 1148 941 1148 941 1149 956 1149 957 1149 941 1150 957 1150 958 1150 925 1151 926 1151 941 1151 941 43 926 43 927 43 941 1152 927 1152 928 1152 928 43 929 43 941 43 941 1153 929 1153 930 1153 941 1154 930 1154 931 1154 939 1155 940 1155 935 1155 935 1156 940 1156 941 1156 935 43 941 43 934 43 944 43 948 43 943 43 943 1157 948 1157 949 1157 943 1158 949 1158 950 1158 944 1159 945 1159 948 1159 948 43 945 43 946 43 948 1160 946 1160 947 1160 931 1161 932 1161 941 1161 941 1162 932 1162 933 1162 941 1163 933 1163 934 1163 936 1164 937 1164 935 1164 935 43 937 43 938 43 935 1165 938 1165 939 1165 970 1166 971 1166 985 1166 964 43 965 43 985 43 985 1167 965 1167 966 1167 985 1168 966 1168 967 1168 967 1169 968 1169 985 1169 985 1170 968 1170 969 1170 985 1171 969 1171 970 1171 971 43 972 43 985 43 985 1172 972 1172 973 1172 985 1173 973 1173 974 1173 974 43 975 43 985 43 985 1174 975 1174 976 1174 985 43 976 43 984 43 986 43 987 43 996 43 996 1175 987 1175 988 1175 986 43 996 43 985 43 985 1176 996 1176 960 1176 985 1177 960 1177 961 1177 961 43 962 43 985 43 985 1178 962 1178 963 1178 985 43 963 43 964 43 984 43 976 43 983 43 983 1179 976 1179 977 1179 983 1180 977 1180 978 1180 994 1181 990 1181 993 1181 993 1182 990 1182 991 1182 993 1183 991 1183 992 1183 978 1184 979 1184 983 1184 983 1185 979 1185 980 1185 983 43 980 43 982 43 982 43 980 43 981 43 988 43 989 43 996 43 996 1186 989 1186 990 1186 996 1187 990 1187 995 1187 995 1188 990 1188 994 1188 997 95 998 95 13 95 13 95 998 95 12 95 998 96 999 96 12 96 12 96 999 96 15 96 999 94 1000 94 15 94 15 94 1000 94 14 94 1000 43 997 43 14 43 14 43 997 43 13 43 1001 0 1002 0 1003 0 997 1189 1004 1189 998 1189 998 0 1004 0 1005 0 1005 1190 1006 1190 998 1190 998 0 1006 0 1001 0 998 0 1001 0 999 0 999 1191 1001 1191 1003 1191 999 1192 1003 1192 1000 1192 1000 0 1003 0 1007 0 1000 0 1007 0 997 0 997 0 1007 0 1008 0 997 0 1008 0 1004 0 1004 96 1009 96 1005 96 1005 96 1009 96 1010 96 1011 95 1009 95 1008 95 1008 95 1009 95 1004 95 1012 43 1011 43 1007 43 1007 43 1011 43 1008 43 1003 94 1013 94 1007 94 1007 94 1013 94 1012 94 1002 96 1014 96 1003 96 1003 96 1014 96 1013 96 1015 94 1014 94 1001 94 1001 94 1014 94 1002 94 1006 96 1016 96 1001 96 1001 96 1016 96 1015 96 1005 95 1010 95 1006 95 1006 95 1010 95 1016 95 1014 0 1017 0 1018 0 1015 0 1016 0 1014 0 1014 0 1016 0 1010 0 1014 0 1010 0 1017 0 1017 0 1010 0 1009 0 1017 0 1009 0 1019 0 1019 1193 1009 1193 1011 1193 1019 0 1011 0 1020 0 1020 0 1011 0 1012 0 1020 0 1012 0 1018 0 1018 0 1012 0 1013 0 1018 0 1013 0 1014 0 1020 95 1018 95 1021 95 1021 95 1018 95 1022 95 1023 96 1019 96 1021 96 1021 96 1019 96 1020 96 1024 94 1017 94 1023 94 1023 94 1017 94 1019 94 1018 43 1017 43 1022 43 1022 43 1017 43 1024 43 1023 0 1021 0 1024 0 1024 0 1021 0 1022 0 1025 1194 1026 1194 1027 1194 1027 96 1028 96 1025 96 1025 1195 1028 1195 1029 1195 1025 1196 1029 1196 1030 1196 1031 96 1032 96 1033 96 1030 96 1034 96 1025 96 1025 1197 1034 1197 1035 1197 1025 1198 1035 1198 1036 1198 1031 1199 1033 1199 1025 1199 1025 1200 1033 1200 1037 1200 1025 1201 1037 1201 1038 1201 1039 1202 1040 1202 1025 1202 1025 96 1040 96 1041 96 1025 96 1041 96 1042 96 1042 1203 1043 1203 1025 1203 1025 96 1043 96 1044 96 1025 96 1044 96 1026 96 1036 96 1045 96 1025 96 1025 1204 1045 1204 1046 1204 1025 1205 1046 1205 1047 1205 1047 96 1048 96 1025 96 1025 1206 1048 1206 1049 1206 1025 1207 1049 1207 1050 1207 1032 1208 1051 1208 1033 1208 1033 1209 1051 1209 1052 1209 1033 1210 1052 1210 1053 1210 1038 96 1054 96 1025 96 1025 96 1054 96 1055 96 1025 1211 1055 1211 1039 1211 1056 96 1057 96 1050 96 1050 1212 1057 1212 1058 1212 1050 1213 1058 1213 1025 1213 1056 96 1059 96 1057 96 1057 96 1059 96 1060 96 1057 1214 1060 1214 1061 1214 1062 43 1063 43 1064 43 1065 43 1066 43 1067 43 1063 43 1068 43 1064 43 1064 1215 1068 1215 1069 1215 1064 43 1069 43 1070 43 1065 43 1067 43 1064 43 1064 1216 1067 1216 1071 1216 1064 1217 1071 1217 1072 1217 1072 43 1073 43 1064 43 1064 1218 1073 1218 1074 1218 1064 43 1074 43 1075 43 1075 1219 1076 1219 1064 1219 1064 1220 1076 1220 1077 1220 1064 1221 1077 1221 1062 1221 1070 1222 1078 1222 1064 1222 1064 1223 1078 1223 1079 1223 1064 1224 1079 1224 1080 1224 1080 1225 1081 1225 1064 1225 1064 1226 1081 1226 1082 1226 1064 1227 1082 1227 1083 1227 1084 43 1085 43 1086 43 1086 1228 1085 1228 1064 1228 1086 43 1064 43 1087 43 1088 1229 1089 1229 1066 1229 1066 1230 1089 1230 1090 1230 1066 1231 1090 1231 1067 1231 1088 1232 1091 1232 1089 1232 1089 1233 1091 1233 1092 1233 1089 1234 1092 1234 1093 1234 1083 43 1094 43 1064 43 1064 1235 1094 1235 1095 1235 1064 1236 1095 1236 1087 1236 1096 43 1097 43 1086 43 1086 43 1097 43 1098 43 1086 43 1098 43 1084 43 1068 1237 1026 1237 1069 1237 1069 1238 1026 1238 1044 1238 1069 1239 1044 1239 1070 1239 1070 1240 1044 1240 1043 1240 1070 1241 1043 1241 1078 1241 1078 1242 1043 1242 1042 1242 1078 1243 1042 1243 1079 1243 1079 1073 1042 1073 1041 1073 1079 1244 1041 1244 1080 1244 1080 1245 1041 1245 1040 1245 1080 1246 1040 1246 1081 1246 1081 1247 1040 1247 1039 1247 1081 1248 1039 1248 1082 1248 1082 1249 1039 1249 1055 1249 1082 1250 1055 1250 1083 1250 1083 1251 1055 1251 1054 1251 1083 1251 1054 1251 1094 1251 1094 1079 1054 1079 1038 1079 1094 1252 1038 1252 1095 1252 1095 1080 1038 1080 1037 1080 1095 1253 1037 1253 1087 1253 1087 1254 1037 1254 1033 1254 1087 1255 1033 1255 1086 1255 1086 1256 1033 1256 1053 1256 1086 1257 1053 1257 1096 1257 1096 1258 1053 1258 1052 1258 1096 1258 1052 1258 1097 1258 1097 1259 1052 1259 1051 1259 1097 1260 1051 1260 1098 1260 1098 1261 1051 1261 1032 1261 1098 1262 1032 1262 1084 1262 1084 1263 1032 1263 1031 1263 1084 1264 1031 1264 1085 1264 1085 1265 1031 1265 1025 1265 1085 1266 1025 1266 1064 1266 1064 1267 1025 1267 1058 1267 1064 1268 1058 1268 1065 1268 1065 0 1058 0 1057 0 1065 0 1057 0 1066 0 1066 1269 1057 1269 1061 1269 1066 1269 1061 1269 1088 1269 1088 1270 1061 1270 1060 1270 1088 1271 1060 1271 1091 1271 1091 1272 1060 1272 1059 1272 1091 1273 1059 1273 1092 1273 1092 1274 1059 1274 1056 1274 1092 1102 1056 1102 1093 1102 1093 1275 1056 1275 1050 1275 1093 1276 1050 1276 1089 1276 1089 1277 1050 1277 1049 1277 1089 1277 1049 1277 1090 1277 1090 1278 1049 1278 1048 1278 1090 1279 1048 1279 1067 1279 1067 1280 1048 1280 1047 1280 1067 1281 1047 1281 1071 1281 1071 1109 1047 1109 1046 1109 1071 1282 1046 1282 1072 1282 1072 1110 1046 1110 1045 1110 1072 1110 1045 1110 1073 1110 1073 1283 1045 1283 1036 1283 1073 1283 1036 1283 1074 1283 1074 1284 1036 1284 1035 1284 1074 1285 1035 1285 1075 1285 1075 1113 1035 1113 1034 1113 1075 1286 1034 1286 1076 1286 1076 1287 1034 1287 1030 1287 1076 1288 1030 1288 1077 1288 1077 1289 1030 1289 1029 1289 1077 1290 1029 1290 1062 1290 1062 1291 1029 1291 1028 1291 1062 1291 1028 1291 1063 1291 1063 1292 1028 1292 1027 1292 1063 1293 1027 1293 1068 1293 1068 1294 1027 1294 1026 1294 1099 96 1100 96 1101 96 1101 1295 1100 1295 1102 1295 1103 96 1104 96 1101 96 1101 1296 1104 1296 1105 1296 1105 96 1106 96 1101 96 1101 1297 1106 1297 1107 1297 1101 1298 1107 1298 1108 1298 1109 96 1110 96 1111 96 1108 1299 1112 1299 1101 1299 1101 1300 1112 1300 1113 1300 1101 1301 1113 1301 1099 1301 1102 1302 1114 1302 1101 1302 1101 1303 1114 1303 1115 1303 1101 1304 1115 1304 1116 1304 1116 1305 1117 1305 1101 1305 1101 1306 1117 1306 1118 1306 1101 96 1118 96 1119 96 1109 1307 1111 1307 1101 1307 1101 1308 1111 1308 1120 1308 1101 1309 1120 1309 1103 1309 1110 96 1121 96 1111 96 1111 1310 1121 1310 1122 1310 1111 1311 1122 1311 1123 1311 1123 96 1124 96 1111 96 1111 1312 1124 1312 1125 1312 1111 1313 1125 1313 1126 1313 1119 1314 1127 1314 1101 1314 1101 1315 1127 1315 1128 1315 1101 96 1128 96 1129 96 1130 96 1131 96 1132 96 1132 96 1131 96 1133 96 1129 96 1134 96 1101 96 1101 96 1134 96 1131 96 1101 96 1131 96 1135 96 1135 1316 1131 1316 1130 1316 1136 43 1137 43 1138 43 1139 43 1140 43 1138 43 1138 1317 1140 1317 1141 1317 1138 1318 1141 1318 1142 1318 1142 1319 1143 1319 1138 1319 1138 1320 1143 1320 1144 1320 1138 1321 1144 1321 1136 1321 1137 43 1145 43 1138 43 1138 1322 1145 1322 1146 1322 1138 1323 1146 1323 1147 1323 1147 43 1148 43 1138 43 1138 43 1148 43 1149 43 1138 43 1149 43 1150 43 1151 43 1152 43 1153 43 1153 1324 1152 1324 1154 1324 1151 43 1153 43 1138 43 1138 1325 1153 1325 1155 1325 1138 1326 1155 1326 1156 1326 1156 43 1157 43 1138 43 1138 1327 1157 1327 1158 1327 1138 1328 1158 1328 1139 1328 1150 43 1149 43 1159 43 1159 1329 1149 1329 1160 1329 1159 1330 1160 1330 1161 1330 1162 1331 1163 1331 1164 1331 1164 1332 1163 1332 1165 1332 1164 1333 1165 1333 1166 1333 1161 1334 1167 1334 1159 1334 1159 1335 1167 1335 1168 1335 1159 1336 1168 1336 1169 1336 1169 1337 1168 1337 1170 1337 1154 43 1171 43 1153 43 1153 1338 1171 1338 1163 1338 1153 1339 1163 1339 1172 1339 1172 1340 1163 1340 1162 1340 1155 1341 1116 1341 1156 1341 1156 1238 1116 1238 1115 1238 1156 1239 1115 1239 1157 1239 1157 1342 1115 1342 1114 1342 1157 1343 1114 1343 1158 1343 1158 1344 1114 1344 1102 1344 1158 1345 1102 1345 1139 1345 1139 1346 1102 1346 1100 1346 1139 1347 1100 1347 1140 1347 1140 1245 1100 1245 1099 1245 1140 1246 1099 1246 1141 1246 1141 1124 1099 1124 1113 1124 1141 1348 1113 1348 1142 1348 1142 1349 1113 1349 1112 1349 1142 1350 1112 1350 1143 1350 1143 1126 1112 1126 1108 1126 1143 1351 1108 1351 1144 1351 1144 1352 1108 1352 1107 1352 1144 1353 1107 1353 1136 1353 1136 1080 1107 1080 1106 1080 1136 1253 1106 1253 1137 1253 1137 1354 1106 1354 1105 1354 1137 1355 1105 1355 1145 1355 1145 1356 1105 1356 1104 1356 1145 1357 1104 1357 1146 1357 1146 1358 1104 1358 1103 1358 1146 1359 1103 1359 1147 1359 1147 1360 1103 1360 1120 1360 1147 1361 1120 1361 1148 1361 1148 1261 1120 1261 1111 1261 1148 1262 1111 1262 1149 1262 1149 1362 1111 1362 1126 1362 1149 1363 1126 1363 1160 1363 1160 1364 1126 1364 1125 1364 1160 1365 1125 1365 1161 1365 1161 1267 1125 1267 1124 1267 1161 1268 1124 1268 1167 1268 1167 0 1124 0 1123 0 1167 0 1123 0 1168 0 1168 1366 1123 1366 1122 1366 1168 1367 1122 1367 1170 1367 1170 1368 1122 1368 1121 1368 1170 1369 1121 1369 1169 1369 1169 1370 1121 1370 1110 1370 1169 1371 1110 1371 1159 1371 1159 1274 1110 1274 1109 1274 1159 1102 1109 1102 1150 1102 1150 1275 1109 1275 1101 1275 1150 1276 1101 1276 1138 1276 1138 1277 1101 1277 1135 1277 1138 1277 1135 1277 1151 1277 1151 1278 1135 1278 1130 1278 1151 1279 1130 1279 1152 1279 1152 1280 1130 1280 1132 1280 1152 1281 1132 1281 1154 1281 1154 1372 1132 1372 1133 1372 1154 1373 1133 1373 1171 1373 1171 1138 1133 1138 1131 1138 1171 1374 1131 1374 1163 1374 1163 1283 1131 1283 1134 1283 1163 1283 1134 1283 1165 1283 1165 1284 1134 1284 1129 1284 1165 1285 1129 1285 1166 1285 1166 1375 1129 1375 1128 1375 1166 1376 1128 1376 1164 1376 1164 1377 1128 1377 1127 1377 1164 1377 1127 1377 1162 1377 1162 1289 1127 1289 1119 1289 1162 1290 1119 1290 1172 1290 1172 1291 1119 1291 1118 1291 1172 1291 1118 1291 1153 1291 1153 1292 1118 1292 1117 1292 1153 1293 1117 1293 1155 1293 1155 1378 1117 1378 1116 1378</p> + </polylist> + </mesh> + </geometry> + </library_geometries> + <library_controllers/> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Camera" name="Camera" type="NODE"> + <matrix sid="transform">0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1</matrix> + <instance_camera url="#Camera-camera"/> + </node> + <node id="Lamp" name="Lamp" type="NODE"> + <matrix sid="transform">-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</matrix> + <instance_light url="#Lamp-light"/> + </node> + <node id="lidarlite" name="lidarlite" type="NODE"> + <matrix sid="transform">-4.37114e-11 0.001 0 0.015 -0.001 -4.37114e-11 0 0 0 0 0.001 0 0 0 0 1</matrix> + <instance_geometry url="#lidarlite-mesh" name="lidarlite"> + <bind_material> + <technique_common> + <instance_material symbol="Material_001-material" target="#Material_001-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> \ No newline at end of file diff --git a/kinton_description/meshes/sonar_sensor/max_sonar_ez4.blend b/kinton_description/meshes/sonar_sensor/max_sonar_ez4.blend new file mode 100644 index 0000000000000000000000000000000000000000..e95fcbda5420d381d7ffb11952c6d3cc30331211 Binary files /dev/null and b/kinton_description/meshes/sonar_sensor/max_sonar_ez4.blend differ diff --git a/kinton_description/meshes/sonar_sensor/max_sonar_ez4.dae b/kinton_description/meshes/sonar_sensor/max_sonar_ez4.dae new file mode 100644 index 0000000000000000000000000000000000000000..3b4789fdf5e7adc1911545d1d61ccb79b1930730 --- /dev/null +++ b/kinton_description/meshes/sonar_sensor/max_sonar_ez4.dae @@ -0,0 +1,252 @@ +<?xml version="1.0" encoding="utf-8"?> +<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1"> + <asset> + <contributor> + <author>Stefan Kohlbrecher</author> + <authoring_tool>Blender 2.61.4 r43995</authoring_tool> + </contributor> + <created>2012-02-09T09:19:02</created> + <modified>2012-02-09T09:19:02</modified> + <unit name="meter" meter="1"/> + <up_axis>Z_UP</up_axis> + </asset> + <library_cameras> + <camera id="Camera-camera" name="Camera"> + <optics> + <technique_common> + <perspective> + <xfov sid="xfov">49.13434</xfov> + <aspect_ratio>1.777778</aspect_ratio> + <znear sid="znear">0.1</znear> + <zfar sid="zfar">100</zfar> + </perspective> + </technique_common> + </optics> + </camera> + </library_cameras> + <library_lights> + <light id="Lamp-light" name="Lamp"> + <technique_common> + <point> + <color sid="color">1 1 1</color> + <constant_attenuation>1</constant_attenuation> + <linear_attenuation>0</linear_attenuation> + <quadratic_attenuation>0.00111109</quadratic_attenuation> + </point> + </technique_common> + <extra> + <technique profile="blender"> + <adapt_thresh>0.000999987</adapt_thresh> + <area_shape>0</area_shape> + <area_size>1</area_size> + <area_sizey>1</area_sizey> + <area_sizez>1</area_sizez> + <atm_distance_factor>1</atm_distance_factor> + <atm_extinction_factor>1</atm_extinction_factor> + <atm_turbidity>2</atm_turbidity> + <att1>0</att1> + <att2>1</att2> + <backscattered_light>1</backscattered_light> + <bias>1</bias> + <blue>1</blue> + <buffers>1</buffers> + <bufflag>0</bufflag> + <bufsize>2880</bufsize> + <buftype>2</buftype> + <clipend>30.002</clipend> + <clipsta>1.000799</clipsta> + <compressthresh>0.04999995</compressthresh> + <dist sid="blender_dist">29.99998</dist> + <energy sid="blender_energy">1</energy> + <falloff_type>2</falloff_type> + <filtertype>0</filtertype> + <flag>0</flag> + <gamma sid="blender_gamma">1</gamma> + <green>1</green> + <halo_intensity sid="blnder_halo_intensity">1</halo_intensity> + <horizon_brightness>1</horizon_brightness> + <mode>8192</mode> + <ray_samp>1</ray_samp> + <ray_samp_method>1</ray_samp_method> + <ray_samp_type>0</ray_samp_type> + <ray_sampy>1</ray_sampy> + <ray_sampz>1</ray_sampz> + <red>1</red> + <samp>3</samp> + <shadhalostep>0</shadhalostep> + <shadow_b sid="blender_shadow_b">0</shadow_b> + <shadow_g sid="blender_shadow_g">0</shadow_g> + <shadow_r sid="blender_shadow_r">0</shadow_r> + <shadspotsize>45</shadspotsize> + <sky_colorspace>0</sky_colorspace> + <sky_exposure>1</sky_exposure> + <skyblendfac>1</skyblendfac> + <skyblendtype>1</skyblendtype> + <soft>3</soft> + <spotblend>0.15</spotblend> + <spotsize>75</spotsize> + <spread>1</spread> + <sun_brightness>1</sun_brightness> + <sun_effect_type>0</sun_effect_type> + <sun_intensity>1</sun_intensity> + <sun_size>1</sun_size> + <type>0</type> + </technique> + </extra> + </light> + </library_lights> + <library_effects> + <effect id="PCB_Green-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0.05536731 0.2029368 0.01810702 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.05536731 0.2029368 0.01810702 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + <effect id="Sonar_Black-effect"> + <profile_COMMON> + <technique sid="common"> + <phong> + <emission> + <color sid="emission">0 0 0 1</color> + </emission> + <ambient> + <color sid="ambient">0.02484926 0.02484926 0.02484926 1</color> + </ambient> + <diffuse> + <color sid="diffuse">0.02484926 0.02484926 0.02484926 1</color> + </diffuse> + <specular> + <color sid="specular">0.5 0.5 0.5 1</color> + </specular> + <shininess> + <float sid="shininess">50</float> + </shininess> + <index_of_refraction> + <float sid="index_of_refraction">1</float> + </index_of_refraction> + </phong> + </technique> + <extra> + <technique profile="GOOGLEEARTH"> + <double_sided>1</double_sided> + </technique> + </extra> + </profile_COMMON> + <extra><technique profile="MAX3D"><double_sided>1</double_sided></technique></extra> + </effect> + </library_effects> + <library_materials> + <material id="PCB_Green-material" name="PCB Green"> + <instance_effect url="#PCB_Green-effect"/> + </material> + <material id="Sonar_Black-material" name="Sonar_Black"> + <instance_effect url="#Sonar_Black-effect"/> + </material> + </library_materials> + <library_geometries> + <geometry id="Plane-mesh" name="Plane"> + <mesh> + <source id="Plane-mesh-positions"> + <float_array id="Plane-mesh-positions-array" count="75">0.01099997 0.01099979 0 0.01099991 -0.01100003 0 -0.01100021 -0.01099991 0 -0.01099973 0.01100021 0 -0.01099973 0.01100021 0.002601444 -0.01100021 -0.01099991 0.002601444 0.01099991 -0.01100003 0.002601444 0.01099997 0.01099979 0.002601444 0 0.007999956 0.003145456 0.005656838 0.005656838 0.003145456 0.007999956 0 0.003145456 0.005656838 -0.005656838 0.003145456 0 -0.007999956 0.003145456 -0.005656838 -0.005656838 0.003145456 -0.007999956 0 0.003145456 -0.005656838 0.005656838 0.003145456 0 0.007999956 0.01499998 0.005656838 0.005656838 0.01499998 0.007999956 0 0.01499998 0.005656838 -0.005656838 0.01499998 0 -0.007999956 0.01499998 -0.005656838 -0.005656838 0.01499998 -0.007999956 0 0.01499998 -0.005656838 0.005656838 0.01499998 0 0 0.01499998</float_array> + <technique_common> + <accessor source="#Plane-mesh-positions-array" count="25" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <source id="Plane-mesh-normals"> + <float_array id="Plane-mesh-normals-array" count="108">0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.7070834 0.7070834 0 -0.548967 0.548967 0.6302378 0 0.7763603 0.6302378 0 1 0 -1 0 0 -0.7763603 0 0.6302378 -0.7070834 -0.7070834 0 -0.548967 -0.548967 0.6302378 0 -1 0 0 -0.7763603 0.6302378 0.7070834 -0.7070834 0 0.548967 -0.548967 0.6302378 1 0 0 0.7763603 0 0.6302378 0.7070834 0.7070834 0 0.548967 0.548967 0.6302378 0 0 1 0 0 1 -5.41857e-6 -1 0 -5.41857e-6 -1 0 1 -2.70932e-6 0 1 -2.70932e-6 0 1.89654e-5 1 0 1.89654e-5 1 0 -1 2.16743e-5 0 -1 2.16743e-5 0 0 0 -1 0 0 -1</float_array> + <technique_common> + <accessor source="#Plane-mesh-normals-array" count="36" stride="3"> + <param name="X" type="float"/> + <param name="Y" type="float"/> + <param name="Z" type="float"/> + </accessor> + </technique_common> + </source> + <vertices id="Plane-mesh-vertices"> + <input semantic="POSITION" source="#Plane-mesh-positions"/> + </vertices> + <polylist material="PCB_Green1" count="12"> + <input semantic="VERTEX" source="#Plane-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Plane-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>5 24 7 24 4 24 5 25 6 25 7 25 1 26 5 26 2 26 1 27 6 27 5 27 0 28 6 28 1 28 0 29 7 29 6 29 7 30 0 30 3 30 3 31 4 31 7 31 2 32 4 32 3 32 2 33 5 33 4 33 0 34 2 34 3 34 0 35 1 35 2 35</p> + </polylist> + <polylist material="Sonar_Black2" count="24"> + <input semantic="VERTEX" source="#Plane-mesh-vertices" offset="0"/> + <input semantic="NORMAL" source="#Plane-mesh-normals" offset="1"/> + <vcount>3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 </vcount> + <p>24 0 17 0 16 0 24 1 18 1 17 1 24 2 19 2 18 2 24 3 20 3 19 3 24 4 21 4 20 4 24 5 22 5 21 5 24 6 23 6 22 6 24 7 16 7 23 7 15 8 23 9 16 10 15 8 16 10 8 11 14 12 22 13 23 9 14 12 23 9 15 8 13 14 21 15 22 13 13 14 22 13 14 12 12 16 20 17 21 15 12 16 21 15 13 14 11 18 19 19 20 17 11 18 20 17 12 16 10 20 18 21 19 19 10 20 19 19 11 18 9 22 17 23 18 21 9 22 18 21 10 20 8 11 16 10 17 23 8 11 17 23 9 22</p> + </polylist> + </mesh> + <extra><technique profile="MAYA"><double_sided>1</double_sided></technique></extra> + </geometry> + </library_geometries> + <library_visual_scenes> + <visual_scene id="Scene" name="Scene"> + <node id="Plane" type="NODE"> + <translate sid="location">0 0 0</translate> + <rotate sid="rotationZ">0 0 1 0</rotate> + <rotate sid="rotationY">0 1 0 89.99999</rotate> + <rotate sid="rotationX">1 0 0 -7.69819e-6</rotate> + <scale sid="scale">1 1 1</scale> + <instance_geometry url="#Plane-mesh"> + <bind_material> + <technique_common> + <instance_material symbol="PCB_Green1" target="#PCB_Green-material"/> + <instance_material symbol="Sonar_Black2" target="#Sonar_Black-material"/> + </technique_common> + </bind_material> + </instance_geometry> + </node> + <node id="Lamp" type="NODE"> + <translate sid="location">5.903862 1.005455 -4.076244</translate> + <rotate sid="rotationZ">0 0 1 93.30684</rotate> + <rotate sid="rotationY">0 1 0 -16.90973</rotate> + <rotate sid="rotationX">1 0 0 126.2982</rotate> + <scale sid="scale">1 1 1</scale> + <instance_light url="#Lamp-light"/> + </node> + <node id="Camera" type="NODE"> + <translate sid="location">5.343667 -6.507638 -7.481132</translate> + <rotate sid="rotationZ">0 0 1 90.85168</rotate> + <rotate sid="rotationY">0 1 0 43.30489</rotate> + <rotate sid="rotationX">1 0 0 154.1435</rotate> + <scale sid="scale">1 1 1</scale> + <instance_camera url="#Camera-camera"/> + </node> + </visual_scene> + </library_visual_scenes> + <scene> + <instance_visual_scene url="#Scene"/> + </scene> +</COLLADA> diff --git a/kinton_description/urdf/kinton_arm.urdf b/kinton_description/urdf/kinton_arm.urdf new file mode 100644 index 0000000000000000000000000000000000000000..f63a1d6689fac26d72423dedba177291b347c911 --- /dev/null +++ b/kinton_description/urdf/kinton_arm.urdf @@ -0,0 +1,721 @@ +<?xml version="1.0" ?> +<!-- =================================================================================== --> +<!-- | This document was autogenerated by xacro from kinton_arm.xacro | --> +<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- =================================================================================== --> +<robot name="kinton" xmlns:xacro="http://ros.org/wiki/xacro"> + <!-- Be sure the parameter server has the correct chain joints + <param name="root_name" value="base_link" /> + <param name="tip_name" value="arm_joint6" /> --> + <material name="black"> + <color rgba="0.15 0.15 0.15 1.0"/> + </material> + <material name="blue"> + <color rgba="0.17 0.3 0.56 1.0"/> + </material> + <material name="orange"> + <color rgba="0.93 0.44 0.01 1.0"/> + </material> + <material name="green"> + <color rgba="0.0 0.8 0.0 1.0"/> + </material> + <material name="grey"> + <color rgba="0.3 0.3 0.3 1.0"/> + </material> + <material name="grey2"> + <color rgba="0.7 0.7 0.7 1.0"/> + </material> + <material name="grey3"> + <color rgba="0.9 0.9 0.9 1.0"/> + </material> + <material name="red"> + <color rgba="0.8 0.0 0.0 1.0"/> + </material> + <material name="white"> + <color rgba="0.9 0.9 0.9 1.0"/> + </material> + <link name="base_link"> + <inertial> + <mass value="1.477"/> + <origin xyz="0 0 0"/> + <inertia ixx="0.01152" ixy="0.0" ixz="0.0" iyy="0.01152" iyz="0.0" izz="0.0218"/> + </inertial> + <visual> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/kinton/kinton2.dae" scale="1 1 1"/> + </geometry> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/kinton/kinton2.stl" scale="1 1 1"/> + </geometry> + </collision> + </link> + <!-- Base footprint --> + <!-- <link name="base_footprint"> + <inertial> + <mass value="0.01" /> + <origin xyz="0 0 -0.195" rpy="0 0 0"/> + <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> + </inertial> + <visual> + <origin xyz="0 0 0" rpy="0 0 0"/> + <geometry> + <box size="0.00001 0.00001 0.00001" /> + </geometry> + <material name="grey"/> + </visual> + </link> + <joint name="base_link_to_base_footprint" type="fixed"> + <parent link="base_link"/> + <child link="base_footprint"/> + <origin xyz="0.00 0.00 -0.195" rpy="0.0 0.0 0.0"/> + </joint> --> + <!-- COMPASS --> + <link name="compass"> + <inertial> + <mass value="0.01"/> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> + </inertial> + <visual> + <geometry> + <box size="0.02 0.02 0.01"/> + </geometry> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <geometry> + <box size="0.02 0.02 0.01"/> + </geometry> + </collision> + </link> + <joint name="base_link_to_compass" type="fixed"> + <parent link="base_link"/> + <child link="compass"/> + <origin rpy="0.0 0.0 -2.35619449019" xyz="-0.015 0.0 0.066"/> + </joint> + <gazebo> + <plugin filename="libhector_gazebo_ros_magnetic.so" name="magnetic_sim"> + <alwaysOn>true</alwaysOn> + <updateRate>10.0</updateRate> + <bodyName>base_link</bodyName> + <topicName>kinton/magnetic</topicName> + <offset>0 0 0</offset> + <drift>0.0 0.0 0.0</drift> + <driftFrequency>0.0 0.0 0.0</driftFrequency> + <gaussianNoise>1.3e-2 1.3e-2 1.3e-2</gaussianNoise> + </plugin> + </gazebo> + <gazebo reference="compass"> + <material>Gazebo/Black</material> + <turnGravityOff>true</turnGravityOff> + </gazebo> + <!-- GYROS --> + <link name="imu"> + <inertial> + <mass value="0.01"/> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> + </inertial> + <visual> + <geometry> + <box size="0.03 0.03 0.005"/> + </geometry> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0.0 0.0 2.35619449019" xyz="0.0 0.0 0.0"/> + <geometry> + <box size="0.03 0.03 0.005"/> + </geometry> + </collision> + </link> + <joint name="base_link_to_imu" type="fixed"> + <parent link="base_link"/> + <child link="imu"/> + <origin rpy="0.0 0.0 0.785398163397" xyz="0.0 0.0 0.04"/> + </joint> + <gazebo> + <plugin filename="libhector_gazebo_ros_imu.so" name="imu_sim"> + <alwaysOn>true</alwaysOn> + <updateRate>100.0</updateRate> + <bodyName>base_link</bodyName> + <frameId>kinton/imu</frameId> + <topicName>kinton/imu_raw</topicName> + <rpyOffsets>0 0 0</rpyOffsets> + <!-- deprecated --> + <gaussianNoise>0</gaussianNoise> + <!-- deprecated --> + <accelDrift>0.5 0.5 0.5</accelDrift> + <accelOffset>0.0 0.0 0.0</accelOffset> + <accelDriftFrequency>0.0 0.0 0.0</accelDriftFrequency> + <accelGaussianNoise>0.35 0.35 0.3</accelGaussianNoise> + <rateDrift>0.0 0.0 0.0</rateDrift> + <rateOffset>0.0 0.0 0.0</rateOffset> + <rateDriftFrequency>0.0 0.0 0.0</rateDriftFrequency> + <rateGaussianNoise>0.00 0.00 0.00</rateGaussianNoise> + <headingDrift>0.0</headingDrift> + <headingGaussianNoise>0.00</headingGaussianNoise> + <headingOffset>0.0</headingOffset> + <headingDriftFrequency>0.0</headingDriftFrequency> + </plugin> + </gazebo> + <gazebo reference="imu"> + <material>Gazebo/Black</material> + <turnGravityOff>true</turnGravityOff> + </gazebo> + <gazebo> + <plugin filename="libgazebo_ros_p3d.so" name="odom_sim"> + <alwaysOn>true</alwaysOn> + <updateRate>100.0</updateRate> + <bodyName>base_link</bodyName> + <topicName>kinton/odom</topicName> + <gaussianNoise>0.0</gaussianNoise> + <frameName>world</frameName> + </plugin> + </gazebo> + <!-- GPS --> + <link name="gps"> + <inertial> + <mass value="0.01"/> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> + </inertial> + <visual> + <geometry> + <box size="0.02 0.04 0.02"/> + </geometry> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <material name="grey"/> + </visual> + <collision> + <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/> + <geometry> + <box size="0.02 0.04 0.02"/> + </geometry> + </collision> + </link> + <joint name="base_link_to_gps" type="fixed"> + <parent link="base_link"/> + <child link="gps"/> + <origin rpy="0.0 0.0 0.0" xyz="0.02 0.0 0.066"/> + </joint> + <gazebo> + <plugin filename="libhector_gazebo_ros_gps.so" name="gps_sim"> + <alwaysOn>true</alwaysOn> + <updateRate>5.0</updateRate> + <bodyName>base_link</bodyName> + <topicName>kinton/fix</topicName> + <velocityTopicName>kinton/fix_velocity</velocityTopicName> + <referenceLatitude>41.3851</referenceLatitude> + <referenceLongitude>2.1734</referenceLongitude> + <referenceAltitude>5.0</referenceAltitude> + <referenceHeading>0.0</referenceHeading> + <!--TEST 90 for testing with robot_pose_ekf --> + <offset>0 0 0</offset> + <drift>5.0 5.0 5.0</drift> + <driftFrequency>0.0 0.0 0.0</driftFrequency> + <gaussianNoise>0.1 0.1 0.1</gaussianNoise> + <velocityOffset>0 0 0</velocityOffset> + <velocityDrift>0 0 0</velocityDrift> + <velocityDriftFrequency>0 0 0</velocityDriftFrequency> + <velocityGaussianNoise>0.1 0.1 0.1</velocityGaussianNoise> + </plugin> + </gazebo> + <gazebo reference="gps"> + <material>Gazebo/Black</material> + <turnGravityOff>true</turnGravityOff> + </gazebo> + <!-- WITHOUT ARM --> + <!-- <gazebo> + <plugin name="quadrotor_simple_controller" filename="libkinton_gazebo.so"> + <alwaysOn>true</alwaysOn> + <updateRate>0.0</updateRate> + <bodyName>base_link</bodyName> + <stateTopic>${prefix}/odom</stateTopic> + <imuTopic>${prefix}/imu_raw</imuTopic> + <cmdvelTopic>${prefix}/cmd_vel</cmdvelTopic> + <mavctrlTopic>fcu/control</mavctrlTopic> + <rollpitchProportionalGain>10.0</rollpitchProportionalGain> + <rollpitchDifferentialGain>5.0</rollpitchDifferentialGain> + <rollpitchLimit>0.5</rollpitchLimit> + <yawProportionalGain>2.0</yawProportionalGain> + <yawDifferentialGain>1.0</yawDifferentialGain> + <yawLimit>1.0</yawLimit> + <velocityXYProportionalGain>5.0</velocityXYProportionalGain> + <velocityXYDifferentialGain>1.0</velocityXYDifferentialGain> + <velocityXYLimit>1.0</velocityXYLimit> + <velocityZProportionalGain>50.0</velocityZProportionalGain> + <velocityZDifferentialGain>1.1</velocityZDifferentialGain> + <velocityZLimit>1.0</velocityZLimit> + <maxForce>30</maxForce> + <motionSmallNoise>0.05</motionSmallNoise> + <motionDriftNoise>0.03</motionDriftNoise> + <motionDriftNoiseTime>5.0</motionDriftNoiseTime> + </plugin> + </gazebo> --> + <!-- WITH ARM >> NOT TUNNED --> + <gazebo> + <plugin filename="libkinton_gazebo.so" name="quadrotor_simple_controller"> + <alwaysOn>true</alwaysOn> + <updateRate>0.0</updateRate> + <bodyName>base_link</bodyName> + <stateTopic>kinton/odom</stateTopic> + <imuTopic>kinton/imu_raw</imuTopic> + <cmdvelTopic>kinton/cmd_vel</cmdvelTopic> + <mavctrlTopic>fcu/control</mavctrlTopic> + <rollpitchProportionalGain>10.0</rollpitchProportionalGain> + <rollpitchDifferentialGain>5.0</rollpitchDifferentialGain> + <rollpitchLimit>0.5</rollpitchLimit> + <yawProportionalGain>2.0</yawProportionalGain> + <yawDifferentialGain>1.0</yawDifferentialGain> + <yawLimit>1.0</yawLimit> + <velocityXYProportionalGain>5.0</velocityXYProportionalGain> + <velocityXYDifferentialGain>1.0</velocityXYDifferentialGain> + <velocityXYLimit>1.0</velocityXYLimit> + <velocityZProportionalGain>50.0</velocityZProportionalGain> + <velocityZDifferentialGain>1.1</velocityZDifferentialGain> + <velocityZLimit>1.0</velocityZLimit> + <maxForce>30</maxForce> + <motionSmallNoise>0.05</motionSmallNoise> + <motionDriftNoise>0.03</motionDriftNoise> + <motionDriftNoiseTime>5.0</motionDriftNoiseTime> + </plugin> + </gazebo> + <!-- Kinton-Arm joint --> + <joint name="fixed" type="fixed"> + <parent link="base_link"/> + <child link="arm_base"/> + <origin rpy="0 0 0" xyz="0 0 -0.09"/> + </joint> + <!-- Arm Base --> + <link name="arm_base"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0.0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/base.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0.0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/base.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0.0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint1" type="revolute"> + <parent link="arm_base"/> + <child link="link1"/> + <origin rpy="3.14159265359 0 3.14159265359" xyz="0.0 0.0 0.0"/> + <axis xyz="0 0 1"/> + <limit effort="1.0" lower="-0.35" upper="0.35" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran1"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor1"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link1 --> + <link name="link1"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link1.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link1.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint2" type="revolute"> + <parent link="link1"/> + <child link="link2"/> + <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0.038"/> + <axis xyz="0 0 1"/> + <limit effort="1.0" lower="-0.523" upper="0.523" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran2"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor2"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link2 --> + <link name="link2"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link2.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link2.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint3" type="revolute"> + <parent link="link2"/> + <child link="link3"/> + <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/> + <axis xyz="0 0 1"/> + <!-- <limit effort="1.0" lower="-0.35" upper="1.92" velocity="1.0"/> --> + <limit effort="1.0" lower="0.0" upper="1.5" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran3"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint3"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor3"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link3 --> + <link name="link3"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link3.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link3.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint4" type="revolute"> + <parent link="link3"/> + <child link="link4"/> + <origin rpy="0 0 -1.57079632679" xyz="0 -0.063 0"/> + <axis xyz="0 0 1"/> + <!-- <limit effort="1.0" lower="-2.35" upper="2.35" velocity="1.0"/> --> + <limit effort="1.0" lower="-2.1" upper="2.1" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran4"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint4"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor4"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link4 --> + <link name="link4"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link4.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link4.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint5" type="revolute"> + <parent link="link4"/> + <child link="link5"/> + <origin rpy="0 0 0" xyz="0.063 0 0"/> + <axis xyz="0 0 1"/> + <limit effort="1.0" lower="-2.35" upper="2.35" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran5"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint5"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor5"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link5 --> + <link name="link5"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link5.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link5.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <joint name="joint6" type="revolute"> + <parent link="link5"/> + <child link="link6"/> + <origin rpy="1.57079632679 0 1.57079632679" xyz="0.0561 -0.0034 0"/> + <axis xyz="0 0 1"/> + <limit effort="1.0" lower="-2.094" upper="2.094" velocity="1.0"/> + <dynamics damping="1.0"/> + </joint> + <transmission name="tran6"> + <type>transmission_interface/SimpleTransmission</type> + <joint name="joint6"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + </joint> + <actuator name="motor6"> + <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> + <mechanicalReduction>1</mechanicalReduction> + </actuator> + </transmission> + <!-- Link6 --> + <link name="link6"> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link6.stl"/> + </geometry> + <contact_coefficients kd="1.0" kp="1000.0" mu="0"/> + </collision> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://kinton_description/meshes/arm/link6.dae"/> + </geometry> + <material name="white"/> + </visual> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0.0002"/> + <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> + </inertial> + </link> + <!-- ros_control plugin --> + <gazebo> + <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"> + <robotNamespace>kinton</robotNamespace> + <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> + </plugin> + </gazebo> + <!-- Arm Base --> + <gazebo reference="arm_base"> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link1 --> + <gazebo reference="link1"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link2 --> + <gazebo reference="link2"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link3 --> + <gazebo reference="link3"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link4 --> + <gazebo reference="link4"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link5 --> + <gazebo reference="link5"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>true</selfCollide> + </gazebo> + <!-- Link6 --> + <gazebo reference="link6"> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/White</material> + <selfCollide>false</selfCollide> + </gazebo> + <joint name="arm_cam_joint" type="fixed"> + <origin rpy="3.14159265359 -1.57079632679 0.0" xyz="0.0 0.0 0.01"/> + <parent link="link6"/> + <child link="arm_cam_link"/> + </joint> + <link name="arm_cam_link"> + <inertial> + <mass value="0.0001"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/> + </inertial> + <visual> + <origin rpy="0 1.57079632679 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.01" radius="0.005"/> + </geometry> + <material name="Blue"> + <color rgba="0.0 0.0 0.8 1"/> + </material> + </visual> + <collision> + <origin rpy="0 1.57079632679 0" xyz="0 0 0"/> + <geometry> + <cylinder length="0.01" radius="0.005"/> + </geometry> + </collision> + </link> + <joint name="arm_cam_optical_joint" type="fixed"> + <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0.001 0 0"/> + <parent link="arm_cam_link"/> + <child link="arm_cam_optical_frame"/> + </joint> + <link name="arm_cam_optical_frame"> + <inertial> + <mass value="0.0001"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.001 0.001 0.001"/> + </geometry> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.001 0.001 0.001"/> + </geometry> + </collision> + </link> + <gazebo reference="arm_cam_link"> + <sensor name="arm_cam_camera_sensor" type="camera"> + <update_rate>25</update_rate> + <camera name="head"> + <horizontal_fov>1.5708</horizontal_fov> + <image> + <width>1280</width> + <height>960</height> + <format>R8G8B8</format> + </image> + <clip> + <near>0.01</near> + <far>100</far> + </clip> + <noise> + <type>gaussian</type> + <mean>0.0</mean> + <stddev>0.000</stddev> + </noise> + </camera> + <plugin filename="libgazebo_ros_camera.so" name="camera_plugin"> + <alwaysOn>true</alwaysOn> + <updateRate>0.0</updateRate> + <cameraName>kinton/arm_cam</cameraName> + <imageTopicName>image_raw</imageTopicName> + <cameraInfoTopicName>camera_info</cameraInfoTopicName> + <frameName>kinton/arm_cam_optical_frame</frameName> + <hackBaseline>0.07</hackBaseline> + <distortionK1>0.0</distortionK1> + <distortionK2>0.0</distortionK2> + <distortionK3>0.0</distortionK3> + <distortionT1>0.0</distortionT1> + <distortionT2>0.0</distortionT2> + </plugin> + </sensor> + <mu1>0.2</mu1> + <mu2>0.2</mu2> + <material>Gazebo/Black</material> + </gazebo> + <gazebo> + <turnGravityOff>false</turnGravityOff> + <static>false</static> + </gazebo> + <!-- <gazebo> + <turnGravityOff>true</turnGravityOff> + <static>true</static> + <plugin name="ground_truth" filename="libgazebo_ros_p3d.so"> + <frameName>world</frameName> + <bodyName>${name}_optical_frame</bodyName> + <topicName>${prefix}/${name}/odom</topicName> + <updateRate>30.0</updateRate> + </plugin> + </gazebo> + --> +</robot>